moveit_msgs

Summary

moveit_msgs
Version:

0.6.1

Description:

Messages, services and actions used by MoveIt

Maintainers:
  • Ioan Sucan <isucan AT google DOT com>
Licenses:
  • BSD
Urls:
Authors:
  • Ioan Sucan <isucan AT google DOT com>
  • Sachin Chitta <sachinc AT sri DOT com>
BuildDepends:
BuildtoolDepends:
 
BuildExportDepends:
 
ExecDepends:

Types

Message types

moveit_msgs/PositionConstraint
Field:

This message contains the definition of a position constraint.

# This message contains the definition of a position constraint.

Header header

# The robot link this constraint refers to
string link_name

# The offset (in the link frame) for the target point on the link we are planning for
geometry_msgs/Vector3 target_point_offset

# The volume this constraint refers to 
BoundingVolume constraint_region

# A weighting factor for this constraint (denotes relative importance to other constraints. Closer to zero means less important)
float64 weight
moveit_msgs/OrientationConstraint
Field:
  • header (std_msgs/Header) –
  • orientation (geometry_msgs/Quaternion) –
  • link_name (string) –
  • absolute_x_axis_tolerance (float64) –
  • absolute_y_axis_tolerance (float64) –
  • absolute_z_axis_tolerance (float64) –
  • weight (float64) –

This message contains the definition of an orientation constraint.

# This message contains the definition of an orientation constraint.

Header header

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

# The robot link this constraint refers to
string link_name

# optional axis-angle error tolerances specified
float64 absolute_x_axis_tolerance
float64 absolute_y_axis_tolerance
float64 absolute_z_axis_tolerance

# A weighting factor for this constraint (denotes relative importance to other constraints. Closer to zero means less important)
float64 weight
moveit_msgs/PlanningSceneWorld
Field:

collision objects

# collision objects
CollisionObject[] collision_objects

# The octomap that represents additional collision data
octomap_msgs/OctomapWithPose octomap
moveit_msgs/GripperTranslation
Field:

defines a translation for the gripper, used in pickup or place tasks for example for lifting an object off a table or approaching the table for placing

the direction of the translation

# defines a translation for the gripper, used in pickup or place tasks
# for example for lifting an object off a table or approaching the table for placing

# the direction of the translation
geometry_msgs/Vector3Stamped direction

# the desired translation distance
float32 desired_distance

# the min distance that must be considered feasible before the
# grasp is even attempted
float32 min_distance
moveit_msgs/BoundingVolume
Field:

Define a volume in 3D

A set of solid geometric primitives that make up the volume to define (as a union)

# Define a volume in 3D

# A set of solid geometric primitives that make up the volume to define (as a union)
shape_msgs/SolidPrimitive[] primitives

# The poses at which the primitives are located
geometry_msgs/Pose[] primitive_poses

# In addition to primitives, meshes can be specified to add to the bounding volume (again, as union)
shape_msgs/Mesh[] meshes

# The poses at which the meshes are located
geometry_msgs/Pose[] mesh_poses
moveit_msgs/JointLimits
Field:
  • joint_name (string) –
  • has_position_limits (bool) –
  • min_position (float64) –
  • max_position (float64) –
  • has_velocity_limits (bool) –
  • max_velocity (float64) –
  • has_acceleration_limits (bool) –
  • max_acceleration (float64) –

This message contains information about limits of a particular joint (or control dimension)

# This message contains information about limits of a particular joint (or control dimension)
string joint_name

# true if the joint has position limits
bool has_position_limits

# min and max position limits
float64 min_position
float64 max_position

# true if joint has velocity limits
bool has_velocity_limits

# max velocity limit
float64 max_velocity
# min_velocity is assumed to be -max_velocity

# true if joint has acceleration limits
bool has_acceleration_limits
# max acceleration limit
float64 max_acceleration
# min_acceleration is assumed to be -max_acceleration
moveit_msgs/KinematicSolverInfo
Field:

A list of joints in the kinematic tree

# A list of joints in the kinematic tree
string[] joint_names
# A list of joint limits corresponding to the joint names
moveit_msgs/JointLimits[] limits
# A list of links that the kinematics node provides solutions for
string[] link_names
moveit_msgs/DisplayRobotState
Field:

The robot state to display

# The robot state to display
RobotState state

# Optionally, various links can be highlighted
ObjectColor[] highlight_links
moveit_msgs/PlanningScene
Field:

name of planning scene

# name of planning scene
string name

# full robot state
RobotState robot_state

# The name of the robot model this scene is for
string robot_model_name

#additional frames for duplicating tf (with respect to the planning frame)
geometry_msgs/TransformStamped[] fixed_frame_transforms

#full allowed collision matrix
AllowedCollisionMatrix allowed_collision_matrix

# all link paddings
LinkPadding[] link_padding

# all link scales
LinkScale[] link_scale

# Attached objects, collision objects, even the octomap or collision map can have 
# colors associated to them. This array specifies them.
ObjectColor[] object_colors

# the collision map
PlanningSceneWorld world

# Flag indicating whether this scene is to be interpreted as a diff with respect to some other scene
bool is_diff
moveit_msgs/PlaceLocation
Field:

A name for this grasp

