Skip to content
Snippets Groups Projects
Commit 2efc5759 authored by Fernando Herrero's avatar Fernando Herrero
Browse files

Fix namespaces

parent 8acbfae7
No related branches found
No related tags found
No related merge requests found
......@@ -3,8 +3,17 @@
<root xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:include filename="$(find iri_laser2d_gazebo)/urdf/laser2d.gazebo" />
<xacro:macro name="hokuyo_laser2d" params="name parent resolution model *origin">
<xacro:property name="default_config" value="$(find iri_laser2d_gazebo)/config/hokuyo_utm30lx.yaml"/>
<xacro:macro name="hokuyo_laser2d"
params="name:=main
prefix:=robot
parent:=base
mesh_resolution:=low
config_file:=${default_config}
model:=utm30lx
*origin">
<link name="${name}_hokuyo_base">
<inertial>
......@@ -17,7 +26,7 @@
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://iri_hokuyo_laser2d_description/meshes/${resolution}_hokuyo_${model}.stl" />
<mesh filename="package://iri_hokuyo_laser2d_description/meshes/${mesh_resolution}_hokuyo_${model}.stl" />
</geometry>
<material name="DarkGrey">
<color rgba="0.2 0.2 0.2 1.0"/>
......@@ -37,16 +46,16 @@
<xacro:insert_block name="origin" />
</joint>
<link name="${name}_hokuyo_sense">
<link name="${name}_hokuyo_scan_frame">
</link>
<joint name="joint_${name}_hokuyo_base_to_${name}_hokuyo_sense" type="fixed" >
<joint name="joint_${name}_hokuyo_base_to_${name}_hokuyo_scan_frame" type="fixed" >
<parent link="${name}_hokuyo_base"/>
<child link="${name}_hokuyo_sense"/>
<child link="${name}_hokuyo_scan_frame"/>
<origin xyz="0.0 0.0 0.05625" rpy="0 0 0" />
</joint>
<xacro:iri_laser2d_gazebo name="${name}_hokuyo" model="hokuyo_${model}"/>
<xacro:iri_laser2d_gazebo name="${name}_hokuyo" prefix="${prefix}" config_file="${config_file}"/>
</xacro:macro>
......
......@@ -27,7 +27,7 @@
</collision>
</link>
<xacro:hokuyo_laser2d name="top" parent="hokuyo_base" resolution="low_res" model="utm30lx">
<xacro:hokuyo_laser2d name="top" prefix="robot" parent="hokuyo_base" resolution="low_res" model="utm30lx">
<origin xyz="0.0 0.0 0.5" rpy="0 0 0" />
</xacro:hokuyo_laser2d>
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment