-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathrobot.urdf.xacro
More file actions
103 lines (76 loc) · 3.37 KB
/
robot.urdf.xacro
File metadata and controls
103 lines (76 loc) · 3.37 KB
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
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro"
name="robot">
<!-- MODELS -->
<xacro:include filename="$(find vito_description)/model/materials.urdf"/>
<xacro:include filename="$(find soft_hand_description)/model/soft_hand.urdf.xacro"/>
<!-- joint properties -->
<xacro:property name="pris_lb" value="-3" />
<xacro:property name="pris_ub" value="3" />
<xacro:property name="rev_lb" value="0" />
<xacro:property name="rev_ub" value="360" />
<xacro:property name="pris_eff" value="100" />
<xacro:property name="pris_vel" value="100" />
<xacro:property name="rev_eff" value="100" />
<xacro:property name="rev_vel" value="100" />
<link name="world" />
<link name="floating_base_link_trasl_x" />
<link name="floating_base_link_trasl_y" />
<link name="floating_base_link_trasl_z" />
<link name="floating_base_link_rot_x" />
<link name="floating_base_link_rot_y" />
<link name="floating_base_link_rot_z" />
<!-- FLOATING BASE -->
<joint name="floating_base_joint_trasl_x" type="prismatic">
<origin xyz="0 0 0" rpy="0 0 0" />
<parent link="world"/>
<child link="floating_base_link_trasl_x"/>
<axis xyz="1 0 0" />
<limit lower="${pris_lb}" upper="${pris_ub}" effort="${pris_eff}" velocity="${pris_vel}"/>
</joint>
<joint name="floating_base_joint_trasl_y" type="prismatic">
<origin xyz="0 0 0" rpy="0 0 0" />
<parent link="floating_base_link_trasl_x"/>
<child link="floating_base_link_trasl_y"/>
<axis xyz="0 1 0" />
<limit lower="${pris_lb}" upper="${pris_ub}" effort="${pris_eff}" velocity="${pris_vel}"/>
</joint>
<joint name="floating_base_joint_trasl_z" type="prismatic">
<origin xyz="0 0 0" rpy="0 0 0" />
<parent link="floating_base_link_trasl_y"/>
<child link="floating_base_link_trasl_z"/>
<axis xyz="0 0 1" />
<limit lower="${pris_lb}" upper="${pris_ub}" effort="${pris_eff}" velocity="${pris_vel}"/>
</joint>
<joint name="floating_base_joint_rot_x" type="revolute">
<origin xyz="0 0 0" rpy="0 0 0" />
<parent link="floating_base_link_trasl_z"/>
<child link="floating_base_link_rot_x"/>
<axis xyz="1 0 0" />
<limit lower="${rev_lb *pi/180}" upper="${rev_ub *pi/180}" effort="${rev_eff}" velocity="${rev_vel}"/>
</joint>
<joint name="floating_base_joint_rot_y" type="revolute">
<origin xyz="0 0 0" rpy="0 0 0" />
<parent link="floating_base_link_rot_x"/>
<child link="floating_base_link_rot_y"/>
<axis xyz="0 1 0" />
<limit lower="${rev_lb *pi/180}" upper="${rev_ub *pi/180}" effort="${rev_eff}" velocity="${rev_vel}"/>
</joint>
<joint name="floating_base_joint_rot_z" type="revolute">
<origin xyz="0 0 0" rpy="0 0 0" />
<parent link="floating_base_link_rot_y"/>
<child link="floating_base_link_rot_z"/>
<axis xyz="0 0 1" />
<limit lower="${rev_lb *pi/180}" upper="${rev_ub *pi/180}" effort="${rev_eff}" velocity="${rev_vel}"/>
</joint>
<!-- don t work
<joint name="floating_base_joint" type="floating">
<origin xyz="0 0 1" rpy="0 0 0"/>
<parent link="world"/>
<child link="floating_base_link"/>
</joint>
<link name="floating_base_link" /> -->
<xacro:soft_hand parent="floating_base_link_rot_z" name="right_hand" left="false" withAdaptiveTransmission="true" useMimicTag="true">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:soft_hand>
</robot>