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

Integrate a GPS sensor with robot_localization and use move_base node

asked 2015-01-30 08:45:15 -0600

ASoriano gravatar image

updated 2015-02-11 07:08:51 -0600

Hello,

I’m trying to integrate a GPS sensor to my mobile robot with the robot_localization_node. I have an IMU sensor added to my robot_localization_node but now I have some theoretical questions about how to integrate the GPS.

I would like to use the output of the robot_localization node to feed the move_base node in order to set some waypoints in GPS coordinates (can be in UTM) and then the robot follow them. I’m a bit lost about how to proceed. This is what I think:

I launch ek_localization_node with this inputs: IMU and wheel_odom. And I remap the output topic to local_odometry. It'll be the local odometry in odom frame. (I must use this topic to input to move_base if I want to navigate in odom frame).

Then I launch navsat_transform_node with IMU, wheel_odom, and GPS NavSatFix and the output topic in world frame is /odometry/gps. But this topic is publishing only when the GPS signal is received so...

I launch another ekf_localization node with IMU,Wheel_odom and odom1 (/odometry/gps from navsat_transform node). The output of this node (/odometry/filtered) is in world frame and is what I have to put as input to move_base, right? With this configuration I don’t need to use gps_common, right? When I launch all, I have to call the service set_pose in order to give some estimation pose in UTM coordinates to /odom in base to /world, isn’t?

UPDATE 1:

Thanks Tom. I've taken into account all your comments and here's my robot_localization launch file and my tf tree.

  1. I feed the move_base odometry with the local_odometry returned by my first instance of ekf_localization_node.

  2. As I've my waypoints in UTM coordinates, their should be in utm frame. I can't see the tf of utm frame publishing, but in the source code I see it's /utm.

  3. I think the global planner of move_base_node needs the global frame set to the same frame of the waypoints. So It should be /utm, but when I launch this configuration, move_base_node says this:

[ WARN] [1422876635.213009322]: Waiting on transform from summit_a/base_footprint to utm to become available before running costmap, tf error:

I understand that move_base can't find the tf between utm and base_footprint frames. I don't know if it can be because the tf isn't visible by move_base_node or I'm doing something wrong.

  • (Just to test.) If I set the global frame of the global_panner of move_base_node to summit_a/world it reports me this:

[ERROR] [1422873579.326459610]: The goal pose passed to this planner must be in the summit_a/world frame. It is instead in the summit_a/utm frame.

  • (other test) Setting the global frame of global_planner to summit_a/odom:

[ERROR] [1422876188.622192440]: The goal pose passed to this planner must be in the summit_a/odom frame. It is instead in the utm frame.

So, the global_planner frame of move_base_node needs to be consistent or the same that the frame of the ... (more)

edit retag flag offensive close merge delete

Comments

Thanks for the update. I'll look into this and get back to you.

Tom Moore gravatar image Tom Moore  ( 2015-02-02 16:41:05 -0600 )edit

Yeah, I can't make the utm frame the parent of odom, as that would conflict with any other nodes (like amcl) that need to publish a map->odom transform. I need to look at move_base, but in general, if you use tf's transform methods, parentage shouldn't matter.

Tom Moore gravatar image Tom Moore  ( 2015-02-03 16:25:25 -0600 )edit

In response to EDIT 1. Yes, it's still true. My IMU only offers me angular velocity and linear acceleration. Maybe can I use the orientation that the GPS gives me?

Is it possible do visible the tf odom->utm? Thanks.

ASoriano gravatar image ASoriano  ( 2015-02-04 02:49:01 -0600 )edit

Sure, as long as it's being broadcast. Just do this:

rosrun tf tf_echo odom utm
Tom Moore gravatar image Tom Moore  ( 2015-02-04 08:19:57 -0600 )edit

