Skip to content

Add support for ros_control joint limits? #198

Open
@gavanderhoorn

Description

@gavanderhoorn

Summary

The current implementation of the hardware_interface does not seem to register any joint limit interfaces:

// Create ros_control interfaces
for (std::size_t i = 0; i < joint_positions_.size(); ++i)
{
ROS_DEBUG_STREAM("Registering handles for joint " << joint_names_[i]);
// Create joint state interface for all joints
js_interface_.registerHandle(hardware_interface::JointStateHandle(joint_names_[i], &joint_positions_[i],
&joint_velocities_[i], &joint_efforts_[i]));
// Create joint position control interface
pj_interface_.registerHandle(
hardware_interface::JointHandle(js_interface_.getHandle(joint_names_[i]), &joint_position_command_[i]));
vj_interface_.registerHandle(
hardware_interface::JointHandle(js_interface_.getHandle(joint_names_[i]), &joint_velocity_command_[i]));
spj_interface_.registerHandle(ur_controllers::ScaledJointHandle(
js_interface_.getHandle(joint_names_[i]), &joint_position_command_[i], &speed_scaling_combined_));
svj_interface_.registerHandle(ur_controllers::ScaledJointHandle(
js_interface_.getHandle(joint_names_[i]), &joint_velocity_command_[i], &speed_scaling_combined_));
}
speedsc_interface_.registerHandle(
ur_controllers::SpeedScalingHandle("speed_scaling_factor", &speed_scaling_combined_));
fts_interface_.registerHandle(hardware_interface::ForceTorqueSensorHandle(
"wrench", tf_prefix_ + "tool0_controller", fts_measurements_.begin(), fts_measurements_.begin() + 3));
robot_status_interface_.registerHandle(industrial_robot_status_interface::IndustrialRobotStatusHandle(
"industrial_robot_status_handle", robot_status_resource_));
// Register interfaces
registerInterface(&js_interface_);
registerInterface(&spj_interface_);
registerInterface(&pj_interface_);
registerInterface(&vj_interface_);
registerInterface(&svj_interface_);
registerInterface(&speedsc_interface_);
registerInterface(&fts_interface_);
registerInterface(&robot_status_interface_);

It's unclear whether this is by design or an oversight.

Earlier issue in ur_modern_driver: ros-industrial-attic/ur_modern_driver#249.

Versions

All versions.

Impact

Currently nothing for me personally. But a user expecting to be able to set more conservative limits on their robot motions by setting the appropriate values on the ROS parameter server will not be able to affect motion execution, as the driver doesn't load nor enforce them.

Issue details

As the robot controller itself already adheres to the relevant safety standards, not having limits enforced in the driver is not really a safety risk (and even if it were: ros_control is not safety-rated).

At this point it affects user experience more than anything I believe.

Steps to Reproduce

  • update the .launch file to load joint limits on the parameter server
  • start the driver
  • try to command motion clearly violating a specific (ie: more conservative) limit

Expected Behavior

As ros_control implements saturation mostly, saturated velocity profiles (fi).

Actual Behavior

No limiting.

Workaround Suggestion

Reducing the slider on the TP, but that does not allow individual limits to be set, nor does it support any units. It's just a percentage of maximum performance.

Alternative: configuring reduced limits on the UR controller, but this is invisible to the ROS side.

Metadata

Metadata

Assignees

Labels

Type

No type

Projects

No projects

Milestone

No milestone

Relationships

None yet

Development

No branches or pull requests

Issue actions