|
2 | 2 | <robot xmlns:xacro="http://www.ros.org/wiki/xacro"> |
3 | 3 |
|
4 | 4 | <xacro:macro name="ur_ft_sensor_gazebo" params="prefix:=''"> |
5 | | - <!-- Tool/Payload link with significant mass to generate forces --> |
6 | | - <link name="${prefix}tool_payload"> |
7 | | - <inertial> |
8 | | - <mass value="1.0"/> <!-- 1 kg tool mass --> |
9 | | - <origin xyz="0 0 0.05" rpy="0 0 0"/> <!-- Center of mass 5cm from joint --> |
10 | | - <inertia ixx="0.002" ixy="0" ixz="0" iyy="0.002" iyz="0" izz="0.001"/> |
11 | | - </inertial> |
| 5 | + <!-- ATI NET-FT Sensor Properties --> |
| 6 | + <xacro:property name="sensor_dip" value="0.003" /> |
| 7 | + <xacro:property name="sensor_length" value="0.04906" /> |
| 8 | + <xacro:property name="sensor_collision_radius" value="0.065" /> |
| 9 | + |
| 10 | + <!-- P42V Probe Properties --> |
| 11 | + <xacro:property name="p42v_collision_width" value="0.065" /> |
| 12 | + <xacro:property name="wrist_height" value="0.035" /> |
| 13 | + <xacro:property name="p42v_adapter_intrusion" value="0.020" /> |
| 14 | + <xacro:property name="p42v_cable_end" value="0.080078" /> |
| 15 | + <xacro:property name="p42v_trans_len" value="0.13859" /> |
| 16 | + <xacro:property name="p42v_collision_height" value="${wrist_height - p42v_adapter_intrusion + p42v_cable_end + p42v_trans_len}" /> |
| 17 | + |
| 18 | + <material name="visual_grey"> |
| 19 | + <color rgba="0.5 0.5 0.5 1" /> |
| 20 | + </material> |
| 21 | + |
| 22 | + <material name="visual_green"> |
| 23 | + <color rgba="0.0 1.0 0.3 1" /> |
| 24 | + </material> |
| 25 | + |
| 26 | + <!-- NET-FT Sensor Link 0 (mounting side) --> |
| 27 | + <joint name="${prefix}netft_joint0" type="fixed"> |
| 28 | + <parent link="${prefix}tool0"/> |
| 29 | + <child link="${prefix}netft_link0"/> |
| 30 | + <origin rpy="0 0 0" xyz="0 0 ${-sensor_dip}"/> |
| 31 | + </joint> |
| 32 | + <link name="${prefix}netft_link0"> |
12 | 33 | <visual> |
13 | | - <origin xyz="0 0 0.05" rpy="0 0 0"/> |
14 | 34 | <geometry> |
15 | | - <cylinder radius="0.04" length="0.1"/> |
| 35 | + <mesh filename="file://$(find ur_simulation_gz)/meshes/visual/ati_netft_gamma.stl" /> |
16 | 36 | </geometry> |
17 | | - <material name="blue"> |
18 | | - <color rgba="0.2 0.2 0.8 1.0"/> |
19 | | - </material> |
| 37 | + <material name="visual_grey" /> |
20 | 38 | </visual> |
21 | 39 | <collision> |
22 | | - <origin xyz="0 0 0.05" rpy="0 0 0"/> |
23 | 40 | <geometry> |
24 | | - <cylinder radius="0.04" length="0.1"/> |
| 41 | + <cylinder length="${sensor_length}" radius="${sensor_collision_radius}" /> |
25 | 42 | </geometry> |
| 43 | + <origin xyz="0 0 ${sensor_dip+(sensor_length/2)}" rpy="0 0 0" /> |
26 | 44 | </collision> |
27 | 45 | </link> |
| 46 | + |
| 47 | + <!-- NET-FT Sensor Link 1 (output side - massless frame) --> |
| 48 | + <joint name="${prefix}netft_joint1" type="fixed"> |
| 49 | + <origin xyz="0 0 ${sensor_dip+sensor_length}" rpy="0 0 0"/> |
| 50 | + <parent link="${prefix}netft_link0"/> |
| 51 | + <child link="${prefix}netft_link1"/> |
| 52 | + </joint> |
| 53 | + <link name="${prefix}netft_link1"/> |
28 | 54 |
|
29 | 55 | <!-- F/T measurement joint (MUST be revolute for force measurement) --> |
30 | | - <!-- Direct connection from wrist_3_link to tool_payload --> |
| 56 | + <!-- Connection from sensor output to probe with mass --> |
31 | 57 | <joint name="${prefix}ft_sensor_joint" type="revolute"> |
32 | | - <parent link="${prefix}wrist_3_link"/> |
33 | | - <child link="${prefix}tool_payload"/> |
| 58 | + <parent link="${prefix}netft_link1"/> |
| 59 | + <child link="${prefix}p42v_link0"/> |
34 | 60 | <origin xyz="0 0 0" rpy="0 0 0"/> <!-- No rotation - ATI sign fix in software --> |
35 | 61 | <axis xyz="0 0 1"/> |
36 | 62 | <limit lower="0" upper="0" effort="1000" velocity="0"/> |
37 | 63 | <dynamics damping="100.0" friction="100.0"/> |
38 | 64 | </joint> |
| 65 | + |
| 66 | + <!-- P42V Probe Link 0 (adapter with mass) --> |
| 67 | + <link name="${prefix}p42v_link0"> |
| 68 | + <inertial> |
| 69 | + <mass value="1.0"/> <!-- 1 kg tool mass --> |
| 70 | + <origin xyz="0 0 ${p42v_collision_height/2}" rpy="0 0 0"/> <!-- Center of mass at probe center --> |
| 71 | + <inertia ixx="0.002" ixy="0" ixz="0" iyy="0.002" iyz="0" izz="0.001"/> |
| 72 | + </inertial> |
| 73 | + <visual> |
| 74 | + <geometry> |
| 75 | + <mesh filename="file://$(find ur_simulation_gz)/meshes/visual/vera_p42v_adapter.stl"/> |
| 76 | + </geometry> |
| 77 | + <material name="visual_green" /> |
| 78 | + </visual> |
| 79 | + <collision> |
| 80 | + <geometry> |
| 81 | + <box size="${p42v_collision_width} ${p42v_collision_width} ${p42v_collision_height}" /> |
| 82 | + </geometry> |
| 83 | + <origin xyz="0 0 ${p42v_collision_height/2}" rpy="0 0 0" /> |
| 84 | + </collision> |
| 85 | + </link> |
| 86 | + |
| 87 | + <!-- P42V Probe Link 1 (TCP frame) --> |
| 88 | + <joint name="${prefix}p42v_joint1" type="fixed"> |
| 89 | + <origin xyz="0 0 ${p42v_collision_height}" rpy="0 0 0" /> |
| 90 | + <parent link="${prefix}p42v_link0" /> |
| 91 | + <child link="${prefix}p42v_link1" /> |
| 92 | + </joint> |
| 93 | + <link name="${prefix}p42v_link1" /> |
39 | 94 |
|
40 | 95 | <!-- Gazebo Force/Torque Sensor Plugin --> |
41 | | - <!-- Sensor measures forces at the tool joint --> |
| 96 | + <!-- Sensor measures forces between sensor output and probe --> |
42 | 97 | <gazebo reference="${prefix}ft_sensor_joint"> |
43 | 98 | <sensor name="${prefix}tcp_fts_sensor" type="force_torque"> |
44 | 99 | <always_on>true</always_on> |
45 | 100 | <update_rate>100</update_rate> <!-- 100 Hz update rate --> |
46 | 101 | <visualize>true</visualize> |
47 | | - <topic>force_torque</topic> |
48 | | - <frame>${prefix}wrist_3_link</frame> |
| 102 | + <topic>/netft/raw_sensor</topic> |
| 103 | + <frame>${prefix}p42v_link0</frame> |
49 | 104 | <force_torque> |
50 | 105 | <frame>child</frame> <!-- Measure in child (tool) frame --> |
51 | 106 | <measure_direction>parent_to_child</measure_direction> |
52 | 107 | </force_torque> |
53 | 108 | </sensor> |
54 | 109 | </gazebo> |
55 | 110 |
|
56 | | - <!-- Visual indication of tool in Gazebo --> |
57 | | - <gazebo reference="${prefix}tool_payload"> |
58 | | - <material>Gazebo/Blue</material> |
| 111 | + <!-- Visual indication in Gazebo --> |
| 112 | + <gazebo reference="${prefix}netft_link0"> |
| 113 | + <material>Gazebo/Grey</material> |
| 114 | + </gazebo> |
| 115 | + |
| 116 | + <gazebo reference="${prefix}p42v_link0"> |
| 117 | + <material>Gazebo/Green</material> |
59 | 118 | </gazebo> |
60 | 119 | </xacro:macro> |
61 | 120 |
|
|
0 commit comments