Skip to content

Commit 05c76c5

Browse files
Feat/update gps tutorial (#32)
* Gps navigation Tutorial update Signed-off-by: Stevedan Omodolor <[email protected]> * revert back Signed-off-by: Stevedan Omodolor <[email protected]> --------- Signed-off-by: Stevedan Omodolor <[email protected]>
1 parent 12577c6 commit 05c76c5

File tree

1 file changed

+11
-0
lines changed

1 file changed

+11
-0
lines changed

nav2_minimal_tb3_sim/urdf/gz_waffle_gps.sdf.xacro

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -105,6 +105,8 @@
105105
<navsat>
106106
<position_sensing>
107107
<horizontal>
108+
<!-- Be carefull setting this.
109+
Units in degree not in meters https://github.com/gazebosim/sdformat/issues/1572 -->
108110
<noise type="gaussian">
109111
<mean>0.0</mean>
110112
<stddev>0.0</stddev>
@@ -496,10 +498,14 @@
496498
<plugin
497499
filename="gz-sim-diff-drive-system"
498500
name="gz::sim::systems::DiffDrive">
501+
502+
<!-- wheel information -->
499503
<left_joint>wheel_left_joint</left_joint>
500504
<right_joint>wheel_right_joint</right_joint>
501505
<wheel_separation>0.287</wheel_separation>
502506
<wheel_radius>0.033</wheel_radius>
507+
508+
<!-- limits -->
503509
<max_linear_acceleration>1</max_linear_acceleration>
504510
<min_linear_acceleration>-1</min_linear_acceleration>
505511
<max_angular_acceleration>2</max_angular_acceleration>
@@ -508,12 +514,17 @@
508514
<min_linear_velocity>-0.46</min_linear_velocity>
509515
<max_angular_velocity>1.9</max_angular_velocity>
510516
<min_angular_velocity>-1.9</min_angular_velocity>
517+
518+
<!-- input -->
511519
<topic>$(arg namespace)/cmd_vel</topic>
520+
521+
<!-- output -->
512522
<odom_topic>$(arg namespace)/odom</odom_topic>
513523
<tf_topic>$(arg namespace)/tf</tf_topic>
514524
<frame_id>odom</frame_id>
515525
<child_frame_id>base_footprint</child_frame_id>
516526
<odom_publish_frequency>30</odom_publish_frequency>
527+
517528
</plugin>
518529

519530
<plugin

0 commit comments

Comments
 (0)