ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

robot_localization - IMU orientation query

asked 2017-10-09 08:39:38 -0500

CJ Davies gravatar image

I am trying to use robot_localization to fuse data from a BNO055 IMU & a MTK3339 GPS receiver. I have what appears to be sensible output coming out of the system, however I would like to clarify one thing about the IMU orientation.

My launch file is linked below [1] & sets up a nmea_topic_driver to convert raw NMEA messages from the MTK3339 into NavSatFix messages, then a navsat_transform_node & a ukf_localization_node. The outputs that I am interested in are filtered IMU data (as orientation in x,y,z Euler angles) & filtered GPS data (as latitude & longitude) so I am subscribing to /odometry/filtered (which I then convert from quaternion to Euler) & /gps/filtered.

The quick start guide for the BNO055 [2] shows on page 4 that it outputs orientation data in the ENU convention expected by REP-0103 & robot_localization, except that it gives 0° at North rather than East, so I have set yaw_offset for navsat_transform_node to 1.5707963 as explained by the doc. However there doesn't appear to be an equivalent parameter for the ukf_localization_node. Do I need to specify this 90° in the transform between base_link frame & imu frame?

Any other input on other parts of my setup that may be wrong are of course welcomed!

[1] https://gist.github.com/CJ-Davies/4eb...

[2] https://ae-bst.resource.bosch.com/med...

edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
0

answered 2018-01-08 04:18:17 -0500

Tom Moore gravatar image

updated 2018-01-08 04:19:08 -0500

The UKF doesn't have any knowledge of how your IMU heading relates to the geographic frames. It just sees, at the start of execution, that its first orientation measurement is X radians. Imagine that you didn't have a GPS or IMU at all, and your heading came from, say, an overhead camera in a laboratory environment. That orientation has nothing to do with a geographic coordinate frame; it would have more to do with the camera mounting and whatever arbitrary pose you considered to be your origin.

All that navsat_transform_node is doing is converting the GPS data into coordinates that are consistent with the UKF coordinate frame. So, now imagine that you have the same scenario as before (overhead camera, no IMU going into the UKF), but now you have a GPS and IMU going into navsat_transform_node. It's still going to function, because navsat_transform_node takes into account your robot's UKF pose when it computes its transform. The only reason navsat_transform_node needs the yaw offset and magnetic declination data is so that I can convert everything into the UTM frame, which assumes that +X is East and +Y is north. Once it's in the UTM frame, it's easy to define the transform to your robot's world frame.

Bottom line: your robot's orientation in the UKF frame doesn't matter, as long as it is right-handed. navsat_transform_node will do the legwork of making sure the poses that go into the UKF are consistent.

edit flag offensive delete link more

Question Tools

Stats

Asked: 2017-10-09 08:39:38 -0500

Seen: 1,117 times

Last updated: Jan 08 '18