# A name for this grasp
string id

# The internal posture of the hand for the grasp
# positions and efforts are used
trajectory_msgs/JointTrajectory post_place_posture

# The position of the end-effector for the grasp relative to a reference frame 
# (that is always specified elsewhere, not in this message)
geometry_msgs/PoseStamped place_pose

# The approach motion
GripperTranslation pre_place_approach

# The retreat motion
GripperTranslation post_place_retreat

# an optional list of obstacles that we have semantic information about
# and that can be touched/pushed/moved in the course of grasping
string[] allowed_touch_objects
moveit_msgs/CollisionObject
Field:
Constant:
  • ADD (byte):0
  • REMOVE (byte):1
  • APPEND (byte):2
  • MOVE (byte):3

a header, used for interpreting the poses

# a header, used for interpreting the poses
Header header

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

# The object type in a database of known objects
object_recognition_msgs/ObjectType type

# the the collision geometries associated with the object;
# their poses are with respect to the specified header

# solid geometric primitives
shape_msgs/SolidPrimitive[] primitives
geometry_msgs/Pose[] primitive_poses

# meshes
shape_msgs/Mesh[] meshes
geometry_msgs/Pose[] mesh_poses

# bounding planes (equation is specified, but the plane can be oriented using an additional pose)
shape_msgs/Plane[] planes
geometry_msgs/Pose[] plane_poses

# Adds the object to the planning scene. If the object previously existed, it is replaced.
byte ADD=0

# Removes the object from the environment entirely (everything that matches the specified id)
byte REMOVE=1

# Append to an object that already exists in the planning scene. If the does not exist, it is added.
byte APPEND=2

# If an object already exists in the scene, new poses can be sent (the geometry arrays must be left empty)
# if solely moving the object is desired
byte MOVE=3

# Operation to be performed
byte operation
moveit_msgs/DisplayTrajectory
Field:

The model id for which this path has been generated

# The model id for which this path has been generated
string model_id

# The representation of the path contains position values for all the joints that are moving along the path; a sequence of trajectories may be specified
RobotTrajectory[] trajectory

# The robot state is used to obtain positions for all/some of the joints of the robot. 
# It is used by the path display node to determine the positions of the joints that are not specified in the joint path message above. 
# If the robot state message contains joint position information for joints that are also mentioned in the joint path message, the positions in the joint path message will overwrite the positions specified in the robot state message. 
RobotState trajectory_start
moveit_msgs/AllowedCollisionMatrix
Field:

The list of entry names in the matrix

# The list of entry names in the matrix
string[] entry_names

# The individual entries in the allowed collision matrix
# square, symmetric, with same order as entry_names
AllowedCollisionEntry[] entry_values

# In addition to the collision matrix itself, we also have 
# the default entry value for each entry name.

# If the allowed collision flag is queried for a pair of names (n1, n2)
# that is not found in the collision matrix itself, the value of
# the collision flag is considered to be that of the entry (n1 or n2)
# specified in the list below. If both n1 and n2 are found in the list 
# of defaults, the result is computed with an AND operation

string[] default_entry_names
bool[] default_entry_values
moveit_msgs/MotionPlanRequest
Field:

This service contains the definition for a request to the motion planner and the output it provides

Parameters for the workspace that the planner should work inside

# This service contains the definition for a request to the motion
# planner and the output it provides

# Parameters for the workspace that the planner should work inside
WorkspaceParameters workspace_parameters

# Starting state updates. If certain joints should be considered
# at positions other than the current ones, these positions should
# be set here
RobotState start_state

# The possible goal states for the model to plan for. Each element of
# the array defines a goal region. The goal is achieved
# if the constraints for a particular region are satisfied
Constraints[] goal_constraints

# No state at any point along the path in the produced motion plan will violate these constraints (this applies to all points, not just waypoints)
Constraints path_constraints

# The constraints the resulting trajectory must satisfy
TrajectoryConstraints trajectory_constraints

# The name of the motion planner to use. If no name is specified,
# a default motion planner will be used
string planner_id

# The name of the group of joints on which this planner is operating
string group_name

# The number of times this plan is to be computed. Shortest solution
# will be reported.
int32 num_planning_attempts

# The maximum amount of time the motion planner is allowed to plan for (in seconds)
float64 allowed_planning_time

# The scaling factor for optionally reducing the maximum joint velocities.
# Allowed values are in (0,1]. The maximum joint velocity specified
# in the robot model is multiplied by the factor. If outside valid range
# (imporantly, this includes it being set to 0.0), the factor is set to a
# default value of 1.0 internally (i.e. maximum joint velocity)
float64 max_velocity_scaling_factor
moveit_msgs/MotionPlanResponse
Field:

The representation of a solution to a planning problem

The corresponding robot state

# The representation of a solution to a planning problem

# The corresponding robot state
RobotState trajectory_start

# The group used for planning (usually the same as in the request)
string group_name

# A solution trajectory, if found
RobotTrajectory trajectory

# Planning time (seconds)
float64 planning_time

# Error code - encodes the overall reason for failure
MoveItErrorCodes error_code
moveit_msgs/RobotState
Field:

This message contains information about the robot state, i.e. the positions of its joints and links

