Skip to content
Snippets Groups Projects
Commit 230f7574 authored by Sergi Hernandez's avatar Sergi Hernandez
Browse files

Removed the origin parameter from the sensors xacro because it was not used.

Used the base_footprint link as the IMU parent because problems with the IMU plugin.
parent dd8ae42b
No related branches found
No related tags found
No related merge requests found
......@@ -11,6 +11,5 @@
</xacro:pioneer3>
<xacro:sensors name="$(arg name)" parent="top_plate">
<origin xyz="0.0 0.0 0.27" rpy="0 0 0" />
</xacro:sensors>
</robot>
......@@ -3,8 +3,9 @@
<root xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:include filename="$(find iri_velodyne_lidar_description)/urdf/velodyne_vlp16.xacro" />
<xacro:include filename="$(find iri_realsense_depth_description)/urdf/realsense.xacro" />
<xacro:include filename="$(find iri_bno055_imu_description)/urdf/bno055_imu.xacro" />
<xacro:macro name="sensors" params="name parent *origin">
<xacro:macro name="sensors" params="name parent">
<link name="${name}_box">
<inertial>
......@@ -17,7 +18,6 @@
<visual>
<origin xyz="0 0 0.1" rpy="0 0 0"/>
<geometry>
<!--<mesh filename="package://iri_ana_description/meshes/low_res_ana_payload.stl" />-->
<box size="0.3 0.3 0.2"/>
</geometry>
<material name="DarkGrey">
......@@ -27,7 +27,6 @@
<collision>
<origin xyz="0 0 0.1" rpy="0 0 0"/>
<geometry>
<!--<mesh filename="package://iri_ana_description/meshes/low_res_ana_payload.stl" />-->
<box size="0.3 0.3 0.2"/>
</geometry>
</collision>
......@@ -56,6 +55,10 @@
<origin xyz="0.0 0.0 0.0265" rpy="0 0.52 0" />
</xacro:realsense_depth>
<xacro:bno055_imu name="imu" parent="base_footprint" resolution="low_res" sim_config="$(find iri_ana_gazebo)/config/ana_bno055_config.yaml">
<origin xyz="0.11928 -0.08805 0.23061" rpy="0 -1.5707 0" />
</xacro:bno055_imu>
</xacro:macro>
</root>
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