Skip to content

Commit

Permalink
fix(franka_gazebo): fix external torque calculation
Browse files Browse the repository at this point in the history
This commit ensures that the internal controller forces are not used in
the external torque (i.e. `tau_ext`) calculation when a joint is in its
limit.
  • Loading branch information
rickstaa committed Sep 1, 2023
1 parent d439fc7 commit cbc6c4f
Show file tree
Hide file tree
Showing 4 changed files with 17 additions and 3 deletions.
1 change: 1 addition & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@ Requires `libfranka` >= 0.8.0
* `franka_gazebo`: `FrankaHWSim` only acts on joints belonging to a Franka robot. This allows to combine a Franka robot and others (like mobile platforms) in same URDF ([#313](https://github.com/frankaemika/franka_ros/issues/313))
* `franka_description`: `<xacro:franka_robot/>` 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`: Fix `tau_ext` calculation by accounting for internal joint limits

## 0.10.1 - 2022-09-15

Expand Down
4 changes: 4 additions & 0 deletions franka_gazebo/include/franka_gazebo/joint.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
3 changes: 2 additions & 1 deletion franka_gazebo/src/franka_hw_sim.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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] =
Expand Down
12 changes: 10 additions & 2 deletions franka_gazebo/src/joint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,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 {
Expand Down Expand Up @@ -105,10 +111,12 @@ 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;
}
} // namespace franka_gazebo

0 comments on commit cbc6c4f

Please sign in to comment.