# This message contains information about the robot state, i.e. the positions of its joints and links
sensor_msgs/JointState joint_state

# Joints that may have multiple DOF are specified here
sensor_msgs/MultiDOFJointState multi_dof_joint_state

# Attached collision objects (attached to some link on the robot)
AttachedCollisionObject[] attached_collision_objects

# Flag indicating whether this scene is to be interpreted as a diff with respect to some other scene
# This is mostly important for handling the attached bodies (whether or not to clear the attached bodies
# of a moveit::core::RobotState before updating it with this message)
bool is_diff
moveit_msgs/PositionIKRequest
Field:

A Position IK request message

The name of the group which will be used to compute IK e.g. “right_arm”, or “arms” - see IK specification for multiple-groups below Information from the SRDF will be used to automatically determine which link to solve IK for, unless ik_link_name is also specified

# A Position IK request message

# The name of the group which will be used to compute IK
# e.g. "right_arm", or "arms" - see IK specification for multiple-groups below
# Information from the SRDF will be used to automatically determine which link 
# to solve IK for, unless ik_link_name is also specified
string group_name

# A RobotState consisting of hint/seed positions for the IK computation and positions 
# for all the other joints in the robot. Additional state information provided here is 
# used to specify starting positions for other joints/links on the robot.  
# This state MUST contain state for all joints to be used by the IK solver
# to compute IK. The list of joints that the IK solver deals with can be 
# found using the SRDF for the corresponding group
moveit_msgs/RobotState robot_state

# A set of constraints that the IK must obey; by default, this set of constraints is empty
Constraints constraints

# Find an IK solution that avoids collisions. By default, this is false
bool avoid_collisions

# (OPTIONAL) The name of the link for which we are computing IK
# If not specified, the link name will be inferred from a combination 
# of the group name and the SRDF. If any values are specified for ik_link_names,
# this value is ignored
string ik_link_name

# The stamped pose of the link, when the IK solver computes the joint values
# for all the joints in a group. This value is ignored if pose_stamped_vector
# has any elements specified.
geometry_msgs/PoseStamped pose_stamped

# Multi-group parameters

# (OPTIONAL) The names of the links for which we are computing IK
# If not specified, the link name will be inferred from a combination 
# of the group name and the SRDF
string[] ik_link_names

# (OPTIONAL) The (stamped) poses of the links we are computing IK for (when a group has more than one end effector)
# e.g. The "arms" group might consist of both the "right_arm" and the "left_arm"
# The order of the groups referred to is the same as the order setup in the SRDF
geometry_msgs/PoseStamped[] pose_stamped_vector

# Maximum allowed time for IK calculation
duration timeout

# Maximum number of IK attempts (if using random seeds; leave as 0 for the default value specified on the param server to be used)
int32 attempts
moveit_msgs/AllowedCollisionEntry
Field:
  • enabled[] (bool) –

whether or not collision checking is enabled

# whether or not collision checking is enabled
bool[] enabled
moveit_msgs/PlannerInterfaceDescription
Field:
  • name (string) –
  • planner_ids[] (string) –

The name of the planner interface

# The name of the planner interface
string name

# The names of the planner ids within the interface
string[] planner_ids
moveit_msgs/MotionPlanDetailedResponse
Field:

The representation of a solution to a planning problem, including intermediate data

The starting state considered for the robot solution path

# The representation of a solution to a planning problem, including intermediate data

# The starting state considered for the robot solution path
RobotState trajectory_start

# The group used for planning (usually the same as in the request)
string group_name

# Multiple solution paths are reported, each reflecting intermediate steps in the trajectory processing

# The list of reported trajectories
RobotTrajectory[] trajectory

# Description of the reported trajectories (name of processing step)
string[] description

# The amount of time spent computing a particular step in motion plan computation 
float64[] processing_time

# Status at the end of this plan
MoveItErrorCodes error_code
moveit_msgs/WorkspaceParameters
Field:

This message contains a set of parameters useful in setting up the volume (a box) in which the robot is allowed to move. This is useful only when planning for mobile parts of the robot as well.

Define the frame of reference for the box corners

# This message contains a set of parameters useful in
# setting up the volume (a box) in which the robot is allowed to move.
# This is useful only when planning for mobile parts of 
# the robot as well.

# Define the frame of reference for the box corners
Header header

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

# The maximum corner of the box, with respect to the robot starting pose
geometry_msgs/Vector3 max_corner
moveit_msgs/TrajectoryConstraints
Field:

The array of constraints to consider along the trajectory

# The array of constraints to consider along the trajectory
Constraints[] constraints
moveit_msgs/ConstraintEvalResult
Field:
  • result (bool) –
  • distance (float64) –

This message contains result from constraint evaluation result specifies the result of constraint evaluation (true indicates state satisfies constraint, false indicates state violates constraint) if false, distance specifies a measure of the distance of the state from the constraint if true, distance is set to zero

# This message contains result from constraint evaluation
# result specifies the result of constraint evaluation 
# (true indicates state satisfies constraint, false indicates state violates constraint)
# if false, distance specifies a measure of the distance of the state from the constraint
# if true, distance is set to zero
bool result
float64 distance
moveit_msgs/PlanningOptions
Field:
  • planning_scene_diff (moveit_msgs/PlanningScene) –
  • plan_only (bool) –
  • look_around (bool) –
  • look_around_attempts (int32) –
  • max_safe_execution_cost (float64) –
  • replan (bool) –
  • replan_attempts (int32) –
  • replan_delay (float64) –

