Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add support for ros_control joint limits? #198

Open
gavanderhoorn opened this issue Jun 16, 2020 · 6 comments
Open

Add support for ros_control joint limits? #198

gavanderhoorn opened this issue Jun 16, 2020 · 6 comments
Assignees
Labels
enhancement New feature or request wrid20

Comments

@gavanderhoorn
Copy link
Contributor

gavanderhoorn commented Jun 16, 2020

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.

@gavanderhoorn
Copy link
Contributor Author

I noticed this as I was working on aligning the joint limits files in the new ur_description (like this one) with the ros_control/MoveIt style.

Doing that would allow reuse of those limits files, instead of needing to maintain a few separate ones.

@fmauch
Copy link
Collaborator

fmauch commented Jun 16, 2020

Yes, this was never prioritized enough to tackle this. I fully agree

@gavanderhoorn
Copy link
Contributor Author

Related: ros-industrial/universal_robot#510.

@hsd-dev
Copy link

hsd-dev commented Jul 7, 2020

@fmauch could you please assign this to me?

@hsd-dev
Copy link

hsd-dev commented Jul 7, 2020

HardwareInterface class doesn't use urdf::Model object at the moment. Is that left out on purpose? I can read the limits only from the joint_limits.yaml and ignore the ones from URDF file altogether if that's the case. In any case, the values in yaml file will override the ones in URDF.

@hsd-dev
Copy link

hsd-dev commented Jul 7, 2020

[WIP] #223

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
enhancement New feature or request wrid20
Projects
None yet
Development

No branches or pull requests

4 participants