From a3be4c1f7f42c234912052d637819faa7fc55151 Mon Sep 17 00:00:00 2001 From: fherrero <fherrero@iri.upc.edu> Date: Mon, 25 Feb 2019 16:11:55 +0100 Subject: [PATCH] sensors.xacro: independent front/rear laser config file, because is where topic is defined --- urdf/include/sensors.xacro | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/urdf/include/sensors.xacro b/urdf/include/sensors.xacro index b48b552..709ac78 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> -- GitLab