moveit_msgs¶
Contents:
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: - website<http://moveit.ros.org>
- bugtracker<https://github.com/ros-planning/moveit_msgs/issues>
- repository<https://github.com/ros-planning/moveit_msgs>
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
moveit_msgs/OrientationConstraint
moveit_msgs/PlanningSceneWorld
moveit_msgs/GripperTranslation
moveit_msgs/BoundingVolume
moveit_msgs/JointLimits
moveit_msgs/KinematicSolverInfo
moveit_msgs/DisplayRobotState
moveit_msgs/PlanningScene
moveit_msgs/PlaceLocation
moveit_msgs/CollisionObject
moveit_msgs/DisplayTrajectory
moveit_msgs/AllowedCollisionMatrix
moveit_msgs/MotionPlanRequest
moveit_msgs/MotionPlanResponse
moveit_msgs/RobotState
moveit_msgs/PositionIKRequest
moveit_msgs/AllowedCollisionEntry
moveit_msgs/PlannerInterfaceDescription
moveit_msgs/MotionPlanDetailedResponse
moveit_msgs/WorkspaceParameters
moveit_msgs/TrajectoryConstraints
moveit_msgs/ConstraintEvalResult
moveit_msgs/PlanningOptions
moveit_msgs/Constraints
moveit_msgs/CostSource
moveit_msgs/VisibilityConstraint
moveit_msgs/RobotTrajectory
moveit_msgs/ObjectColor
moveit_msgs/PlanningSceneComponents
moveit_msgs/AttachedCollisionObject
moveit_msgs/OrientedBoundingBox
moveit_msgs/MoveItErrorCodes
moveit_msgs/LinkPadding
moveit_msgs/ContactInformation
moveit_msgs/Grasp
moveit_msgs/LinkScale
moveit_msgs/JointConstraint
Service types¶
moveit_msgs/GetMotionPlan
moveit_msgs/LoadMap
moveit_msgs/GetCartesianPath
moveit_msgs/SaveMap
moveit_msgs/GetPositionFK
moveit_msgs/GetKinematicSolverInfo
moveit_msgs/GetConstraintAwarePositionIK
moveit_msgs/ExecuteKnownTrajectory
moveit_msgs/QueryPlannerInterfaces
moveit_msgs/GetStateValidity
moveit_msgs/GetPlanningScene
moveit_msgs/GetPositionIK
-
moveit_msgs/GetMotionPlan
¶ Field (Request): - motion_plan_request (moveit_msgs/MotionPlanRequest) –
Field (Response): - motion_plan_response (moveit_msgs/MotionPlanResponse) –
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): - header (std_msgs/Header) –
- start_state (moveit_msgs/RobotState) –
- group_name (string) –
- link_name (string) –
- waypoints[] (geometry_msgs/Pose) –
- max_step (float64) –
- jump_threshold (float64) –
- avoid_collisions (bool) –
- path_constraints (moveit_msgs/Constraints) –
Field (Response): - start_state (moveit_msgs/RobotState) –
- solution (moveit_msgs/RobotTrajectory) –
- fraction (float64) –
- error_code (moveit_msgs/MoveItErrorCodes) –
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): - header (std_msgs/Header) –
- fk_link_names[] (string) –
- robot_state (moveit_msgs/RobotState) –
Field (Response): - pose_stamped[] (geometry_msgs/PoseStamped) –
- fk_link_names[] (string) –
- error_code (moveit_msgs/MoveItErrorCodes) –
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): - kinematic_solver_info (moveit_msgs/KinematicSolverInfo) –
# 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): - ik_request (moveit_msgs/PositionIKRequest) –
- constraints (moveit_msgs/Constraints) –
Field (Response): - solution (moveit_msgs/RobotState) –
- error_code (moveit_msgs/MoveItErrorCodes) –
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): - trajectory (moveit_msgs/RobotTrajectory) –
- wait_for_execution (bool) –
Field (Response): - error_code (moveit_msgs/MoveItErrorCodes) –
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): - planner_interfaces[] (moveit_msgs/PlannerInterfaceDescription) –
--- # The planning instances that could be used in the benchmark PlannerInterfaceDescription[] planner_interfaces
-
moveit_msgs/GetStateValidity
¶ Field (Request): - robot_state (moveit_msgs/RobotState) –
- group_name (string) –
- constraints (moveit_msgs/Constraints) –
Field (Response): - valid (bool) –
- contacts[] (moveit_msgs/ContactInformation) –
- cost_sources[] (moveit_msgs/CostSource) –
- constraint_result[] (moveit_msgs/ConstraintEvalResult) –
RobotState robot_state string group_name Constraints constraints --- bool valid ContactInformation[] contacts CostSource[] cost_sources ConstraintEvalResult[] constraint_result
-
moveit_msgs/GetPlanningScene
¶ Field (Request): - components (moveit_msgs/PlanningSceneComponents) –
Field (Response): - scene (moveit_msgs/PlanningScene) –
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): - ik_request (moveit_msgs/PositionIKRequest) –
Field (Response): - solution (moveit_msgs/RobotState) –
- error_code (moveit_msgs/MoveItErrorCodes) –
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): - request (moveit_msgs/MotionPlanRequest) –
- planning_options (moveit_msgs/PlanningOptions) –
Field (Result): - error_code (moveit_msgs/MoveItErrorCodes) –
- trajectory_start (moveit_msgs/RobotState) –
- planned_trajectory (moveit_msgs/RobotTrajectory) –
- executed_trajectory (moveit_msgs/RobotTrajectory) –
- planning_time (float64) –
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): - error_code (moveit_msgs/MoveItErrorCodes) –
- trajectory_start (moveit_msgs/RobotState) –
- trajectory_stages[] (moveit_msgs/RobotTrajectory) –
- trajectory_descriptions[] (string) –
- grasp (moveit_msgs/Grasp) –
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): - error_code (moveit_msgs/MoveItErrorCodes) –
- trajectory_start (moveit_msgs/RobotState) –
- trajectory_stages[] (moveit_msgs/RobotTrajectory) –
- trajectory_descriptions[] (string) –
- place_location (moveit_msgs/PlaceLocation) –
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