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

Add uvc_wideangle_camera.xacro

parent 4425469c
No related branches found
No related tags found
No related merge requests found
<?xml version="1.0"?>
<root xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:include filename="$(find iri_camera_gazebo)/urdf/wideangle_camera.gazebo" />
<xacro:macro name="uvc_wideangle_camera" params="name parent resolution model *origin sim_config">
<link name="${name}_uvc_camera_base">
<inertial>
<mass value="0.07700000" />
<origin xyz="-0.03379724 0.00000000 0.00000000" rpy="0 0 0"/>
<inertia ixx="0.00001570" ixy="0.00000000" ixz="0.0"
iyy="0.00001824" iyz="0.0"
izz="0.00001824" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://iri_uvc_camera_description/meshes/${resolution}_uvc_camera_${model}.stl" />
</geometry>
<material name="DarkGrey">
<color rgba="0.2 0.2 0.2 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://iri_uvc_camera_description/meshes/low_res_uvc_camera_${model}.stl" />
</geometry>
</collision>
</link>
<joint name="joint_${parent}_to_${name}_uvc_camera_base" type="fixed" >
<parent link="${parent}"/>
<child link="${name}_uvc_camera_base"/>
<xacro:insert_block name="origin" />
</joint>
<link name="${name}_uvc_camera_optical">
</link>
<joint name="joint_${name}_uvc_camera_base_to_${name}_uvc_camera_optical" type="fixed" >
<parent link="${name}_uvc_camera_base"/>
<child link="${name}_uvc_camera_optical"/>
<origin xyz="0.0 0.0 0.0" rpy="-1.5707 0 -1.5707" />
</joint>
<xacro:iri_wideangle_camera_gazebo name="${name}_uvc" config="${sim_config}"/>
</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