Synchronizing visual odometry with RTK GPS

classic Classic list List threaded Threaded
2 messages Options
Reply | Threaded
Open this post in threaded view
|

Synchronizing visual odometry with RTK GPS

vasimv
I'm trying to use visual odometry on lawnmower robot. Problem is the robot often drives over quite open field without close obstacles to navigate with only visual. There are some very far objects that visual odometry uses but quality is very poor and sometimes loses it completely.

I have RTK GPS on the robot with 2 cm accuracy, so i could use it to feed really good coordinates to the odometry but the RTK loses its fix when robot drives under trees and close to walls (right where visual odometry could be used).

So, my question - it is possible to "reset" visual odometry with coordinates from RTK and IMU while it is possible and use only visual when there aren't? robot_localization seems doing some strange stuff, not exactly what i want. I just need to work with RTK GPS as priority source of navigation with visual as backup.

As i see, visual odometry do listen for "guess_frame_id", "ground_truth_frame_id" and "ground_truth_base_frame_id" transformations and it looks like i could use these. But sending transformations with coordinates from RTK (translated to utm of course) to them seems doing wrong stuff and i see no good explanation on these in documentation. Could someone help me with understanding these parameters?
Reply | Threaded
Open this post in threaded view
|

Re: Synchronizing visual odometry with RTK GPS

matlabbe
Administrator
Hi,

It is possible to reset odometry at a specific pose with service /rtabmap/reset_odom_to_pose.

With robot_localization, I think you could use RTK+IMU as position estimation and visual odometry as velocity estimation. When RTK is not available, the pose will be computed from visual odometry velocities. For visual odometry node, you may set publish_null_when_lost to false so that when odometry is lost nothing is published. Set also Odom/ResetCountdown to 1 so that visual odometry is automatically reset when lost. publish_tf should be false with robot_localization.
<node pkg="rtabmap_ros" type="stereo_odometry" name="visual_odometry">
   ...
  <param name="publish_null_when_lost" value="false"/>
  <param name="publish_tf" value="false"/>
  <param name="Odom/ResetCountdown" value="1"/>
</node>


<node pkg="robot_localization" type="ekf_localization_node" name="ekf_localization">
   ...
      <!-- position from GPS... -->
   <param name="odom0" value="/your_state_estimation_gps_node_topic">
   <rosparam param="odom0_config">[true,  true,  false,
                                false, false, false,
                                false, false, false,
                                false, false, false,
                                false, false, false]</rosparam>
   <param name="odom0_differential" value="false"/>

   <!-- velocity for odometry... -->
   <param name="odom1" value="/rtabmap/odom">
   <rosparam param="odom1_config">[false, false, false,
                                      true, true, true,
                                      false, false, false,
                                      true, true, true,
                                      false, false, false]</rosparam>
   <param name="odom1_differential" value="true"/>
</node>

See http://docs.ros.org/melodic/api/robot_localization/html/integrating_gps.html for node publishing the GPS odometry.

ground_truth_frame_id and ground_truth_base_frame_id parameters are only used to initialize odometry with corresponding ground truth pose. For guess_frame_id, the guess frame id should be always valid, mainly used if the robot has wheel odometry.

cheers,
Mathieu