diff --git a/ur_rtde_driver/CMakeLists.txt b/ur_rtde_driver/CMakeLists.txt index 5a698fd..c522c8b 100644 --- a/ur_rtde_driver/CMakeLists.txt +++ b/ur_rtde_driver/CMakeLists.txt @@ -25,7 +25,6 @@ find_package(catkin REQUIRED trajectory_msgs ur_controllers ur_msgs - ur_rtde_msgs ) find_package(Boost REQUIRED) @@ -50,7 +49,6 @@ catkin_package( ur_controllers ur_msgs std_srvs - ur_rtde_msgs DEPENDS Boost ) diff --git a/ur_rtde_driver/include/ur_rtde_driver/ros/hardware_interface.h b/ur_rtde_driver/include/ur_rtde_driver/ros/hardware_interface.h index 33f5d68..4f3654a 100644 --- a/ur_rtde_driver/include/ur_rtde_driver/ros/hardware_interface.h +++ b/ur_rtde_driver/include/ur_rtde_driver/ros/hardware_interface.h @@ -43,12 +43,12 @@ #include #include #include +#include "ur_msgs/SetSpeedSliderFraction.h" #include #include #include "ur_rtde_driver/ur/ur_driver.h" -#include "ur_rtde_msgs/SetSpeedSlider.h" namespace ur_driver { @@ -113,7 +113,7 @@ protected: void readBitsetData(const std::unique_ptr& data_pkg, const std::string& var_name, std::bitset& data); - bool setSpeedSlider(ur_rtde_msgs::SetSpeedSliderRequest& req, ur_rtde_msgs::SetSpeedSliderResponse& res); + bool setSpeedSlider(ur_msgs::SetSpeedSliderFractionRequest& req, ur_msgs::SetSpeedSliderFractionResponse& res); bool setIO(ur_msgs::SetIORequest& req, ur_msgs::SetIOResponse& res); void commandCallback(const std_msgs::StringConstPtr& msg); diff --git a/ur_rtde_driver/package.xml b/ur_rtde_driver/package.xml index 76da1f0..b69aa00 100644 --- a/ur_rtde_driver/package.xml +++ b/ur_rtde_driver/package.xml @@ -35,7 +35,6 @@ ur_controllers ur_msgs std_srvs - ur_rtde_msgs force_torque_sensor_controller joint_state_controller diff --git a/ur_rtde_driver/src/ros/hardware_interface.cpp b/ur_rtde_driver/src/ros/hardware_interface.cpp index 5da8180..e14e0ca 100644 --- a/ur_rtde_driver/src/ros/hardware_interface.cpp +++ b/ur_rtde_driver/src/ros/hardware_interface.cpp @@ -538,12 +538,12 @@ bool HardwareInterface::stopControl(std_srvs::TriggerRequest& req, std_srvs::Tri return true; } -bool HardwareInterface::setSpeedSlider(ur_rtde_msgs::SetSpeedSliderRequest& req, - ur_rtde_msgs::SetSpeedSliderResponse& res) +bool HardwareInterface::setSpeedSlider(ur_msgs::SetSpeedSliderFractionRequest& req, + ur_msgs::SetSpeedSliderFractionResponse& res) { - if (req.data >= 0.01 && req.data <= 1.0 && ur_driver_ != nullptr) + if (req.speed_slider_fraction >= 0.01 && req.speed_slider_fraction <= 1.0 && ur_driver_ != nullptr) { - res.success = ur_driver_->getRTDEWriter().sendSpeedSlider(req.data); + res.success = ur_driver_->getRTDEWriter().sendSpeedSlider(req.speed_slider_fraction); } else {