ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
My urdf was not in the correct form. Modifying my previous work with correct <gazebo> tags ended up being the solution.
I was initially missing my <gazebo reference="xxx_link"/> tags as well as any associated <dampingfactor> tags (which I ended up needing to add later when my model was falling down due to gravity).
The URDF can be seen below as an example of what worked for me:
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from arm.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="arm" xmlns:xacro="http://www.ros.org/wiki/xacro">
<!--Joints-->
<!--Cylinder-->
<!--Rectangular Prism-->
<!--Cylinder Mesh-->
<!--Box Mesh-->
<!-- ros_control plugin -->
<!-- base_link -->
<gazebo reference="base_link">
</gazebo>
<!-- plat_link -->
<gazebo reference="plat_link">
<dampingFactor>1</dampingFactor>
</gazebo>
<!-- lock_link -->
<gazebo reference="lock_link">
<dampingFactor>1</dampingFactor>
</gazebo>
<!-- shoulder_link -->
<gazebo reference="shoulder_link">
<dampingFactor>1</dampingFactor>
</gazebo>
<!-- forearm_link -->
<gazebo reference="forearm_link">
<dampingFactor>1</dampingFactor>
</gazebo>
<!-- wrist_link -->
<gazebo reference="wrist_link">
<dampingFactor>1</dampingFactor>
</gazebo>
<create/>
<gazebo>
<plugin filename="libgazebo_ros_control.so" name="gazebo_ros_control">
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
<legacyModeNS>true</legacyModeNS>
</plugin>
</gazebo>
<link name="dummy_link"/>
<!-- Dummy End Effector -->
<joint name="dummy_joint" type="fixed">
<parent link="dummy_link"/>
<child link="base_link"/>
</joint>
<!--Base Link-->
<link name="base_link">
<inertial>
<mass value="1.0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.00153508333333" ixy="0" ixz="0" iyy="0.00153508333333" iyz="0" izz="0.00245"/>
</inertial>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.061" radius="0.07"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://version1_desc/meshes/base_link.dae" scale="1 1 1"/>
</geometry>
<material name="light_black"/>
</visual>
</link>
<!--Plat Joint-->
<joint name="plat_joint" type="revolute">
<parent link="base_link"/>
<child link="plat_link"/>
<origin rpy="0 0 0" xyz="0 0 0.0305"/>
<limit effort="10" lower="-1.5" upper="1.5" velocity="0.5"/>
<axis xyz="0 0 1"/>
</joint>
<transmission name="trans_plat">
<type> transmission_interface/SimpleTransmission</type>
<joint name="plat_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="motor_plat">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<!--Plat Link-->
<link name="plat_link">
<inertial>
<mass value="0.072"/>
<origin rpy="0 0 0" xyz="0 0 0.004"/>
<inertia ixx="6.5184e-05" ixy="0" ixz="0" iyy="6.5184e-05" iyz="0" izz="0.0001296"/>
</inertial>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.004"/>
<geometry>
<cylinder length="0.008" radius="0.06"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 0 0.004"/>
<geometry>
<mesh filename="package://version1_desc/meshes/plat_link.dae" scale="1 1 1"/>
</geometry>
<material name="light_black"/>
</visual>
</link>
<!--Lock Joint-->
<joint name="lock_joint" type="fixed">
<parent link="plat_link"/>
<child link="lock_link"/>
<origin rpy="0 0 0" xyz="0 0 0.004"/>
<limit effort="0.1" lower="-1.5" upper="1.5" velocity="0.5"/>
<axis xyz="0 0 1"/>
</joint>
<!--Lock Link-->
<link name="lock_link">
<inertial>
<mass value="0.001"/>
<origin rpy="0 0 0" xyz="0 0 0.0185"/>
<inertia ixx="1.47416666667e-07" ixy="0" ixz="0" iyy="3.66166666667e-07" iyz="0" izz="2.85416666667e-07"/>
</inertial>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.0185"/>
<geometry>
<box size="0.02 0.055 0.037"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 0 0.0185"/>
<geometry>
<mesh filename="package://version1_desc/meshes/lock_link.dae" scale="1 1 1"/>
</geometry>
<material name="light_black"/>
</visual>
</link>
<!--Shoulder Joint-->
<joint name="shoulder_joint" type="revolute">
<parent link="lock_link"/>
<child link="shoulder_link"/>
<origin rpy="0 0 0" xyz="0 0 0.0265"/>
<limit effort="10" lower="-1.5" upper="1.5" velocity="0.5"/>
<axis xyz="0 1 0"/>
</joint>
<transmission name="trans_shoulder">
<type> transmission_interface/SimpleTransmission</type>
<joint name="shoulder_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="motor_shoulder">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<!--Shoulder Link-->
<link name="shoulder_link">
<inertial>
<mass value="0.163"/>
<origin rpy="0 0 0" xyz="0 0 0.098"/>
<inertia ixx="0.000639177333333" ixy="0" ixz="0" iyy="0.000700302333333" iyz="0" izz="7.19916666667e-05"/>
</inertial>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.098"/>
<geometry>
<box size="0.02 0.07 0.216"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 0 0.098"/>
<geometry>
<mesh filename="package://version1_desc/meshes/shoulder_link.dae" scale="1 1 1"/>
</geometry>
<material name="light_black"/>
</visual>
</link>
<!--Forearm Joint-->
<joint name="forearm_joint" type="revolute">
<parent link="shoulder_link"/>
<child link="forearm_link"/>
<origin rpy="0 0 0" xyz="0 0 0.191"/>
<limit effort="10" lower="-1.5" upper="1.5" velocity="0.5"/>
<axis xyz="0 1 0"/>
</joint>
<transmission name="trans_forearm">
<type> transmission_interface/SimpleTransmission</type>
<joint name="forearm_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="motor_forearm">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<!--Forearm Link-->
<link name="forearm_link">
<inertial>
<mass value="0.217"/>
<origin rpy="0 0 0" xyz="0 0 0.055"/>
<inertia ixx="0.00042315" ixy="0" ixz="0" iyy="0.000471975" iyz="0" izz="8.1375e-05"/>
</inertial>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.055"/>
<geometry>
<box size="0.03 0.06 0.150"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 0 0.055"/>
<geometry>
<mesh filename="package://version1_desc/meshes/forearm_link.dae" scale="1 1 1"/>
</geometry>
<material name="light_black"/>
</visual>
</link>
<!--Wrist Joint-->
<joint name="wrist_joint" type="revolute">
<parent link="forearm_link"/>
<child link="wrist_link"/>
<origin rpy="0 0 0" xyz="0 0 0.110"/>
<limit effort="1000" lower="-2.5" upper="2.5" velocity="0.5"/>
<axis xyz="0 1 0"/>
</joint>
<transmission name="trans_wrist">
<type> transmission_interface/SimpleTransmission</type>
<joint name="wrist_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="motor_wrist">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<!--Wrist Link-->
<link name="wrist_link">
<inertial>
<mass value="0.057"/>
<origin rpy="0 0 0" xyz="0 0 0.045"/>
<inertia ixx="7.03e-05" ixy="0" ixz="0" iyy="9.1675e-05" iyz="0" izz="2.5175e-05"/>
</inertial>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.045"/>
<geometry>
<box size="0.02 0.07 0.120"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 0 0.045"/>
<geometry>
<mesh filename="package://version1_desc/meshes/wrist_link.dae" scale="1 1 1"/>
</geometry>
<material name="light_black"/>
</visual>
</link>
<!-- Dummy End Effector -->
<link name="dummy_eef"/>
<!-- Dummy End Effector -->
<joint name="eef_joint" type="fixed">
<parent link="wrist_link"/>
<child link="dummy_eef"/>
</joint>
</robot>