Skip to content
This repository was archived by the owner on Mar 28, 2025. It is now read-only.

Commit 708423d

Browse files
Add support for getting PID parameters from loaded parameters (#374) (#376)
Co-authored-by: Christoph Fröhlich <[email protected]> Co-authored-by: Alejandro Hernández Cordero <[email protected]> (cherry picked from commit 6a4cc84) Co-authored-by: Sai Kishor Kothakota <[email protected]>
1 parent 798b9e9 commit 708423d

File tree

6 files changed

+357
-50
lines changed

6 files changed

+357
-50
lines changed

doc/index.rst

+35
Original file line numberDiff line numberDiff line change
@@ -189,6 +189,30 @@ Where the parameters are as follows:
189189

190190
The same definitions apply to the ``vel_*`` parameters.
191191

192+
The PID parameters can be defined for ``position`` or ``position_pid`` and ``velocity`` or ``velocity_pid`` command interfaces as explained above, or defining them in a YAML file and loading it in the ``gazebo_ros2_control`` plugin as below:
193+
194+
.. code-block:: yaml
195+
196+
gazebo_ros2_control:
197+
ros__parameters:
198+
pid_gains:
199+
position_pid: # (or) position
200+
slider_to_cart: {kp: 100.0, kd: 10.0, ki: 1.0, max_integral_error: 10000.0}
201+
202+
.. code-block:: xml
203+
204+
<gazebo>
205+
<plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
206+
...
207+
<ros>
208+
<argument>--ros-args</argument>
209+
<argument>--params-file</argument>
210+
<argument>Path to the configuration file</argument>
211+
</ros>
212+
</plugin>
213+
</gazebo>
214+
215+
192216
Add the gazebo_ros2_control plugin
193217
==========================================
194218

@@ -392,10 +416,21 @@ The following examples shows a vertical cart control by a PID joint using positi
392416

393417
.. code-block:: shell
394418
419+
ros2 launch gazebo_ros2_control_demos vertical_cart_example_position_pids_in_yaml.launch.py
395420
ros2 launch gazebo_ros2_control_demos vertical_cart_example_position_pid.launch.py
396421
ros2 launch gazebo_ros2_control_demos vertical_cart_example_velocity_pid.launch.py
397422
398423
.. code-block:: shell
399424
400425
ros2 run gazebo_ros2_control_demos example_position_pid
401426
ros2 run gazebo_ros2_control_demos example_velocity
427+
428+
The ``vertical_cart_example_position_pids_in_yaml.launch.py`` example uses a YAML file as following to set the PID gains:
429+
430+
.. code-block:: yaml
431+
432+
gazebo_ros2_control:
433+
ros__parameters:
434+
pid_gains:
435+
position:
436+
slider_to_cart: {kp: 100.0, kd: 10.0, ki: 1.0, max_integral_error: 10000.0}

gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system.hpp

+6-3
Original file line numberDiff line numberDiff line change
@@ -90,9 +90,12 @@ class GazeboSystem : public GazeboSystemInterface
9090
const hardware_interface::HardwareInfo & hardware_info,
9191
gazebo::physics::ModelPtr parent_model);
9292

93-
control_toolbox::Pid extractPID(
94-
std::string prefix,
95-
hardware_interface::ComponentInfo joint_info);
93+
bool extractPID(
94+
const std::string & prefix,
95+
const hardware_interface::ComponentInfo & joint_info, control_toolbox::Pid & pid);
96+
97+
bool extractPIDFromParameters(
98+
const std::string & control_mode, const std::string & joint_name, control_toolbox::Pid & pid);
9699

97100
/// \brief Private data class
98101
std::unique_ptr<GazeboSystemPrivate> dataPtr;

gazebo_ros2_control/src/gazebo_system.cpp

+135-47
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,7 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15+
#include <cmath>
1516
#include <limits>
1617
#include <map>
1718
#include <memory>
@@ -119,6 +120,12 @@ class gazebo_ros2_control::GazeboSystemPrivate
119120

120121
// Should hold the joints if no control_mode is active
121122
bool hold_joints_ = true;
123+
124+
// Current position and velocity control method
125+
GazeboSystemInterface::ControlMethod_ position_control_method_ =
126+
GazeboSystemInterface::ControlMethod_::POSITION;
127+
GazeboSystemInterface::ControlMethod_ velocity_control_method_ =
128+
GazeboSystemInterface::ControlMethod_::VELOCITY;
122129
};
123130

