chomp_motion_planner/GetStateCost Service

File: chomp_motion_planner/GetStateCost.srv

# A service call to get the cost for a given state of the robot (specified in the form of a RobotState message)

# A list of link names for which the cost should be computed
string[] link_names
# The robot state for which the cost should be computed
motion_planning_msgs/RobotState robot_state
----
# True if the cost computation was valid
bool valid
# The cost corresponding to each link
float64[] costs

Expanded Definition

string[] link_names
motion_planning_msgs/RobotState robot_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

bool valid
float64[] costs