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

robot_localization and navsat_transform_node results

asked 2017-12-23 13:20:40 -0500

Marcus Barnet gravatar image

updated 2018-01-29 02:48:44 -0500

Hi to all, Hi Tom,

I'm using robot_localization and the navsat_transform_node to obtain the 3D position of my mobile robot. I'm using XSens IMU Mti-300 with magnetometer, a SICK laser, Husky A200 and C94-MP8 U-blox GPS with RTK correction.

The node runs fine and I receive no errors, but when I try to run the bag in RVIZ, I see that there are lot of jumps and that even the /odometry/filtered/local (blue arrows) is not accurate even if the robot is moving on a straight line.

In this bag file [16MB], the robot is moving on a straight line and as you can see the path is not accurate.

(The steering maneuver at the end is correct)

image description


image description

I think that the jumps on /odometry/gps (red arrows) and /odometry/filtered/global (green arrows) are caused by the GPS (it is in FIXED mode, but may be sometimes it loses the signal with the base station), but I can't explain why the /odometry/filtered/local is not accurate.

Can you give me some suggestions, please?

it is possible to set a priority on /odometry/filtered/local to obtain more accurate results with the GPS signal is not good?

This is my launch file:

<!-- Test launch file for two EKF instances and one navsat_transform instance -->

<launch>

 <rosparam command="load" file="$(find husky_control)/config/control.yaml" />

  <node name="base_controller_spawner" pkg="controller_manager" type="spawner" args="husky_joint_publisher husky_velocity_controller --shutdown-timeout 3"/>



 <node pkg="rosbag" type="play" name="rosbag_play" output="screen" args="--clock /home/rocco/Desktop/gps/vine.bag -k -d 3"/>      


  <node pkg="tf2_ros" type="static_transform_publisher" name="bl_imu" args="0 0 0 0 0 0 base_link base_imu" />
  <node pkg="tf2_ros" type="static_transform_publisher" name="bl_gps" args="0 0 0.4 0 0 0 base_link gps" /> 
  <node pkg="tf2_ros" type="static_transform_publisher" name="bl_laser" args="0 0 0.4 0 0 0 base_link laser" /> 
  <node pkg="tf2_ros" type="static_transform_publisher"  name="base_to_realsense" args="0 0 0 -1.5707963 0 -1.5707963 base_link realsense_frame" />

    <!-- Local (odom) instance -->
    <node pkg="robot_localization" type="ekf_localization_node" name="ekf_localization_local" clear_params="true">
      <param name="frequency" value="10"/>
      <param name="sensor_timeout" value="0.1"/>
      <param name="two_d_mode" value="false"/>

      <param name="map_frame" value="map"/>
      <param name="odom_frame" value="odom"/>
      <param name="base_link_frame" value="base_link"/>
      <param name="world_frame" value="odom"/>

      <param name="transform_time_offset" value="0.0"/>

      <param name="odom0" value="/husky_velocity_controller/odom"/>
      <param name="imu0" value="/imu/data"/>

      <rosparam param="odom0_config">[false, false, false,
                                      false, false, false,
                                      true, true, true,
                                      false, false, true,
                                      false, false, false]</rosparam>

      <rosparam param="imu0_config">[false, false, false,
                                     true,  true,  true,
                                     false, false, false,
                                     true,  true,  true,
                                     true,  true,  true]</rosparam>

      <param name="odom0_differential" value="false"/>
      <param name="imu0_differential" value="false"/>

      <param name="odom0_relative" value="false"/>
      <param name="imu0_relative" value="false"/>

      <param name="imu0_remove_gravitational_acceleration" value="true"/>
      <param name="print_diagnostics" value="true"/>

      <param name="odom0_queue_size" value="10"/>
      <param name="imu0_queue_size" value="10"/>

      <param name="debug"           value="false"/>
      <param name="debug_out_file"  value="debug_ekf_localization.txt"/>

      <remap from="/odometry/filtered" to="/odometry/filtered/local"/>
    </node>

    <!-- Global (map) instance -->
    <node pkg="robot_localization" type="ekf_localization_node ...
(more)
edit retag flag offensive close merge delete

Comments

UPDATE: I tried to play the bag without the /ublox_gps/fix topic and the path is more accurate even if there are still some strange jumps mostly during steering!

Marcus Barnet gravatar image Marcus Barnet  ( 2017-12-23 13:51:26 -0500 )edit
1

Please post sample input messages from every sensor.

Tom Moore gravatar image Tom Moore  ( 2018-01-26 03:03:24 -0500 )edit

Thank you, Tom! I edited my main question by adding the input from the IMU, the GPS and the odometry topic. The samples come from this bag file [16MB].

Marcus Barnet gravatar image Marcus Barnet  ( 2018-01-26 03:25:11 -0500 )edit
1

In what frame are you visualizing data in rviz? Remember that the "local" odom data is going to get transformed to the map frame by rviz before it gets displayed. This accounts for the jumpiness, but it doesn't account for the fact that they are not perfectly overlaid on each other.