The diff to consider for the planning scene (optional)

# The diff to consider for the planning scene (optional)
PlanningScene planning_scene_diff

# If this flag is set to true, the action
# returns an executable plan in the response but does not attempt execution  
bool plan_only

# If this flag is set to true, the action of planning &
# executing is allowed to look around  (move sensors) if
# it seems that not enough information is available about
# the environment
bool look_around

# If this value is positive, the action of planning & executing
# is allowed to look around for a maximum number of attempts;
# If the value is left as 0, the default value is used, as set
# with dynamic_reconfigure
int32 look_around_attempts

# If set and if look_around is true, this value is used as
# the maximum cost allowed for a path to be considered executable.
# If the cost of a path is higher than this value, more sensing or 
# a new plan needed. If left as 0.0 but look_around is true, then 
# the default value set via dynamic_reconfigure is used
float64 max_safe_execution_cost

# If the plan becomes invalidated during execution, it is possible to have
# that plan recomputed and execution restarted. This flag enables this
# functionality 
bool replan

# The maximum number of replanning attempts 
int32 replan_attempts

# The amount of time to wait in between replanning attempts (in seconds)
float64 replan_delay
moveit_msgs/Constraints
Field:

This message contains a list of motion planning constraints. All constraints must be satisfied for a goal to be considered valid

# This message contains a list of motion planning constraints.
# All constraints must be satisfied for a goal to be considered valid

string name

JointConstraint[] joint_constraints

PositionConstraint[] position_constraints

OrientationConstraint[] orientation_constraints

VisibilityConstraint[] visibility_constraints
moveit_msgs/CostSource
Field:

The density of the cost source

# The density of the cost source
float64 cost_density

# The volume of the cost source is represented as an
# axis-aligned bounding box (AABB)
# The AABB is specified by two of its opposite corners

geometry_msgs/Vector3 aabb_min

geometry_msgs/Vector3 aabb_max
moveit_msgs/VisibilityConstraint
Field:
  • target_radius (float64) –
  • target_pose (geometry_msgs/PoseStamped) –
  • cone_sides (int32) –
  • sensor_pose (geometry_msgs/PoseStamped) –
  • max_view_angle (float64) –
  • max_range_angle (float64) –
  • sensor_view_direction (uint8) –
  • weight (float64) –
Constant:
  • SENSOR_Z (uint8):0
  • SENSOR_Y (uint8):1
  • SENSOR_X (uint8):2

The constraint is useful to maintain visibility to a disc (the target) in a particular frame. This disc forms the base of a visibiliy cone whose tip is at the origin of the sensor. Maintaining visibility is done by ensuring the robot does not obstruct the visibility cone. Note: This constraint does NOT enforce minimum or maximum distances between the sensor and the target, nor does it enforce the target to be in the field of view of the sensor. A PositionConstraint can (and probably should) be used for such purposes.

The radius of the disc that should be maintained visible

# The constraint is useful to maintain visibility to a disc (the target) in a particular frame.
# This disc forms the base of a visibiliy cone whose tip is at the origin of the sensor.
# Maintaining visibility is done by ensuring the robot does not obstruct the visibility cone.
# Note:
# This constraint does NOT enforce minimum or maximum distances between the sensor
# and the target, nor does it enforce the target to be in the field of view of
# the sensor. A PositionConstraint can (and probably should) be used for such purposes.

# The radius of the disc that should be maintained visible 
float64 target_radius

# The pose of the disc; as the robot moves, the pose of the disc may change as well
# This can be in the frame of a particular robot link, for example
geometry_msgs/PoseStamped target_pose

# From the sensor origin towards the target, the disc forms a visibility cone
# This cone is approximated using many sides. For example, when using 4 sides, 
# that in fact makes the visibility region be a pyramid.
# This value should always be 3 or more.
int32 cone_sides

# The pose in which visibility is to be maintained.
# The frame id should represent the robot link to which the sensor is attached.
# It is assumed the sensor can look directly at the target, in any direction.
# This assumption is usually not true, but additional PositionConstraints
# can resolve this issue.
geometry_msgs/PoseStamped sensor_pose

# Even though the disc is maintained visible, the visibility cone can be very small
# because of the orientation of the disc with respect to the sensor. It is possible
# for example to view the disk almost from a side, in which case the visibility cone 
# can end up having close to 0 volume. The view angle is defined to be the angle between
# the normal to the visibility disc and the direction vector from the sensor origin.
# The value below represents the minimum desired view angle. For a perfect view,
# this value will be 0 (the two vectors are exact opposites). For a completely obstructed view
# this value will be Pi/2 (the vectors are perpendicular). This value defined below 
# is the maximum view angle to be maintained. This should be a value in the open interval
# (0, Pi/2). If 0 is set, the view angle is NOT enforced.
float64 max_view_angle

