robot_localization and navsat_transform_node results
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)
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 ...
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!Please post sample input messages from every sensor.
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].
In what frame are you visualizing data in
rviz
? Remember that the "local" odom data is going to get transformed to the map frame byrviz
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.I'm using the "map frame" as "Fixed Frame" in RVIZ.
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.
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?Oh! You are visualizing the wrong thing for the "local" data. You are visualizing the Husky raw odometry. Visualize the
/odometry/filtered/local
data.