Skip to content

Commit 57d334c

Browse files
Ajay Gunalanclaude
andcommitted
feat: Implement complex F/T sensor chain with realistic meshes and fix topic compatibility
🤖 Generated with [Claude Code](https://claude.ai/code) Co-Authored-By: Claude <noreply@anthropic.com>
1 parent 73225a2 commit 57d334c

File tree

5 files changed

+85
-29
lines changed

5 files changed

+85
-29
lines changed

ur_simulation_gz/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,7 @@ option(
1010
OFF
1111
)
1212

13-
install(DIRECTORY config launch urdf worlds
13+
install(DIRECTORY config launch urdf worlds meshes
1414
DESTINATION share/${PROJECT_NAME}
1515
)
1616

ur_simulation_gz/launch/ur_sim_control.launch.py

Lines changed: 2 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -200,12 +200,9 @@ def launch_setup(context, *args, **kwargs):
200200
name="ft_sensor_bridge",
201201
output="screen",
202202
arguments=[
203-
"/force_torque@geometry_msgs/msg/WrenchStamped[gz.msgs.Wrench"
204-
],
205-
remappings=[
206-
# Remap to F_P_P_raw for compatibility with calibration node
207-
("/force_torque", "/F_P_P_raw")
203+
"/netft/raw_sensor@geometry_msgs/msg/WrenchStamped[gz.msgs.Wrench"
208204
]
205+
# No remapping needed - direct topic from Gazebo sensor
209206
)
210207

211208
nodes_to_start = [
2.72 MB
Binary file not shown.
521 KB
Binary file not shown.

ur_simulation_gz/urdf/ur_ft_sensor.xacro

Lines changed: 82 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -2,60 +2,119 @@
22
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
33

44
<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">
1233
<visual>
13-
<origin xyz="0 0 0.05" rpy="0 0 0"/>
1434
<geometry>
15-
<cylinder radius="0.04" length="0.1"/>
35+
<mesh filename="file://$(find ur_simulation_gz)/meshes/visual/ati_netft_gamma.stl" />
1636
</geometry>
17-
<material name="blue">
18-
<color rgba="0.2 0.2 0.8 1.0"/>
19-
</material>
37+
<material name="visual_grey" />
2038
</visual>
2139
<collision>
22-
<origin xyz="0 0 0.05" rpy="0 0 0"/>
2340
<geometry>
24-
<cylinder radius="0.04" length="0.1"/>
41+
<cylinder length="${sensor_length}" radius="${sensor_collision_radius}" />
2542
</geometry>
43+
<origin xyz="0 0 ${sensor_dip+(sensor_length/2)}" rpy="0 0 0" />
2644
</collision>
2745
</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"/>
2854

2955
<!-- 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 -->
3157
<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"/>
3460
<origin xyz="0 0 0" rpy="0 0 0"/> <!-- No rotation - ATI sign fix in software -->
3561
<axis xyz="0 0 1"/>
3662
<limit lower="0" upper="0" effort="1000" velocity="0"/>
3763
<dynamics damping="100.0" friction="100.0"/>
3864
</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" />
3994

4095
<!-- Gazebo Force/Torque Sensor Plugin -->
41-
<!-- Sensor measures forces at the tool joint -->
96+
<!-- Sensor measures forces between sensor output and probe -->
4297
<gazebo reference="${prefix}ft_sensor_joint">
4398
<sensor name="${prefix}tcp_fts_sensor" type="force_torque">
4499
<always_on>true</always_on>
45100
<update_rate>100</update_rate> <!-- 100 Hz update rate -->
46101
<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>
49104
<force_torque>
50105
<frame>child</frame> <!-- Measure in child (tool) frame -->
51106
<measure_direction>parent_to_child</measure_direction>
52107
</force_torque>
53108
</sensor>
54109
</gazebo>
55110

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>
59118
</gazebo>
60119
</xacro:macro>
61120

0 commit comments

Comments
 (0)