Also, yes, you can use the GPS heading, but you'd have to have some logic in there to (a) make sure the heading isn't bogus, because it will be until you move, and (b), send out an IMU message with that heading in it (might want to include the roll and pitch from your actual IMU as well).

Tom Moore gravatar image Tom Moore  ( 2015-02-04 08:43:39 -0600 )edit

2 Answers

Sort by » oldest newest most voted
3

answered 2015-01-30 12:15:10 -0600

Tom Moore gravatar image

updated 2015-02-11 08:31:55 -0600

Ok, so here's your setup as I see it:

ekf_localization_node instance 1:

  • Inputs: wheel odometry and IMU
  • Relevant parameters: world_frame is set to odom
  • Outputs: local_odometry and odom->base_link transform

ekf_localization_node instance 2:

  • Inputs: wheel odometry, IMU, and transformed GPS data from navsat_transform_node
  • Relevant parameters: world_frame is set to map
  • Outputs: odometry/filtered and map->odom transform

navsat_transform_node:

  • Inputs: local_odometry (incorrect, see below), IMU, and raw GPS data
  • Outputs: odometry/gps

Additionally, you are using the second instance of ekf_localization_node because you want GPS-integrated data to be available at a faster rate.

Answers and comments:

  1. Both odom and map are "world frames." When your robot starts, they have the same origin. They will diverge as you move, however.
  2. As I recall, move_base will let you issue a goal in any frame, but will transform it into a target frame before executing the motion commands. Someone please correct me if this is wrong. If you want to issue goals in UTM coordinates, you're in luck: there's a parameter for navsat_transform_node named broadcast_utm_transform. Set it to true. (I just realized that this wasn't documented properly on the wiki. Sorry about that.) Now you should be able to issue goals in the utm frame.
  3. It's a minor point, but your odometry input to navsat_transform_node should be your odometry/filtered data from the second instance of ekf_localization_node.
  4. No, you don't need gps_common per se, but the package should be installed, as I'm using a header file from it.
  5. You should have no need to use set_pose. The output of navsat_transform_node is in a world-fixed frame that is aligned with your vehicle's start position and orientation. In other words, if your robot is at (4, 2) in the odom frame (ekf_localization_node instance 1), then its position, in a perfect world, would be (4, 2) in the map frame (ekf_localization_node instance 2).
  6. Make sure your IMU reports in the ENU frame, and that you know what it reads when it points to magnetic north, and then make sure you set the parameters to navsat_transform_node accordingly.

Hope this helps! Let me know how it goes.

EDIT 1: Quick question: I noticed that in your launch file, you have this:

  <!--My IMU doesn't have compas-->

Is that still true? If so, that's going to be a problem. You need an IMU that has some knowledge of its orientation relative to north (east, really, but knowing one gives the other).

EDIT in response to update 2: I'm afraid it's been some time since I used move_base. There may be someone else who's integrated it. My guess is that you want to give it your non-GPS-enabled instance (instance 1) of ekf_localization_node. Assuming move_base requires your current location and a goal location, then I would hope/think it's transforming the current location and goal location into whatever frame it wants to use. However, I think you'll want the position estimate that you give to move_base ... (more)

edit flag offensive delete link more
0

answered 2016-11-30 07:57:24 -0600

surya97531 gravatar image

Hi, I have a doubt in the topics being published and subscribed by ekf 2nd instance and navsat node ekf 2nd instance subscribes odometry/gps and publishes odometry/filtered which is subscribed by navsat node and publishes odometry/gps. Doesn't this loop in topics cause any problem? please help me clear this confusion. thanks in advance.

edit flag offensive delete link more

Comments

1

This is not an answer, and it would be better to post this as a separate question, or as a comment under the original question or the accepted answer.

gvdhoorn gravatar image gvdhoorn  ( 2016-11-30 09:46:45 -0600 )edit

Question Tools

7 followers

Stats

Asked: 2015-01-30 08:45:15 -0600

Seen: 4,691 times

Last updated: Nov 30 '16