diff --git a/urdf/include/sensors.xacro b/urdf/include/sensors.xacro index b48b552cc1522c4c91e8f4780aa5e1b0388b55cb..709ac786827393c19b0e74b8a3374f71890932d3 100644 --- a/urdf/include/sensors.xacro +++ b/urdf/include/sensors.xacro @@ -7,13 +7,14 @@ <xacro:macro name="sensors" params="name parent"> - <xacro:property name="laser_config" value="$(find iri_dabo_gazebo)/config/hokuyo_utm30lx.yaml"/> + <xacro:property name="front_laser_config" value="$(find iri_dabo_gazebo)/config/front_hokuyo_utm30lx.yaml"/> + <xacro:property name="rear_laser_config" value="$(find iri_dabo_gazebo)/config/rear_hokuyo_utm30lx.yaml"/> - <xacro:hokuyo_laser2d name="front" prefix="${name}" parent="${parent}" mesh_resolution="low_res" model="utm30lx" config_file="${laser_config}"> + <xacro:hokuyo_laser2d name="front" prefix="${name}" parent="${parent}" mesh_resolution="low_res" model="utm30lx" config_file="${front_laser_config}"> <origin xyz="0.28 0.0 0.15" rpy="0 0 0" /> </xacro:hokuyo_laser2d> - <xacro:hokuyo_laser2d name="rear" prefix="${name}" parent="${parent}" mesh_resolution="low_res" model="utm30lx" config_file="${laser_config}"> + <xacro:hokuyo_laser2d name="rear" prefix="${name}" parent="${parent}" mesh_resolution="low_res" model="utm30lx" config_file="${rear_laser_config}"> <origin xyz="-0.28 0.0 0.15" rpy="0 0 3.14159" /> </xacro:hokuyo_laser2d>