diff --git a/urdf/rslidar16.xacro b/urdf/rslidar16.xacro index 7eab7bc2010e712a739938d777f63f42c24cd7ed..521611fe94dea94f99a9e59b02ec83f0d0171ef0 100644 --- a/urdf/rslidar16.xacro +++ b/urdf/rslidar16.xacro @@ -24,10 +24,10 @@ <joint name="${name}_base_scan_joint" type="fixed" > <origin xyz="0 0 0.0414" rpy="0 0 0" /> <parent link="${name}_base" /> - <child link="rslidar"/> + <child link="${name}"/> </joint> - <link name="rslidar"> + <link name="${name}"> <inertial> <mass value="0.1"/> <origin xyz="0 0 0"/> @@ -47,7 +47,7 @@ </collision> </link> - <xacro:iri_velodyne_gazebo name="rslidar" config="${sim_config}"/> + <xacro:iri_velodyne_gazebo name="${name}" config="${sim_config}"/> </xacro:macro> </root>