Skip to content

Commit

Permalink
Update rtabmap.launch
Browse files Browse the repository at this point in the history
  • Loading branch information
matlabbe authored Oct 5, 2021
1 parent 1ecce15 commit 06c2933
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions launch/rtabmap.launch
Original file line number Diff line number Diff line change
Expand Up @@ -110,8 +110,8 @@
<arg name="odom_topic" default="odom"/> <!-- Odometry topic name -->
<arg name="vo_frame_id" default="$(arg odom_topic)"/> <!-- Visual/Icp odometry frame ID for TF -->
<arg name="publish_tf_odom" default="true"/>
<arg name="odom_tf_angular_variance" default="1"/> <!-- If TF is used to get odometry, this is the default angular variance -->
<arg name="odom_tf_linear_variance" default="1"/> <!-- If TF is used to get odometry, this is the default linear variance -->
<arg name="odom_tf_angular_variance" default="0.001"/> <!-- If TF is used to get odometry, this is the default angular variance -->
<arg name="odom_tf_linear_variance" default="0.001"/> <!-- If TF is used to get odometry, this is the default linear variance -->
<arg name="odom_args" default=""/> <!-- More arguments for odometry (overwrite same parameters in rtabmap_args) -->
<arg name="odom_sensor_sync" default="false"/>
<arg name="odom_guess_frame_id" default=""/>
Expand Down

0 comments on commit 06c2933

Please sign in to comment.