fast_plane_detection/PlaneInRegion Service

File: fast_plane_detection/PlaneInRegion.srv

# Takes in a disparity image, a 3D point and a region size and 
# output the most dominant plane in that region

geometry_msgs/Vector3Stamped point

int64 width
int64 height

---

fast_plane_detection/Plane plane

Expanded Definition

geometry_msgs/Vector3Stamped point
    Header header
        uint32 seq
        time stamp
        string frame_id
    geometry_msgs/Vector3 vector
        float64 x
        float64 y
        float64 z
int64 width
int64 height

fast_plane_detection/Plane plane
    int32 SUCCESS=1
    int32 FEW_INLIERS=2
    int32 NO_PLANE=3
    int32 OTHER_ERROR=4
    geometry_msgs/PoseStamped 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
    geometry_msgs/PointStamped plane_point
        Header header
            uint32 seq
            time stamp
            string frame_id
        geometry_msgs/Point point
            float64 x
            float64 y
            float64 z
    geometry_msgs/Vector3Stamped normal
        Header header
            uint32 seq
            time stamp
            string frame_id
        geometry_msgs/Vector3 vector
            float64 x
            float64 y
            float64 z
    float64 plane_d
    geometry_msgs/PointStamped slave_point
        Header header
            uint32 seq
            time stamp
            string frame_id
        geometry_msgs/Point point
            float64 x
            float64 y
            float64 z
    geometry_msgs/Point32 top_left
        float32 x
        float32 y
        float32 z
    geometry_msgs/Point32 top_right
        float32 x
        float32 y
        float32 z
    geometry_msgs/Point32 bottom_left
        float32 x
        float32 y
        float32 z
    geometry_msgs/Point32 bottom_right
        float32 x
        float32 y
        float32 z
    int32 result
    int32 percentage_inliers
    float32 error