Skip to content
GitLab
Menu
Projects
Groups
Snippets
/
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Menu
Open sidebar
humanoides
tv3
arm
ROS
arm_description
Commits
6e1fc41e
Commit
6e1fc41e
authored
Jul 13, 2020
by
Sergi Hernandez
Browse files
Added the URDF description file for the second version of the arm.
parent
d9f8b4d3
Changes
1
Hide whitespace changes
Inline
Side-by-side
urdf/arm2.xacro
0 → 100644
View file @
6e1fc41e
<?xml version="1.0"?>
<robot
name=
"arm"
xmlns:xacro=
"http://ros.org/wiki/xacro"
>
<xacro:include
filename=
"$(find arm_gazebo)/urdf/arm.gazebo"
/>
<xacro:include
filename=
"$(find iri_uvc_camera_description)/urdf/uvc_camera.xacro"
/>
<xacro:arg
name=
"robot_name"
default=
"darwin"
/>
<xacro:arg
name=
"sim_config_path"
default=
"$(find arm_description)/config"
/>
<link
name=
"base_footprint"
>
</link>
<joint
name=
"base_footprint_to_base_link"
type=
"fixed"
>
<origin
xyz=
"0.0 0.0 0.0"
rpy=
"0 0 0"
/>
<parent
link=
"base_footprint"
/>
<child
link=
"base_link"
/>
</joint>
<link
name=
"base_link"
>
<inertial>
<mass
value=
"0.52508170"
/>
<origin
xyz=
"0.00019318 0.00000000 0.16525697"
/>
<inertia
ixx=
"0.00497362"
ixy=
"0.00000000"
ixz=
"0.00001665"
iyy=
"0.00497877"
iyz=
"0.00000000"
izz=
"0.00013887"
/>
</inertial>
<visual>
<origin
xyz=
"0 0 0"
rpy=
"0 0 0"
/>
<geometry>
<mesh
filename=
"package://arm_description/meshes/arm_base2.stl"
/>
</geometry>
<material
name=
"Grey"
>
<color
rgba=
"0.4 0.4 0.4 1.0"
/>
</material>
</visual>
<collision>
<origin
xyz=
"0 0 0"
rpy=
"0 0 0"
/>
<geometry>
<mesh
filename=
"package://arm_description/meshes/arm_base2.stl"
/>
</geometry>
</collision>
</link>
<joint
name=
"pan"
type=
"revolute"
>
<origin
xyz=
"0.0133 0.0 0.34825"
rpy=
"0 0 0"
/>
<parent
link=
"base_link"
/>
<child
link=
"pan_link"
/>
<axis
xyz=
"0 0 1"
/>
<anchor
xyz=
"0 0 0"
/>
<limit
lower=
"-1.5707"
upper=
"1.5707"
effort=
"1.5"
velocity=
"10.0"
/>
<dynamics
damping=
"0.7"
/>
</joint>
<transmission
name=
"tran_pan"
>
<type>
transmission_interface/SimpleTransmission
</type>
<joint
name=
"pan"
>
<hardwareInterface>
hardware_interface/EffortJointInterface
</hardwareInterface>
</joint>
<actuator
name=
"pan_motor"
>
<hardwareInterface>
hardware_interface/EffortJointInterface
</hardwareInterface>
<mechanicalReduction>
1
</mechanicalReduction>
</actuator>
</transmission>
<link
name=
"pan_link"
>
<inertial>
<mass
value=
"0.01883444"
/>
<origin
xyz=
"0.03479693 0.00025021 -0.00035980"
/>
<inertia
ixx=
"0.00000406"
ixy=
"0.00000015"
ixz=
"-0.00000173"
iyy=
"0.00002849"
iyz=
"-0.00000001"
izz=
"0.00003060"
/>
</inertial>
<visual>
<origin
xyz=
"0 0 0"
rpy=
"0 0 0"
/>
<geometry>
<mesh
filename=
"package://arm_description/meshes/pan2.stl"
/>
</geometry>
<material
name=
"Grey"
>
<color
rgba=
"0.4 0.4 0.4 1.0"
/>
</material>
</visual>
<collision>
<origin
xyz=
"0 0 0"
rpy=
"0 0 0"
/>
<geometry>
<mesh
filename=
"package://arm_description/meshes/pan2.stl"
/>
</geometry>
</collision>
</link>
<joint
name=
"roll"
type=
"revolute"
>
<origin
xyz=
"0.0675 0.0 -0.03"
rpy=
"0 0 1.5707"
/>
<parent
link=
"pan_link"
/>
<child
link=
"roll_link"
/>
<axis
xyz=
"0 1 0"
/>
<anchor
xyz=
"0 0 0"
/>
<limit
lower=
"-1.5707"
upper=
"1.5707"
effort=
"1.5"
velocity=
"10.0"
/>
<dynamics
damping=
"0.7"
/>
</joint>
<transmission
name=
"tran_roll"
>
<type>
transmission_interface/SimpleTransmission
</type>
<joint
name=
"roll"
>
<hardwareInterface>
hardware_interface/EffortJointInterface
</hardwareInterface>
</joint>
<actuator
name=
"roll_motor"
>
<hardwareInterface>
hardware_interface/EffortJointInterface
</hardwareInterface>
<mechanicalReduction>
1
</mechanicalReduction>
</actuator>
</transmission>
<link
name=
"roll_link"
>
<inertial>
<mass
value=
"0.09213256"
/>
<origin
xyz=
"-0.00487870 0.00002296 -0.02436388"
/>
<inertia
ixx=
"0.00007323"
ixy=
"-0.00000019"
ixz=
"-0.00001312"
iyy=
"0.00008152"
iyz=
"0.00000005"
izz=
"0.00002526"
/>
</inertial>
<visual>
<origin
xyz=
"0 0 0"
rpy=
"0 0 0"
/>
<geometry>
<mesh
filename=
"package://arm_description/meshes/roll2.stl"
/>
</geometry>
<material
name=
"Grey"
>
<color
rgba=
"0.4 0.4 0.4 1.0"
/>
</material>
</visual>
<collision>
<origin
xyz=
"0 0 0"
rpy=
"0 0 0"
/>
<geometry>
<mesh
filename=
"package://arm_description/meshes/roll2.stl"
/>
</geometry>
</collision>
</link>
<joint
name=
"tilt"
type=
"revolute"
>
<origin
xyz=
"0.001 -0.00171 -0.06189"
rpy=
"0 1.5707 -1.5707"
/>
<parent
link=
"roll_link"
/>
<child
link=
"tilt_link"
/>
<axis
xyz=
"0 1 0"
/>
<anchor
xyz=
"0 0 0"
/>
<limit
lower=
"-1.5707"
upper=
"1.5707"
effort=
"1.5"
velocity=
"10.0"
/>
<dynamics
damping=
"0.7"
/>
</joint>
<transmission
name=
"tran_tilt"
>
<type>
transmission_interface/SimpleTransmission
</type>
<joint
name=
"tilt"
>
<hardwareInterface>
hardware_interface/EffortJointInterface
</hardwareInterface>
</joint>
<actuator
name=
"tilt_motor"
>
<hardwareInterface>
hardware_interface/EffortJointInterface
</hardwareInterface>
<mechanicalReduction>
1
</mechanicalReduction>
</actuator>
</transmission>
<link
name=
"tilt_link"
>
<inertial>
<mass
value=
"0.00495209"
/>
<origin
xyz=
"0.01853248 0.00000000 -0.00216849"
/>
<inertia
ixx=
"0.00000178"
ixy=
"0.00000000"
ixz=
"0.00000002"
iyy=
"0.00000073"
iyz=
"0.00000000"
izz=
"0.00000205"
/>
</inertial>
<visual>
<origin
xyz=
"0 0 0"
rpy=
"0 0 0"
/>
<geometry>
<mesh
filename=
"package://arm_description/meshes/tilt2.stl"
/>
</geometry>
<material
name=
"Grey"
>
<color
rgba=
"0.4 0.4 0.4 1.0"
/>
</material>
</visual>
<collision>
<origin
xyz=
"0 0 0"
rpy=
"0 0 0"
/>
<geometry>
<mesh
filename=
"package://arm_description/meshes/tilt2.stl"
/>
</geometry>
</collision>
</link>
<xacro:arm_gazebo
robot_name=
"$(arg robot_name)"
/>
<xacro:uvc_camera
name=
"gopro"
parent=
"tilt_link"
resolution=
"low_res"
model=
"gopro"
sim_config=
"$(arg sim_config_path)/gopro_config.yaml"
>
<origin
xyz=
"0.06254 -0.01525 -0.01404"
rpy=
"3.14159 -0.78535 0"
/>
</xacro:uvc_camera>
</robot>
Write
Preview
Supports
Markdown
0%
Try again
or
attach a new file
.
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment