From: Nick Lamprianidis Date: Thu, 6 Aug 2020 10:55:10 +0000 (+0200) Subject: Use SetParam for effort limit X-Git-Tag: 0.1.0~2^2 X-Git-Url: http://git.ece.ufrgs.br/?a=commitdiff_plain;h=632620101e89cedc4c277c9c0a893af14300ab7c;p=roboticsgroup_upatras_gazebo_plugins.git Use SetParam for effort limit --- diff --git a/src/mimic_joint_plugin.cpp b/src/mimic_joint_plugin.cpp index ca53e2f..7c06232 100644 --- a/src/mimic_joint_plugin.cpp +++ b/src/mimic_joint_plugin.cpp @@ -132,7 +132,7 @@ namespace gazebo { // Set max effort if (!has_pid_) { #if GAZEBO_MAJOR_VERSION > 2 - mimic_joint_->SetEffortLimit(0, max_effort_); + mimic_joint_->SetParam("fmax", 0, max_effort_); #else mimic_joint_->SetMaxForce(0, max_effort_); #endif