sbpl_cart_planner/SBPLCartPlannerStats Message

File: sbpl_cart_planner/SBPLCartPlannerStats.msg

#planner stats
float64 initial_epsilon
float64 final_epsilon
bool plan_to_first_solution
float64 allocated_time
float64 actual_time
float64 time_to_first_solution
float64 solution_cost
float64 path_size
int64 final_number_of_expands
int64 number_of_expands_initial_solution

#problem stats
geometry_msgs/PoseStamped start
float64 start_cart_angle
geometry_msgs/PoseStamped goal
float64 goal_cart_angle

#solution
cart_pushing_msgs/RobotCartPath solution

Expanded Definition

float64 initial_epsilon
float64 final_epsilon
bool plan_to_first_solution
float64 allocated_time
float64 actual_time
float64 time_to_first_solution
float64 solution_cost
float64 path_size
int64 final_number_of_expands
int64 number_of_expands_initial_solution
geometry_msgs/PoseStamped start
    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 start_cart_angle
geometry_msgs/PoseStamped goal
    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 goal_cart_angle
cart_pushing_msgs/RobotCartPath solution
    Header header
        uint32 seq
        time stamp
        string frame_id
    cart_pushing_msgs/RobotCartConfiguration[] path
        geometry_msgs/Pose robot_pose
            geometry_msgs/Point position
                float64 x
                float64 y
                float64 z
            geometry_msgs/Quaternion orientation
                float64 x
                float64 y
                float64 z
                float64 w
        geometry_msgs/Pose cart_pose
            geometry_msgs/Point position
                float64 x
                float64 y
                float64 z
            geometry_msgs/Quaternion orientation
                float64 x
                float64 y
                float64 z
                float64 w