Skip to content

Commit 6ac3ae4

Browse files
Gps navigation Tutorial update
Signed-off-by: Stevedan Omodolor <[email protected]>
1 parent 12577c6 commit 6ac3ae4

File tree

2 files changed

+23
-6
lines changed

2 files changed

+23
-6
lines changed

nav2_minimal_tb3_sim/configs/turtlebot3_waffle_gps_bridge.yaml

Lines changed: 12 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -1,11 +1,13 @@
11
# replace clock_bridge
2-
- topic_name: "/clock"
2+
- ros_topic_name: "/clock"
3+
gz_topic_name: "/clock"
34
ros_type_name: "rosgraph_msgs/msg/Clock"
45
gz_type_name: "gz.msgs.Clock"
56
direction: GZ_TO_ROS
67

78
# no equivalent in TB3 - add
8-
- topic_name: "joint_states"
9+
- ros_topic_name: "joint_states"
10+
gz_topic_name: "joint_states"
911
ros_type_name: "sensor_msgs/msg/JointState"
1012
gz_type_name: "gz.msgs.Model"
1113
direction: GZ_TO_ROS
@@ -20,25 +22,29 @@
2022
# replace odom_tf_bridge - check gz and ros topic names
2123
# gz topic published by DiffDrive plugin
2224
# prefix ros2 topic with gz
23-
- topic_name: "tf"
25+
- ros_topic_name: "tf"
26+
gz_topic_name: "/tf"
2427
ros_type_name: "tf2_msgs/msg/TFMessage"
2528
gz_type_name: "gz.msgs.Pose_V"
2629
direction: GZ_TO_ROS
2730

2831
# replace imu_bridge - check gz topic name
29-
- topic_name: "imu/data"
32+
- ros_topic_name: "imu/data"
33+
gz_topic_name: "/imu/data"
3034
ros_type_name: "sensor_msgs/msg/Imu"
3135
gz_type_name: "gz.msgs.IMU"
3236
direction: GZ_TO_ROS
3337

3438
# replace lidar_bridge
35-
- topic_name: "scan"
39+
- ros_topic_name: "scan"
40+
gz_topic_name: "/scan"
3641
ros_type_name: "sensor_msgs/msg/LaserScan"
3742
gz_type_name: "gz.msgs.LaserScan"
3843
direction: GZ_TO_ROS
3944

4045
# replace cmd_vel_bridge
41-
- topic_name: "cmd_vel"
46+
- ros_topic_name: "cmd_vel"
47+
gz_topic_name: "/cmd_vel"
4248
ros_type_name: "geometry_msgs/msg/TwistStamped"
4349
gz_type_name: "gz.msgs.Twist"
4450
direction: ROS_TO_GZ

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)