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

Problem with GPS and robot_localization: map frame

asked 2020-03-24 08:45:14 -0500

tseco gravatar image

updated 2020-05-19 02:47:47 -0500

Tom Moore gravatar image

Hello,

We are running two instances of robot_localization node (as recommended) in order to fuse the information provide by an imu, odometry and GPS-RTK (ardusimple). The first instance of robot_localizaiton fuses only relative values using the imu (imu/data) and the odometry data (/odom) and setting world_frame param to odom. The result is /odometry/filtered. The second instance fuses the information that comes from the imu (imu/data), the odometry (/odom) and the odometry from gps (/odometry/gps) obatined using the navsat_transform_node. In this case, world_frame is set to map. So, we obtained the transform from odom to base_link from the first robot_localization node and the transform from map to odom using the second one.

The navsat_tranform_node use the information provided by /odometry/filtered, by the gps (/gps/fix) and the heading provied also with a specific setup of our ardusimple gps-rtk (different from the other imu we use). We have checked that the /odometry/gps provided by this node is correctly oriented and the accuracy in terms of position and orientation is good enough.

These are the main parameters of the relative configuration:

map_frame: map
odom_frame: odom
base_link_frame: base_link
world_frame: odom 

odom0: /odom

odom0_config: [true,  true,  false,
               false, false, true,
               true, true, false,
               false, false, false,
               false, false, false]
odom0_queue_size: 2
odom0_nodelay: false
odom0_differential: true
odom0_relative: false

imu0: /imu/data
imu0_config: [false, false, false,
              false,  false,  false,
              false, false, false,
              false,  false,  true,
              false,  false,  false]
imu0_nodelay: false
imu0_differential: false
imu0_relative: true
imu0_queue_size: 5
imu0_pose_rejection_threshold: 0.8                 
imu0_twist_rejection_threshold: 0.8                
imu0_linear_acceleration_rejection_threshold: 0.8  
imu0_remove_gravitational_acceleration: true

The params used for the other robot_localizacion instance are:

map_frame: map              
odom_frame: odom            
base_link_frame: base_link 
world_frame: map           

odom0: /odom
odom0_config: [false,  false,  false,
               false, false, false,
               true, true, false,
               false, false, false,
               false, false, false]
odom0_queue_size: 10
odom0_nodelay: false
odom0_differential: true
odom0_relative: false  

#  Odometry that comes from gps data (navsat_transform_node)
odom1: /odometry/gps
odom1_config: [true, true, false,
 false, false, false,
 false, false, false,
 false, false, false,
 false, false, false]
odom1_differential: false
odom1_relative: false
odom1_queue_size: 10
odom1_pose_rejection_threshold: 5
odom1_twist_rejection_threshold: 1
odom1_nodelay: true

imu0: /imu/data
imu0_config: [false, false, false,
              false,  false,  false,
              false, false, false,
              false,  false,  true,
              false,  false,  false]
imu0_nodelay: false
imu0_differential: false
imu0_relative: true
imu0_queue_size: 10
imu0_pose_rejection_threshold: 0.8                 
imu0_twist_rejection_threshold: 0.8                
imu0_linear_acceleration_rejection_threshold: 0.8  
imu0_remove_gravitational_acceleration: true

Using these configurations, the odom frame is continously jumping with repect to map frame. You can see the effect in the next video:

gps map_odom problem

The issue is observed when the robot starts moving.

Any suggestions?

Thanks in advance

Edit: adding sensor message samples

/odom

header: 
  seq: 403
  stamp: 
    secs: 1583947075
    nsecs: 926265907
  frame_id: "odom"
child_frame_id: "base_link"
pose: 
  pose: 
    position: 
      x: -9.40900611877
      y: 158.370346069
      z: 0.0
    orientation: 
      x: 0.0
      y: 0.0
      z: 0.986108124256
      w: 0.166104823351
  covariance: [100.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 100.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1000000.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0 ...
(more)
edit retag flag offensive close merge delete

Comments

Any suggestions about this issue? Thanks in advance!

tseco gravatar image tseco  ( 2020-04-15 01:41:27 -0500 )edit

Please include sample messages from every sensor input.

Tom Moore gravatar image Tom Moore  ( 2020-05-04 03:27:47 -0500 )edit

I have a 200 M bag, so I am going to reduce it. Apart from that, we are using a node in order to convert the heading data provided by the ardusimple gps-rtk to a sensor_msgs/Imu type. Do you need also this code? I will upload also the configuration and launch files.

tseco gravatar image tseco  ( 2020-05-04 03:42:28 -0500 )edit

I won't get the cycles to replay bags and review code, I'm afraid, so if you could just paste a single sample input message from every sensor in the question, we'll go from there. Thanks.

Tom Moore gravatar image Tom Moore  ( 2020-05-04 04:32:09 -0500 )edit

I have just added some samples for the sensors.

tseco gravatar image tseco  ( 2020-05-04 06:39:17 -0500 )edit

Hi Tom, did you have the chance to have a look to the data? Thanks in advance!

tseco gravatar image tseco  ( 2020-05-13 05:13:48 -0500 )edit

Edited the question and added the required info. This is not a thread format, so you should just update your question, rather than posting answers. Also, I was just looking for one sensor message per sensor, so I fixed that, too.

Tom Moore gravatar image Tom Moore  ( 2020-05-19 02:49:00 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2020-05-19 03:01:16 -0500

Tom Moore gravatar image

From what you described, the issue is that you are feeding the wrong odometry topic to navsat_transform_node. Here's how it should look:

EKF 1 (odom frame)

Inputs: /imu/data, /odom

Outputs: /odometry/filtered, odom->base_link transform

EKF 2 (map frame)

Inputs: /imu/data, /odom, /odometry/gps

Outputs: odometry/filtered_gps, map->odom transform

navsat_transform_node

Inputs: /imu/data/gps, /ublox_gps_rover/fix, odometry/filtered_gps <-- You need this

Outputs: /odometry/gps

Your issue (or at least one issue that I see) is that you are missing a remap in your navsat_transform_node launch:

<remap from="/odometry/filtered" to="/odometry/filtered_gps" />

edit flag offensive delete link more

Comments

Thank you very much Tom. This remap solved one of my issues.

tseco gravatar image tseco  ( 2020-06-10 01:58:04 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2020-03-24 08:45:14 -0500

Seen: 772 times

Last updated: May 19 '20