gazebo_simulation_ros_package/gazebo_demo1/urdf/gazebo_demo1.urdf

343 lines
8.6 KiB
XML

<?xml version="1.0" encoding="utf-8"?>
<!-- This URDF was automatically created by SolidWorks to URDF Exporter! Originally created by Stephen Brawner (brawner@gmail.com)
Commit Version: 1.5.1-0-g916b5db Build Version: 1.5.7152.31018
For more information, please see http://wiki.ros.org/sw_urdf_exporter -->
<robot
name="gazebo_demo1">
<link
name="base_link">
<inertial>
<origin
xyz="-6.0445212263786E-18 1.39257863414922E-18 -2.20581496680807E-19"
rpy="0 0 0" />
<mass
value="0.468" />
<inertia
ixx="0.0001443"
ixy="-1.53384791846956E-20"
ixz="-1.37563571644961E-21"
iyy="0.0003939"
iyz="-1.29382985829106E-37"
izz="0.0005304" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://gazebo_demo1/meshes/base_link.STL" />
</geometry>
<material
name="">
<color
rgba="0.529411764705882 0.549019607843137 0.549019607843137 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://gazebo_demo1/meshes/base_link.STL" />
</geometry>
</collision>
<dynamic damping="0.7" friction="0.5" />
</link>
<link
name="LF_LINK">
<inertial>
<origin
xyz="0.01 -1.59413400484866E-18 0"
rpy="0 0 0" />
<mass
value="0.0108630528372501" />
<inertia
ixx="1.06775440310417E-07"
ixy="1.20998908503938E-22"
ixz="-1.75453282727152E-23"
iyy="7.38080724035423E-07"
iyz="8.06501097239194E-25"
izz="7.99593444190632E-07" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://gazebo_demo1/meshes/LF_LINK.STL" />
</geometry>
<material
name="">
<color
rgba="0.529411764705882 0.549019607843137 0.549019607843137 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://gazebo_demo1/meshes/LF_LINK.STL" />
</geometry>
</collision>
<dynamic damping="0.7" friction="0.5" />
</link>
<joint
name="LF_JOINT"
type="continuous">
<origin
xyz="0.045 0.0325 0"
rpy="1.5708 0 0" />
<parent
link="base_link" />
<child
link="LF_LINK" />
<axis
xyz="0 0 1" />
</joint>
<link
name="LB_LINK">
<inertial>
<origin
xyz="0.01 -1.90361538571609E-18 6.93889390390723E-18"
rpy="0 0 0" />
<mass
value="0.0108630528372501" />
<inertia
ixx="1.06775440310417E-07"
ixy="1.10469815160512E-22"
ixz="3.53711447230329E-24"
iyy="7.38080724035424E-07"
iyz="5.37667398159464E-25"
izz="7.99593444190632E-07" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://gazebo_demo1/meshes/LB_LINK.STL" />
</geometry>
<material
name="">
<color
rgba="0.529411764705882 0.549019607843137 0.549019607843137 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://gazebo_demo1/meshes/LB_LINK.STL" />
</geometry>
</collision>
<dynamic damping="0.7" friction="0.5" />
</link>
<joint
name="LB_JOINT"
type="continuous">
<origin
xyz="-0.045 0.0325 0"
rpy="1.5708 0 0" />
<parent
link="base_link" />
<child
link="LB_LINK" />
<axis
xyz="0 0 1" />
</joint>
<link
name="RF_LINK">
<inertial>
<origin
xyz="0.01 -1.85843759880028E-18 0"
rpy="0 0 0" />
<mass
value="0.0108630528372501" />
<inertia
ixx="1.06775440310417E-07"
ixy="1.5173510835766E-22"
ixz="-9.00355753711158E-24"
iyy="7.38080724035423E-07"
iyz="-3.49483808803654E-24"
izz="7.99593444190632E-07" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://gazebo_demo1/meshes/RF_LINK.STL" />
</geometry>
<material
name="">
<color
rgba="0.529411764705882 0.549019607843137 0.549019607843137 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://gazebo_demo1/meshes/RF_LINK.STL" />
</geometry>
</collision>
<dynamic damping="0.7" friction="0.5" />
</link>
<joint
name="RF_JOINT"
type="continuous">
<origin
xyz="0.045 -0.0325 0"
rpy="1.5708 0 0" />
<parent
link="base_link" />
<child
link="RF_LINK" />
<axis
xyz="0 0 1" />
</joint>
<link
name="RB_LINK">
<inertial>
<origin
xyz="0.01 -1.6227366665734E-18 0"
rpy="0 0 0" />
<mass
value="0.0108630528372501" />
<inertia
ixx="1.06775440310417E-07"
ixy="1.36659023251123E-22"
ixz="1.17764472964423E-23"
iyy="7.38080724035423E-07"
iyz="-1.6130021944784E-24"
izz="7.99593444190632E-07" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://gazebo_demo1/meshes/RB_LINK.STL" />
</geometry>
<material
name="">
<color
rgba="0.529411764705882 0.549019607843137 0.549019607843137 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://gazebo_demo1/meshes/RB_LINK.STL" />
</geometry>
</collision>
<dynamic damping="0.7" friction="0.5" />
</link>
<joint
name="RB_JOINT"
type="continuous">
<origin
xyz="-0.045 -0.0325 0"
rpy="1.5708 0 0" />
<parent
link="base_link" />
<child
link="RB_LINK" />
<axis
xyz="0 0 1" />
</joint>
<gazebo reference="base_link">
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="LF_LINK">
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="LB_LINK">
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="RF_LINK">
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="RB_LINK">
<material>Gazebo/Black</material>
</gazebo>
<transmission name="LF_JOINT_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="LF_JOINT">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="LF_JOINT_motor">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="LB_JOINT_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="LB_JOINT">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="LB_JOINT_motor">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="RF_JOINT_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="RF_JOINT">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="RF_JOINT_motor">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="RB_JOINT_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="RB_JOINT">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="RB_JOINT_motor">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/gazebo_demo1</robotNamespace>
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
<legacyModeNS>true</legacyModeNS>
</plugin>
</gazebo>
</robot>