Skip to content

Commit

Permalink
Added center_of_gravity to SetPayload service
Browse files Browse the repository at this point in the history
"Newer" version of URScript (>= 1.7) have the CoG as second optional
parameter to the script function setting up the payload.
  • Loading branch information
fmauch committed Nov 27, 2019
1 parent c8c27c1 commit 101a0e9
Show file tree
Hide file tree
Showing 3 changed files with 4 additions and 1 deletion.
3 changes: 2 additions & 1 deletion ur_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@ project(ur_msgs)
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS message_generation std_msgs)
find_package(catkin REQUIRED COMPONENTS message_generation std_msgs geometry_msgs)


## Generate messages in the 'msg' folder
Expand Down Expand Up @@ -32,6 +32,7 @@ add_service_files(
generate_messages(
DEPENDENCIES
std_msgs
geometry_msgs
)

###################################
Expand Down
1 change: 1 addition & 0 deletions ur_msgs/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@

<buildtool_depend>catkin</buildtool_depend>
<build_depend>message_generation</build_depend>
<depend>geometry_msgs</depend>
<depend>std_msgs</depend>
<exec_depend>message_runtime</exec_depend>

Expand Down
1 change: 1 addition & 0 deletions ur_msgs/srv/SetPayload.srv
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
float32 payload
geometry_msgs/Vector3 center_of_gravity
-----------------------
bool success

0 comments on commit 101a0e9

Please sign in to comment.