Skip to content

Commit

Permalink
msgs: cleanup build script and manifest.
Browse files Browse the repository at this point in the history
 - remove redundant dependencies
 - migrate to format 2
 - correct dependencies on msg generation and runtime
  • Loading branch information
gavanderhoorn committed May 1, 2018
1 parent 4ef1460 commit b5c68ef
Show file tree
Hide file tree
Showing 2 changed files with 38 additions and 23 deletions.
39 changes: 28 additions & 11 deletions motoman_msgs/CMakeLists.txt
@@ -1,26 +1,43 @@
cmake_minimum_required(VERSION 2.8.3)
project(motoman_msgs)

find_package(catkin REQUIRED COMPONENTS std_msgs trajectory_msgs industrial_msgs genmsg message_generation)
find_package(catkin
REQUIRED COMPONENTS
industrial_msgs
message_generation
std_msgs
trajectory_msgs
)

add_message_files(
DIRECTORY
msg
FILES
DynamicJointsGroup.msg
DynamicJointPoint.msg
DynamicJointTrajectory.msg
DynamicJointState.msg
DynamicJointTrajectoryFeedback.msg
)
DynamicJointPoint.msg
DynamicJointsGroup.msg
DynamicJointState.msg
DynamicJointTrajectory.msg
DynamicJointTrajectoryFeedback.msg
)

add_service_files(
DIRECTORY
srv
FILES
CmdJointTrajectoryEx.srv
)
CmdJointTrajectoryEx.srv
)

generate_messages(
DEPENDENCIES trajectory_msgs std_msgs industrial_msgs
DEPENDENCIES
industrial_msgs
std_msgs
trajectory_msgs
)

catkin_package(
CATKIN_DEPENDS message_runtime std_msgs trajectory_msgs industrial_msgs genmsg
CATKIN_DEPENDS
industrial_msgs
message_runtime
std_msgs
trajectory_msgs
)
22 changes: 10 additions & 12 deletions motoman_msgs/package.xml
@@ -1,24 +1,22 @@
<?xml version="1.0"?>
<package>
<package format="2">
<name>motoman_msgs</name>
<version>0.3.5</version>
<description>set of messages to serve as support for the multi-groups driver</description>
<description>Set of messages to serve as support for the multi-group driver.</description>

<maintainer email="tdf@ipa.fhg.de">Thiago de Freitas</maintainer>

<license>BSD</license>
<url type="website">http://ros.org/wiki/motoman_msgs</url>
<url type="website">http://wiki.ros.org/motoman_msgs</url>
<author>Thiago de Freitas</author>

<buildtool_depend>catkin</buildtool_depend>
<build_depend>std_msgs</build_depend>
<build_depend>industrial_msgs</build_depend>
<build_depend>trajectory_msgs</build_depend>
<build_depend>genmsg</build_depend>

<build_depend>message_generation</build_depend>
<run_depend>std_msgs</run_depend>
<run_depend>trajectory_msgs</run_depend>
<run_depend>industrial_msgs</run_depend>
<run_depend>genmsg</run_depend>
<run_depend>message_runtime</run_depend>
<build_export_depend>message_runtime</build_export_depend>
<exec_depend>message_runtime</exec_depend>

<depend>std_msgs</depend>
<depend>industrial_msgs</depend>
<depend>trajectory_msgs</depend>
</package>

0 comments on commit b5c68ef

Please sign in to comment.