|
4 | 4 | <xacro:arg name="use_fake_hardware" default="false"/>
|
5 | 5 | <xacro:arg name="use_manipulation_controllers" default="false"/>
|
6 | 6 |
|
7 |
| - <!-- Franka Arm Xacro (without the comments) --> |
8 |
| - <xacro:macro name="franka_arm" params="arm_id arm_prefix:='' no_prefix:=false description_pkg:='franka_description' connected_to:='base' xyz:='0 0 0' rpy:='0 0 0' gazebo:='false' safety_distance:=0 joint_limits inertials kinematics dynamics with_sc:=false" > |
9 |
| - |
10 |
| - <!-- Define a property that defaults to 'arm_prefix_arm_id' concatenated with an underscore if 'no_prefix' is not set --> |
11 |
| - <xacro:property name="prefix" value="${'' if no_prefix else arm_prefix + arm_id + '_'}" /> |
12 |
| - |
13 |
| - <xacro:if value="${gazebo}"> |
14 |
| - <xacro:property name="connected_to" value="" /> |
15 |
| - </xacro:if> |
16 |
| - |
17 |
| - <xacro:unless value="${not connected_to}"> |
18 |
| - <link name="${connected_to}"> |
19 |
| - </link> |
20 |
| - <joint name="${prefix}${connected_to}_joint" type="fixed"> |
21 |
| - <parent link="${connected_to}"/> |
22 |
| - <child link="${prefix}link0"/> |
23 |
| - <origin rpy="${rpy}" xyz="${xyz}"/> |
24 |
| - </joint> |
25 |
| - </xacro:unless> |
26 |
| - |
27 |
| - <xacro:link_with_sc no_prefix="${no_prefix}" name="link0" gazebo="${gazebo}" with_sc="${with_sc}"> |
28 |
| - <self_collision_geometries> |
29 |
| - <xacro:collision_capsule xyz="-0.075 0 0.06" direction="x" radius="${0.06+safety_distance}" length="0.03" /> |
30 |
| - </self_collision_geometries> |
31 |
| - </xacro:link_with_sc> |
32 |
| - |
33 |
| - <xacro:link_with_sc no_prefix="${no_prefix}" name="link1" gazebo="${gazebo}" with_sc="${with_sc}"> |
34 |
| - <self_collision_geometries> |
35 |
| - <xacro:collision_capsule xyz="0 0 -191.5e-3" radius="${0.06+safety_distance}" length="0.283" /> |
36 |
| - </self_collision_geometries> |
37 |
| - </xacro:link_with_sc> |
38 |
| - |
39 |
| - <joint name="${prefix}joint1" type="revolute"> |
40 |
| - <xacro:franka-kinematics name="joint1" config="${kinematics}" /> |
41 |
| - <parent link="${prefix}link0" /> |
42 |
| - <child link="${prefix}link1" /> |
43 |
| - <axis xyz="0 0 1" /> |
44 |
| - <xacro:franka-limits name="joint1" config="${joint_limits}" /> |
45 |
| - <xacro:franka-dynamics name="joint1" config="${dynamics}" /> |
46 |
| - </joint> |
47 |
| - |
48 |
| - <xacro:link_with_sc no_prefix="${no_prefix}" name="link2" gazebo="${gazebo}" with_sc="${with_sc}"> |
49 |
| - <self_collision_geometries> |
50 |
| - <xacro:collision_capsule xyz="0 0 0" radius="${0.06+safety_distance}" length="0.12" /> |
51 |
| - </self_collision_geometries> |
52 |
| - </xacro:link_with_sc> |
53 |
| - |
54 |
| - <joint name="${prefix}joint2" type="revolute"> |
55 |
| - <xacro:franka-kinematics name="joint2" config="${kinematics}" /> |
56 |
| - <parent link="${prefix}link1" /> |
57 |
| - <child link="${prefix}link2" /> |
58 |
| - <axis xyz="0 0 1" /> |
59 |
| - <xacro:franka-limits name="joint2" config="${joint_limits}" /> |
60 |
| - <xacro:franka-dynamics name="joint2" config="${dynamics}" /> |
61 |
| - </joint> |
62 |
| - |
63 |
| - <xacro:link_with_sc no_prefix="${no_prefix}" name="link3" gazebo="${gazebo}" with_sc="${with_sc}"> |
64 |
| - <self_collision_geometries> |
65 |
| - <xacro:collision_capsule xyz="0 0 -0.145" radius="${0.06+safety_distance}" length="0.15" /> |
66 |
| - </self_collision_geometries> |
67 |
| - </xacro:link_with_sc> |
68 |
| - |
69 |
| - <joint name="${prefix}joint3" type="revolute"> |
70 |
| - <xacro:franka-kinematics name="joint3" config="${kinematics}" /> |
71 |
| - <parent link="${prefix}link2" /> |
72 |
| - <child link="${prefix}link3" /> |
73 |
| - <axis xyz="0 0 1" /> |
74 |
| - <xacro:franka-limits name="joint3" config="${joint_limits}" /> |
75 |
| - <xacro:franka-dynamics name="joint3" config="${dynamics}" /> |
76 |
| - </joint> |
77 |
| - |
78 |
| - <xacro:link_with_sc no_prefix="${no_prefix}" name="link4" gazebo="${gazebo}" with_sc="${with_sc}"> |
79 |
| - <self_collision_geometries> |
80 |
| - <xacro:collision_capsule xyz="0 0 0" radius="${0.06+safety_distance}" length="0.12" /> |
81 |
| - </self_collision_geometries> |
82 |
| - </xacro:link_with_sc> |
83 |
| - |
84 |
| - <joint name="${prefix}joint4" type="revolute"> |
85 |
| - <xacro:franka-kinematics name="joint4" config="${kinematics}" /> |
86 |
| - <parent link="${prefix}link3" /> |
87 |
| - <child link="${prefix}link4" /> |
88 |
| - <axis xyz="0 0 1" /> |
89 |
| - <xacro:franka-limits name="joint4" config="${joint_limits}" /> |
90 |
| - <xacro:franka-dynamics name="joint4" config="${dynamics}" /> |
91 |
| - </joint> |
92 |
| - |
93 |
| - <xacro:link_with_sc no_prefix="${no_prefix}" name="link5" gazebo="${gazebo}" with_sc="${with_sc}"> |
94 |
| - <self_collision_geometries> |
95 |
| - <xacro:collision_capsule xyz="0 0 -0.26" radius="${0.060+safety_distance}" length="0.10" /> |
96 |
| - <xacro:collision_capsule xyz="0 0.08 -0.13" radius="${0.025+safety_distance}" length="0.14" /> |
97 |
| - </self_collision_geometries> |
98 |
| - </xacro:link_with_sc> |
99 |
| - |
100 |
| - <joint name="${prefix}joint5" type="revolute"> |
101 |
| - <xacro:franka-kinematics name="joint5" config="${kinematics}" /> |
102 |
| - <parent link="${prefix}link4" /> |
103 |
| - <child link="${prefix}link5" /> |
104 |
| - <axis xyz="0 0 1" /> |
105 |
| - <xacro:franka-limits name="joint5" config="${joint_limits}" /> |
106 |
| - <xacro:franka-dynamics name="joint5" config="${dynamics}" /> |
107 |
| - </joint> |
108 |
| - |
109 |
| - <xacro:link_with_sc no_prefix="${no_prefix}" name="link6" gazebo="${gazebo}" with_sc="${with_sc}"> |
110 |
| - <self_collision_geometries> |
111 |
| - <xacro:collision_capsule xyz="0 0 -0.03" radius="${0.05+safety_distance}" length="0.08" /> |
112 |
| - </self_collision_geometries> |
113 |
| - </xacro:link_with_sc> |
114 |
| - |
115 |
| - <joint name="${prefix}joint6" type="revolute"> |
116 |
| - <xacro:franka-kinematics name="joint6" config="${kinematics}" /> |
117 |
| - <parent link="${prefix}link5" /> |
118 |
| - <child link="${prefix}link6" /> |
119 |
| - <axis xyz="0 0 1" /> |
120 |
| - <xacro:franka-limits name="joint6" config="${joint_limits}" /> |
121 |
| - <xacro:franka-dynamics name="joint6" config="${dynamics}" /> |
122 |
| - </joint> |
123 |
| - |
124 |
| - <xacro:link_with_sc no_prefix="${no_prefix}" name="link7" gazebo="${gazebo}" rpy="0 0 ${pi/4}" with_sc="${with_sc}"> |
125 |
| - <self_collision_geometries> |
126 |
| - <xacro:collision_capsule xyz="0 0 0.01" direction="z" radius="${0.04+safety_distance}" length="0.14" /> |
127 |
| - <xacro:collision_capsule xyz="0.06 0 0.082" direction="x" radius="${0.03+safety_distance}" length="0.01" /> |
128 |
| - </self_collision_geometries> |
129 |
| - </xacro:link_with_sc> |
130 |
| - |
131 |
| - <joint name="${prefix}joint7" type="revolute"> |
132 |
| - <xacro:franka-kinematics name="joint7" config="${kinematics}" /> |
133 |
| - <parent link="${prefix}link6"/> |
134 |
| - <child link="${prefix}link7"/> |
135 |
| - <axis xyz="0 0 1"/> |
136 |
| - <xacro:franka-limits name="joint7" config="${joint_limits}" /> |
137 |
| - <xacro:franka-dynamics name="joint7" config="${dynamics}" /> |
138 |
| - </joint> |
139 |
| - |
140 |
| - <link name="${prefix}link8"/> |
141 |
| - |
142 |
| - <joint name="${prefix}joint8" type="fixed"> |
143 |
| - <xacro:franka-kinematics name="joint8" config="${kinematics}" /> |
144 |
| - <parent link="${prefix}link7" /> |
145 |
| - <child link="${prefix}link8" /> |
146 |
| - </joint> |
147 |
| - </xacro:macro> |
148 |
| - |
149 | 7 | <!-- Franka ROS2 Control -->
|
150 | 8 | <xacro:macro name="franka_arm_ros2_control"
|
151 | 9 | params="arm_id
|
|
161 | 19 | <xacro:property name="arm_prefix_modified" value="${'' if arm_prefix == '' else arm_prefix + '_'}" />
|
162 | 20 | <ros2_control name="${arm_prefix_modified}FrankaHardwareInterface" type="system">
|
163 | 21 | <hardware>
|
| 22 | + <param name="version">0.1.0</param> |
164 | 23 | <param name="arm_id">${arm_id}</param>
|
165 | 24 | <param name="prefix">${arm_prefix}</param>
|
166 | 25 | <xacro:if value="${use_fake_hardware}">
|
|
187 | 46 |
|
188 | 47 | <xacro:macro name="configure_joint" params="joint_name initial_position">
|
189 | 48 | <joint name="${joint_name}">
|
190 |
| - <xacro:unless value="${gazebo and gazebo_effort}"> |
191 |
| - <command_interface name="position"/> |
192 |
| - <command_interface name="velocity"/> |
193 |
| - </xacro:unless> |
194 |
| - <xacro:if value="${gazebo_effort}"> |
| 49 | + <command_interface name="position"/> |
| 50 | + <command_interface name="velocity"/> |
| 51 | + <xacro:if value="${gazebo == 0 or gazebo_effort == 1}"> |
195 | 52 | <command_interface name="effort"/>
|
196 | 53 | </xacro:if>
|
197 | 54 |
|
|
239 | 96 | connected_to:='base'
|
240 | 97 | multi_arm:=false">
|
241 | 98 | <xacro:include filename="$(find franka_description)/robots/common/utils.xacro" />
|
| 99 | + <xacro:include filename="$(find franka_description)/robots/common/franka_arm.xacro" /> |
242 | 100 |
|
243 | 101 | <xacro:property name="arm_prefix_modified" value="${'' if arm_prefix == '' else arm_prefix + '_'}" />
|
244 | 102 |
|
|
0 commit comments