@@ -311,6 +311,8 @@ bool HardwareInterface::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw
311
311
js_interface_.getHandle (joint_names_[i]), &joint_position_command_[i], &speed_scaling_combined_));
312
312
svj_interface_.registerHandle (ur_controllers::ScaledJointHandle (
313
313
js_interface_.getHandle (joint_names_[i]), &joint_velocity_command_[i], &speed_scaling_combined_));
314
+
315
+ registerJointLimits (robot_hw_nh, joint_handle_position, joint_handle_velocity, joint_handle_effort, i);
314
316
}
315
317
316
318
speedsc_interface_.registerHandle (
@@ -391,6 +393,142 @@ bool HardwareInterface::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw
391
393
return true ;
392
394
}
393
395
396
+ void HardwareInterface::registerJointLimits (ros::NodeHandle& robot_hw_nh,
397
+ const hardware_interface::JointHandle& joint_handle_position,
398
+ const hardware_interface::JointHandle& joint_handle_velocity,
399
+ const hardware_interface::JointHandle& joint_handle_effort,
400
+ std::size_t joint_id)
401
+ {
402
+ // Default values
403
+ joint_position_lower_limits_[joint_id] = -std::numeric_limits<double >::max ();
404
+ joint_position_upper_limits_[joint_id] = std::numeric_limits<double >::max ();
405
+ joint_velocity_limits_[joint_id] = std::numeric_limits<double >::max ();
406
+ joint_effort_limits_[joint_id] = std::numeric_limits<double >::max ();
407
+
408
+ // Limits datastructures
409
+ joint_limits_interface::JointLimits joint_limits; // Position
410
+ joint_limits_interface::SoftJointLimits soft_limits; // Soft Position
411
+ bool has_joint_limits = false ;
412
+ bool has_soft_limits = false ;
413
+
414
+ // Get limits from URDF
415
+ if (urdf_model_ == NULL )
416
+ {
417
+ ROS_WARN_STREAM (" No URDF model loaded, unable to get joint limits" );
418
+ return ;
419
+ }
420
+
421
+ // Get limits from URDF
422
+ urdf::JointConstSharedPtr urdf_joint = urdf_model_->getJoint (joint_names_[joint_id]);
423
+
424
+ // Get main joint limits
425
+ if (urdf_joint == NULL )
426
+ {
427
+ ROS_ERROR_STREAM (" URDF joint not found " << joint_names_[joint_id]);
428
+ return ;
429
+ }
430
+
431
+ // Get limits from URDF
432
+ if (joint_limits_interface::getJointLimits (urdf_joint, joint_limits))
433
+ {
434
+ has_joint_limits = true ;
435
+ ROS_DEBUG_STREAM (" Joint " << joint_names_[joint_id] << " has URDF position limits [" << joint_limits.min_position
436
+ << " , " << joint_limits.max_position << " ]" );
437
+ if (joint_limits.has_velocity_limits )
438
+ ROS_DEBUG_STREAM (" Joint " << joint_names_[joint_id] << " has URDF velocity limit [" << joint_limits.max_velocity
439
+ << " ]" );
440
+ }
441
+ else
442
+ {
443
+ if (urdf_joint->type != urdf::Joint::CONTINUOUS)
444
+ ROS_WARN_STREAM (" Joint " << joint_names_[joint_id]
445
+ << " does not have a URDF "
446
+ " position limit" );
447
+ }
448
+
449
+ // Get limits from ROS param
450
+ if (joint_limits_interface::getJointLimits (joint_names_[joint_id], robot_hw_nh, joint_limits))
451
+ {
452
+ has_joint_limits = true ;
453
+ ROS_DEBUG_STREAM (" Joint " << joint_names_[joint_id] << " has rosparam position limits ["
454
+ << joint_limits.min_position << " , " << joint_limits.max_position << " ]" );
455
+ if (joint_limits.has_velocity_limits )
456
+ ROS_DEBUG_STREAM (" Joint " << joint_names_[joint_id] << " has rosparam velocity limit ["
457
+ << joint_limits.max_velocity << " ]" );
458
+ } // the else debug message provided internally by joint_limits_interface
459
+
460
+ // Get soft limits from URDF
461
+ if (joint_limits_interface::getSoftJointLimits (urdf_joint, soft_limits))
462
+ {
463
+ has_soft_limits = true ;
464
+ ROS_DEBUG_STREAM (" Joint " << joint_names_[joint_id] << " has soft joint limits." );
465
+ }
466
+ else
467
+ {
468
+ ROS_DEBUG_STREAM (" Joint " << joint_names_[joint_id]
469
+ << " does not have soft joint "
470
+ " limits" );
471
+ }
472
+
473
+ // Quit we we haven't found any limits in URDF or rosparam server
474
+ if (!has_joint_limits)
475
+ {
476
+ return ;
477
+ }
478
+
479
+ // Copy position limits if available
480
+ if (joint_limits.has_position_limits )
481
+ {
482
+ // Slighly reduce the joint limits to prevent floating point errors
483
+ joint_limits.min_position += std::numeric_limits<double >::epsilon ();
484
+ joint_limits.max_position -= std::numeric_limits<double >::epsilon ();
485
+
486
+ joint_position_lower_limits_[joint_id] = joint_limits.min_position ;
487
+ joint_position_upper_limits_[joint_id] = joint_limits.max_position ;
488
+ }
489
+
490
+ // Copy velocity limits if available
491
+ if (joint_limits.has_velocity_limits )
492
+ {
493
+ joint_velocity_limits_[joint_id] = joint_limits.max_velocity ;
494
+ }
495
+
496
+ // Copy effort limits if available
497
+ if (joint_limits.has_effort_limits )
498
+ {
499
+ joint_effort_limits_[joint_id] = joint_limits.max_effort ;
500
+ }
501
+
502
+ if (has_soft_limits) // Use soft limits
503
+ {
504
+ ROS_DEBUG_STREAM (" Using soft saturation limits" );
505
+ const joint_limits_interface::PositionJointSoftLimitsHandle soft_handle_position (joint_handle_position,
506
+ joint_limits, soft_limits);
507
+ pos_jnt_soft_interface_.registerHandle (soft_handle_position);
508
+ const joint_limits_interface::VelocityJointSoftLimitsHandle soft_handle_velocity (joint_handle_velocity,
509
+ joint_limits, soft_limits);
510
+ vel_jnt_soft_interface_.registerHandle (soft_handle_velocity);
511
+ const joint_limits_interface::EffortJointSoftLimitsHandle soft_handle_effort (joint_handle_effort, joint_limits,
512
+ soft_limits);
513
+ eff_jnt_soft_interface_.registerHandle (soft_handle_effort);
514
+ }
515
+ else // Use saturation limits
516
+ {
517
+ ROS_DEBUG_STREAM (" Using saturation limits (not soft limits)" );
518
+
519
+ const joint_limits_interface::PositionJointSaturationHandle sat_handle_position (joint_handle_position,
520
+ joint_limits);
521
+ pos_jnt_sat_interface_.registerHandle (sat_handle_position);
522
+
523
+ const joint_limits_interface::VelocityJointSaturationHandle sat_handle_velocity (joint_handle_velocity,
524
+ joint_limits);
525
+ vel_jnt_sat_interface_.registerHandle (sat_handle_velocity);
526
+
527
+ const joint_limits_interface::EffortJointSaturationHandle sat_handle_effort (joint_handle_effort, joint_limits);
528
+ eff_jnt_sat_interface_.registerHandle (sat_handle_effort);
529
+ }
530
+ }
531
+
394
532
template <typename T>
395
533
void HardwareInterface::readData (const std::unique_ptr<rtde_interface::DataPackage>& data_pkg,
396
534
const std::string& var_name, T& data)
@@ -528,10 +666,14 @@ void HardwareInterface::write(const ros::Time& time, const ros::Duration& period
528
666
{
529
667
if (position_controller_running_)
530
668
{
669
+ pos_jnt_soft_interface_.enforceLimits (period);
670
+ pos_jnt_sat_interface_.enforceLimits (period);
531
671
ur_driver_->writeJointCommand (joint_position_command_, comm::ControlMode::MODE_SERVOJ);
532
672
}
533
673
else if (velocity_controller_running_)
534
674
{
675
+ vel_jnt_soft_interface_.enforceLimits (period);
676
+ vel_jnt_sat_interface_.enforceLimits (period);
535
677
ur_driver_->writeJointCommand (joint_velocity_command_, comm::ControlMode::MODE_SPEEDJ);
536
678
}
537
679
else
0 commit comments