Skip to content
Snippets Groups Projects
Commit c0f73dde authored by Mikael Arguedas's avatar Mikael Arguedas Committed by Carl Delsey
Browse files

[eloquent] use remapping tag in urdf/sdf (#1449)


Signed-off-by: default avatarMikael Arguedas <mikael.arguedas@gmail.com>
parent 124663a8
No related branches found
No related tags found
No related merge requests found
......@@ -139,9 +139,7 @@
<plugin name="turtlebot3_imu" filename="libgazebo_ros_imu_sensor.so">
<ros>
<!-- <namespace>/tb3</namespace> -->
<argument>--ros-args</argument>
<argument>-r</argument>
<argument>~/out:=imu</argument>
<remapping>~/out:=imu</remapping>
</ros>
</plugin>
</sensor>
......@@ -209,9 +207,7 @@
<plugin name="turtlebot3_laserscan" filename="libgazebo_ros_ray_sensor.so">
<ros>
<!-- <namespace>/tb3</namespace> -->
<argument>--ros-args</argument>
<argument>-r </argument>
<argument>~/out:=scan</argument>
<remapping>~/out:=scan</remapping>
</ros>
<output_type>sensor_msgs/LaserScan</output_type>
<frame_name>base_scan</frame_name>
......@@ -552,9 +548,7 @@
<plugin name="turtlebot3_joint_state" filename="libgazebo_ros_joint_state_publisher.so">
<ros>
<!-- <namespace>/tb3</namespace> -->
<argument>--ros-args</argument>
<argument>-r </argument>
<argument>~/out:=joint_states</argument>
<remapping>~/out:=joint_states</remapping>
</ros>
<update_rate>30</update_rate>
<joint_name>wheel_left_joint</joint_name>
......
......@@ -89,7 +89,7 @@
<plugin name="turtlebot3_imu" filename="libgazebo_ros_imu_sensor.so">
<ros>
<!-- <namespace>/tb3</namespace> -->
<argument>~/out:=imu</argument>
<remapping>~/out:=imu</remapping>
</ros>
</plugin>
</sensor>
......@@ -157,7 +157,7 @@
<plugin name="turtlebot3_laserscan" filename="libgazebo_ros_ray_sensor.so">
<ros>
<!-- <namespace>/tb3</namespace> -->
<argument>~/out:=scan</argument>
<remapping>~/out:=scan</remapping>
</ros>
<output_type>sensor_msgs/LaserScan</output_type>
<frame_name>base_scan</frame_name>
......@@ -401,8 +401,8 @@
<plugin name="camera_driver" filename="libgazebo_ros_camera.so">
<ros>
<!-- <namespace>test_cam</namespace> -->
<!-- <argument>image_raw:=image_demo</argument> -->
<!-- <argument>camera_info:=camera_info_demo</argument> -->
<!-- <remapping>image_raw:=image_demo</remapping> -->
<!-- <remapping>camera_info:=camera_info_demo</remapping> -->
</ros>
<!-- camera_name>omit so it defaults to sensor name</camera_name-->
<!-- frame_name>omit so it defaults to link name</frameName-->
......@@ -508,7 +508,7 @@
<plugin name="turtlebot3_joint_state" filename="libgazebo_ros_joint_state_publisher.so">
<ros>
<!-- <namespace>/tb3</namespace> -->
<argument>~/out:=joint_states</argument>
<remapping>~/out:=joint_states</remapping>
</ros>
<update_rate>30</update_rate>
<joint_name>wheel_left_joint</joint_name>
......
......@@ -89,7 +89,7 @@
<plugin name="turtlebot3_imu" filename="libgazebo_ros_imu_sensor.so">
<ros>
<!-- <namespace>/tb3</namespace> -->
<argument>~/out:=imu</argument>
<remapping>~/out:=imu</remapping>
</ros>
</plugin>
</sensor>
......@@ -157,7 +157,7 @@
<plugin name="turtlebot3_laserscan" filename="libgazebo_ros_ray_sensor.so">
<ros>
<!-- <namespace>/tb3</namespace> -->
<argument>~/out:=scan</argument>
<remapping>~/out:=scan</remapping>
</ros>
<output_type>sensor_msgs/LaserScan</output_type>
<frame_name>base_scan</frame_name>
......@@ -401,8 +401,8 @@
<plugin name="camera_driver" filename="libgazebo_ros_camera.so">
<ros>
<!-- <namespace>test_cam</namespace> -->
<!-- <argument>image_raw:=image_demo</argument> -->
<!-- <argument>camera_info:=camera_info_demo</argument> -->
<!-- <remapping>image_raw:=image_demo</remapping> -->
<!-- <remapping>camera_info:=camera_info_demo</remapping> -->
</ros>
<!-- camera_name>omit so it defaults to sensor name</camera_name-->
<!-- frame_name>omit so it defaults to link name</frameName-->
......@@ -508,7 +508,7 @@
<plugin name="turtlebot3_joint_state" filename="libgazebo_ros_joint_state_publisher.so">
<ros>
<!-- <namespace>/tb3</namespace> -->
<argument>~/out:=joint_states</argument>
<remapping>~/out:=joint_states</remapping>
</ros>
<update_rate>30</update_rate>
<joint_name>wheel_left_joint</joint_name>
......
<?xml version="1.0" ?>
<sdf version="1.5">
<model name="TurtleBot3_Waffle_DepthCamera">
<model name="TurtleBot3_Waffle_DepthCamera">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<link name="base_footprint"/>
......@@ -79,13 +79,13 @@
<plugin name="turtlebot3_imu" filename="libgazebo_ros_imu_sensor.so">
<ros>
<!-- <namespace>/tb3</namespace> -->
<argument>~/out:=imu</argument>
<remapping>~/out:=imu</remapping>
</ros>
</plugin>
</sensor>
</link>
<link name="base_scan">
<link name="base_scan">
<inertial>
<pose>-0.052 0 0.111 0 0 0</pose>
<inertia>
......@@ -137,7 +137,7 @@
<plugin name="turtlebot3_laserscan" filename="libgazebo_ros_ray_sensor.so">
<ros>
<!-- <namespace>/tb3</namespace> -->
<argument>~/out:=scan</argument>
<remapping>~/out:=scan</remapping>
</ros>
<output_type>sensor_msgs/LaserScan</output_type>
<frame_name>base_scan</frame_name>
......@@ -207,7 +207,7 @@
</inertia>
<mass>0.1</mass>
</inertial>
<collision name="wheel_right_collision">
<pose>0.0 -0.144 0.023 -1.57 0 0</pose>
<geometry>
......@@ -341,12 +341,12 @@
</camera>
<plugin name="intel_realsense_r200_depth_driver" filename="libgazebo_ros_camera.so">
<ros>
<!--
<argument>custom_camera/image_raw:=custom_camera/custom_image</argument>
<argument>custom_camera/image_depth:=custom_camera/custom_image_depth</argument>
<argument>custom_camera/camera_info:=custom_camera/custom_info_raw</argument>
<argument>custom_camera/camera_info_depth:=custom_camera/custom_info_depth</argument>
<argument>custom_camera/points:=custom_camera/custom_points</argument>
<!--
<remapping>custom_camera/image_raw:=custom_camera/custom_image</remapping>
<remapping>custom_camera/image_depth:=custom_camera/custom_image_depth</remapping>
<remapping>custom_camera/camera_info:=custom_camera/custom_info_raw</remapping>
<remapping>custom_camera/camera_info_depth:=custom_camera/custom_info_depth</remapping>
<remapping>custom_camera/points:=custom_camera/custom_points</remapping>
-->
</ros>
<camera_name>intel_realsense_r200_depth</camera_name>
......@@ -355,7 +355,7 @@
<min_depth>0.001</min_depth>
</plugin>
</sensor>
</link>
</link>
<joint name="base_joint" type="fixed">
<parent>base_footprint</parent>
......@@ -441,12 +441,12 @@
<plugin name="turtlebot3_joint_state" filename="libgazebo_ros_joint_state_publisher.so">
<ros>
<!-- <namespace>/tb3</namespace> -->
<argument>~/out:=joint_states</argument>
<remapping>~/out:=joint_states</remapping>
</ros>
<update_rate>30</update_rate>
<joint_name>wheel_left_joint</joint_name>
<joint_name>wheel_right_joint</joint_name>
</plugin>
</plugin>
</model>
</sdf>
......@@ -139,9 +139,7 @@
<plugin name="my_imu_plugin" filename="libgazebo_ros_imu_sensor.so">
<ros>
<!-- <namespace>/tb3</namespace> -->
<argument>--ros-args</argument>
<argument>-r</argument>
<argument>~/out:=imu</argument>
<remapping>~/out:=imu</remapping>
</ros>
</plugin>
</sensor>
......@@ -209,9 +207,7 @@
<plugin name="laserscan" filename="libgazebo_ros_ray_sensor.so">
<ros>
<!-- <namespace>/tb3</namespace> -->
<argument>--ros-args</argument>
<argument>-r </argument>
<argument>~/out:=scan</argument>
<remapping>~/out:=scan</remapping>
</ros>
<output_type>sensor_msgs/LaserScan</output_type>
</plugin>
......@@ -485,9 +481,7 @@
<plugin name="turtlebot3_joint_state" filename="libgazebo_ros_joint_state_publisher.so">
<ros>
<!-- <namespace>/tb3</namespace> -->
<argument>--ros-args</argument>
<argument>-r </argument>
<argument>~/out:=joint_states</argument>
<remapping>~/out:=joint_states</remapping>
</ros>
<update_rate>250</update_rate>
<joint_name>wheel_left_joint</joint_name>
......
......@@ -139,9 +139,7 @@
<plugin name="my_imu_plugin" filename="libgazebo_ros_imu_sensor.so">
<ros>
<!-- <namespace>/tb3</namespace> -->
<argument>--ros-args</argument>
<argument>-r</argument>
<argument>~/out:=imu</argument>
<remapping>~/out:=imu</remapping>
</ros>
</plugin>
</sensor>
......@@ -209,9 +207,7 @@
<plugin name="laserscan" filename="libgazebo_ros_ray_sensor.so">
<ros>
<!-- <namespace>/tb3</namespace> -->
<argument>--ros-args</argument>
<argument>-r </argument>
<argument>~/out:=scan</argument>
<remapping>~/out:=scan</remapping>
</ros>
<output_type>sensor_msgs/LaserScan</output_type>
</plugin>
......@@ -485,9 +481,7 @@
<plugin name="turtlebot3_joint_state" filename="libgazebo_ros_joint_state_publisher.so">
<ros>
<!-- <namespace>/tb3</namespace> -->
<argument>--ros-args</argument>
<argument>-r </argument>
<argument>~/out:=joint_states</argument>
<remapping>~/out:=joint_states</remapping>
</ros>
<update_rate>250</update_rate>
<joint_name>wheel_left_joint</joint_name>
......
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment