Skip to content
Snippets Groups Projects
Commit 05075dee authored by Alejandro Lopez Gestoso's avatar Alejandro Lopez Gestoso
Browse files

Adapted to simulation

parent b3804ffc
No related branches found
No related tags found
No related merge requests found
<?xml version="1.0"?>
<root xmlns:xacro="http://www.ros.org/wiki/xacro">
<!--<xacro:include filename="$(find iri_dynamixel_pan_tilt_gazebo)/urdf/dynamixel_pan_tilt.gazebo"/>-->
<xacro:include filename="$(find iri_dynamixel_pan_tilt_gazebo)/urdf/ax12_pan_tilt.gazebo"/>
<xacro:include filename="$(find iri_dynamixel_pan_tilt_description)/urdf/ax12.xacro"/>
<xacro:macro name="pan_tilt_ax12" params="prefix parent pan_joint_name tilt_joint_name load_name *origin">
......@@ -10,6 +10,7 @@
<container>
<geometry>
<box size=".054 .032 .04"/>
<!--<mesh filename="package://iri_dynamixel_pan_tilt_description/meshes/dynamixel_ax12.stl"/>-->
</geometry>
</container>
<container>
......@@ -26,6 +27,7 @@
<container>
<geometry>
<box size=".054 .04 .032"/>
<!--<mesh filename="package://iri_dynamixel_pan_tilt_description/meshes/dynamixel_ax12.stl"/>-->
</geometry>
</container>
<container>
......@@ -44,27 +46,29 @@
<xacro:insert_block name="origin" />
</joint>
<xacro:servo_joint name="${pan_joint_name}" parent="${prefix}_pan" child="${prefix}_tilt">
<container>
<origin rpy="0 0 0" xyz="0 0 0.04"/>
</container>
<container>
<limit effort="25.0" lower="-3.14159" upper="3.14159" velocity="0.5"/>
</container>
</xacro:servo_joint>
<xacro:servo_joint name="${pan_joint_name}" parent="${prefix}_pan" child="${prefix}_tilt">
<container>
<origin rpy="0 0 0" xyz="0 0 0.04"/>
</container>
<container>
<limit effort="25.0" lower="-3.14159" upper="3.14159" velocity="0.5"/>
</container>
</xacro:servo_joint>
<xacro:servo_transmission name="${pan_joint_name}" joint_interface="EffortJointInterface" reduction="1"/>
<xacro:servo_transmission name="${pan_joint_name}" joint_interface="EffortJointInterface" reduction="1"/>
<xacro:servo_joint name="${tilt_joint_name}" parent="${prefix}_tilt" child="${load_name}">
<container>
<origin rpy="-1.57 -1.57 0" xyz="0 0.02 0.0205"/>
</container>
<container>
<limit effort="25.0" lower="-3.14159" upper="3.14159" velocity="0.5"/>
</container>
</xacro:servo_joint>
<xacro:servo_joint name="${tilt_joint_name}" parent="${prefix}_tilt" child="${load_name}">
<container>
<origin rpy="-1.57 -1.57 0" xyz="0 0.02 0.0205"/>
</container>
<container>
<limit effort="25.0" lower="-3.14159" upper="3.14159" velocity="0.5"/>
</container>
</xacro:servo_joint>
<xacro:servo_transmission name="${tilt_joint_name}" joint_interface="EffortJointInterface" reduction="1"/>
<xacro:servo_transmission name="${tilt_joint_name}" joint_interface="EffortJointInterface" reduction="1"/>
<xacro:ax12_pan_tilt_gazebo prefix="${prefix}" pan_joint_name="${pan_joint_name}" tilt_joint_name="${tilt_joint_name}"/>
</xacro:macro>
......
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