diff --git a/bioloid_description/urdf/sensors/cny70_ir.gazebo b/bioloid_description/urdf/sensors/cny70_ir.gazebo index ed1b1f68bc35457fda2ad3346c01f6068727f8fc..907f5a1df8a094c64f25494cbdabba79d2eb64f5 100644 --- a/bioloid_description/urdf/sensors/cny70_ir.gazebo +++ b/bioloid_description/urdf/sensors/cny70_ir.gazebo @@ -2,7 +2,7 @@ <root xmlns:xacro="http://ros.org/wiki/xacro"> - <xacro:macro name="cny70_ir_gazebo" params="name update_rate fov min_range max_range"> + <xacro:macro name="cny70_ir_gazebo" params="name namespace update_rate fov min_range max_range"> <gazebo reference="${name}_ir_link"> <material>Gazebo/Black</material> <gravity>true</gravity> @@ -42,8 +42,8 @@ </range> </ray> <plugin name="${name}_range_sensor" filename="libgazebo_ros_range.so"> - <frameName>/bioloid/${name}_ir_link</frameName> - <topicName>/bioloid/sensors/range</topicName> + <frameName>/${namespace}/${name}_ir_link</frameName> + <topicName>/${namespace}/sensors/range</topicName> <radiation>infrared</radiation> <fov>${fov}</fov> <gaussianNoise>0.0005</gaussianNoise> diff --git a/bioloid_description/urdf/sensors/cny70_ir.xacro b/bioloid_description/urdf/sensors/cny70_ir.xacro index 94ba899ace725453d0e18e9df7efd6fca6aab23f..bac20e16eca687ae3ec32f7806623d5bf41bf2cf 100644 --- a/bioloid_description/urdf/sensors/cny70_ir.xacro +++ b/bioloid_description/urdf/sensors/cny70_ir.xacro @@ -4,7 +4,7 @@ <xacro:include filename="$(find bioloid_description)/urdf/sensors/cny70_ir.gazebo" /> - <xacro:macro name="cny70_ir" params="name parent *origin update_rate fov min_range max_range"> + <xacro:macro name="cny70_ir" params="name namespace parent *origin update_rate fov min_range max_range"> <!-- IR distance sensors --> <link name="${name}_ir_link"> <collision> @@ -32,7 +32,7 @@ <child link="${name}_ir_link"/> </joint> - <xacro:cny70_ir_gazebo name="${name}" update_rate="${update_rate}" fov="${fov}" min_range="${min_range}" max_range="${max_range}"/> + <xacro:cny70_ir_gazebo name="${name}" namespace="${namespace}" update_rate="${update_rate}" fov="${fov}" min_range="${min_range}" max_range="${max_range}"/> </xacro:macro> </root> diff --git a/bioloid_description/urdf/sensors/feet_ir.xacro b/bioloid_description/urdf/sensors/feet_ir.xacro index 4e6b8dee80932ff3fbe0be5d9d8f0ebaf5901cd5..ecb44956a554d78b42039b9e1adb84d71633b98e 100644 --- a/bioloid_description/urdf/sensors/feet_ir.xacro +++ b/bioloid_description/urdf/sensors/feet_ir.xacro @@ -34,15 +34,15 @@ </joint> <!-- sensor links --> - <xacro:cny70_ir name="left_front_fwd" parent="left_board_link" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}"> + <xacro:cny70_ir name="left_front_fwd" namespace="bioloid" parent="left_board_link" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}"> <origin xyz="0.0085 -0.0055 0.038" rpy="-1.5707 -1.5707 0" /> </xacro:cny70_ir> - <xacro:cny70_ir name="left_front_dwn" parent="left_board_link" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}"> + <xacro:cny70_ir name="left_front_dwn" namespace="bioloid" parent="left_board_link" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}"> <origin xyz="0.0225 -0.012 0.0345" rpy="0 0 -1.5707" /> </xacro:cny70_ir> - <xacro:cny70_ir name="left_lateral_dwn" parent="left_board_link" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}"> + <xacro:cny70_ir name="left_lateral_dwn" namespace="bioloid" parent="left_board_link" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}"> <origin xyz="0.0575 -0.012 0.0065" rpy="0 0 -1.5707" /> </xacro:cny70_ir> @@ -74,15 +74,15 @@ </joint> <!-- sensor links --> - <xacro:cny70_ir name="right_front_fwd" parent="right_board_link" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}"> + <xacro:cny70_ir name="right_front_fwd" namespace="bioloid" parent="right_board_link" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}"> <origin xyz="-0.0085 -0.0055 0.038" rpy="-1.5707 -1.5707 0" /> </xacro:cny70_ir> - <xacro:cny70_ir name="right_front_dwn" parent="right_board_link" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}"> + <xacro:cny70_ir name="right_front_dwn" namespace="bioloid" parent="right_board_link" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}"> <origin xyz="-0.0225 -0.012 0.0345" rpy="0 0 -1.5707" /> </xacro:cny70_ir> - <xacro:cny70_ir name="right_lateral_dwn" parent="right_board_link" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}"> + <xacro:cny70_ir name="right_lateral_dwn" namespace="bioloid" parent="right_board_link" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}"> <origin xyz="-0.0575 -0.012 0.0065" rpy="0 0 -1.5707" /> </xacro:cny70_ir>