Skip to content

Commit b7de5ce

Browse files
Update sam_bot_description for the new Gazebo (#102)
* Update DiffDrive, and IMU for new Gazebo Update nav2_params.yaml Update to use stamped twist messages Add SDF description Signed-off-by: Aarav Gupta <[email protected]> * Add plugins to world file Signed-off-by: Aarav Gupta <[email protected]> * Fix/Update sensors and add them to SDF also Signed-off-by: Aarav Gupta <[email protected]> * Update robot footprint Signed-off-by: Aarav Gupta <[email protected]> * Update imu_sensor frame_id Signed-off-by: Aarav Gupta <[email protected]> * Make caster close to frictionless Signed-off-by: Aarav Gupta <[email protected]> * Implement review comments Signed-off-by: Aarav Gupta <[email protected]> * Add argument for using ekf Signed-off-by: Aarav Gupta <[email protected]> * Some fixes Signed-off-by: Aarav Gupta <[email protected]> * Update sam_bot_description/launch/display.launch.py Co-authored-by: Steve Macenski <[email protected]> Signed-off-by: Aarav Gupta <[email protected]> * Add needed dependencies to package.xml Signed-off-by: Aarav Gupta <[email protected]> * Rename urdf_config.rviz to config.rviz Signed-off-by: Aarav Gupta <[email protected]> * Small argument description fix Signed-off-by: Aarav Gupta <[email protected]> * Fix ekf config Signed-off-by: Aarav Gupta <[email protected]> * Remove Gazebo specific things from URDF Signed-off-by: Aarav Gupta <[email protected]> * Implement review comments Signed-off-by: Aarav Gupta <[email protected]> * Small code style fix Signed-off-by: Aarav Gupta <[email protected]> --------- Signed-off-by: Aarav Gupta <[email protected]> Co-authored-by: Steve Macenski <[email protected]>
1 parent b7c4a71 commit b7de5ce

File tree

9 files changed

+849
-370
lines changed

9 files changed

+849
-370
lines changed
Lines changed: 57 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,57 @@
1+
---
2+
- ros_topic_name: "/clock"
3+
gz_topic_name: "/clock"
4+
ros_type_name: "rosgraph_msgs/msg/Clock"
5+
gz_type_name: "gz.msgs.Clock"
6+
direction: GZ_TO_ROS
7+
8+
- ros_topic_name: "/demo/imu"
9+
gz_topic_name: "/demo/imu"
10+
ros_type_name: "sensor_msgs/msg/Imu"
11+
gz_type_name: "gz.msgs.IMU"
12+
direction: GZ_TO_ROS
13+
14+
# Topic published by DiffDrive plugin
15+
- ros_topic_name: "/demo/odom"
16+
gz_topic_name: "/demo/odom"
17+
ros_type_name: "nav_msgs/msg/Odometry"
18+
gz_type_name: "gz.msgs.Odometry"
19+
direction: GZ_TO_ROS
20+
21+
# Topic published by JointStatePublisher plugin
22+
- ros_topic_name: "/joint_states"
23+
gz_topic_name: "/joint_states"
24+
ros_type_name: "sensor_msgs/msg/JointState"
25+
gz_type_name: "gz.msgs.Model"
26+
direction: GZ_TO_ROS
27+
28+
# Topic subscribed to by DiffDrive plugin
29+
- ros_topic_name: "/demo/cmd_vel"
30+
gz_topic_name: "/demo/cmd_vel"
31+
ros_type_name: "geometry_msgs/msg/TwistStamped"
32+
gz_type_name: "gz.msgs.Twist"
33+
direction: ROS_TO_GZ
34+
35+
- ros_topic_name: "/scan"
36+
gz_topic_name: "/scan"
37+
ros_type_name: "sensor_msgs/msg/LaserScan"
38+
gz_type_name: "gz.msgs.LaserScan"
39+
direction: GZ_TO_ROS
40+
41+
- ros_topic_name: "/scan/points"
42+
gz_topic_name: "/scan/points"
43+
ros_type_name: "sensor_msgs/msg/PointCloud2"
44+
gz_type_name: "gz.msgs.PointCloudPacked"
45+
direction: GZ_TO_ROS
46+
47+
- ros_topic_name: "/depth_camera/camera_info"
48+
gz_topic_name: "/depth_camera/camera_info"
49+
ros_type_name: "sensor_msgs/msg/CameraInfo"
50+
gz_type_name: "gz.msgs.CameraInfo"
51+
direction: GZ_TO_ROS
52+
53+
- ros_topic_name: "/depth_camera/points"
54+
gz_topic_name: "/depth_camera/points"
55+
ros_type_name: "sensor_msgs/msg/PointCloud2"
56+
gz_type_name: "gz.msgs.PointCloudPacked"
57+
direction: GZ_TO_ROS

sam_bot_description/config/ekf.yaml

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
### ekf config file ###
2-
ekf_filter_node:
2+
ekf_node:
33
ros__parameters:
44
# The frequency, in Hz, at which the filter will output a position estimate. Note that the filter will not begin
55
# computation until it receives at least one message from one of the inputs. It will then run continuously at the
@@ -33,15 +33,15 @@ ekf_filter_node:
3333
world_frame: odom # Defaults to the value of odom_frame if unspecified
3434

3535
odom0: demo/odom
36-
odom0_config: [true, true, true,
37-
false, false, false,
36+
odom0_config: [false, false, false,
3837
false, false, false,
38+
true, true, false,
3939
false, false, true,
4040
false, false, false]
4141

4242
imu0: demo/imu
4343
imu0_config: [false, false, false,
44-
true, true, true,
4544
false, false, false,
4645
false, false, false,
46+
false, false, true,
4747
false, false, false]

0 commit comments

Comments
 (0)