LORD-MicroStrain / microstrain_inertial

ROS driver for all of MicroStrain's current G and C series products. To learn more visit
https://www.microstrain.com/inertial
100 stars 76 forks source link

IMU Orientation solution's coordinate frames don't follow ROS convention #45

Closed CaptKrasno closed 3 years ago

CaptKrasno commented 3 years ago

When the microstrain is sitting in it's upright configuration (flat on a desk with the mounting holes against the surface) it reports roll and pitch = 0. In this configuration x and y are horizontal and z is down. So, in the ROS convention roll or pitch should report 180 deg when sitting flat on a desk.

This means they IMU orientation solution can not be used in common ROS packages like robot_localization without modification.

Acceleration reports -9.8 m/s along the z axis which does follow convention.

Angular velocities also seem to follow the ROS convention as well.

nathanmillermicrostrain commented 3 years ago

Hey CaptKrasno,

The ROS launch file contains a sensor-to-vehicle transformation that you can use to rotate the data into the frame you would like to use. It can be defined with Euler angles, a matrix, or a quaternion (for non-GQ7 products.) For all of our products, our default is when the the device axes are aligned with NED, you get 0 rotation reported. We understand this is not the ROS convention, but is the convention for all of our devices. Having the ROS driver act differently than our documented defaults was/is a point of concern for us. Hopefully, the sensor-to-vehicle frame transformation can satisfy your requirement. Please let me know if it doesn't.

Starting on line 138, the setup options are defined as follows:

<param name="filter_sensor2vehicle_frame_selector" value="0" type="int" />

<rosparam param="filter_sensor2vehicle_frame_transformation_euler">      [0.0, 0.0, 0.0]</rosparam>
<rosparam param="filter_sensor2vehicle_frame_transformation_matrix">     [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0]</rosparam>
<rosparam param="filter_sensor2vehicle_frame_transformation_quaternion"> [0.0, 0.0, 0.0, 1.0]</rosparam>
CaptKrasno commented 3 years ago

Nathan,

This looks like it may do the trick for the orientation. However, won't adjusting this parameter change the orientation of the acceleration vector too? If I apply the rotation to make the orientation solution comply with ROS convention won't I just break the acceleration vector?

At any rate, I will play with this next time I have my hands on our vehicle/microstrain.

Thanks, Kris

nathanmillermicrostrain commented 3 years ago

Hey Kris,

Yes, it will affect the acceleration vector, but I think it should still be what you want. An important note is that at rest (in a gravitational field), that vector isn't pointing in the direction of gravity, it is actually measuring the normal force... so it might be pointing in the opposite direction than you are expecting. If you add the gravity vector (in the IMU frame) to the output value at rest, you should get 0 acceleration +- noise/bias.

Hope that helps,

Nathan

CaptKrasno commented 3 years ago

<rosparam param="filter_sensor2vehicle_frame_transformation_quaternion"> [0.0, 0.0, 0.0, 1.0]</rosparam>

also... is this quaternion of the form [x,y,z,w] or [w,x,y,z]? I assume it's [x,y,z,w] so the default value, [0.0, 0.0, 0.0, 1.0], makes no rotation?

nathanmillermicrostrain commented 3 years ago

Quaternion order is [x, y, z, w], so yep, [0.0, 0.0, 0.0, 1.0] is 0 rotation.

CaptKrasno commented 3 years ago

Ok, I tried to set euler, rotation maxtrix, and quaternion and I adjusted the filter_sensor2vehicle_frame_selector accordingly (1,2,3 respectively). None of the options had any effect on the IMU orientation solution or the normal vector. Is it possible the 3dm-gx5-25 does not support this option?

I checked the parameter server to make sure the params were set properly. and they looked good as far as I could tell.

Yes, it will affect the acceleration vector, but I think it should still be what you want. An important note is that at rest (in a gravitational field), that vector isn't pointing in the direction of gravity, it is actually measuring the normal force... so it might be pointing in the opposite direction than you are expecting. If you add the gravity vector (in the IMU frame) to the output value at rest, you should get 0 acceleration +- noise/bias.

I am also not sure that this rotation will solve my problem. I think I would need to rotate the orientation solution and NOT the acceleration/angular velocities. Right now my URDF model has the coordinate frames matching those printed on the device In my case( y back, x right z down it is mounted sideways but upright on a flat surface see attached picture). This works for the acceleration vector, In the global view I see a 9.8m/s normal force pointing upward in the world frame as I would expect. It also appears to work for the angular velocities.

I am further convinced that acceleration and angular velocity are currently following ros convention because I used the raw values to compute an orientation solution using imu_filter_madgewick. This produces the orientation results I would expect and have been field tested successfully. However, these values are "upside down" from the one reported directly by the microstrain.

image the large upright coordinate frame is base_link and the other large axis is the microstrain.

nathanmillermicrostrain commented 3 years ago

