Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fixes bug with odometry. #37

Merged
merged 1 commit into from
Apr 24, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 5 additions & 5 deletions andino_gz/config/bridge_config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
gz_type_name: "gz.msgs.Clock"
direction: GZ_TO_ROS
- ros_topic_name: "/odom"
gz_topic_name: "/odom"
gz_topic_name: "/model/andino/odometry"
ros_type_name: "nav_msgs/msg/Odometry"
gz_type_name: "gz.msgs.Odometry"
direction: GZ_TO_ROS
Expand All @@ -14,22 +14,22 @@
gz_type_name: "gz.msgs.Pose_V"
direction: GZ_TO_ROS
- ros_topic_name: "/camera_info"
gz_topic_name: "/camera_info"
gz_topic_name: "/world/gazebo_world/model/andino/link/base_link/sensor/camera/camera_info"
ros_type_name: "sensor_msgs/msg/CameraInfo"
gz_type_name: "gz.msgs.CameraInfo"
direction: GZ_TO_ROS
- ros_topic_name: "/image_raw"
gz_topic_name: "/image_raw"
gz_topic_name: "/world/gazebo_world/model/andino/link/base_link/sensor/camera/image"
ros_type_name: "sensor_msgs/msg/Image"
gz_type_name: "gz.msgs.Image"
direction: GZ_TO_ROS
- ros_topic_name: "/scan"
gz_topic_name: "/scan"
gz_topic_name: "/world/gazebo_world/model/andino/link/base_link/sensor/sensor_ray_front/scan"
ros_type_name: "sensor_msgs/msg/LaserScan"
gz_type_name: "gz.msgs.LaserScan"
direction: GZ_TO_ROS
- ros_topic_name: "/scan/points"
gz_topic_name: "/scan/points"
gz_topic_name: "/world/gazebo_world/model/andino/link/base_link/sensor/sensor_ray_front/scan/points"
ros_type_name: "sensor_msgs/msg/PointCloud2"
gz_type_name: "gz.msgs.PointCloudPacked"
direction: GZ_TO_ROS
Expand Down
7 changes: 3 additions & 4 deletions andino_gz/urdf/andino_gz.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -6,12 +6,14 @@
<gazebo>
<plugin
filename="ignition-gazebo-diff-drive-system"
name="ignition::gazebo::systems::DiffDrive">
name="ignition::gazebo::systems::DiffDrive">
<left_joint>left_wheel_joint</left_joint>
<right_joint>right_wheel_joint</right_joint>
<wheel_separation>0.137</wheel_separation>
<wheel_radius>0.0175</wheel_radius>
<odom_publish_frequency>1</odom_publish_frequency>
<frame_id>odom</frame_id>
<child_frame_id>base_link</child_frame_id>
</plugin>
</gazebo>

Expand All @@ -37,7 +39,6 @@
<stddev>0.01</stddev>
</noise>
</ray>
<topic>scan</topic>
<always_on>true</always_on>
<visualize>true</visualize>
<update_rate>20.0</update_rate>
Expand Down Expand Up @@ -70,8 +71,6 @@
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>true</visualize>
<topic>image_raw</topic>
<camera_info_topic>camera_info</camera_info_topic>
</sensor>
</gazebo>

Expand Down
2 changes: 1 addition & 1 deletion andino_gz/worlds/depot.sdf
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version='1.0' encoding='ASCII'?>
<sdf version='1.7'>
<!-- Model taken from https://app.gazebosim.org/Fahadalbahoth/fuel/worlds/tugbot_depot -->
<world name='world_demo'>
<world name='gazebo_world'>
<physics name='1ms' type='ignored'>
<max_step_size>0.01</max_step_size>
<real_time_factor>1</real_time_factor>
Expand Down
2 changes: 1 addition & 1 deletion andino_gz/worlds/empty.sdf
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<?xml version='1.0' encoding='ASCII'?>
<sdf version='1.7'>
<world name='empty'>
<world name='gazebo_world'>
<physics name='1ms' type='ignored'>
<max_step_size>0.01</max_step_size>
<real_time_factor>1</real_time_factor>
Expand Down
Loading