Use SetParam for effort limit
authorNick Lamprianidis <nlamprian@gmail.com>
Thu, 6 Aug 2020 10:55:10 +0000 (12:55 +0200)
committerNick Lamprianidis <nlamprian@gmail.com>
Thu, 6 Aug 2020 10:55:10 +0000 (12:55 +0200)
src/mimic_joint_plugin.cpp

index ca53e2f..7c06232 100644 (file)
@@ -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