Public Member Functions | |
FastRegionPlaneService () | |
bool | planeCallback (fast_plane_detection::PlaneInRegion::Request &req, fast_plane_detection::PlaneInRegion::Response &res) |
Callback for disparity image messages. | |
~FastRegionPlaneService () | |
Public Attributes | |
Plane | plane_ |
the plane | |
Private Member Functions | |
bool | maskDisparityImage (fast_plane_detection::PlaneInRegion::Request &req, const stereo_msgs::DisparityImage::ConstPtr &disparity, const sensor_msgs::CameraInfo::ConstPtr &camera_info, const stereo_msgs::DisparityImage::Ptr &masked_disparity) |
Private Attributes | |
ros::Publisher | disparity_image_pub_ |
Publisher to Filtered Disparity Images. | |
int | inlier_threshold_ |
Minimum number of points necessary to pass a plane detection. | |
PlaneDetection * | plane_detect_ |
plane detection object | |
PlaneTransform * | plane_transform_ |
object for transforming from x,y,d space to x,y,z | |
ros::NodeHandle | priv_nh_ |
Node handle in the private namespace. | |
ros::NodeHandle | root_nh_ |
The node handle. | |
double | up_direction_ |
Definition at line 58 of file fast_plane_detector_server.cpp.
fast_plane_detection::FastRegionPlaneService::FastRegionPlaneService | ( | ) |
Definition at line 107 of file fast_plane_detector_server.cpp.
fast_plane_detection::FastRegionPlaneService::~FastRegionPlaneService | ( | ) |
Definition at line 125 of file fast_plane_detector_server.cpp.
bool fast_plane_detection::FastRegionPlaneService::maskDisparityImage | ( | fast_plane_detection::PlaneInRegion::Request & | req, | |
const stereo_msgs::DisparityImage::ConstPtr & | disparity, | |||
const sensor_msgs::CameraInfo::ConstPtr & | camera_info, | |||
const stereo_msgs::DisparityImage::Ptr & | masked_disparity | |||
) | [private] |
Definition at line 287 of file fast_plane_detector_server.cpp.
bool fast_plane_detection::FastRegionPlaneService::planeCallback | ( | fast_plane_detection::PlaneInRegion::Request & | req, | |
fast_plane_detection::PlaneInRegion::Response & | res | |||
) |
Callback for disparity image messages.
Definition at line 130 of file fast_plane_detector_server.cpp.
ros::Publisher fast_plane_detection::FastRegionPlaneService::disparity_image_pub_ [private] |
Publisher to Filtered Disparity Images.
Definition at line 87 of file fast_plane_detector_server.cpp.
Minimum number of points necessary to pass a plane detection.
Definition at line 84 of file fast_plane_detector_server.cpp.
the plane
Definition at line 102 of file fast_plane_detector_server.cpp.
plane detection object
Definition at line 74 of file fast_plane_detector_server.cpp.
object for transforming from x,y,d space to x,y,z
Definition at line 77 of file fast_plane_detector_server.cpp.
ros::NodeHandle fast_plane_detection::FastRegionPlaneService::priv_nh_ [private] |
Node handle in the private namespace.
Definition at line 71 of file fast_plane_detector_server.cpp.
ros::NodeHandle fast_plane_detection::FastRegionPlaneService::root_nh_ [private] |
The node handle.
Definition at line 69 of file fast_plane_detector_server.cpp.
double fast_plane_detection::FastRegionPlaneService::up_direction_ [private] |
Which direction along optical axis is pointing best towards up direction
Definition at line 81 of file fast_plane_detector_server.cpp.