-
Notifications
You must be signed in to change notification settings - Fork 36
/
wrist.transmission.xacro
58 lines (52 loc) · 2.52 KB
/
wrist.transmission.xacro
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
<?xml version="1.0"?>
<!--
Copyright (c) 2015, PAL Robotics, S.L.
All rights reserved.
This work is licensed under the Creative Commons Attribution-NonCommercial-NoDerivs 3.0 Unported License.
To view a copy of this license, visit http://creativecommons.org/licenses/by-nc-nd/3.0/ or send a letter to
Creative Commons, 444 Castro Street, Suite 900, Mountain View, California, 94041, USA.
-->
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<!--File includes-->
<xacro:include filename="$(find tiago_description_calibration)/urdf/calibration/calibration_constants.urdf.xacro" />
<xacro:macro name="wrist_simple_transmission" params="name number reduction" >
<transmission name="${name}_${number}_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="${name}_${number}_motor" >
<mechanicalReduction>${reduction}</mechanicalReduction>
</actuator>
<joint name="${name}_${number}_joint">
<offset>${arm_5_joint_offset}</offset>
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
</transmission>
</xacro:macro>
<xacro:macro name="wrist_differential_transmission"
params="name number_1 number_2 act_reduction_1 act_reduction_2 jnt_reduction_1 jnt_reduction_2" >
<transmission name="wrist_trans">
<type>transmission_interface/DifferentialTransmission</type>
<actuator name="${name}_${number_1}_motor">
<role>actuator1</role>
<mechanicalReduction>${act_reduction_1}</mechanicalReduction>
</actuator>
<actuator name="${name}_${number_2}_motor">
<role>actuator2</role>
<mechanicalReduction>${act_reduction_2}</mechanicalReduction>
</actuator>
<joint name="${name}_${number_1}_joint">
<role>joint1</role>
<offset>${arm_6_joint_offset}</offset>
<mechanicalReduction>${jnt_reduction_1}</mechanicalReduction>
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<ignoreTransmissionAbsoluteEncoder>1</ignoreTransmissionAbsoluteEncoder>
</joint>
<joint name="${name}_${number_2}_joint">
<role>joint2</role>
<offset>${arm_7_joint_offset}</offset>
<mechanicalReduction>${jnt_reduction_2}</mechanicalReduction>
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<ignoreTransmissionAbsoluteEncoder>1</ignoreTransmissionAbsoluteEncoder>
</joint>
</transmission>
</xacro:macro>
</robot>