From 7743c79f6d86bf28c2de108f814e85451464a615 Mon Sep 17 00:00:00 2001 From: Felix Mauch Date: Wed, 15 May 2019 16:43:16 +0200 Subject: [PATCH] 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. --- ur_rtde_driver/launch/ur10_ros_control.launch | 2 +- ur_rtde_driver/src/ros/hardware_interface.cpp | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/ur_rtde_driver/launch/ur10_ros_control.launch b/ur_rtde_driver/launch/ur10_ros_control.launch index 5a67b19..445d971 100644 --- a/ur_rtde_driver/launch/ur10_ros_control.launch +++ b/ur_rtde_driver/launch/ur10_ros_control.launch @@ -16,7 +16,7 @@ - + diff --git a/ur_rtde_driver/src/ros/hardware_interface.cpp b/ur_rtde_driver/src/ros/hardware_interface.cpp index e7143da..bf214d4 100644 --- a/ur_rtde_driver/src/ros/hardware_interface.cpp +++ b/ur_rtde_driver/src/ros/hardware_interface.cpp @@ -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");