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

Added the realsense depth camera to the Ana robot.

parent 3a9f496a
No related branches found
No related tags found
No related merge requests found
...@@ -2,11 +2,11 @@ ...@@ -2,11 +2,11 @@
<root xmlns:xacro="http://ros.org/wiki/xacro"> <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_velodyne_lidar_description)/urdf/velodyne_vlp16.xacro" />
<xacro:include filename="$(find iri_realsense_depth_description)/urdf/realsense.xacro" />
<xacro:macro name="sensors" params="name parent *origin"> <xacro:macro name="sensors" params="name parent *origin">
<link name="box"> <link name="${name}_box">
<inertial> <inertial>
<mass value="4.00000000" /> <mass value="4.00000000" />
<origin xyz="-0.02349208 0.00000000 0.20998619" rpy="0 0 0"/> <origin xyz="-0.02349208 0.00000000 0.20998619" rpy="0 0 0"/>
...@@ -33,14 +33,9 @@ ...@@ -33,14 +33,9 @@
</collision> </collision>
</link> </link>
<gazebo reference="box"> <joint name="joint_${parent}_to_${name}_box" type="fixed" >
<material>Gazebo/Grey</material>
</gazebo>
<joint name="joint_${parent}_to_box" type="fixed" >
<parent link="${parent}"/> <parent link="${parent}"/>
<child link="box"/> <child link="${name}_box"/>
<origin xyz="0 0 0.3" rpy="0 0 0"/> <origin xyz="0 0 0.3" rpy="0 0 0"/>
</joint> </joint>
...@@ -48,6 +43,19 @@ ...@@ -48,6 +43,19 @@
<origin xyz="0.0 0.0 0.1" rpy="0 0 0" /> <origin xyz="0.0 0.0 0.1" rpy="0 0 0" />
</xacro:velodyne_vlp16> </xacro:velodyne_vlp16>
<link name="${name}_realsense_support">
</link>
<joint name="joint_${parent}_to_${name}_realsense_support" type="fixed" >
<parent link="${parent}"/>
<child link="${name}_realsense_support"/>
<origin xyz="0.26374 0 -0.0485" rpy="0 0 0"/>
</joint>
<xacro:realsense_depth parent="${name}_realsense_support" model="d435" sim_config="$(find iri_ana_gazebo)/config/ana_realsense_config.yaml">
<origin xyz="0.0 0.0 0.0265" rpy="0 0.52 0" />
</xacro:realsense_depth>
</xacro:macro> </xacro:macro>
</root> </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