mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 18:10:47 +02:00
added separate speed_scaling handle and controller
In theory that handle could be used to also set the speed_scaling, done by the controller. However, this is not yet implemented.
This commit is contained in:
@@ -72,14 +72,14 @@ bool HardwareInterface ::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_h
|
||||
js_interface_.getHandle(joint_names_[i]), &joint_position_command_[i], &speed_scaling_combined_));
|
||||
}
|
||||
|
||||
// speedsc_interface_.registerHandle(
|
||||
// ur_controllers::SpeedScalingHandle("speed_scaling_factor", &speed_scaling_combined_));
|
||||
speedsc_interface_.registerHandle(
|
||||
ur_controllers::SpeedScalingHandle("speed_scaling_factor", &speed_scaling_combined_));
|
||||
|
||||
// Register interfaces
|
||||
registerInterface(&js_interface_);
|
||||
registerInterface(&spj_interface_);
|
||||
// registerInterface(&pj_interface_);
|
||||
// registerInterface(&speedsc_interface_);
|
||||
registerInterface(&speedsc_interface_);
|
||||
|
||||
ROS_INFO_STREAM_NAMED("hardware_interface", "Loaded ur_rtde_driver hardware_interface");
|
||||
|
||||
|
||||
Reference in New Issue
Block a user