# This angle is used similarly to max_view_angle but limits the maximum angle
# between the sensor origin direction vector and the axis that connects the
# sensor origin to the target frame origin. The value is again in the range (0, Pi/2)
# and is NOT enforced if set to 0.
float64 max_range_angle

# The axis that is assumed to indicate the direction of view for the sensor
# X = 2, Y = 1, Z = 0
uint8 SENSOR_Z=0
uint8 SENSOR_Y=1
uint8 SENSOR_X=2
uint8 sensor_view_direction

# A weighting factor for this constraint (denotes relative importance to other constraints. Closer to zero means less important)
float64 weight
moveit_msgs/RobotTrajectory
Field:
trajectory_msgs/JointTrajectory joint_trajectory
trajectory_msgs/MultiDOFJointTrajectory multi_dof_joint_trajectory
moveit_msgs/ObjectColor
Field:

The object id for which we specify color

# The object id for which we specify color
string id

# The value of the color
std_msgs/ColorRGBA color
moveit_msgs/PlanningSceneComponents
Constant:
  • SCENE_SETTINGS (uint32):1
  • ROBOT_STATE (uint32):2
  • ROBOT_STATE_ATTACHED_OBJECTS (uint32):4
  • WORLD_OBJECT_NAMES (uint32):8
  • WORLD_OBJECT_GEOMETRY (uint32):16
  • OCTOMAP (uint32):32
  • TRANSFORMS (uint32):64
  • ALLOWED_COLLISION_MATRIX (uint32):128
  • LINK_PADDING_AND_SCALING (uint32):256
  • OBJECT_COLORS (uint32):512
Field:
  • components (uint32) –

This message defines the components that make up the PlanningScene message. The values can be used as a bitfield to specify which parts of the PlanningScene message are of interest

Scene name, model name, model root

# This message defines the components that make up the PlanningScene message.
# The values can be used as a bitfield to specify which parts of the PlanningScene message
# are of interest

# Scene name, model name, model root
uint32 SCENE_SETTINGS=1

# Joint values of the robot state
uint32 ROBOT_STATE=2

# Attached objects (including geometry) for the robot state
uint32 ROBOT_STATE_ATTACHED_OBJECTS=4

# The names of the world objects
uint32 WORLD_OBJECT_NAMES=8

# The geometry of the world objects
uint32 WORLD_OBJECT_GEOMETRY=16

# The maintained octomap 
uint32 OCTOMAP=32

# The maintained list of transforms
uint32 TRANSFORMS=64

# The allowed collision matrix
uint32 ALLOWED_COLLISION_MATRIX=128

# The default link padding and link scaling
uint32 LINK_PADDING_AND_SCALING=256

# The stored object colors
uint32 OBJECT_COLORS=512

# Bitfield combining options indicated above
uint32 components
moveit_msgs/AttachedCollisionObject
Field:

The CollisionObject will be attached with a fixed joint to this link

# The CollisionObject will be attached with a fixed joint to this link
string link_name

#This contains the actual shapes and poses for the CollisionObject
#to be attached to the link
#If action is remove and no object.id is set, all objects
#attached to the link indicated by link_name will be removed
CollisionObject object

# The set of links that the attached objects are allowed to touch
# by default - the link_name is already considered by default
string[] touch_links

# If certain links were placed in a particular posture for this object to remain attached 
# (e.g., an end effector closing around an object), the posture necessary for releasing
# the object is stored here
trajectory_msgs/JointTrajectory detach_posture

# The weight of the attached object, if known
float64 weight
moveit_msgs/OrientedBoundingBox
Field:

the pose of the box

# the pose of the box
geometry_msgs/Pose pose

# the extents of the box, assuming the center is at the origin
geometry_msgs/Point32 extents
moveit_msgs/MoveItErrorCodes
Field:
  • val (int32) –
Constant:
  • SUCCESS (int32):1
  • FAILURE (int32):99999
  • PLANNING_FAILED (int32):-1
  • INVALID_MOTION_PLAN (int32):-2
  • MOTION_PLAN_INVALIDATED_BY_ENVIRONMENT_CHANGE (int32):-3
  • CONTROL_FAILED (int32):-4
  • UNABLE_TO_AQUIRE_SENSOR_DATA (int32):-5
  • TIMED_OUT (int32):-6
  • PREEMPTED (int32):-7
  • START_STATE_IN_COLLISION (int32):-10
  • START_STATE_VIOLATES_PATH_CONSTRAINTS (int32):-11
  • GOAL_IN_COLLISION (int32):-12
  • GOAL_VIOLATES_PATH_CONSTRAINTS (int32):-13
  • GOAL_CONSTRAINTS_VIOLATED (int32):-14
  • INVALID_GROUP_NAME (int32):-15
  • INVALID_GOAL_CONSTRAINTS (int32):-16
  • INVALID_ROBOT_STATE (int32):-17
  • INVALID_LINK_NAME (int32):-18
  • INVALID_OBJECT_NAME (int32):-19
  • FRAME_TRANSFORM_FAILURE (int32):-21
  • COLLISION_CHECKING_UNAVAILABLE (int32):-22
  • ROBOT_STATE_STALE (int32):-23
  • SENSOR_INFO_STALE (int32):-24
  • NO_IK_SOLUTION (int32):-31
int32 val

