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

How to fuse IMU & GPS using robot_localization

asked 2014-12-25 22:21:31 -0500

AK47 gravatar image

I am trying to estimate the position of a robot using robot_localization. There are ONLY two sensors used in the problem: an IMU and a GPS receiver. After reading the tutorials about robot_localization and studying many threads in the ros-answer website, I am still a little confused about how to structure the overall estimation process. I would greatly appreciate if someone with experience in this topic can offer some suggestions.

I understand I need to use navsat_transform_node in order to integrate GPS into robot_localization, but navsat_transform_node requires three inputs. In addition to IMU & GPS, it requires an odometry input, which is not available in my system. To solve this issue, I first feed IMU (sensor_msgs/Imu) and GPS (sensor_msgs/NavSatFix) measurements to utm_odometry_node, which is a node of the gps_common package. The output of utm_odometry_node is of the type nav_msgs/Odometry, and it is feed to navsat_transform_node along with the original IMU and GPS measurements. The output of navsat_transform_node, named odometry/gps, is then feed to ekf_localization_node with the original IMU measurements.

I was wondering if this is the correct structure of the estimation process. Any comments and suggestions will be appreciated!

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
13

answered 2014-12-26 10:43:20 -0500

Tom Moore gravatar image

updated 2019-11-04 04:43:21 -0500

No, I don't think your setup will work, although I haven't thought through it in great depth. In any case, it's not the way it's intended to be used. The odometry input to navsat_transform_node can just be your ekf_localization_node output (it defaults to odometry/filtered). navsat_transform_node needs the third input (the odometry from your state estimate) because it converts the GPS data into the coordinate frame of that message. If your robot starts out, for example, indoors, and then moves outdoors, you need to know its pose estimate at the moment it starts receiving GPS in order to make the transformed GPS data consistent with your current state estimate.

For you, as soon as your IMU data is fed to the filter, ekf_localization_node will produce a state estimate, at which point navsat_transform_node will have all the data it needs.

EDIT in response to question:

Your final setup will be this:

ekf_localization_node

  • Inputs

    • IMU
    • Transformed GPS data as an odometry message (navsat_transform_node output)
  • Outputs

    • Odometry message (this is what you want to use as your state estimate for your robot)

navsat_transform_node

  • Inputs

    • IMU
    • Raw GPS (NavSatFix)
    • Odometry (output of ekf_localization_node)
  • Outputs

    • Transformed GPS data as odometry message

The data path is circular, but it's necessary. Once navsat_transform_node gets the first IMU message, it drops the subscription.

edit flag offensive delete link more

Comments

1

Tom, thank you very much. If I understand correctly, the correct setup is to feed IMU data to ekf_localization_node, and then feed the output of this node. along with IMU and GPS data, to the navsat_transform_node to get the final estimation. Is this the correct setup? Thanks!

AK47 gravatar image AK47  ( 2014-12-26 15:17:15 -0500 )edit

No, sorry. See the answer edit.

Tom Moore gravatar image Tom Moore  ( 2014-12-26 17:41:02 -0500 )edit
1

Tom, many thanks! I configure my estimation in the way as you suggested, and it seems to be working!

AK47 gravatar image AK47  ( 2014-12-26 20:31:04 -0500 )edit
1

Hello,

I am really interested in the topic! Could you please post your launch files here to familiarizamyselfof how to setup my similar project? Thank you!

Zoid gravatar image Zoid  ( 2017-02-19 09:43:08 -0500 )edit

Hello AK47

I am really interested in the topic! Could you please post your launch files here to familiarizamyselfof how to setup my similar project? Thank you!

rz gravatar image rz  ( 2018-04-19 18:17:11 -0500 )edit

Hi Tom, Are you sure the navsat_transform_node drops subscription to odometry message(after first message)? What I see in source code is that the subscription to IMU is shutdown after the first message. But not the Odometry. Please clarify this issue.

rezafirouzi gravatar image rezafirouzi  ( 2019-10-22 02:54:38 -0500 )edit

Yes, that is correct. Edited, thanks.

Tom Moore gravatar image Tom Moore  ( 2019-11-04 04:43:30 -0500 )edit

Hi Tom, The setup that you have captured would require another ekf_localization_node correct? To establish the odom->base_link transform and then this setup for the map->odom transform. My question is what is the right odometry message to use for the input to the ekf_localization_node that is creating the odom->base_link transform if the odometry/gps output is feeding into the odometry input of the ekf_localization_node creating the map->odom transform?

The circular reference gets a little confusing. Thank you.

ClintQ gravatar image ClintQ  ( 2021-03-19 16:03:23 -0500 )edit

Question Tools

13 followers

Stats

Asked: 2014-12-25 22:21:31 -0500

Seen: 8,422 times

Last updated: Nov 04 '19