Hey @Rocky_Shao !
Great work with the thread. I’ve been following a very similar path regarding data collection: I’ve embedded the ‘CheatCode’ logic as a custom teleoperator bridge within the LeRobot framework.
Like you, I found that manual teleoperation with a keyboard or spacemouse is just too tricky for this level of precision. Using the expert policy (CheatCode) to generate the demonstrations inside LeRobot is a complete game-changer for getting clean, synchronized data to train policy models.
While refining my data collection pipeline, I’ve been digging into the Force/Torque (F/T) sensor data. After seeing your latest comment, I felt encouraged to share some of my findings with you in case they are useful for your own setup, especially regarding the safety scoring and Sim-to-Real transition.
I noticed that the /fts_broadcaster/wrench topic provides raw, uncompensated sensor data. Even after calling the tare service, this specific topic continues to broadcast the raw values (including the gravity bias). To ensure that the policy model receives a zero-centered signal, I modified aic_robot_aic_controller.py to subscribe to the wrench topic and manually apply the bias compensation using the fts_tare_offset from the controller state.
Here is a snippet of how I’m handling data in the get_observation method to ensure the AI sees 0.0N at the beginning.
# Extracting the clean net force by subtracting the tare offset
raw_wrist_wrench = self.last_wrist_wrench.wrench
tare_offset = self.last_controller_state.fts_tare_offset
controller_state_obs: ObservationState = {
# ... other state fields ...
"wrist_wrench.force.x": raw_wrist_wrench.force.x - tare_offset.wrench.force.x,
"wrist_wrench.force.y": raw_wrist_wrench.force.y - tare_offset.wrench.force.y,
"wrist_wrench.force.z": raw_wrist_wrench.force.z - tare_offset.wrench.force.z,
"wrist_wrench.torque.x": raw_wrist_wrench.torque.x - tare_offset.wrench.torque.x,
"wrist_wrench.torque.y": raw_wrist_wrench.torque.y - tare_offset.wrench.torque.y,
"wrist_wrench.torque.z": raw_wrist_wrench.torque.z - tare_offset.wrench.torque.z,
}
Mastering the “Sense of Touch”: F/T Sensor Calibration
In high-precision insertion tasks, the Force/Torque (F/T) sensor acts as the robot’s nervous system. However, sensors are rarely “pure”—they are heavily influenced by gravity and the weight of the tooling.
1. Gravity Bias (Default State)
Upon launching the simulation, the robot inherits the physical weight of the Robotiq Hand-E gripper (~1.1kg) and the attached cable. The sensor registers this mass as a constant force on the Z-axis.
pixi run ros2 topic echo /observations --once
Figure 1: Initial controller state. The fts_tare_offset field is empty (zero), meaning the system is delivering “raw” uncompensated values.
2. Deep Dive: The Physics Behind the 20 Newtons
To an external observer, seeing 20N of force while moving through mid-air looks like an error, but it is actually elementary physics. The Axia80 sensor is located at the wrist; therefore, everything “hanging” from it is detected according to Newton’s Second Law:
F = m \cdot g
Where:
- m (Total Tool Mass):
- Robotiq Hand-E Gripper: 1.1 kg
- Coupling and sensor housing: ~0.4 kg
- Flexible cable and SFP/SC connector: ~0.5 kg
- Total Mass \approx 2.0 \, kg
- g (Gravity): \approx 9.81 \, m/s^2
The Calculation:
2.0 \, kg \times 9.81 \, m/s^2 \approx \mathbf{19.62 \, N}
This figure matches our Rerun telemetry almost perfectly (~20N). The sensor is not broken; it is simply doing its job: weighing the robot’s hand.
As a result, we observe a “Gravity Ghost” in the telemetry. Training an AI with this data is like trying to weigh flour on a scale that already has a brick sitting on it.
Figure 2: Visualization of “Raw Force.” Training a model with this bias would make the AI dependent on specific tool weights, hindering Sim-to-Real transfer.
3. The Intervention: Active Calibration (Tare)
To ensure our AI learns to recognize actual contact instead of gravity, we must perform a “Zero-Reset” or Tare. This is achieved by invoking the controller’s hardware service:
pixi run ros2 service call /aic_controller/tare_force_torque_sensor std_srvs/srv/Trigger {}
# Response:
# std_srvs.srv.Trigger_Response(
# success=True, message='Successfully tared force torque sensor.')
Figure 3: System response after the calibration command. The controller captures the current weight and stores it as an internal negative bias.
4. Results: High-Fidelity Tactile Sensing
Following calibration, the fts_tare_offset is updated with the tool’s “gravity footprint.” The robot now automatically subtracts this weight from the real-time stream.
What do we see now?
- 0.0N Baseline: The robot registers zero while moving through the air.
- Negative Pressure: As the robot descends and touches the board, the force drops into negative values (e.g., -10N). In this coordinate system, this indicates compression (the connector pushing against the port).
Figure 4: Final Telemetry. The peaks and valleys now represent pure physical interactions. This is the “Gold Standard” data required to train robust ACT models.
5. Closing the “Sim-to-Real Gap”
This step is the key for Phase 3 (Physical Workcell):
- Weight Discrepancies: In simulation, a cable weighs exactly what the URDF file defines. In the real world, cable tension, manufacturing tolerances, or dust can slightly alter the weight.
- Robustness Strategy: If we trained the AI to expect exactly 20.68N in the air, it would fail on a physical robot that registers 21.20N.
- Conclusion: By using the Tare service, the policy becomes “weight-agnostic.” It focuses solely on the Net Contact Force. The AI will see identical data whether it is running in Gazebo or on the real factory floor.
Hope this helps! Looking forward to your next update and seeing your advances.
Regards!