1
0
mirror of https://gitlab.com/obbart/universal_robots_ros_driver.git synced 2026-04-12 11:00:47 +02:00

moved service definition to seperate package

This commit is contained in:
Tristan Schnell
2019-08-05 15:50:07 +02:00
parent 82bb4bd8ff
commit 2980c19a40
7 changed files with 268 additions and 16 deletions

View File

@@ -25,18 +25,10 @@ find_package(catkin REQUIRED
trajectory_msgs
ur_controllers
ur_msgs
message_generation
ur_rtde_msgs
)
find_package(Boost REQUIRED)
## Generate services in the 'srv' folder
add_service_files(
FILES
SetSpeedSlider.srv
)
generate_messages()
catkin_package(
INCLUDE_DIRS
include
@@ -58,7 +50,7 @@ catkin_package(
ur_controllers
ur_msgs
std_srvs
message_runtime
ur_rtde_msgs
DEPENDS
Boost
)

View File

@@ -47,7 +47,7 @@
#include <ur_controllers/scaled_joint_command_interface.h>
#include "ur_rtde_driver/ur/ur_driver.h"
#include "ur_rtde_driver/SetSpeedSlider.h"
#include "ur_rtde_msgs/SetSpeedSlider.h"
namespace ur_driver
{
@@ -112,7 +112,7 @@ protected:
void readBitsetData(const std::unique_ptr<rtde_interface::DataPackage>& data_pkg, const std::string& var_name,
std::bitset<N>& data);
bool setSpeedSlider(ur_rtde_driver::SetSpeedSliderRequest& req, ur_rtde_driver::SetSpeedSliderResponse& res);
bool setSpeedSlider(ur_rtde_msgs::SetSpeedSliderRequest& req, ur_rtde_msgs::SetSpeedSliderResponse& res);
bool setIO(ur_msgs::SetIORequest& req, ur_msgs::SetIOResponse& res);
std::unique_ptr<UrDriver> ur_driver_;

View File

@@ -19,7 +19,6 @@
<buildtool_depend>catkin</buildtool_depend>
<build_depend>boost</build_depend>
<build_depend>message_generation</build_depend>
<depend>actionlib</depend>
<depend>control_msgs</depend>
@@ -36,6 +35,7 @@
<depend>ur_controllers</depend>
<depend>ur_msgs</depend>
<depend>std_srvs</depend>
<depend>ur_rtde_msgs</depend>
<exec_depend>force_torque_sensor_controller</exec_depend>
<exec_depend>joint_state_controller</exec_depend>
@@ -44,7 +44,6 @@
<exec_depend>socat</exec_depend>
<exec_depend>ur_description</exec_depend>
<exec_depend>velocity_controllers</exec_depend>
<exec_depend>message_runtime</exec_depend>
<export>
<rosdoc config="rosdoc.yaml" />

View File

@@ -537,8 +537,8 @@ bool HardwareInterface::stopControl(std_srvs::TriggerRequest& req, std_srvs::Tri
return true;
}
bool HardwareInterface::setSpeedSlider(ur_rtde_driver::SetSpeedSliderRequest& req,
ur_rtde_driver::SetSpeedSliderResponse& res)
bool HardwareInterface::setSpeedSlider(ur_rtde_msgs::SetSpeedSliderRequest& req,
ur_rtde_msgs::SetSpeedSliderResponse& res)
{
if (req.data >= 0.01 && req.data <= 1.0 && ur_driver_ != nullptr)
{

View File

@@ -1,3 +0,0 @@
float64 data
---
bool success