Public Member Functions | |
FastPlaneDetector (int buffer_size) | |
void | planeCallback (const stereo_msgs::DisparityImage::ConstPtr &disparity_image) |
Callback for disparity image messages. | |
~FastPlaneDetector () | |
Public Attributes | |
Plane | plane_ |
the plane | |
Private Member Functions | |
void | clearOldMarkers (std::string frame_id) |
void | maskDisparityImage (const stereo_msgs::DisparityImage::ConstPtr &disparity_image, const sensor_msgs::Image &labels, stereo_msgs::DisparityImage &masked_disparity) |
Private Attributes | |
int | buffer_size_ |
Buffer size for callbacks. | |
sensor_msgs::CameraInfo::ConstPtr | camera_info_ |
camera info (needs to be obtained only once) | |
ros::Subscriber | camera_info_sub_ |
Subscriber to camera info. | |
std::string | camera_info_topic_ |
int | current_marker_id_ |
The current marker being published. | |
stereo_msgs::DisparityImage::ConstPtr | disparity_image_ |
disparity image (needs to be obtained always) | |
ros::Publisher | disparity_image_pub_ |
Publisher to Filtered Disparity Images. | |
ros::Subscriber | disparity_image_sub_ |
Subscriber to disparity images. | |
std::string | disparity_image_topic_ |
bool | find_table_ |
whether to restrict search for plane to table like orientation | |
image_transport::Publisher | image_pub_ |
Publishing images (for debug only). | |
int | inlier_threshold_ |
Minimum number of points necessary to pass a plane detection. | |
int | num_markers_published_ |
Used to remember the number of markers we publish so we can delete them later. | |
PlaneDetection * | plane_detect_ |
plane detection object | |
ros::Publisher | plane_marker_pub_ |
Publisher to Plane Parameters. | |
ros::Publisher | plane_msg_pub_ |
Publisher to Plane Parameters. | |
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_ |
Which direction along optical axis is pointing best towards up direction. |
Definition at line 50 of file fast_plane_detector_node.cpp.
fast_plane_detection::FastPlaneDetector::FastPlaneDetector | ( | int | buffer_size | ) |
Publisher for labeled images
Definition at line 137 of file fast_plane_detector_node.cpp.
fast_plane_detection::FastPlaneDetector::~FastPlaneDetector | ( | ) |
Definition at line 215 of file fast_plane_detector_node.cpp.
void fast_plane_detection::FastPlaneDetector::clearOldMarkers | ( | std::string | frame_id | ) | [private] |
Definition at line 293 of file fast_plane_detector_node.cpp.
void fast_plane_detection::FastPlaneDetector::maskDisparityImage | ( | const stereo_msgs::DisparityImage::ConstPtr & | disparity_image, | |
const sensor_msgs::Image & | labels, | |||
stereo_msgs::DisparityImage & | masked_disparity | |||
) | [private] |
Definition at line 315 of file fast_plane_detector_node.cpp.
void fast_plane_detection::FastPlaneDetector::planeCallback | ( | const stereo_msgs::DisparityImage::ConstPtr & | disparity_image | ) |
Callback for disparity image messages.
Definition at line 219 of file fast_plane_detector_node.cpp.
int fast_plane_detection::FastPlaneDetector::buffer_size_ [private] |
Buffer size for callbacks.
Definition at line 73 of file fast_plane_detector_node.cpp.
sensor_msgs::CameraInfo::ConstPtr fast_plane_detection::FastPlaneDetector::camera_info_ [private] |
camera info (needs to be obtained only once)
Definition at line 79 of file fast_plane_detector_node.cpp.
ros::Subscriber fast_plane_detection::FastPlaneDetector::camera_info_sub_ [private] |
Subscriber to camera info.
Definition at line 65 of file fast_plane_detector_node.cpp.
std::string fast_plane_detection::FastPlaneDetector::camera_info_topic_ [private] |
Definition at line 66 of file fast_plane_detector_node.cpp.
The current marker being published.
Definition at line 113 of file fast_plane_detector_node.cpp.
stereo_msgs::DisparityImage::ConstPtr fast_plane_detection::FastPlaneDetector::disparity_image_ [private] |
disparity image (needs to be obtained always)
Definition at line 76 of file fast_plane_detector_node.cpp.
ros::Publisher fast_plane_detection::FastPlaneDetector::disparity_image_pub_ [private] |
Publisher to Filtered Disparity Images.
Definition at line 88 of file fast_plane_detector_node.cpp.
ros::Subscriber fast_plane_detection::FastPlaneDetector::disparity_image_sub_ [private] |
Subscriber to disparity images.
Definition at line 69 of file fast_plane_detector_node.cpp.
std::string fast_plane_detection::FastPlaneDetector::disparity_image_topic_ [private] |
Definition at line 70 of file fast_plane_detector_node.cpp.
bool fast_plane_detection::FastPlaneDetector::find_table_ [private] |
whether to restrict search for plane to table like orientation
Definition at line 99 of file fast_plane_detector_node.cpp.
image_transport::Publisher fast_plane_detection::FastPlaneDetector::image_pub_ [private] |
Publishing images (for debug only).
Definition at line 91 of file fast_plane_detector_node.cpp.
Minimum number of points necessary to pass a plane detection.
Definition at line 108 of file fast_plane_detector_node.cpp.
Used to remember the number of markers we publish so we can delete them later.
Definition at line 111 of file fast_plane_detector_node.cpp.
the plane
Definition at line 129 of file fast_plane_detector_node.cpp.
plane detection object
Definition at line 96 of file fast_plane_detector_node.cpp.
ros::Publisher fast_plane_detection::FastPlaneDetector::plane_marker_pub_ [private] |
Publisher to Plane Parameters.
Definition at line 82 of file fast_plane_detector_node.cpp.
ros::Publisher fast_plane_detection::FastPlaneDetector::plane_msg_pub_ [private] |
Publisher to Plane Parameters.
Definition at line 85 of file fast_plane_detector_node.cpp.
object for transforming from x,y,d space to x,y,z
Definition at line 102 of file fast_plane_detector_node.cpp.
ros::NodeHandle fast_plane_detection::FastPlaneDetector::priv_nh_ [private] |
Node handle in the private namespace.
Definition at line 62 of file fast_plane_detector_node.cpp.
ros::NodeHandle fast_plane_detection::FastPlaneDetector::root_nh_ [private] |
The node handle.
Definition at line 60 of file fast_plane_detector_node.cpp.
double fast_plane_detection::FastPlaneDetector::up_direction_ [private] |
Which direction along optical axis is pointing best towards up direction.
Definition at line 105 of file fast_plane_detector_node.cpp.