unitreerobotics / unitree_ros

BSD 3-Clause "New" or "Revised" License
463 stars 224 forks source link

Reimplement `computeTorque()` for Accurate B1 Motor Simulation #89

Open paulblum opened 4 months ago

paulblum commented 4 months ago

Description:

This pull request addresses issue #66, which identifies the clamping of joint torque commands to ±55 Nm by UnitreeJointController. This limitation hinders the accurate simulation of B1 motors, which have ±140 Nm capability.

The impact is evident in the following visualizations, where B1 is commanded to trot in place:

b1_default b1_default
B1 attempting to trot in Gazebo Torque clamping to 55 Nm

Problem:

The issue lies in UnitreeJointController's usage (line 180, below) of the computeTorque() function from unitree_ros/unitree_legged_control/lib, which inadvertently clamps its output to ±55 Nm.

https://github.com/unitreerobotics/unitree_ros/blob/67ac2124494e93af87d34d6e53ef9060dbf9c923/unitree_legged_control/src/joint_controller.cpp#L178-L181

Notably, this clamping is redundant, as the joint torque computation is already clamped to URDF specifications (line 181, above) by the effortLimits() function.

Solution:

This pull request proposes the removal of the ±55 Nm clamp from computeTorque(), introducing the following implementation:

calcTorque = servoCmd.torque + servoCmd.posStiffness*(servoCmd.pos - currentPos)
    + servoCmd.velStiffness*(servoCmd.vel - currentVel);

Rationale:

This modification allows for the utilization of UnitreeJointController to accurately simulate B1 control, while preserving its original functionality for smaller quadrupeds.

b1_updated b1_updated
B1 trotting in Gazebo via updated code Update enables accurate B1 torque computation
a1_updated a1_updated
A1 trotting in Gazebo via updated code Update maintains identical torque computation in the [-55,55] Nm range