mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 01:50:46 +02:00
added custom service to set speed slider value
This commit is contained in:
@@ -25,9 +25,18 @@ find_package(catkin REQUIRED
|
|||||||
trajectory_msgs
|
trajectory_msgs
|
||||||
ur_controllers
|
ur_controllers
|
||||||
ur_msgs
|
ur_msgs
|
||||||
|
message_generation
|
||||||
)
|
)
|
||||||
find_package(Boost REQUIRED)
|
find_package(Boost REQUIRED)
|
||||||
|
|
||||||
|
## Generate services in the 'srv' folder
|
||||||
|
add_service_files(
|
||||||
|
FILES
|
||||||
|
SetSpeedSlider.srv
|
||||||
|
)
|
||||||
|
|
||||||
|
generate_messages()
|
||||||
|
|
||||||
catkin_package(
|
catkin_package(
|
||||||
INCLUDE_DIRS
|
INCLUDE_DIRS
|
||||||
include
|
include
|
||||||
@@ -49,11 +58,11 @@ catkin_package(
|
|||||||
ur_controllers
|
ur_controllers
|
||||||
ur_msgs
|
ur_msgs
|
||||||
std_srvs
|
std_srvs
|
||||||
|
message_runtime
|
||||||
DEPENDS
|
DEPENDS
|
||||||
Boost
|
Boost
|
||||||
)
|
)
|
||||||
|
|
||||||
|
|
||||||
# check c++11 / c++0x
|
# check c++11 / c++0x
|
||||||
include(CheckCXXCompilerFlag)
|
include(CheckCXXCompilerFlag)
|
||||||
check_cxx_compiler_flag("-std=c++11" COMPILER_SUPPORTS_CXX11)
|
check_cxx_compiler_flag("-std=c++11" COMPILER_SUPPORTS_CXX11)
|
||||||
|
|||||||
@@ -19,6 +19,7 @@
|
|||||||
<buildtool_depend>catkin</buildtool_depend>
|
<buildtool_depend>catkin</buildtool_depend>
|
||||||
|
|
||||||
<build_depend>boost</build_depend>
|
<build_depend>boost</build_depend>
|
||||||
|
<build_depend>message_generation</build_depend>
|
||||||
|
|
||||||
<depend>actionlib</depend>
|
<depend>actionlib</depend>
|
||||||
<depend>control_msgs</depend>
|
<depend>control_msgs</depend>
|
||||||
@@ -43,6 +44,7 @@
|
|||||||
<exec_depend>socat</exec_depend>
|
<exec_depend>socat</exec_depend>
|
||||||
<exec_depend>ur_description</exec_depend>
|
<exec_depend>ur_description</exec_depend>
|
||||||
<exec_depend>velocity_controllers</exec_depend>
|
<exec_depend>velocity_controllers</exec_depend>
|
||||||
|
<exec_depend>message_runtime</exec_depend>
|
||||||
|
|
||||||
<export>
|
<export>
|
||||||
<rosdoc config="rosdoc.yaml" />
|
<rosdoc config="rosdoc.yaml" />
|
||||||
|
|||||||
3
ur_rtde_driver/srv/SetSpeedSlider.srv
Normal file
3
ur_rtde_driver/srv/SetSpeedSlider.srv
Normal file
@@ -0,0 +1,3 @@
|
|||||||
|
float64 data
|
||||||
|
---
|
||||||
|
bool success
|
||||||
Reference in New Issue
Block a user