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

robot_localization GPS integration error

asked 2015-08-10 16:00:20 -0500

Mike Hosmar gravatar image

updated 2015-08-13 15:18:23 -0500

###Overview I have been having quite a hard time with setting up my robot to use its GPS. I am attempting to use the navsat_transform_node and two instances of robot_localization. The set up is almost identical to the example in the wiki.

However, the localization node which combines the gps data to the data of the first localization node acts wildly. The transform it produces slowly drifts but then shoots off into one direction and doesnt stop. It sometimes rotates around the initial position while moving outwards. This happens with the robot standing still. The gps data does vary slightly and wanders a bit but within a closed area.

To get some context The robot I am using is a Jackal. It has a laser mounted up front and gps and imu built in. Much of the ros code for the integrated sensors runs on the onboard computer and is installed via debs making it difficult to modify. The GPS integration is running on my laptop which communicates to the jackal through through LAN to a router then through WiFi. I have made sure that the times are synced because this was giving me issues earlier.

###More Detail I have three frames of interest map, odom and base_link. Odom->base_link is generated by a primary localization node which combines an IMU which is earth referenced (the orientation includes the magnetometer) and wheel odometry. The second localization node combines the gps odometry from navsat_transform and the output of the first localization node. (I have also tried to combine the wheel odometry and imu directly in this node) This creates the map->odom transform.

I have used an old commit for the jackal as my starting point. Its intention was to implement this gps integration but then was removed for later development. The commit is found here. I haven't made too many changes to these file other to include a yaw offset (the imu has north pointing to x+) and magnetic declination. I have just tried making small changes to try to see if anything would help.

###Thoughts I'm not sure but I have a feeling that there is trouble transforming the data from a frame on the robot up to the map frame. To me it doesnt make sense to use data in a frame below the transform you are trying to create. You need to use the transform you're creating to transform the data to create the transform. It seems to me like a cyclical problem. But this may work I'm not sure.

The feeling im getting from what I'm seeing is that the gps is drifting a little bit and the transform is drifting as a result. Then a jump occurs in the gps data and through some delay in the tf and the fact that there is some cyclical component to the setup the same value gets added to the system repeatedly. (Data gets transformed using old tf, tf gets updated using previous ... (more)

edit retag flag offensive close merge delete

Comments

Are you using the output of the first EKF as input to the second? I can't access Drop Box from work, so I'll check this out later. Your use case is pretty typical and works well for me on our Husky, so I'd have to check out the bags.

Tom Moore gravatar image Tom Moore  ( 2015-08-11 09:07:21 -0500 )edit

I have tried that and I have tried duplicating the inputs from the first with the addition of the GPS.

Mike Hosmar gravatar image Mike Hosmar  ( 2015-08-11 09:58:58 -0500 )edit

OK, I'll look at the bags later today.

Tom Moore gravatar image Tom Moore  ( 2015-08-11 10:07:54 -0500 )edit

I looked at the bag file. You're missing a topic, I'm afraid. I need one that has all the inputs to the filter, including /jackal_velocity_controller/odom. Also, if you can post it on Google Drive, that would help.

Tom Moore gravatar image Tom Moore  ( 2015-08-12 08:21:56 -0500 )edit

Ok I updated the bag. I just recorded all this time. I was avoiding this b/c the wiki said rosbag would drop a few of the first messages on a new topic.

Mike Hosmar gravatar image Mike Hosmar  ( 2015-08-13 15:20:17 -0500 )edit

Hello,

I downloaded the script. But it doesn't work. When I'm running the launch file I always get those errors:

[ WARN] [1484744122.707880271]: Could not obtain base_link->navsat_link transform. Will not remove offset of navsat device from robot's origin.

Can someone help me?

modotz gravatar image modotz  ( 2017-01-18 07:06:07 -0500 )edit

@modotz Please only use answers for answering questions (not for asking new questions). I've moved your question to a comment. If you don't receive any help, please open a new question.