124131
namespace gazebo_ros2_control
@@ -166,7 +173,8 @@ bool GazeboSystem::initSim(
166173
this->nh_->get_logger(), "Using default value: " << this->dataPtr->hold_joints_);
167174
}
168175
RCLCPP_DEBUG_STREAM(
169-
this->nh_->get_logger(), "hold_joints (system): " << this->dataPtr->hold_joints_ << std::endl);
176+
this->nh_->get_logger(),
177+
"hold_joints (system): " << std::boolalpha << this->dataPtr->hold_joints_ << std::endl);
170178

171179
registerJoints(hardware_info, parent_model);
172180
registerSensors(hardware_info, parent_model);
@@ -179,9 +187,9 @@ bool GazeboSystem::initSim(
179187
return true;
180188
}
181189

182-
control_toolbox::Pid GazeboSystem::extractPID(
183-
std::string prefix,
184-
hardware_interface::ComponentInfo joint_info)
190+
bool GazeboSystem::extractPID(
191+
const std::string & prefix,
192+
const hardware_interface::ComponentInfo & joint_info, control_toolbox::Pid & pid)
185193
{
186194
double kp;
187195
double ki;
@@ -190,52 +198,127 @@ control_toolbox::Pid GazeboSystem::extractPID(
190198
double min_integral_error;
191199
bool antiwindup = false;
192200

201+
bool are_pids_set = false;
193202
if (joint_info.parameters.find(prefix + "kp") != joint_info.parameters.end()) {
194203
kp = std::stod(joint_info.parameters.at(prefix + "kp"));
204+
are_pids_set = true;
195205
} else {
196206
kp = 0.0;
197207
}
198208

199209
if (joint_info.parameters.find(prefix + "ki") != joint_info.parameters.end()) {
200210
ki = std::stod(joint_info.parameters.at(prefix + "ki"));
211+
are_pids_set = true;
201212
} else {
202213
ki = 0.0;
203214
}
204215

205216
if (joint_info.parameters.find(prefix + "kd") != joint_info.parameters.end()) {
206217
kd = std::stod(joint_info.parameters.at(prefix + "kd"));
218+
are_pids_set = true;
207219
} else {
208220
kd = 0.0;
209221
}
210222

211-
if (joint_info.parameters.find(prefix + "max_integral_error") != joint_info.parameters.end()) {
212-
max_integral_error = std::stod(joint_info.parameters.at(prefix + "max_integral_error"));
213-
} else {
214-
max_integral_error = std::numeric_limits<double>::max();
215-
}
223+
if (are_pids_set) {
224+
if (joint_info.parameters.find(prefix + "max_integral_error") != joint_info.parameters.end()) {
225+
max_integral_error = std::stod(joint_info.parameters.at(prefix + "max_integral_error"));
226+
} else {
227+
max_integral_error = std::numeric_limits<double>::max();
228+
}
216229

217-
if (joint_info.parameters.find(prefix + "min_integral_error") != joint_info.parameters.end()) {
218-
min_integral_error = std::stod(joint_info.parameters.at(prefix + "min_integral_error"));
219-
} else {
220-
min_integral_error = std::numeric_limits<double>::min();
221-
}
230+
if (joint_info.parameters.find(prefix + "min_integral_error") != joint_info.parameters.end()) {
231+
min_integral_error = std::stod(joint_info.parameters.at(prefix + "min_integral_error"));
232+
} else {
233+
min_integral_error = std::numeric_limits<double>::min();
234+
}
222235

223-
if (joint_info.parameters.find(prefix + "antiwindup") != joint_info.parameters.end()) {
224-
if (joint_info.parameters.at(prefix + "antiwindup") == "true" ||
225-
joint_info.parameters.at(prefix + "antiwindup") == "True")
226-
{
227-
antiwindup = true;
236+
if (joint_info.parameters.find(prefix + "antiwindup") != joint_info.parameters.end()) {
237+
if (joint_info.parameters.at(prefix + "antiwindup") == "true" ||
238+
joint_info.parameters.at(prefix + "antiwindup") == "True")
239+
{
240+
antiwindup = true;
241+
}
228242
}
243+
244+
RCLCPP_INFO_STREAM(
245+
this->nh_->get_logger(),
246+
"Setting kp = " << kp << "\t"
247+
<< " ki = " << ki << "\t"
248+
<< " kd = " << kd << "\t"
249+
<< " max_integral_error = " << max_integral_error << "\t"
250+
<< "antiwindup =" << std::boolalpha << antiwindup);
251+
252+
pid.initPid(kp, ki, kd, max_integral_error, min_integral_error, antiwindup);
229253
}
254+
return are_pids_set;
255+
}
230256

231-
RCLCPP_INFO_STREAM(
232-
this->nh_->get_logger(),
233-
"Setting kp = " << kp << "\t"
234-
<< " ki = " << ki << "\t"
235-
<< " kd = " << kd << "\t"
236-
<< " max_integral_error = " << max_integral_error);
237257

238-
return control_toolbox::Pid(kp, ki, kd, max_integral_error, min_integral_error, antiwindup);
258+
bool GazeboSystem::extractPIDFromParameters(
259+
const std::string & control_mode, const std::string & joint_name,
260+
control_toolbox::Pid & pid)
261+
{
262+
const std::string parameter_prefix = "pid_gains." + control_mode + "." + joint_name;
263+
auto get_pid_entry = [this, parameter_prefix](const std::string & entry, double & value) -> bool {
264+
try {
265+
// Check if the parameter is declared, if not, declare the default value NaN
266+
if (!this->nh_->has_parameter(parameter_prefix + "." + entry)) {
267+
this->nh_->declare_parameter<double>(
268+
parameter_prefix + "." + entry,
269+
std::numeric_limits<double>::quiet_NaN());
270+
}
271+
value = this->nh_->get_parameter(parameter_prefix + "." + entry).as_double();
272+
} catch (rclcpp::exceptions::ParameterNotDeclaredException & ex) {
273+
RCLCPP_ERROR(
274+
this->nh_->get_logger(),
275+
"Parameter '%s' not declared, with error %s", entry.c_str(), ex.what());
276+
return false;
277+
} catch (rclcpp::exceptions::InvalidParameterTypeException & ex) {
278+
RCLCPP_ERROR(
279+
this->nh_->get_logger(),
280+
"Parameter '%s' has wrong type: %s", entry.c_str(), ex.what());
281+
return false;
282+
}
283+
return std::isfinite(value);
284+
};
285+
bool are_pids_set = true;
286+
double kp, ki, kd, max_integral_error, min_integral_error;
287+
bool antiwindup;
288+
are_pids_set &= get_pid_entry("kp", kp);
289+
are_pids_set &= get_pid_entry("ki", ki);
290+
are_pids_set &= get_pid_entry("kd", kd);
291+
if (are_pids_set) {
292+
get_pid_entry("max_integral_error", max_integral_error);
293+
get_pid_entry("min_integral_error", min_integral_error);
294+
const std::string antiwindup_str = "antiwindup";
295+
if (!this->nh_->has_parameter(parameter_prefix + "." + antiwindup_str)) {
296+
this->nh_->declare_parameter(
297+
parameter_prefix + "." + antiwindup_str,
298+
false);
299+
}
300+
try {
301+
antiwindup = this->nh_->get_parameter(parameter_prefix + "." + antiwindup_str).as_bool();
302+
} catch (rclcpp::exceptions::ParameterNotDeclaredException & ex) {
303+
RCLCPP_ERROR(
304+
this->nh_->get_logger(),
305+
"Parameter '%s' not declared, with error %s", antiwindup_str.c_str(), ex.what());
306+
} catch (rclcpp::ParameterTypeException & ex) {
307+
RCLCPP_ERROR(
308+
this->nh_->get_logger(),
309+
"Parameter '%s' has wrong type: %s", antiwindup_str.c_str(), ex.what());
310+
}
311+
RCLCPP_INFO_STREAM(
312+
this->nh_->get_logger(),
313+
"Setting kp = " << kp << "\t"
314+
<< " ki = " << ki << "\t"
315+
<< " kd = " << kd << "\t"
316+
<< " max_integral_error = " << max_integral_error << "\t"
317+
<< "antiwindup =" << std::boolalpha << antiwindup << " from node parameters");
318+
pid.initPid(kp, ki, kd, max_integral_error, min_integral_error, antiwindup);
319+
}
320+
321+
return are_pids_set;
239322
}
240323

241324
void GazeboSystem::registerJoints(
@@ -260,7 +343,7 @@ void GazeboSystem::registerJoints(
260343

261344
for (unsigned int j = 0; j < this->dataPtr->n_dof_; j++) {
262345
auto & joint_info = hardware_info.joints[j];
263-
std::string joint_name = this->dataPtr->joint_names_[j] = joint_info.name;
346+
const std::string joint_name = this->dataPtr->joint_names_[j] = joint_info.name;
264347

265348
gazebo::physics::JointPtr simjoint = parent_model->GetJoint(joint_name);
266349
this->dataPtr->sim_joints_.push_back(simjoint);
@@ -377,20 +460,24 @@ void GazeboSystem::registerJoints(
377460
if (has_already_registered_pos) {
378461
RCLCPP_ERROR_STREAM(
379462
this->nh_->get_logger(),
380-
"can't have position and position"
381-
<< "pid command_interface at same time !!!");
463+
"can't have position and position_pid"
464+
<< "command_interface at same time !!!");
382465
continue;
383466
}
384467
has_already_registered_pos = true;
385468
RCLCPP_INFO_STREAM(
386469
this->nh_->get_logger(), "\t\t "
387470
<< joint_info.command_interfaces[i].name);
388471

389-
if (joint_info.command_interfaces[i].name == "position_pid") {
390-
this->dataPtr->is_pos_pid[j] = true;
391-
this->dataPtr->pos_pid[j] = this->extractPID(POSITION_PID_PARAMS_PREFIX, joint_info);
392-
} else {
393-
this->dataPtr->is_pos_pid[j] = false;
472+
this->dataPtr->is_pos_pid[j] = this->extractPID(
473+
POSITION_PID_PARAMS_PREFIX, joint_info,
474+
this->dataPtr->pos_pid[j]) || this->extractPIDFromParameters(
475+
joint_info.command_interfaces[i].name, joint_name, this->dataPtr->pos_pid[j]);
476+
477+
if (this->dataPtr->is_pos_pid[j]) {
478+
RCLCPP_INFO_STREAM(
479+
this->nh_->get_logger(), "Found position PIDs for joint: " << joint_name << "!");
480+
this->dataPtr->position_control_method_ = POSITION_PID;
394481
}
395482

396483
this->dataPtr->command_interfaces_.emplace_back(
@@ -420,10 +507,17 @@ void GazeboSystem::registerJoints(
420507
this->nh_->get_logger(), "\t\t "
421508
<< joint_info.command_interfaces[i].name);
422509

423-
if (joint_info.command_interfaces[i].name == "velocity_pid") {
424-
this->dataPtr->is_vel_pid[j] = true;
425-
this->dataPtr->vel_pid[j] = this->extractPID(VELOCITY_PID_PARAMS_PREFIX, joint_info);
510+
this->dataPtr->is_vel_pid[j] = this->extractPID(
511+
VELOCITY_PID_PARAMS_PREFIX, joint_info,
512+
this->dataPtr->vel_pid[j]) || this->extractPIDFromParameters(
513+
joint_info.command_interfaces[i].name, joint_name, this->dataPtr->vel_pid[j]);
514+
515+
if (this->dataPtr->is_vel_pid[j]) {
516+
RCLCPP_INFO_STREAM(
517+
this->nh_->get_logger(), "Found velocity PIDs for joint: " << joint_name << "!");
518+
this->dataPtr->velocity_control_method_ = VELOCITY_PID;
426519
}
520+
427521
this->dataPtr->command_interfaces_.emplace_back(
428522
joint_name + suffix,
429523
hardware_interface::HW_IF_VELOCITY,
@@ -657,19 +751,13 @@ GazeboSystem::perform_command_mode_switch(
657751
if (interface_name ==
658752
(this->dataPtr->joint_names_[j] + "/" + hardware_interface::HW_IF_POSITION))
659753
{
660-
if (!this->dataPtr->is_pos_pid[j]) {
661-
this->dataPtr->joint_control_methods_[j] |= POSITION;
662-
} else {
663-
this->dataPtr->joint_control_methods_[j] |= POSITION_PID;
664-
}
754+
this->dataPtr->joint_control_methods_[j] |=
755+
static_cast<ControlMethod_>(this->dataPtr->position_control_method_);
665756
} else if (interface_name == // NOLINT
666757
(this->dataPtr->joint_names_[j] + "/" + hardware_interface::HW_IF_VELOCITY))
667758
{
668-
if (!this->dataPtr->is_vel_pid[j]) {
669-
this->dataPtr->joint_control_methods_[j] |= VELOCITY;
670-
} else {
671-
this->dataPtr->joint_control_methods_[j] |= VELOCITY_PID;
672-
}
759+
this->dataPtr->joint_control_methods_[j] |=
760+
static_cast<ControlMethod_>(this->dataPtr->velocity_control_method_);
673761
} else if (interface_name == // NOLINT
674762
(this->dataPtr->joint_names_[j] + "/" + hardware_interface::HW_IF_EFFORT))
675763
{
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,20 @@
1+
controller_manager:
2+
ros__parameters:
3+
update_rate: 100 # Hz
4+
5+
position_controller:
6+
type: position_controllers/JointGroupPositionController
7+
8+
joint_state_broadcaster:
9+
type: joint_state_broadcaster/JointStateBroadcaster
10+
11+
position_controller:
12+
ros__parameters:
13+
joints:
14+
- slider_to_cart
15+
16+
gazebo_ros2_control:
17+
ros__parameters:
18+
pid_gains:
19+
position:
20+
slider_to_cart: {kp: 100.0, kd: 10.0, ki: 1.0, max_integral_error: 10000.0}

0 commit comments

Comments
 (0)