motion_planning_msgs/FilterJointTrajectoryWithConstraints Service

File: motion_planning_msgs/FilterJointTrajectoryWithConstraints.srv

# A trajectory message that encodes joint limits, collision and state constraints within it.
trajectory_msgs/JointTrajectory trajectory

# A vector of JointLimit messages.
# Each message contains the limits for a specific joint
motion_planning_msgs/JointLimits[] limits

# A specification for regions where contact is 
# allowed upto a certain depth
# Any collision within this set of regions with a link 
# specified in the message will be allowed if
# it is less than the penetration depth specified in the message
AllowedContactSpecification[] allowed_contacts

# A set of ordered collision operations, 
# these are applied to all links, objects, 
# namespaces in the collision space
OrderedCollisionOperations ordered_collision_operations

# Specifies a set of links and paddings to change from the default
# specified in the yaml file
motion_planning_msgs/LinkPadding[] link_padding

# A set of path constraints on the trajectory
Constraints path_constraints

# A set of goal constraints on the trajectory
Constraints goal_constraints

duration allowed_time
---
trajectory_msgs/JointTrajectory trajectory
ArmNavigationErrorCodes error_code

Expanded Definition

trajectory_msgs/JointTrajectory trajectory
    Header header
        uint32 seq
        time stamp
        string frame_id
    string[] joint_names
    trajectory_msgs/JointTrajectoryPoint[] points
        float64[] positions
        float64[] velocities
        float64[] accelerations
        duration time_from_start
motion_planning_msgs/JointLimits[] limits
    string joint_name
    uint8 has_position_limits
    float64 min_position
    float64 max_position
    uint8 has_velocity_limits
    float64 max_velocity
    uint8 has_acceleration_limits
    float64 max_acceleration
AllowedContactSpecification[] allowed_contacts
    string name
    geometric_shapes_msgs/Shape shape
        byte SPHERE=0
        byte BOX=1
        byte CYLINDER=2
        byte MESH=3
        byte type
        float64[] dimensions
        int32[] triangles
        geometry_msgs/Point[] vertices
            float64 x
            float64 y
            float64 z
    geometry_msgs/PoseStamped pose_stamped
        Header header
            uint32 seq
            time stamp
            string frame_id
        geometry_msgs/Pose pose
            geometry_msgs/Point position
                float64 x
                float64 y
                float64 z
            geometry_msgs/Quaternion orientation
                float64 x
                float64 y
                float64 z
                float64 w
    string[] link_names
    float64 penetration_depth
OrderedCollisionOperations ordered_collision_operations
    motion_planning_msgs/CollisionOperation[] collision_operations
        string COLLISION_SET_ALL="all"
        string COLLISION_SET_OBJECTS="objects"
        string COLLISION_SET_ATTACHED_OBJECTS="attached"
        int32 DISABLE=0
        int32 ENABLE=1
        string object1
        string object2
        float64 penetration_distance
        int32 operation
motion_planning_msgs/LinkPadding[] link_padding
    string link_name
    float64 padding
Constraints path_constraints
    motion_planning_msgs/JointConstraint[] joint_constraints
        string joint_name
        float64 position
        float64 tolerance_above
        float64 tolerance_below
        float64 weight
    motion_planning_msgs/PositionConstraint[] position_constraints
        Header header
            uint32 seq
            time stamp
            string frame_id
        string link_name
        geometry_msgs/Point target_point_offset
            float64 x
            float64 y
            float64 z
        geometry_msgs/Point position
            float64 x
            float64 y
            float64 z
        geometric_shapes_msgs/Shape constraint_region_shape
            byte SPHERE=0
            byte BOX=1
            byte CYLINDER=2
            byte MESH=3
            byte type
            float64[] dimensions
            int32[] triangles
            geometry_msgs/Point[] vertices
                float64 x
                float64 y
                float64 z
        geometry_msgs/Quaternion constraint_region_orientation
            float64 x
            float64 y
            float64 z
            float64 w
        float64 weight
    motion_planning_msgs/OrientationConstraint[] orientation_constraints
        int32 LINK_FRAME=0
        int32 HEADER_FRAME=1
        Header header
            uint32 seq
            time stamp
            string frame_id
        string link_name
        int32 type
        geometry_msgs/Quaternion orientation
            float64 x
            float64 y
            float64 z
            float64 w
        float64 absolute_roll_tolerance
        float64 absolute_pitch_tolerance
        float64 absolute_yaw_tolerance
        float64 weight
    motion_planning_msgs/VisibilityConstraint[] visibility_constraints
        Header header
            uint32 seq
            time stamp
            string frame_id
        geometry_msgs/PointStamped target
            Header header
                uint32 seq
                time stamp
                string frame_id
            geometry_msgs/Point point
                float64 x
                float64 y
                float64 z
        geometry_msgs/PoseStamped sensor_pose
            Header header
                uint32 seq
                time stamp
                string frame_id
            geometry_msgs/Pose pose
                geometry_msgs/Point position
                    float64 x
                    float64 y
                    float64 z
                geometry_msgs/Quaternion orientation
                    float64 x
                    float64 y
                    float64 z
                    float64 w
        float64 absolute_tolerance