Tom Moore gravatar image Tom Moore  ( 2018-01-26 03:31:40 -0500 )edit

I'm using the "map frame" as "Fixed Frame" in RVIZ.

Marcus Barnet gravatar image Marcus Barnet  ( 2018-01-26 03:44:23 -0500 )edit

I uploaded a short video about the first seconds of the test in RVIZ. It's very strange that the points are not aligned since the robot is only moving straight forward.

Marcus Barnet gravatar image Marcus Barnet  ( 2018-01-26 03:51:00 -0500 )edit
1

Can you add one sample output message for each? Also, try visualizing with the fixed_frame as odom. You should at least see the odom data no jump around. You're not manually publishing the map->odom transform somewhere, are you?

Tom Moore gravatar image Tom Moore  ( 2018-01-26 03:54:20 -0500 )edit

Oh! You are visualizing the wrong thing for the "local" data. You are visualizing the Husky raw odometry. Visualize the /odometry/filtered/local data.

Tom Moore gravatar image Tom Moore  ( 2018-01-26 04:00:31 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
3

answered 2018-01-26 04:08:13 -0500

Tom Moore gravatar image

updated 2018-01-29 03:00:39 -0500

You are visualizing the wrong topic for the "local" data. Here's what I see when I visualize /odometry/filtered/local (green), /odometry/filtered/global (red), and /odometry/gps (blue):

rviz fixed_frame == map:

image description

rviz fixed_frame == odom:

image description

Both of those look completely correct to me. Your GPS is a bit noisy, but that's normal.

EDIT in response to comments:

From the wiki:

image description

Visualization of raw GPS tracks:

image description

EDIT 2 after more analysis:

I figured out why it's so much more jittery. You need to get rid of the 0.4 value for Z in your bl_gps static transform:

 <node pkg="tf2_ros" type="static_transform_publisher" name="bl_gps" args="0 0 0.0 0 0 0 base_link gps" />

image description

That's a bug; I'll file a ticket. Thanks for the report!

Even with that fix, though, the direction of travel doesn't quite match the GPS. The robot has a tiny bit of lateral motion, which suggests something is not right with your IMU heading or the declination parameter.

EDIT 3 to answer more questions:

So you're saying the path is more accurate/in line with the GPS readings when you use the negative declination value (-0.0684)? If so, yes, that makes sense, and it's what I suggested in the comments. Your deviation from "true north" is 0.0684 radians clockwise:

image description

Clockwise rotation in an ENU frame is negative, hence the -0.0684 declination value. I realize r_l uses different standards than geographic services, but it's just so that the nodes handle rotations consistently.

edit flag offensive delete link more

Comments

Thank you for your answer! I can't understand why the data are correct. I drive the robot along a straight line and so I expect to see a straight line like it happens when you set the odom as fixed frame. When I set the map as the fixed frame, I can't understand why the points drift on the left

Marcus Barnet gravatar image Marcus Barnet  ( 2018-01-26 10:39:46 -0500 )edit

Both local and global coordinates are coincident, but they drift and jump randomly. Why do you consider these data as correct? Shouldn't I see a straight line like it happens in the odom frame?

Marcus Barnet gravatar image Marcus Barnet  ( 2018-01-26 10:41:46 -0500 )edit
1

No, they are correct. The blue arrows are your GPS readings, and the filter is just updating itself accordingly. If you plot your raw GPS data using a tool like http://www.gpsvisualizer.com/ or the mapviz package, you will see that the raw GPS data jumps around in the exact manner you see.

Tom Moore gravatar image Tom Moore  ( 2018-01-26 10:44:19 -0500 )edit
1

Having said that, the navsat_transform_node output is a lot noisier than I'd expect. I'll look into it.

Tom Moore gravatar image Tom Moore  ( 2018-01-26 11:00:49 -0500 )edit

Yes, the GPS is not very accurate, but it does not have all the jumps as showed in RVIZ by the navsat_transform_node. I can't explain why since I was expecting to see only few jumps when the GPS module loses the fixed position.

Marcus Barnet gravatar image Marcus Barnet  ( 2018-01-26 11:04:55 -0500 )edit

How was you able to draw the GPS path so fast? When I use http://www.gpsvisualizer.com/ , I always need to manually copy only few GPS data in a TXT file and then upload it on the website. Is there any faster way to do that?

Marcus Barnet gravatar image Marcus Barnet  ( 2018-01-26 11:05:51 -0500 )edit

rostopic echo gps_topic -p > out.txt, then edit the column headers for latitude and longitude to get rid of the field. bit, then upload. Really, we should use something like mapviz instead.

Tom Moore gravatar image Tom Moore  ( 2018-01-26 11:07:09 -0500 )edit

But I concede that the output of navsat_transform_node is not very good. I'll look into it.

Tom Moore gravatar image Tom Moore  ( 2018-01-26 11:07:37 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2017-12-23 13:20:40 -0500

Seen: 2,313 times

Last updated: Jan 29 '18