mirror of
https://github.com/moveit/moveit_task_constructor.git
synced 2025-11-04 14:49:57 +08:00
introspection message definitions
This commit is contained in:
parent
aa37ee7cee
commit
cfe8086f29
@ -2,8 +2,11 @@ cmake_minimum_required(VERSION 2.6.12)
|
|||||||
|
|
||||||
project(moveit_task_constructor)
|
project(moveit_task_constructor)
|
||||||
|
|
||||||
|
set(MSG_DEPS trajectory_msgs moveit_msgs)
|
||||||
|
|
||||||
find_package(catkin REQUIRED COMPONENTS
|
find_package(catkin REQUIRED COMPONENTS
|
||||||
roscpp
|
roscpp
|
||||||
|
genmsg ${MSG_DEPS}
|
||||||
moveit_core
|
moveit_core
|
||||||
moveit_ros_planning
|
moveit_ros_planning
|
||||||
moveit_ros_planning_interface
|
moveit_ros_planning_interface
|
||||||
@ -11,6 +14,20 @@ find_package(catkin REQUIRED COMPONENTS
|
|||||||
eigen_conversions
|
eigen_conversions
|
||||||
)
|
)
|
||||||
|
|
||||||
|
# ROS messages, services and actions
|
||||||
|
add_message_files(DIRECTORY msg
|
||||||
|
FILES
|
||||||
|
Stage.msg
|
||||||
|
Task.msg
|
||||||
|
Solution.msg
|
||||||
|
)
|
||||||
|
add_service_files(DIRECTORY srv
|
||||||
|
FILES
|
||||||
|
GetInterfaceState.srv
|
||||||
|
GetSolutionTrajectory.srv
|
||||||
|
)
|
||||||
|
generate_messages(DEPENDENCIES ${MSG_DEPS})
|
||||||
|
|
||||||
catkin_package(
|
catkin_package(
|
||||||
INCLUDE_DIRS include
|
INCLUDE_DIRS include
|
||||||
)
|
)
|
||||||
|
|||||||
8
msg/Solution.msg
Normal file
8
msg/Solution.msg
Normal file
@ -0,0 +1,8 @@
|
|||||||
|
# unique id within task
|
||||||
|
uint32 id
|
||||||
|
|
||||||
|
# IDs of subsolutions, empty if ID refers to an actual SubTrajectory
|
||||||
|
uint32[] sub_solutions
|
||||||
|
|
||||||
|
# associated cost
|
||||||
|
float32 cost
|
||||||
22
msg/Stage.msg
Normal file
22
msg/Stage.msg
Normal file
@ -0,0 +1,22 @@
|
|||||||
|
# unique id within task
|
||||||
|
uint32 id
|
||||||
|
|
||||||
|
# name of this stage
|
||||||
|
string name
|
||||||
|
|
||||||
|
# flags: interface, ...
|
||||||
|
uint32 flags
|
||||||
|
|
||||||
|
# parent id, parent_id == id means root
|
||||||
|
uint32 parent_id
|
||||||
|
|
||||||
|
# ids of received start / end states
|
||||||
|
uint32[] received_starts
|
||||||
|
uint32[] received_ends
|
||||||
|
# ids of generated start / end states
|
||||||
|
uint32[] generated_starts
|
||||||
|
uint32[] generated_ends
|
||||||
|
|
||||||
|
# successful and failed solutions of this stage
|
||||||
|
Solution[] solutions
|
||||||
|
Solution[] failures
|
||||||
5
msg/Task.msg
Normal file
5
msg/Task.msg
Normal file
@ -0,0 +1,5 @@
|
|||||||
|
# unique of this task
|
||||||
|
string id
|
||||||
|
|
||||||
|
# list of all stages, include the task stage itself
|
||||||
|
Stage[] stages
|
||||||
7
srv/GetInterfaceState.srv
Normal file
7
srv/GetInterfaceState.srv
Normal file
@ -0,0 +1,7 @@
|
|||||||
|
# ID of InterfaceState
|
||||||
|
uint32 state_id
|
||||||
|
|
||||||
|
---
|
||||||
|
|
||||||
|
# planning scene diff to tasks' main planning scene
|
||||||
|
moveit_msgs/PlanningScene scene
|
||||||
7
srv/GetSolutionTrajectory.srv
Normal file
7
srv/GetSolutionTrajectory.srv
Normal file
@ -0,0 +1,7 @@
|
|||||||
|
# ID of solution (as published in Task msg)
|
||||||
|
uint32 solution_id
|
||||||
|
|
||||||
|
---
|
||||||
|
|
||||||
|
# solution trajectory composed from multiple sub trajectories
|
||||||
|
moveit_msgs/DisplayTrajectory trajectory
|
||||||
Loading…
Reference in New Issue
Block a user