Skip to content

Commit 8bbe990

Browse files
committed
Migration to ROS 2
1 parent 53496e7 commit 8bbe990

11 files changed

+131
-105
lines changed

CMakeLists.txt

Lines changed: 102 additions & 83 deletions
Original file line numberDiff line numberDiff line change
@@ -1,94 +1,113 @@
1-
cmake_minimum_required(VERSION 2.8.3)
1+
cmake_minimum_required(VERSION 3.5)
22
project(moveit_msgs)
33

4-
set(MSG_DEPS
5-
std_msgs
6-
actionlib_msgs
7-
sensor_msgs
8-
geometry_msgs
9-
trajectory_msgs
10-
shape_msgs
11-
object_recognition_msgs
12-
octomap_msgs)
4+
# Default to C++14
5+
if(NOT CMAKE_CXX_STANDARD)
6+
set(CMAKE_CXX_STANDARD 14)
7+
endif()
138

14-
find_package(catkin REQUIRED genmsg ${MSG_DEPS})
9+
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
10+
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra -Wpedantic")
11+
endif()
12+
13+
find_package(ament_cmake REQUIRED)
14+
find_package(rosidl_default_generators REQUIRED)
15+
find_package(action_msgs REQUIRED)
16+
find_package(builtin_interfaces REQUIRED)
17+
find_package(std_msgs REQUIRED)
18+
find_package(geometry_msgs REQUIRED)
19+
find_package(sensor_msgs REQUIRED)
20+
find_package(shape_msgs REQUIRED)
21+
find_package(object_recognition_msgs REQUIRED)
22+
find_package(octomap_msgs REQUIRED)
23+
find_package(trajectory_msgs REQUIRED)
1524

16-
set(MSG_FILES
17-
AllowedCollisionEntry.msg
18-
AllowedCollisionMatrix.msg
19-
AttachedCollisionObject.msg
20-
BoundingVolume.msg
21-
CollisionObject.msg
22-
ConstraintEvalResult.msg
23-
Constraints.msg
24-
CostSource.msg
25-
ContactInformation.msg
26-
DisplayTrajectory.msg
27-
DisplayRobotState.msg
28-
Grasp.msg
29-
GripperTranslation.msg
30-
JointConstraint.msg
31-
JointLimits.msg
32-
LinkPadding.msg
33-
LinkScale.msg
34-
MotionPlanRequest.msg
35-
MotionPlanResponse.msg
36-
MotionPlanDetailedResponse.msg
37-
MoveItErrorCodes.msg
38-
TrajectoryConstraints.msg
39-
ObjectColor.msg
40-
OrientationConstraint.msg
41-
OrientedBoundingBox.msg
42-
PlaceLocation.msg
43-
PlannerInterfaceDescription.msg
44-
PlannerParams.msg
45-
PlanningScene.msg
46-
PlanningSceneComponents.msg
47-
PlanningSceneWorld.msg
48-
PlanningOptions.msg
49-
PositionConstraint.msg
50-
RobotState.msg
51-
RobotTrajectory.msg
52-
VisibilityConstraint.msg
53-
WorkspaceParameters.msg
54-
KinematicSolverInfo.msg
55-
PositionIKRequest.msg
56-
)
5725

