Skip to content

Commit

Permalink
Merge pull request #193 in SWDEV/franka_ros from fix/gazebo-torque-th…
Browse files Browse the repository at this point in the history
…resholds-parameter to develop

* commit '2a14287d579571060d343ec76ea51d214a28ac62':
  FIX: Read force threshold from correct parameter
  • Loading branch information
gollth committed Jun 14, 2022
2 parents 442867c + 2a14287 commit ce87eb1
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions franka_gazebo/src/franka_hw_sim.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -464,9 +464,9 @@ bool FrankaHWSim::readParameters(const ros::NodeHandle& nh, const urdf::Model& u
"upper_torque_thresholds_nominal", nh, {20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0});

this->lower_force_thresholds_nominal_ = franka_hw::FrankaHW::getCollisionThresholds(
"lower_torque_thresholds_nominal", nh, {20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0});
"lower_force_thresholds_nominal", nh, {20.0, 20.0, 20.0, 25.0, 25.0, 25.0});
this->upper_force_thresholds_nominal_ = franka_hw::FrankaHW::getCollisionThresholds(
"upper_torque_thresholds_nominal", nh, {20.0, 20.0, 20.0, 25.0, 25.0, 25.0});
"upper_force_thresholds_nominal", nh, {20.0, 20.0, 20.0, 25.0, 25.0, 25.0});

for (int i = 0; i < 7; i++) {
std::string name = this->arm_id_ + "_joint" + std::to_string(i + 1);
Expand Down

0 comments on commit ce87eb1

Please sign in to comment.