chomp_motion_planner/GetChompCollisionCost Service

File: chomp_motion_planner/GetChompCollisionCost.srv

# Array of string names for the links for which cost information is desired
string[] links

# The state of the robot represented as an array of Kinematic states which
# include the joint name and joint value
motion_planning_msgs/RobotState state

---

# Returns an array of costs for the links (in the same order as the input)
float64[] costs

# Each element of this array is a num_joints x 1 array that represents the
# joint velocity that will move the link down the gradient of the distance
# field (away from collisions)
JointVelocityArray[] gradient

# A boolean value which indicates whether the configuration is in collision
uint8 in_collision

Expanded Definition

string[] links
motion_planning_msgs/RobotState state
    sensor_msgs/JointState joint_state
        Header header
            uint32 seq
            time stamp
            string frame_id
        string[] name
        float64[] position
        float64[] velocity
        float64[] effort
    motion_planning_msgs/MultiDOFJointState multi_dof_joint_state
        time stamp
        string[] joint_names
        string[] frame_ids
        string[] child_frame_ids
        geometry_msgs/Pose[] poses
            geometry_msgs/Point position
                float64 x
                float64 y
                float64 z
            geometry_msgs/Quaternion orientation
                float64 x
                float64 y
                float64 z
                float64 w

float64[] costs
JointVelocityArray[] gradient
    string[] joint_names
    float64[] velocities
uint8 in_collision