forked from moveit/moveit_msgs
-
Notifications
You must be signed in to change notification settings - Fork 0
/
CMakeLists.txt
94 lines (86 loc) · 1.89 KB
/
CMakeLists.txt
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
cmake_minimum_required(VERSION 2.8.3)
project(moveit_msgs)
set(MSG_DEPS
std_msgs
actionlib_msgs
sensor_msgs
geometry_msgs
trajectory_msgs
shape_msgs
object_recognition_msgs
octomap_msgs)
find_package(catkin REQUIRED genmsg ${MSG_DEPS})
set(MSG_FILES
AllowedCollisionEntry.msg
AllowedCollisionMatrix.msg
AttachedCollisionObject.msg
BoundingVolume.msg
CollisionObject.msg
ConstraintEvalResult.msg
Constraints.msg
CostSource.msg
ContactInformation.msg
DisplayTrajectory.msg
DisplayRobotState.msg
Grasp.msg
GripperTranslation.msg
JointConstraint.msg
JointLimits.msg
LinkPadding.msg
LinkScale.msg
MotionPlanRequest.msg
MotionPlanResponse.msg
MotionPlanDetailedResponse.msg
MoveItErrorCodes.msg
TrajectoryConstraints.msg
ObjectColor.msg
OrientationConstraint.msg
OrientedBoundingBox.msg
PlaceLocation.msg
PlannerInterfaceDescription.msg
PlannerParams.msg
PlanningScene.msg
PlanningSceneComponents.msg
PlanningSceneWorld.msg
PlanningOptions.msg
PositionConstraint.msg
RobotState.msg
RobotTrajectory.msg
VisibilityConstraint.msg
WorkspaceParameters.msg
KinematicSolverInfo.msg
PositionIKRequest.msg
)
set(SRV_FILES
GetMotionPlan.srv
ExecuteKnownTrajectory.srv
GetStateValidity.srv
GetCartesianPath.srv
GetPlanningScene.srv
GraspPlanning.srv
ApplyPlanningScene.srv
QueryPlannerInterfaces.srv
GetPositionFK.srv
GetPositionIK.srv
GetPlannerParams.srv
SetPlannerParams.srv
SaveMap.srv
LoadMap.srv
SaveRobotStateToWarehouse.srv
ListRobotStatesInWarehouse.srv
GetRobotStateFromWarehouse.srv
CheckIfRobotStateExistsInWarehouse.srv
RenameRobotStateInWarehouse.srv
DeleteRobotStateFromWarehouse.srv
)
set(ACT_FILES
ExecuteTrajectory.action
MoveGroup.action
Pickup.action
Place.action
)
add_action_files(DIRECTORY action FILES ${ACT_FILES})
add_message_files(DIRECTORY msg FILES ${MSG_FILES})
add_service_files(DIRECTORY srv FILES ${SRV_FILES})
generate_messages(DEPENDENCIES ${MSG_DEPS})
catkin_package(DEPENDS ${MSG_DEPS})