diff --git a/CHANGELOG.md b/CHANGELOG.md index 4a075741f..f8971dd42 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -14,6 +14,7 @@ Requires `libfranka` >= 0.8.0 * `franka_description`: `` macro now supports to customize the `parent` frame and its `xyz` + `rpy` offset * `franka_hw`: Fix the bug where the previous controller is still running after switching the controller. ([#326](https://github.com/frankaemika/franka_ros/issues/326)) * `franka_gazebo`: Add `set_franka_model_configuration` service. + * `franka_gazebo`: Fix external torque calculation by accounting for internal joint limits ## 0.10.1 - 2022-09-15 diff --git a/franka_gazebo/include/franka_gazebo/joint.h b/franka_gazebo/include/franka_gazebo/joint.h index b301e8b7d..90c52d3ed 100644 --- a/franka_gazebo/include/franka_gazebo/joint.h +++ b/franka_gazebo/include/franka_gazebo/joint.h @@ -55,6 +55,10 @@ struct Joint { /// \f$Nm\f$ without gravity double command = 0; + /// The clamped applied command from a controller acting on this joint either in \f$N\f$ or + /// \f$Nm\f$ without gravity. Set to zero when joint command is saturated due to joint limits. + double clamped_command = 0; + /// The current desired position that is used for the PID controller when the joints control /// method is "POSITION". When the control method is not "POSITION", this value will only be /// updated once at the start of the controller and stay the same until a new controller is diff --git a/franka_gazebo/src/franka_hw_sim.cpp b/franka_gazebo/src/franka_hw_sim.cpp index fb80907b2..49f324e1f 100644 --- a/franka_gazebo/src/franka_hw_sim.cpp +++ b/franka_gazebo/src/franka_hw_sim.cpp @@ -679,7 +679,8 @@ void FrankaHWSim::updateRobotState(ros::Time time) { } if (this->robot_initialized_) { - double tau_ext = joint->effort - joint->command + joint->gravity; + // NOTE: Use clamped_command to account for internal joint saturation. + double tau_ext = joint->effort - joint->clamped_command + joint->gravity; // Exponential moving average filter from tau_ext -> tau_ext_hat_filtered this->robot_state_.tau_ext_hat_filtered[i] = diff --git a/franka_gazebo/src/joint.cpp b/franka_gazebo/src/joint.cpp index 919dc3292..c8d81a565 100644 --- a/franka_gazebo/src/joint.cpp +++ b/franka_gazebo/src/joint.cpp @@ -59,6 +59,12 @@ void Joint::update(const ros::Duration& dt) { } this->jerk = (this->acceleration - this->lastAcceleration) / dt.toSec(); this->lastAcceleration = this->acceleration; + + /// Store the clamped command, clamped to zero when joint is at its limits. + this->clamped_command = + (this->position > this->limits.min_position && this->position < this->limits.max_position) + ? this->command + : 0.0; } double Joint::getDesiredPosition(const franka::RobotMode& mode) const { @@ -114,11 +120,13 @@ double Joint::getLinkMass() const { } bool Joint::isInCollision() const { - return std::abs(this->effort - this->command) > this->collision_threshold; + // NOTE: Clamped_command used to handle internal collisions. + return std::abs(this->effort - this->clamped_command) > this->collision_threshold; } bool Joint::isInContact() const { - return std::abs(this->effort - this->command) > this->contact_threshold; + // NOTE: Clamped_command used to handle internal contacts. + return std::abs(this->effort - this->clamped_command) > this->contact_threshold; } void Joint::setJointPosition(const double joint_position) {