diff --git a/franka_gazebo/include/franka_gazebo/joint.h b/franka_gazebo/include/franka_gazebo/joint.h index 3770f5372..f900d92e6 100644 --- a/franka_gazebo/include/franka_gazebo/joint.h +++ b/franka_gazebo/include/franka_gazebo/joint.h @@ -67,6 +67,11 @@ struct Joint { /// be controlled. ControlMethod control_method = POSITION; + /// The currently CLAMPED applied command from the controller acting on this joint either in \f$N\f$ or + /// \f$Nm\f$ without gravity. + /// NOTE: Clamped to zero when the joint is in its limits. + double clamped_command = 0; + /// The currently acting gravity force or torque acting on this joint in \f$N\f$ or \f$Nm\f$ double gravity = 0; diff --git a/franka_gazebo/src/franka_hw_sim.cpp b/franka_gazebo/src/franka_hw_sim.cpp index 68d84eb11..747716504 100644 --- a/franka_gazebo/src/franka_hw_sim.cpp +++ b/franka_gazebo/src/franka_hw_sim.cpp @@ -585,7 +585,9 @@ void FrankaHWSim::updateRobotState(ros::Time time) { } if (this->robot_initialized_) { - double tau_ext = joint->effort - joint->command + joint->gravity; + // NOTE: Here we use the clamped command to filter out the internal controller + // force when the joint is in its limits. + 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 d733539db..847f66971 100644 --- a/franka_gazebo/src/joint.cpp +++ b/franka_gazebo/src/joint.cpp @@ -50,6 +50,13 @@ void Joint::update(const ros::Duration& dt) { } this->jerk = (this->acceleration - this->lastAcceleration) / dt.toSec(); this->lastAcceleration = this->acceleration; + + // Store the clamped command + // NOTE: Clamped to zero when joint is in its joint limits. + this->clamped_command = + (this->position > this->limits.min_position && this->position < this->limits.max_position) + ? this->command + : 0.0; } double Joint::getLinkMass() const { @@ -64,10 +71,10 @@ double Joint::getLinkMass() const { } bool Joint::isInCollision() const { - return std::abs(this->effort - this->command) > this->collision_threshold; + return std::abs(this->effort - this->clamped_command + this->gravity) > this->collision_threshold; } bool Joint::isInContact() const { - return std::abs(this->effort - this->command) > this->contact_threshold; + return std::abs(this->effort - this->clamped_command + this->gravity) > this->contact_threshold; } } // namespace franka_gazebo