Support all PID gain parameters, dynamic_reconfigure
authorMartin Günther <martin.guenther@dfki.de>
Wed, 24 Jan 2018 16:46:21 +0000 (17:46 +0100)
committerMartin Günther <martin.guenther@dfki.de>
Wed, 24 Jan 2018 16:46:21 +0000 (17:46 +0100)
This change does the following:

* the PID controllers will read all PID gain parameters (p, i, d, i_clamp, antiwindup, publish_state, ...)
* a warning will be printed if none of those parameters could be found
* it's possible to adjust the parameters using dynamic_reconfigure

src/mimic_joint_plugin.cpp

index 1050624..90a5ba3 100644 (file)
@@ -85,13 +85,7 @@ namespace gazebo {
             has_pid_ = true;
 
             const ros::NodeHandle nh(model_nh, std::string(robot_namespace_ + "/gazebo_ros_control/pid_gains/") + mimic_joint_name_);
-            double p, i, d;
-            // TO-DO: include i_clamp e.t.c.
-            nh.param("p", p, 0.0);
-            nh.param("i", i, 0.0);
-            nh.param("d", d, 0.0);
-
-            pid_ = control_toolbox::Pid(p, i, d);
+            pid_.init(nh);
         }
 
         // Check for multiplier element