58-
set(SRV_FILES
59-
GetMotionPlan.srv
60-
ExecuteKnownTrajectory.srv
61-
GetStateValidity.srv
62-
GetCartesianPath.srv
63-
GetPlanningScene.srv
64-
GraspPlanning.srv
65-
ApplyPlanningScene.srv
66-
QueryPlannerInterfaces.srv
67-
GetPositionFK.srv
68-
GetPositionIK.srv
69-
GetPlannerParams.srv
70-
SetPlannerParams.srv
71-
SaveMap.srv
72-
LoadMap.srv
73-
SaveRobotStateToWarehouse.srv
74-
ListRobotStatesInWarehouse.srv
75-
GetRobotStateFromWarehouse.srv
76-
CheckIfRobotStateExistsInWarehouse.srv
77-
RenameRobotStateInWarehouse.srv
78-
DeleteRobotStateFromWarehouse.srv
26+
set(msg_files
27+
"msg/AllowedCollisionEntry.msg"
28+
"msg/AllowedCollisionMatrix.msg"
29+
"msg/AttachedCollisionObject.msg"
30+
"msg/BoundingVolume.msg"
31+
"msg/CollisionObject.msg"
32+
"msg/ConstraintEvalResult.msg"
33+
"msg/Constraints.msg"
34+
"msg/CostSource.msg"
35+
"msg/ContactInformation.msg"
36+
"msg/DisplayTrajectory.msg"
37+
"msg/DisplayRobotState.msg"
38+
"msg/Grasp.msg"
39+
"msg/GripperTranslation.msg"
40+
"msg/JointConstraint.msg"
41+
"msg/JointLimits.msg"
42+
"msg/LinkPadding.msg"
43+
"msg/LinkScale.msg"
44+
"msg/MotionPlanRequest.msg"
45+
"msg/MotionPlanResponse.msg"
46+
"msg/MotionPlanDetailedResponse.msg"
47+
"msg/MoveItErrorCodes.msg"
48+
"msg/TrajectoryConstraints.msg"
49+
"msg/ObjectColor.msg"
50+
"msg/OrientationConstraint.msg"
51+
"msg/OrientedBoundingBox.msg"
52+
"msg/PlaceLocation.msg"
53+
"msg/PlannerInterfaceDescription.msg"
54+
"msg/PlannerParams.msg"
55+
"msg/PlanningScene.msg"
56+
"msg/PlanningSceneComponents.msg"
57+
"msg/PlanningSceneWorld.msg"
58+
"msg/PlanningOptions.msg"
59+
"msg/PositionConstraint.msg"
60+
"msg/RobotState.msg"
61+
"msg/RobotTrajectory.msg"
62+
"msg/VisibilityConstraint.msg"
63+
"msg/WorkspaceParameters.msg"
64+
"msg/KinematicSolverInfo.msg"
65+
"msg/PositionIKRequest.msg"
7966
)
8067

81-
set(ACT_FILES
82-
ExecuteTrajectory.action
83-
MoveGroup.action
84-
Pickup.action
85-
Place.action
68+
set(srv_files
69+
"srv/GetMotionPlan.srv"
70+
"srv/ExecuteKnownTrajectory.srv"
71+
"srv/GetStateValidity.srv"
72+
"srv/GetCartesianPath.srv"
73+
"srv/GetPlanningScene.srv"
74+
"srv/GraspPlanning.srv"
75+
"srv/ApplyPlanningScene.srv"
76+
"srv/QueryPlannerInterfaces.srv"
77+
"srv/GetPositionFK.srv"
78+
"srv/GetPositionIK.srv"
79+
"srv/GetPlannerParams.srv"
80+
"srv/SetPlannerParams.srv"
81+
"srv/SaveMap.srv"
82+
"srv/LoadMap.srv"
83+
"srv/SaveRobotStateToWarehouse.srv"
84+
"srv/ListRobotStatesInWarehouse.srv"
85+
"srv/GetRobotStateFromWarehouse.srv"
86+
"srv/CheckIfRobotStateExistsInWarehouse.srv"
87+
"srv/RenameRobotStateInWarehouse.srv"
88+
"srv/DeleteRobotStateFromWarehouse.srv"
8689
)
8790

88-
add_action_files(DIRECTORY action FILES ${ACT_FILES})
89-
add_message_files(DIRECTORY msg FILES ${MSG_FILES})
90-
add_service_files(DIRECTORY srv FILES ${SRV_FILES})
91+
set(action_files
92+
"action/ExecuteTrajectory.action"
93+
"action/MoveGroup.action"
94+
"action/Pickup.action"
95+
"action/Place.action"
96+
)
9197

92-
generate_messages(DEPENDENCIES ${MSG_DEPS})
98+
rosidl_generate_interfaces(${PROJECT_NAME}
99+
${msg_files}
100+
${srv_files}
101+
DEPENDENCIES
102+
action_msgs
103+
builtin_interfaces
104+
std_msgs
105+
geometry_msgs
106+
sensor_msgs
107+
shape_msgs
108+
object_recognition_msgs
109+
octomap_msgs
110+
trajectory_msgs
111+
)
93112

94-
catkin_package(DEPENDS ${MSG_DEPS})
113+
ament_package()

README.md

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,7 @@
11
# MoveIt! Msgs
22

3+
## This fork is part of Acutronic Robotics' efforts in the migration of Moveit! to ROS 2.0
4+
35
This package includes the ROS messages specific to MoveIt!
46

57
## Travis - Continuous Integration

msg/CollisionObject.msg

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
# a header, used for interpreting the poses
2-
Header header
2+
std_msgs/Header header
33

44
# the id of the object (name used in MoveIt)
55
string id

msg/ContactInformation.msg

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
# Standard ROS header contains information
22
# about the frame in which this
33
# contact is specified
4-
Header header
4+
std_msgs/Header header
55

66
# Position of the contact point
77
geometry_msgs/Point position

msg/OrientationConstraint.msg

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
# This message contains the definition of an orientation constraint.
22

3-
Header header
3+
std_msgs/Header header
44

55
# The desired orientation of the robot link specified as a quaternion
66
geometry_msgs/Quaternion orientation

msg/PositionConstraint.msg

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
# This message contains the definition of a position constraint.
22

3-
Header header
3+
std_msgs/Header header
44

55
# The robot link this constraint refers to
66
string link_name

msg/PositionIKRequest.msg

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -44,7 +44,7 @@ string[] ik_link_names
4444
geometry_msgs/PoseStamped[] pose_stamped_vector
4545

4646
# Maximum allowed time for IK calculation
47-
duration timeout
47+
builtin_interfaces/Duration timeout
4848

4949
# Maximum number of IK attempts (if using random seeds; leave as 0 for the default value specified on the param server to be used)
5050
int32 attempts

msg/WorkspaceParameters.msg

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,7 @@
44
# the robot as well.
55

66
# Define the frame of reference for the box corners
7-
Header header
7+
std_msgs/Header header
88

99
# The minumum corner of the box, with respect to the robot starting pose
1010
geometry_msgs/Vector3 min_corner

package.xml

Lines changed: 19 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
<package>
1+
<package format="3">
22
<name>moveit_msgs</name>
33
<version>0.10.0</version>
44
<description>Messages, services and actions used by MoveIt</description>
@@ -11,31 +11,36 @@
1111
<maintainer email="[email protected]">Robert Haschke</maintainer>
1212
<maintainer email="[email protected]">Isaac I. Y. Saito</maintainer>
1313

14-
<license>BSD</license>
14+
<license>BSD</license>
1515
<url type="website">http://moveit.ros.org</url>
1616
<url type="bugtracker">https://github.com/ros-planning/moveit_msgs/issues</url>
1717
<url type="repository">https://github.com/ros-planning/moveit_msgs</url>
1818

19-
<buildtool_depend>catkin</buildtool_depend>
20-
2119
<build_depend>message_generation</build_depend>
20+
<build_depend>rosidl_default_generators</build_depend>
2221
<build_depend>octomap_msgs</build_depend>
23-
<build_depend>actionlib_msgs</build_depend>
22+
<build_depend>action_msgs</build_depend>
2423
<build_depend>sensor_msgs</build_depend>
2524
<build_depend>geometry_msgs</build_depend>
2625
<build_depend>trajectory_msgs</build_depend>
2726
<build_depend>shape_msgs</build_depend>
2827
<build_depend>object_recognition_msgs</build_depend>
2928
<build_depend>std_msgs</build_depend>
3029

31-
<run_depend>message_runtime</run_depend>
32-
<run_depend>octomap_msgs</run_depend>
33-
<run_depend>actionlib_msgs</run_depend>
34-
<run_depend>sensor_msgs</run_depend>
35-
<run_depend>geometry_msgs</run_depend>
36-
<run_depend>trajectory_msgs</run_depend>
37-
<run_depend>shape_msgs</run_depend>
38-
<run_depend>object_recognition_msgs</run_depend>
39-
<run_depend>std_msgs</run_depend>
30+
<exec_depend>message_generation</exec_depend> <!-- provide message generation to downstream packages -->
31+
<exec_depend>message_runtime</exec_depend>
32+
<exec_depend>octomap_msgs</exec_depend>
33+
<exec_depend>action_msgs</exec_depend>
34+
<exec_depend>sensor_msgs</exec_depend>
35+
<exec_depend>geometry_msgs</exec_depend>
36+
<exec_depend>trajectory_msgs</exec_depend>
37+
<exec_depend>shape_msgs</exec_depend>
38+
<exec_depend>object_recognition_msgs</exec_depend>
39+
<exec_depend>std_msgs</exec_depend>
40+
41+
<member_of_group>rosidl_interface_packages</member_of_group>
4042

43+
<export>
44+
<build_type>ament_cmake</build_type>
45+
</export>
4146
</package>

srv/GetCartesianPath.srv

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
# Define the frame for the specified waypoints
2-
Header header
2+
std_msgs/Header header
33

44
# The start at which to start the Cartesian path
55
RobotState start_state

0 commit comments

Comments
 (0)