Hey Kris,

I just tested all of the orientation options and they all worked for me... are you running the latest driver? Note, you should see something like the following when the device accepts the command:

image

On the orientation... thank you for the detailed outline of your situation. The issue is the global reference frame used, for our device, like many IMU/AHRS/INS manufacturers, the global frame is NED; whereas, robot_localization assumes ENU for the reference frame. As I looked into this, it appears to be a common issue when integrating an IMU with this package. I can add this transformation in the driver with a parameter option, likely early next week. Will that work for you?

Nathan

CaptKrasno commented 3 years ago

Nathan,

I just tested all of the orientation options and they all worked for me... are you running the latest driver? Note, you should see something like the following when the device accepts the command:

It's been a few weeks since I pulled. I will update, try again, and look for that message

On the orientation... thank you for the detailed outline of your situation. The issue is the global reference frame used, for our device, like many IMU/AHRS/INS manufacturers, the global frame is NED; whereas, robot_localization assumes ENU for the reference frame. As I looked into this, it appears to be a common issue when integrating an IMU with this package. I can add this transformation in the driver with a parameter option, likely early next week. Will that work for you?

That would be great! This solution should work fine for us. Looking through my old code, this is ultimately what I had to do when I wrote my old MCSL driver (although hard coded). image

Differing coordinate conventions are always a pain... I appreciate your willingness to support ROS convention!

-Kris

CaptKrasno commented 3 years ago

I just tested all of the orientation options and they all worked for me... are you running the latest driver? Note, you should see something like the following when the device accepts the command:

I figured it out: the section of code that sets the sensor2vehicle transform is inside this if statement: if(m_publish_filter && supports_filter){

My config had publish_filter set to false since we only use the "raw" imu orientaiton/accelrations/angular vel.

Once I set publish filter to true the transform worked properly.

Is this behavior intentional? The transform seems to effect the "raw" imu orientation so maybe the behavior should be changed?

-Kris

EDIT: After applying the rotation I was able to fix my orientation issue but it DID break acceleration in the process. Our/my assumptions were correct

nathanmillermicrostrain commented 3 years ago

Hey Kris,

I just updated the driver to fix these issues (ENU as a reference frame and setting the sensor2vehicle transformation when not publishing filter data).

There is a flag in the launch file that you can set to enable ENU pos/vel/attitude data. Let me know if you run into any troubles!

Nathan

CaptKrasno commented 3 years ago

Nathan,

I have good news and I have bad news.

The good news:

the m_use_enu_frame flag worked great! Orientations and accelerations all line up in ROS land and work out of the box with robot localization now!

The bad news:

It seems you removed the ability to set the imu_frame_id, gnss1_frame_id, gnss2_frame_id, filter_frame_id and filter_child_frame_id.

It looks like you were trying to get the names to update properly when using ENU vs NED.

 if(m_use_enu_frame)
  {
    m_gnss_frame_id[GNSS1_ID] = "gnss1_antenna_wgs84_enu";
    m_gnss_frame_id[GNSS2_ID] = "gnss2_antenna_wgs84_enu";
    m_filter_frame_id         = "sensor_wgs84_enu";
  }

However, this will (and has in my case) broke user's configurations. I temporary added this line back and everything worked fine private_nh.param("imu_frame_id", m_imu_frame_id, std::string("sensor_ned"));

I assume the behavior you are going for is _enu or _ned. You could still pull those params from the server and add the _enu/ned suffix automatically. However, I think that would still break lots of configs since it would change how frames are named.

Maybe give the user a choice to specify the frame directly or specify a prefix. For example:

m_use_enu_frame:true

# user can specify:
imu_frame_id: "microstrain_imu"  #resolves to microstrain_imu
# --or--
imu_frame_prefix: "microstrain_imu"  #resolves to microstrain_imu_enu

This way you can get the automatic behavior you want but you won't break existing systems.

That's just my 2 cents though. Hope it helps.

-Kris

nathanmillermicrostrain commented 3 years ago

Corrected... let me know if that works for you!

CaptKrasno commented 3 years ago

Just pulled and did a quick test. Seems to work great, thanks for your help!

-Kris

Alex-Beh commented 1 year ago

Hi All,

I am recently trying to use microstrain 3DM CV7 with robot_localization. I have already set use_enu_frame=true and place the IMU with the logo facing up. Do I still need to set the static_tf_transform with 180 rotation around y-axis?

tf_imu_base_link = launch_ros.actions.Node(
    package='tf2_ros',
    executable='static_transform_publisher',
    name='imu_base_link',
    output='screen',
    arguments=["0.0", "0.0", "0.1", "0.0", "3.14159", "0.0", "base_link", "imu_link"]
)
CaptKrasno commented 1 year ago

I do not believe you need the 180 degree rotation. The IMU was actually mounted backwards on our vehicle which is why it's rotated in our URDF.