Constraints goal_constraints
    motion_planning_msgs/JointConstraint[] joint_constraints
        string joint_name
        float64 position
        float64 tolerance_above
        float64 tolerance_below
        float64 weight
    motion_planning_msgs/PositionConstraint[] position_constraints
        Header header
            uint32 seq
            time stamp
            string frame_id
        string link_name
        geometry_msgs/Point target_point_offset
            float64 x
            float64 y
            float64 z
        geometry_msgs/Point position
            float64 x
            float64 y
            float64 z
        geometric_shapes_msgs/Shape constraint_region_shape
            byte SPHERE=0
            byte BOX=1
            byte CYLINDER=2
            byte MESH=3
            byte type
            float64[] dimensions
            int32[] triangles
            geometry_msgs/Point[] vertices
                float64 x
                float64 y
                float64 z
        geometry_msgs/Quaternion constraint_region_orientation
            float64 x
            float64 y
            float64 z
            float64 w
        float64 weight
    motion_planning_msgs/OrientationConstraint[] orientation_constraints
        int32 LINK_FRAME=0
        int32 HEADER_FRAME=1
        Header header
            uint32 seq
            time stamp
            string frame_id
        string link_name
        int32 type
        geometry_msgs/Quaternion orientation
            float64 x
            float64 y
            float64 z
            float64 w
        float64 absolute_roll_tolerance
        float64 absolute_pitch_tolerance
        float64 absolute_yaw_tolerance
        float64 weight
    motion_planning_msgs/VisibilityConstraint[] visibility_constraints
        Header header
            uint32 seq
            time stamp
            string frame_id
        geometry_msgs/PointStamped target
            Header header
                uint32 seq
                time stamp
                string frame_id
            geometry_msgs/Point point
                float64 x
                float64 y
                float64 z
        geometry_msgs/PoseStamped sensor_pose
            Header header
                uint32 seq
                time stamp
                string frame_id
            geometry_msgs/Pose pose
                geometry_msgs/Point position
                    float64 x
                    float64 y
                    float64 z
                geometry_msgs/Quaternion orientation
                    float64 x
                    float64 y
                    float64 z
                    float64 w
        float64 absolute_tolerance
duration allowed_time

trajectory_msgs/JointTrajectory trajectory
    Header header
        uint32 seq
        time stamp
        string frame_id
    string[] joint_names
    trajectory_msgs/JointTrajectoryPoint[] points
        float64[] positions
        float64[] velocities
        float64[] accelerations
        duration time_from_start
ArmNavigationErrorCodes error_code
    int32 PLANNING_FAILED=-1
    int32 SUCCESS=1
    int32 TIMED_OUT=-2
    int32 START_STATE_IN_COLLISION=-3
    int32 START_STATE_VIOLATES_PATH_CONSTRAINTS=-4
    int32 GOAL_IN_COLLISION=-5
    int32 GOAL_VIOLATES_PATH_CONSTRAINTS=-6
    int32 INVALID_ROBOT_STATE=-7
    int32 INCOMPLETE_ROBOT_STATE=-8
    int32 INVALID_PLANNER_ID=-9
    int32 INVALID_NUM_PLANNING_ATTEMPTS=-10
    int32 INVALID_ALLOWED_PLANNING_TIME=-11
    int32 INVALID_GROUP_NAME=-12
    int32 INVALID_GOAL_JOINT_CONSTRAINTS=-13
    int32 INVALID_GOAL_POSITION_CONSTRAINTS=-14
    int32 INVALID_GOAL_ORIENTATION_CONSTRAINTS=-15
    int32 INVALID_PATH_JOINT_CONSTRAINTS=-16
    int32 INVALID_PATH_POSITION_CONSTRAINTS=-17
    int32 INVALID_PATH_ORIENTATION_CONSTRAINTS=-18
    int32 INVALID_TRAJECTORY=-19
    int32 INVALID_INDEX=-20
    int32 JOINT_LIMITS_VIOLATED=-21
    int32 PATH_CONSTRAINTS_VIOLATED=-22
    int32 COLLISION_CONSTRAINTS_VIOLATED=-23
    int32 GOAL_CONSTRAINTS_VIOLATED=-24
    int32 JOINTS_NOT_MOVING=-25
    int32 TRAJECTORY_CONTROLLER_FAILED=-26
    int32 FRAME_TRANSFORM_FAILURE=-27
    int32 COLLISION_CHECKING_UNAVAILABLE=-28
    int32 ROBOT_STATE_STALE=-29
    int32 SENSOR_INFO_STALE=-30
    int32 NO_IK_SOLUTION=-31
    int32 INVALID_LINK_NAME=-32
    int32 IK_LINK_IN_COLLISION=-33
    int32 NO_FK_SOLUTION=-34
    int32 KINEMATICS_STATE_IN_COLLISION=-35
    int32 INVALID_TIMEOUT=-36
    int32 val