# overall behavior
int32 SUCCESS=1
int32 FAILURE=99999

int32 PLANNING_FAILED=-1
int32 INVALID_MOTION_PLAN=-2
int32 MOTION_PLAN_INVALIDATED_BY_ENVIRONMENT_CHANGE=-3
int32 CONTROL_FAILED=-4
int32 UNABLE_TO_AQUIRE_SENSOR_DATA=-5
int32 TIMED_OUT=-6
int32 PREEMPTED=-7

# planning & kinematics request errors
int32 START_STATE_IN_COLLISION=-10
int32 START_STATE_VIOLATES_PATH_CONSTRAINTS=-11

int32 GOAL_IN_COLLISION=-12
int32 GOAL_VIOLATES_PATH_CONSTRAINTS=-13
int32 GOAL_CONSTRAINTS_VIOLATED=-14

int32 INVALID_GROUP_NAME=-15
int32 INVALID_GOAL_CONSTRAINTS=-16
int32 INVALID_ROBOT_STATE=-17
int32 INVALID_LINK_NAME=-18
int32 INVALID_OBJECT_NAME=-19

# system errors
int32 FRAME_TRANSFORM_FAILURE=-21
int32 COLLISION_CHECKING_UNAVAILABLE=-22
int32 ROBOT_STATE_STALE=-23
int32 SENSOR_INFO_STALE=-24

# kinematics errors
int32 NO_IK_SOLUTION=-31
moveit_msgs/LinkPadding
Field:
  • link_name (string) –
  • padding (float64) –

name for the link

#name for the link
string link_name

# padding to apply to the link
float64 padding
moveit_msgs/ContactInformation
Field:
Constant:
  • ROBOT_LINK (uint32):0
  • WORLD_OBJECT (uint32):1
  • ROBOT_ATTACHED (uint32):2

Standard ROS header contains information about the frame in which this contact is specified

# Standard ROS header contains information 
# about the frame in which this 
# contact is specified
Header header

# Position of the contact point
geometry_msgs/Point position

# Normal corresponding to the contact point
geometry_msgs/Vector3 normal 

# Depth of contact point
float64 depth

# Name of the first body that is in contact
# This could be a link or a namespace that represents a body
string contact_body_1
uint32 body_type_1

# Name of the second body that is in contact
# This could be a link or a namespace that represents a body
string contact_body_2
uint32 body_type_2

uint32 ROBOT_LINK=0
uint32 WORLD_OBJECT=1
uint32 ROBOT_ATTACHED=2
moveit_msgs/Grasp
Field:

This message contains a description of a grasp that would be used with a particular end-effector to grasp an object, including how to approach it, grip it, etc. This message does not contain any information about a “grasp point” (a position ON the object). Whatever generates this message should have already combined information about grasp points with information about the geometry of the end-effector to compute the grasp_pose in this message.

A name for this grasp

# This message contains a description of a grasp that would be used
# with a particular end-effector to grasp an object, including how to
# approach it, grip it, etc.  This message does not contain any
# information about a "grasp point" (a position ON the object).
# Whatever generates this message should have already combined
# information about grasp points with information about the geometry
# of the end-effector to compute the grasp_pose in this message.

# A name for this grasp
string id

# The internal posture of the hand for the pre-grasp
# only positions are used
trajectory_msgs/JointTrajectory pre_grasp_posture

# The internal posture of the hand for the grasp
# positions and efforts are used
trajectory_msgs/JointTrajectory grasp_posture

# The position of the end-effector for the grasp.  This is the pose of
# the "parent_link" of the end-effector, not actually the pose of any
# link *in* the end-effector.  Typically this would be the pose of the
# most distal wrist link before the hand (end-effector) links began.
geometry_msgs/PoseStamped grasp_pose

# The estimated probability of success for this grasp, or some other
# measure of how "good" it is.
float64 grasp_quality

# The approach direction to take before picking an object
GripperTranslation pre_grasp_approach

# The retreat direction to take after a grasp has been completed (object is attached)
GripperTranslation post_grasp_retreat

# The retreat motion to perform when releasing the object; this information
# is not necessary for the grasp itself, but when releasing the object,
# the information will be necessary. The grasp used to perform a pickup
# is returned as part of the result, so this information is available for 
# later use.
GripperTranslation post_place_retreat

# the maximum contact force to use while grasping (<=0 to disable)
float32 max_contact_force

# an optional list of obstacles that we have semantic information about
# and that can be touched/pushed/moved in the course of grasping
string[] allowed_touch_objects
moveit_msgs/LinkScale
Field:
  • link_name (string) –
  • scale (float64) –

name for the link

#name for the link
string link_name

# scaling to apply to the link
float64 scale
moveit_msgs/JointConstraint
Field:
  • joint_name (string) –
  • position (float64) –
  • tolerance_above (float64) –
  • tolerance_below (float64) –
  • weight (float64) –

Constrain the position of a joint to be within a certain bound

# Constrain the position of a joint to be within a certain bound
string joint_name

# the bound to be achieved is [position - tolerance_below, position + tolerance_above]
float64 position
float64 tolerance_above
float64 tolerance_below

# A weighting factor for this constraint (denotes relative importance to other constraints. Closer to zero means less important)
float64 weight

