jeskesen / i2c_imu

ROS node for communicating with several models of commercially available IMUs over I2C in linux.
GNU General Public License v3.0
52 stars 44 forks source link

How to use mpu9250? #10

Open sujunqin123 opened 7 years ago

sujunqin123 commented 7 years ago

Hi, I want to run mpu9250 in banana pi M3,I try to modify the mpu_9150.launch, as follow: <?xml version="1.0"?>


and I have detect mpu9250 in i2c bus 2 root@bpi-iot-ros-ai:/home/pi/my_ros_ws# i2cdetect -y 2 0 1 2 3 4 5 6 7 8 9 a b c d e f 00: -- -- -- -- -- -- -- -- -- -- -- -- -- 10: -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- 20: -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- 30: -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- 40: -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- 50: -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- 60: -- -- -- -- -- -- -- -- 68 -- -- -- -- -- -- -- 70: -- -- -- -- -- -- -- --


when i run: roslaunch i2c_imu mpu_9250.launch, the result as follow:

PARAMETERS

NODES /imu/ i2c_imu_node (i2c_imu/i2c_imu_node) / imu_to_base (tf/static_transform_publisher)

ROS_MASTER_URI=http://localhost:11311

core service [/rosout] found process[imu_to_base-1]: started with pid [10098] process[imu/i2c_imu_node-2]: started with pid [10099] [ INFO] [1487039913.152380428]: RTIMU Node for ROS Settings file RTIMULib.ini loaded [ INFO] [1487039913.213003026]: loadSettings: reading IMU parameters from param server [ INFO] [1487039913.381746702]: No Calibration for Compass [ INFO] [1487039913.385535281]: No Calibration for Accelerometer Using fusion algorithm RTQF min/max compass calibration not in use Ellipsoid compass calibration not in use Accel calibration not in use I2C read error from 104, 15 - Failed to read LSM9DS1 accel/gyro id [FATAL] [1487039913.492664405]: I2cImu - Failed to init the IMU [FATAL] [1487039913.492860938]: BREAKPOINT HIT file = /home/pi/my_ros_ws/src/i2c_imu-master/src/i2c_imu_node.cpp line=137

How can I solve this problem? thanks

AllanXyl commented 6 years ago

I have a similar problem, did you happen to resolve the issue?

Alabate commented 6 years ago

To use MPU-9250, you have to set imu_type to 7. Here is an example of launchfile:

<?xml version="1.0"?>
<launch>
    <node pkg="tf" type="static_transform_publisher" name="imu_to_base" 
        args="0 0 .1 0 0 0 base_link imu_link 50" />    

    <node name="i2c_imu_node" pkg="i2c_imu" type="i2c_imu_node" ns="imu" output="screen">
        <param name="imu_frame" value="imu_link" />

        <param name="i2c_bus" value="1" />

        <param name="i2c_slave_address" value="104" />
        <!--imu_type:
            0 = Auto discover
            1 = Null (used when data is provided from a remote IMU
            2 = InvenSense MPU-9150
            3 = STM L3GD20H + LSM303D
            4 = STM L3GD20 + LSM303DLHC
            5 = STM LSM9DS0
            6 = STM LSM9DS1
            7 = InvenSense MPU-9250
            8 = STM L3GD20H + LSM303DLHC
            9 = Bosch BMX055
            10 = Bosch BNX055
        -->
        <param name="imu_type" value="7" />

        <!--fusion_type:
            0 = RTFUSION_TYPE_NULL: just a dummy to keep things happy if not needed
            1 = RTFUSION_TYPE_KALMANSTATE4: kalman state is the quaternion pose
            2 = RTFUSION_TYPE_RTQF: RT quaternion fusion
        -->
        <param name="fusion_type" value="2" />

        <!-- mpu9250/gyro_accel_sample_rate: 5 - 1000 Hz -->
        <param name="mpu9250/gyro_accel_sample_rate" value="80" />

        <!-- mpu9250/compass_sample_rate: 1 - 100 Hz -->
        <param name="mpu9250/compass_sample_rate" value="40" /> 

        <!-- mpu9250/gyro_low_pass_filter:
            0x11 - 8800Hz, 0.64mS delay
            0x10 - 3600Hz, 0.11mS delay
            0x00 - 250Hz, 0.97mS delay
            0x01 - 184Hz, 2.9mS delay
            0x02 - 92Hz, 3.9mS delay
            0x03 - 41Hz, 5.9mS delay
            0x04 - 20Hz, 9.9mS delay
            0x05 - 10Hz, 17.85mS delay
            0x06 - 5Hz, 33.48mS delay
        -->
        <param name="mpu9250/gyro_low_pass_filter" value="3" />

        <!-- mpu9250/accel_low_pass_filter:
            0x00 - 460Hz, 1.94mS delay
            0x01 - 184Hz, 5.80mS delay
            0x02 - 92Hz, 7.80mS delay
            0x03 - 41Hz, 11.80mS delay
            0x04 - 20Hz, 19.80mS delay
            0x05 - 10Hz, 35.70mS delay
            0x06 - 5Hz, 66.96mS delay
        -->
        <param name="mpu9250/accel_low_pass_filter" value="3" />

        <!-- mpu9250/gyro_full_scale_range:
            0 +/- 250 degress per second
            8 +/- 500 degress per second
            16 +/- 1000 degress per second
            24 +/- 2000 degress per second
        -->
        <param name="mpu9250/gyro_full_scale_range" value="16" />

        <!-- mpu9250/accel_full_scale_range:
            0 +/- 2g
            8 +/- 4g
            16 +/- 8g
            24 +/- 16g
        -->
        <param name="mpu9250/accel_full_scale_range" value="16" />
    </node>
</launch>
Sahil-24 commented 6 years ago

Has anyone had success with calibrating the compass/accelerometer via either the yaml or launch file?