From 4a3db5cb2af7c13beaea161b9df3a53f1c6e559f Mon Sep 17 00:00:00 2001 From: Jakub Delicat Date: Tue, 5 Dec 2023 15:36:20 +0100 Subject: [PATCH] fixed clock | added camera Signed-off-by: Jakub Delicat --- rosbot_description/urdf/rosbot.urdf.xacro | 3 ++- rosbot_gazebo/config/gz_remappings.yaml | 9 ++++---- rosbot_gazebo/launch/spawn.launch.py | 27 ----------------------- 3 files changed, 7 insertions(+), 32 deletions(-) diff --git a/rosbot_description/urdf/rosbot.urdf.xacro b/rosbot_description/urdf/rosbot.urdf.xacro index 0437a355..2af6796f 100644 --- a/rosbot_description/urdf/rosbot.urdf.xacro +++ b/rosbot_description/urdf/rosbot.urdf.xacro @@ -31,6 +31,7 @@ parent_link="camera_link" xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" + namespace="$(arg namespace)" simulation_engine="$(arg simulation_engine)" /> - + diff --git a/rosbot_gazebo/config/gz_remappings.yaml b/rosbot_gazebo/config/gz_remappings.yaml index ae2790ac..6f7a6730 100644 --- a/rosbot_gazebo/config/gz_remappings.yaml +++ b/rosbot_gazebo/config/gz_remappings.yaml @@ -1,3 +1,8 @@ +- topic_name: "/clock" + ros_type_name: "rosgraph_msgs/msg/Clock" + gz_type_name: "ignition.msgs.Clock" + direction: GZ_TO_ROS + - topic_name: "/scan" ros_type_name: "sensor_msgs/msg/LaserScan" gz_type_name: "ignition.msgs.LaserScan" @@ -18,10 +23,6 @@ ros_type_name: "sensor_msgs/msg/PointCloud2" gz_type_name: "ignition.msgs.PointCloudPacked" -- topic_name: "/clock" - ros_type_name: "rosgraph_msgs/msg/Clock" - gz_type_name: "ignition.msgs.Clock" - - topic_name: "/range/fl" ros_type_name: "sensor_msgs/msg/LaserScan" gz_type_name: "ignition.msgs.LaserScan" diff --git a/rosbot_gazebo/launch/spawn.launch.py b/rosbot_gazebo/launch/spawn.launch.py index e65e92eb..e2efc611 100644 --- a/rosbot_gazebo/launch/spawn.launch.py +++ b/rosbot_gazebo/launch/spawn.launch.py @@ -133,32 +133,6 @@ def generate_launch_description(): }.items(), ) - # The frame of the pointcloud from ignition gazebo 6 isn't provided by . - # See https://github.com/gazebosim/gz-sensors/issues/239 - depth_cam_frame_fixer = Node( - package="tf2_ros", - executable="static_transform_publisher", - name="depth_to_camera", - output="log", - arguments=[ - "0.0", - "0.0", - "0.0", - "1.57", - "-1.57", - "0.0", - "camera_depth_optical_frame", - LaunchConfiguration( - "gazebo_frame", default=[robot_name, "/base_link/camera_orbbec_astra_camera"] - ), - ], - remappings=[ - ("/tf", "tf"), - ("/tf_static", "tf_static"), - ], - namespace=namespace, - ) - return LaunchDescription( [ declare_namespace_arg, @@ -171,6 +145,5 @@ def generate_launch_description(): ign_bridge, gz_spawn_entity, bringup_launch, - depth_cam_frame_fixer, ] )