Service types

moveit_msgs/GetMotionPlan
Field (Request):
 
Field (Response):
 

This service contains the definition for a request to the motion planner and the output it provides

# This service contains the definition for a request to the motion
# planner and the output it provides

MotionPlanRequest motion_plan_request

---

MotionPlanResponse motion_plan_response
moveit_msgs/LoadMap
Field (Request):
 
  • filename (string) –
Field (Response):
 
  • success (bool) –
string filename
---
bool success
moveit_msgs/GetCartesianPath
Field (Request):
 
Field (Response):
 

Define the frame for the specified waypoints

# Define the frame for the specified waypoints
Header header

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

# Mandatory name of group to compute the path for
string group_name

# Optional name of IK link for which waypoints are specified.
# If not specified, the tip of the group (which is assumed to be a chain)
# is assumed to be the link
string link_name

# A sequence of waypoints to be followed by the specified link, 
# while moving the specified group, such that the group moves only
# in a straight line between waypoints
geometry_msgs/Pose[] waypoints

# The maximum distance (in Cartesian space) between consecutive points
# in the returned path. This must always be specified and > 0
float64 max_step

# If above 0, this value is assumed to be the maximum allowed distance 
# (L infinity) in configuration space, between consecutive points.
# If this distance is found to be above the maximum threshold, the path 
# computation fails.
float64 jump_threshold

# Set to true if collisions should be avoided when possible
bool avoid_collisions

# Specify additional constraints to be met by the Cartesian path
Constraints path_constraints

---

# The state at which the computed path starts
RobotState start_state

# The computed solution trajectory, for the desired group, in configuration space
RobotTrajectory solution

# If the computation was incomplete, this value indicates the fraction of the path
# that was in fact computed (nr of waypoints traveled through)
float64 fraction

# The error code of the computation
MoveItErrorCodes error_code
moveit_msgs/SaveMap
Field (Request):
 
  • filename (string) –
Field (Response):
 
  • success (bool) –
string filename

---

bool success
moveit_msgs/GetPositionFK
Field (Request):
 
Field (Response):
 

A service definition for a standard forward kinematics service The frame_id in the header message is the frame in which the forward kinematics poses will be returned

# A service definition for a standard forward kinematics service
# The frame_id in the header message is the frame in which 
# the forward kinematics poses will be returned
Header header

# A vector of link name for which forward kinematics must be computed
string[] fk_link_names

# A robot state consisting of joint names and joint positions to be used for forward kinematics
RobotState robot_state
---
# The resultant vector of PoseStamped messages that contains the (stamped) poses of the requested links
geometry_msgs/PoseStamped[] pose_stamped

# The list of link names corresponding to the poses
string[] fk_link_names

MoveItErrorCodes error_code
moveit_msgs/GetKinematicSolverInfo
Field (Response):
 
# A service call to get more information about the solver used by a node performing kinematics
---
KinematicSolverInfo kinematic_solver_info
moveit_msgs/GetConstraintAwarePositionIK
Field (Request):
 
Field (Response):
 

A service call to carry out an inverse kinematics computation The inverse kinematics request

# A service call to carry out an inverse kinematics computation
# The inverse kinematics request
PositionIKRequest ik_request

# A set of constraints that the IK must obey
Constraints constraints

---

# The returned solution 
RobotState solution
MoveItErrorCodes error_code
moveit_msgs/ExecuteKnownTrajectory
Field (Request):
 
Field (Response):
 

The trajectory to execute

# The trajectory to execute 
RobotTrajectory trajectory

# Set this to true if the service should block until the execution is complete
bool wait_for_execution

---

# Error code - encodes the overall reason for failure
MoveItErrorCodes error_code
moveit_msgs/QueryPlannerInterfaces
Field (Response):
 
---

# The planning instances that could be used in the benchmark
PlannerInterfaceDescription[] planner_interfaces
moveit_msgs/GetStateValidity
Field (Request):
 
Field (Response):
 
RobotState robot_state
string group_name
Constraints constraints

---

bool valid
ContactInformation[] contacts
CostSource[] cost_sources
ConstraintEvalResult[] constraint_result
moveit_msgs/GetPlanningScene
Field (Request):
 
Field (Response):
 

Get parts of the planning scene that are of interest

# Get parts of the planning scene that are of interest
PlanningSceneComponents components
---
PlanningScene scene
moveit_msgs/GetPositionIK
Field (Request):
 
Field (Response):
 

A service call to carry out an inverse kinematics computation The inverse kinematics request

# A service call to carry out an inverse kinematics computation
# The inverse kinematics request
PositionIKRequest ik_request

---

# The returned solution 
# (in the same order as the list of joints specified in the IKRequest message)
RobotState solution

MoveItErrorCodes error_code

Action types

moveit_msgs/MoveGroup
Field (Goal):
Field (Result):
Field (Feedback):
 
  • state (string) –

Motion planning request to pass to planner

# Motion planning request to pass to planner
MotionPlanRequest request

# Planning options
PlanningOptions planning_options

---

# An error code reflecting what went wrong
MoveItErrorCodes error_code

# The full starting state of the robot at the start of the trajectory
moveit_msgs/RobotState trajectory_start