jarvisschultz gravatar image jarvisschultz  ( 2017-01-18 07:27:47 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
10

answered 2015-08-18 15:48:51 -0500

Tom Moore gravatar image

Hi Mike,

I believe I've solved your problem. The short answer is that I believe your navsat_transform_node configuration was listening to the wrong ekf_localization_node output. You want it to listen to whatever the output of your map instance of ekf_localization_node is.

WHAT I DID

  1. Rather than trying to debug your parameters, I decided to start from the ground up and let you use my settings.
  2. I filtered your bag file down to the just the topics I needed: /jackal_velocity_controller/odom, /navsat/fix, and /imu/data.
  3. I then threw together a launch file from scratch for both instances of ekf_localization_node and the single instance of navsat_transform_node.
  4. I uploaded the filtered bag file and launch file here so that you can verify my results. You'll have to change the absolute path to the bag file that I have in the launch file.

RESULTS

  • My launch file works fine for me. You still see some GPS drift at the start, but it doesn't run away as it did in your bag file. In this image, red is the output of the local (odom) instance of ekf_localization_node, and blue is the output of the global (map) instance. Note that whenever both topics are drawn at the same time, they are right on top of one another (this is harder to see when the robot is still, as rviz doesn't draw the changes to the odom-frame output). This means the transform from map->odom is correct.

    image description

  • I wanted to reproduce your issue based on my best guess as to the problem, so I changed the odometry input into navsat_transform_node to the output of the local (odom) instance of ekf_localization_node instead of the global (map) instance. I was able to successfully reproduce the issue:

    image description

CONCLUSION

  • Change your settings so that navsat_transform_node is listening to the odometry output of your map instance of ekf_localization_node.
  • One note: I'm not sure where your IMU reports zero heading, so I put in a yaw_offset value of 1.570796327 in navsat_transform_node. If your IMU reports data in ENU (with 0 facing east), then you can set that back to 0. I also added the magnetic declination for your location.
edit flag offensive delete link more

Comments

This is a surprising result. I didn't think to suspect the transform node because the position seemed stable enough. I guess It changes the frame that the transform node sets in the header. I am going to test this asap and im going to try to use my own launch files.

Mike Hosmar gravatar image Mike Hosmar  ( 2015-08-19 10:15:41 -0500 )edit

Looks like it works now. The main difference I have to your launch file is that I am using the local odometry as the input to the global odometry with it set as an absolute input. The mag declination I had already but it should be negative I believe.

Mike Hosmar gravatar image Mike Hosmar  ( 2015-08-19 14:12:54 -0500 )edit

I still have the process noise covariance matrix from clearpath's commit. But I have no idea if it's correct. Do you know of some literature on how to tune this. Or should I remove it completely?

Mike Hosmar gravatar image Mike Hosmar  ( 2015-08-19 14:15:02 -0500 )edit

I would use whatever has been committed to the Jackal repo.

Tom Moore gravatar image Tom Moore  ( 2015-08-19 15:28:10 -0500 )edit

Hello Tom, I downloaded the files above and get when I execute the launch file these errors:

[ WARN] [1485188817.469787094]: Could not obtain base_link->navsat_link transform. Will not remove offset of navsat device from robot's origin.

it seems like a tf transform is missing? Any help?

modotz gravatar image modotz  ( 2017-01-23 10:28:45 -0500 )edit

I believe I answered your other question on this very subject.

Tom Moore gravatar image Tom Moore  ( 2017-01-23 10:50:38 -0500 )edit

Hi, the Tom Moore link does not exist is possible to make a new one

Tanks

Pietro gravatar image Pietro  ( 2017-05-03 03:14:13 -0500 )edit

Just want to say thanks Tom. Your answer fixed our identical problem too.

ufr3c_tjc gravatar image ufr3c_tjc  ( 2017-05-14 22:34:39 -0500 )edit

Question Tools

4 followers

Stats

Asked: 2015-08-10 16:00:20 -0500

Seen: 2,929 times

Last updated: Aug 18 '15