12
12
// See the License for the specific language governing permissions and
13
13
// limitations under the License.
14
14
15
+ #include < cmath>
15
16
#include < limits>
16
17
#include < map>
17
18
#include < memory>
@@ -119,6 +120,12 @@ class gazebo_ros2_control::GazeboSystemPrivate
119
120
120
121
// Should hold the joints if no control_mode is active
121
122
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;
122
129
};
123
130
124
131
namespace gazebo_ros2_control
@@ -166,7 +173,8 @@ bool GazeboSystem::initSim(
166
173
this ->nh_ ->get_logger (), " Using default value: " << this ->dataPtr ->hold_joints_ );
167
174
}
168
175
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);
170
178
171
179
registerJoints (hardware_info, parent_model);
172
180
registerSensors (hardware_info, parent_model);
@@ -179,9 +187,9 @@ bool GazeboSystem::initSim(
179
187
return true ;
180
188
}
181
189
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 )
185
193
{
186
194
double kp;
187
195
double ki;
@@ -190,52 +198,127 @@ control_toolbox::Pid GazeboSystem::extractPID(
190
198
double min_integral_error;
191
199
bool antiwindup = false ;
192
200
201
+ bool are_pids_set = false ;
193
202
if (joint_info.parameters .find (prefix + " kp" ) != joint_info.parameters .end ()) {
194
203
kp = std::stod (joint_info.parameters .at (prefix + " kp" ));
204
+ are_pids_set = true ;
195
205
} else {
196
206
kp = 0.0 ;
197
207
}
198
208
199
209
if (joint_info.parameters .find (prefix + " ki" ) != joint_info.parameters .end ()) {
200
210
ki = std::stod (joint_info.parameters .at (prefix + " ki" ));
211
+ are_pids_set = true ;
201
212
} else {
202
213
ki = 0.0 ;
203
214
}
204
215
205
216
if (joint_info.parameters .find (prefix + " kd" ) != joint_info.parameters .end ()) {
206
217
kd = std::stod (joint_info.parameters .at (prefix + " kd" ));
218
+ are_pids_set = true ;
207
219
} else {
208
220
kd = 0.0 ;
209
221
}
210
222
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
+ }
216
229
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
+ }
222
235
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
+ }
228
242
}
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);
229
253
}
254
+ return are_pids_set;
255
+ }
230
256
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);
237
257
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;
239
322
}
240
323
241
324
void GazeboSystem::registerJoints (
@@ -260,7 +343,7 @@ void GazeboSystem::registerJoints(
260
343
261
344
for (unsigned int j = 0 ; j < this ->dataPtr ->n_dof_ ; j++) {
262
345
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 ;
264
347
265
348
gazebo::physics::JointPtr simjoint = parent_model->GetJoint (joint_name);
266
349
this ->dataPtr ->sim_joints_ .push_back (simjoint);
@@ -377,20 +460,24 @@ void GazeboSystem::registerJoints(
377
460
if (has_already_registered_pos) {
378
461
RCLCPP_ERROR_STREAM (
379
462
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 !!!" );
382
465
continue ;
383
466
}
384
467
has_already_registered_pos = true ;
385
468
RCLCPP_INFO_STREAM (
386
469
this ->nh_ ->get_logger (), " \t\t "
387
470
<< joint_info.command_interfaces [i].name );
388
471
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;
394
481
}
395
482
396
483
this ->dataPtr ->command_interfaces_ .emplace_back (
@@ -420,10 +507,17 @@ void GazeboSystem::registerJoints(
420
507
this ->nh_ ->get_logger (), " \t\t "
421
508
<< joint_info.command_interfaces [i].name );
422
509
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;
426
519
}
520
+
427
521
this ->dataPtr ->command_interfaces_ .emplace_back (
428
522
joint_name + suffix,
429
523
hardware_interface::HW_IF_VELOCITY,
@@ -657,19 +751,13 @@ GazeboSystem::perform_command_mode_switch(
657
751
if (interface_name ==
658
752
(this ->dataPtr ->joint_names_ [j] + " /" + hardware_interface::HW_IF_POSITION))
659
753
{
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_ );
665
756
} else if (interface_name == // NOLINT
666
757
(this ->dataPtr ->joint_names_ [j] + " /" + hardware_interface::HW_IF_VELOCITY))
667
758
{
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_ );
673
761
} else if (interface_name == // NOLINT
674
762
(this ->dataPtr ->joint_names_ [j] + " /" + hardware_interface::HW_IF_EFFORT))
675
763
{
0 commit comments