# The trajectory that moved group produced for execution
moveit_msgs/RobotTrajectory planned_trajectory

# The trace of the trajectory recorded during execution
moveit_msgs/RobotTrajectory executed_trajectory

# The amount of time it took to complete the motion plan
float64 planning_time

---

# The internal state that the move group action currently is in
string state
moveit_msgs/Pickup
Field (Goal):
  • target_name (string) –
  • group_name (string) –
  • end_effector (string) –
  • possible_grasps[] (moveit_msgs/Grasp) –
  • support_surface_name (string) –
  • allow_gripper_support_collision (bool) –
  • attached_object_touch_links[] (string) –
  • minimize_object_distance (bool) –
  • path_constraints (moveit_msgs/Constraints) –
  • planner_id (string) –
  • allowed_touch_objects[] (string) –
  • allowed_planning_time (float64) –
  • planning_options (moveit_msgs/PlanningOptions) –
Field (Result):
Field (Feedback):
 
  • state (string) –

An action for picking up an object

The name of the object to pick up (as known in the planning scene)

# An action for picking up an object

# The name of the object to pick up (as known in the planning scene)
string target_name

# which group should be used to plan for pickup
string group_name

# which end-effector to be used for pickup (ideally descending from the group above)
string end_effector

# a list of possible grasps to be used. At least one grasp must be filled in
Grasp[] possible_grasps

# the name that the support surface (e.g. table) has in the collision map
# can be left empty if no name is available
string support_surface_name

# whether collisions between the gripper and the support surface should be acceptable
# during move from pre-grasp to grasp and during lift. Collisions when moving to the
# pre-grasp location are still not allowed even if this is set to true.
bool allow_gripper_support_collision

# The names of the links the object to be attached is allowed to touch;
# If this is left empty, it defaults to the links in the used end-effector
string[] attached_object_touch_links

# Optionally notify the pick action that it should approach the object further,
# as much as possible (this minimizing the distance to the object before the grasp)
# along the approach direction; Note: this option changes the grasping poses
# supplied in possible_grasps[] such that they are closer to the object when possible.
bool minimize_object_distance

# Optional constraints to be imposed on every point in the motion plan
Constraints path_constraints

# The name of the motion planner to use. If no name is specified,
# a default motion planner will be used
string planner_id

# an optional list of obstacles that we have semantic information about
# and that can be touched/pushed/moved in the course of grasping;
# CAREFUL: If the object name 'all' is used, collisions with all objects are disabled during the approach & lift.
string[] allowed_touch_objects

# The maximum amount of time the motion planner is allowed to plan for
float64 allowed_planning_time

# Planning options
PlanningOptions planning_options

---

# The overall result of the pickup attempt
MoveItErrorCodes error_code

# The full starting state of the robot at the start of the trajectory
RobotState trajectory_start

# The trajectory that moved group produced for execution
RobotTrajectory[] trajectory_stages

string[] trajectory_descriptions

# The performed grasp, if attempt was successful
Grasp grasp

---

# The internal state that the pickup action currently is in
string state
moveit_msgs/Place
Field (Goal):
  • group_name (string) –
  • attached_object_name (string) –
  • place_locations[] (moveit_msgs/PlaceLocation) –
  • place_eef (bool) –
  • support_surface_name (string) –
  • allow_gripper_support_collision (bool) –
  • path_constraints (moveit_msgs/Constraints) –
  • planner_id (string) –
  • allowed_touch_objects[] (string) –
  • allowed_planning_time (float64) –
  • planning_options (moveit_msgs/PlanningOptions) –
Field (Result):
Field (Feedback):
 
  • state (string) –

An action for placing an object

which group to be used to plan for grasping

# An action for placing an object

# which group to be used to plan for grasping
string group_name

# the name that the attached object to place
string attached_object_name

# a list of possible transformations for placing the object
PlaceLocation[] place_locations

# if the user prefers setting the eef pose (same as in pick) rather than 
# the location of an end effector, this flag should be set to true
bool place_eef

# the name that the support surface (e.g. table) has in the collision world
# can be left empty if no name is available
string support_surface_name

# whether collisions between the gripper and the support surface should be acceptable
# during move from pre-place to place and during retreat. Collisions when moving to the
# pre-place location are still not allowed even if this is set to true.
bool allow_gripper_support_collision

# Optional constraints to be imposed on every point in the motion plan
Constraints path_constraints

# The name of the motion planner to use. If no name is specified,
# a default motion planner will be used
string planner_id

# an optional list of obstacles that we have semantic information about
# and that can be touched/pushed/moved in the course of grasping;
# CAREFUL: If the object name 'all' is used, collisions with all objects are disabled during the approach & lift.
string[] allowed_touch_objects

# The maximum amount of time the motion planner is allowed to plan for
float64 allowed_planning_time

# Planning options
PlanningOptions planning_options

---

# The result of the pickup attempt
MoveItErrorCodes error_code

# The full starting state of the robot at the start of the trajectory
RobotState trajectory_start

# The trajectory that moved group produced for execution
RobotTrajectory[] trajectory_stages

string[] trajectory_descriptions

# The successful place location, if any
PlaceLocation place_location

---

# The internal state that the place action currently is in
string state