Public Member Functions | |
FastRegionPlaneDetector (int buffer_size) | |
FastRegionPlaneDetector (int buffer_size) | |
void | planeCallback (const stereo_msgs::DisparityImage::ConstPtr &disparity_image) |
Callback for disparity image messages. | |
void | planeCallback (const stereo_msgs::DisparityImage::ConstPtr &disparity_image) |
Callback for disparity image messages. | |
void | Pr2Callback (const fast_plane_detection::SlavePoint msg_pose) |
Subscriber for slave Position. | |
bool | setPosition (fast_plane_detection::SetPosition::Request &req, fast_plane_detection::SetPosition::Response &resp) |
bool | setPosition (fast_plane_detection::SetPosition::Request &req, fast_plane_detection::SetPosition::Response &resp) |
Service call to Slave Position. | |
~FastRegionPlaneDetector () | |
~FastRegionPlaneDetector () | |
Public Attributes | |
Plane | plane_ |
the plane | |
Private Member Functions | |
bool | maskDisparityImage (const stereo_msgs::DisparityImage::ConstPtr &disparity, const sensor_msgs::CameraInfo::ConstPtr &camera_info, const stereo_msgs::DisparityImage::Ptr &masked_disparity) |
bool | maskDisparityImage (const stereo_msgs::DisparityImage::ConstPtr &disparity, const sensor_msgs::CameraInfo::ConstPtr &camera_info, const stereo_msgs::DisparityImage::Ptr &masked_disparity) |
Private Attributes | |
int | buffer_size_ |
Buffer size for callbacks. | |
std::string | camera_frame_ |
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_ |
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_ |
stereo_msgs::DisparityImage | disparity_masked_ |
masked disparity image | |
stereo_msgs::DisparityImage::Ptr | disparity_masked_ptr |
bool | find_table_ |
whether to restrict search for plane to table like orientation | |
std_msgs::ColorRGBA | green_ |
bool | in_contact_ |
int | inlier_threshold_ |
Minimum number of points necessary to pass a plane detection. | |
tf::TransformListener | listener_ |
tf::TransformListener | listener_check2_ |
tf::TransformListener | listener_check_ |
bool | manual_ |
int | marker2_id_ |
int | marker_id_ |
float | mean_error_ |
int | number_inliers_ |
double | percentage_inliers_ |
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 | |
geometry_msgs::Vector3Stamped | point_ |
INPUT THAT SHOULD COME FROM ROBOT POSITION PUBLISHER. | |
ros::Publisher | pos_marker_pub_ |
Publisher to slave Position. | |
ros::NodeHandle | priv_nh_ |
Node handle in the private namespace. | |
std_msgs::ColorRGBA | red_ |
int | region_height_ |
int | region_width_ |
ros::NodeHandle | root_nh_ |
The node handle. | |
std::string | source_frame_ |
ros::ServiceServer | srv_position_ |
ros::Subscriber | sub_position_ |
bool | transform_ |
tf::StampedTransform | transform_check2_ |
tf::StampedTransform | transform_check_ |
double | up_direction_ |
Which direction along optical axis is pointing best towards up direction. | |
double | X |
double | X_ |
double | Y |
double | Y_ |
double | Z |
double | Z_ |
Definition at line 55 of file fast_region_plane_detector.cpp.
fast_plane_detection::FastRegionPlaneDetector::FastRegionPlaneDetector | ( | int | buffer_size | ) |
Definition at line 178 of file fast_region_plane_detector.cpp.
fast_plane_detection::FastRegionPlaneDetector::~FastRegionPlaneDetector | ( | ) |
Definition at line 283 of file fast_region_plane_detector.cpp.
fast_plane_detection::FastRegionPlaneDetector::FastRegionPlaneDetector | ( | int | buffer_size | ) |
fast_plane_detection::FastRegionPlaneDetector::~FastRegionPlaneDetector | ( | ) |
bool fast_plane_detection::FastRegionPlaneDetector::maskDisparityImage | ( | const stereo_msgs::DisparityImage::ConstPtr & | disparity, | |
const sensor_msgs::CameraInfo::ConstPtr & | camera_info, | |||
const stereo_msgs::DisparityImage::Ptr & | masked_disparity | |||
) | [private] |
bool fast_plane_detection::FastRegionPlaneDetector::maskDisparityImage | ( | const stereo_msgs::DisparityImage::ConstPtr & | disparity, | |
const sensor_msgs::CameraInfo::ConstPtr & | camera_info, | |||
const stereo_msgs::DisparityImage::Ptr & | masked_disparity | |||
) | [private] |
Definition at line 423 of file fast_region_plane_detector.cpp.
void fast_plane_detection::FastRegionPlaneDetector::planeCallback | ( | const stereo_msgs::DisparityImage::ConstPtr & | disparity_image | ) |
Callback for disparity image messages.
void fast_plane_detection::FastRegionPlaneDetector::planeCallback | ( | const stereo_msgs::DisparityImage::ConstPtr & | disparity_image | ) |
Callback for disparity image messages.
Definition at line 288 of file fast_region_plane_detector.cpp.
void fast_plane_detection::FastRegionPlaneDetector::Pr2Callback | ( | const fast_plane_detection::SlavePoint | msg_pose | ) |
Subscriber for slave Position.
Definition at line 530 of file fast_region_plane_detector.cpp.
bool fast_plane_detection::FastRegionPlaneDetector::setPosition | ( | fast_plane_detection::SetPosition::Request & | req, | |
fast_plane_detection::SetPosition::Response & | resp | |||
) |
bool fast_plane_detection::FastRegionPlaneDetector::setPosition | ( | fast_plane_detection::SetPosition::Request & | req, | |
fast_plane_detection::SetPosition::Response & | resp | |||
) |
Service call to Slave Position.
Service call to set Start Position.
Definition at line 507 of file fast_region_plane_detector.cpp.
Buffer size for callbacks.
Definition at line 75 of file fast_region_plane_detector.cpp.
std::string fast_plane_detection::FastRegionPlaneDetector::camera_frame_ [private] |
Definition at line 145 of file fast_region_plane_detector.cpp.
sensor_msgs::CameraInfo::ConstPtr fast_plane_detection::FastRegionPlaneDetector::camera_info_ [private] |
camera info (needs to be obtained only once)
Definition at line 85 of file fast_region_plane_detector.cpp.
ros::Subscriber fast_plane_detection::FastRegionPlaneDetector::camera_info_sub_ [private] |
Subscriber to camera info.
Definition at line 67 of file fast_region_plane_detector.cpp.
std::string fast_plane_detection::FastRegionPlaneDetector::camera_info_topic_ [private] |
Definition at line 68 of file fast_region_plane_detector.cpp.
stereo_msgs::DisparityImage::ConstPtr fast_plane_detection::FastRegionPlaneDetector::disparity_image_ [private] |
disparity image (needs to be obtained always)
Definition at line 78 of file fast_region_plane_detector.cpp.
ros::Publisher fast_plane_detection::FastRegionPlaneDetector::disparity_image_pub_ [private] |
Publisher to Filtered Disparity Images.
Definition at line 97 of file fast_region_plane_detector.cpp.
ros::Subscriber fast_plane_detection::FastRegionPlaneDetector::disparity_image_sub_ [private] |
Subscriber to disparity images.
Definition at line 71 of file fast_region_plane_detector.cpp.
std::string fast_plane_detection::FastRegionPlaneDetector::disparity_image_topic_ [private] |
Definition at line 72 of file fast_region_plane_detector.cpp.
stereo_msgs::DisparityImage fast_plane_detection::FastRegionPlaneDetector::disparity_masked_ [private] |
masked disparity image
Definition at line 81 of file fast_region_plane_detector.cpp.
stereo_msgs::DisparityImage::Ptr fast_plane_detection::FastRegionPlaneDetector::disparity_masked_ptr [private] |
Definition at line 82 of file fast_region_plane_detector.cpp.
bool fast_plane_detection::FastRegionPlaneDetector::find_table_ [private] |
whether to restrict search for plane to table like orientation
Definition at line 111 of file fast_region_plane_detector.cpp.
std_msgs::ColorRGBA fast_plane_detection::FastRegionPlaneDetector::green_ [private] |
Definition at line 148 of file fast_region_plane_detector.cpp.
bool fast_plane_detection::FastRegionPlaneDetector::in_contact_ [private] |
Definition at line 131 of file fast_region_plane_detector.cpp.
Minimum number of points necessary to pass a plane detection.
Definition at line 120 of file fast_region_plane_detector.cpp.
tf::TransformListener fast_plane_detection::FastRegionPlaneDetector::listener_ [private] |
Definition at line 99 of file fast_region_plane_detector.cpp.
tf::TransformListener fast_plane_detection::FastRegionPlaneDetector::listener_check2_ [private] |
Definition at line 104 of file fast_region_plane_detector.cpp.
tf::TransformListener fast_plane_detection::FastRegionPlaneDetector::listener_check_ [private] |
Definition at line 101 of file fast_region_plane_detector.cpp.
bool fast_plane_detection::FastRegionPlaneDetector::manual_ [private] |
Definition at line 130 of file fast_region_plane_detector.cpp.
Definition at line 141 of file fast_region_plane_detector.cpp.
Definition at line 140 of file fast_region_plane_detector.cpp.
float fast_plane_detection::FastRegionPlaneDetector::mean_error_ [private] |
Definition at line 123 of file fast_region_plane_detector.cpp.
Definition at line 121 of file fast_region_plane_detector.cpp.
double fast_plane_detection::FastRegionPlaneDetector::percentage_inliers_ [private] |
Definition at line 122 of file fast_region_plane_detector.cpp.
the plane
Definition at line 172 of file fast_region_plane_detector.cpp.
plane detection object
Definition at line 108 of file fast_region_plane_detector.cpp.
ros::Publisher fast_plane_detection::FastRegionPlaneDetector::plane_marker_pub_ [private] |
Publisher to Plane Parameters.
Definition at line 88 of file fast_region_plane_detector.cpp.
ros::Publisher fast_plane_detection::FastRegionPlaneDetector::plane_msg_pub_ [private] |
Publisher to Plane Parameters.
Definition at line 94 of file fast_region_plane_detector.cpp.
object for transforming from x,y,d space to x,y,z
Definition at line 114 of file fast_region_plane_detector.cpp.
geometry_msgs::Vector3Stamped fast_plane_detection::FastRegionPlaneDetector::point_ [private] |
INPUT THAT SHOULD COME FROM ROBOT POSITION PUBLISHER.
Definition at line 136 of file fast_region_plane_detector.cpp.
ros::Publisher fast_plane_detection::FastRegionPlaneDetector::pos_marker_pub_ [private] |
Publisher to slave Position.
Definition at line 91 of file fast_region_plane_detector.cpp.
ros::NodeHandle fast_plane_detection::FastRegionPlaneDetector::priv_nh_ [private] |
Node handle in the private namespace.
Definition at line 64 of file fast_region_plane_detector.cpp.
std_msgs::ColorRGBA fast_plane_detection::FastRegionPlaneDetector::red_ [private] |
Definition at line 149 of file fast_region_plane_detector.cpp.
Definition at line 138 of file fast_region_plane_detector.cpp.
Definition at line 137 of file fast_region_plane_detector.cpp.
ros::NodeHandle fast_plane_detection::FastRegionPlaneDetector::root_nh_ [private] |
The node handle.
Definition at line 62 of file fast_region_plane_detector.cpp.
std::string fast_plane_detection::FastRegionPlaneDetector::source_frame_ [private] |
Definition at line 144 of file fast_region_plane_detector.cpp.
ros::ServiceServer fast_plane_detection::FastRegionPlaneDetector::srv_position_ [private] |
Definition at line 126 of file fast_region_plane_detector.cpp.
ros::Subscriber fast_plane_detection::FastRegionPlaneDetector::sub_position_ [private] |
Definition at line 133 of file fast_region_plane_detector.cpp.
bool fast_plane_detection::FastRegionPlaneDetector::transform_ [private] |
Definition at line 120 of file fast_region_plane_detector_jeanette.cpp.
tf::StampedTransform fast_plane_detection::FastRegionPlaneDetector::transform_check2_ [private] |
Definition at line 105 of file fast_region_plane_detector.cpp.
tf::StampedTransform fast_plane_detection::FastRegionPlaneDetector::transform_check_ [private] |
Definition at line 102 of file fast_region_plane_detector.cpp.
double fast_plane_detection::FastRegionPlaneDetector::up_direction_ [private] |
Which direction along optical axis is pointing best towards up direction.
Definition at line 117 of file fast_region_plane_detector.cpp.
double fast_plane_detection::FastRegionPlaneDetector::X [private] |
Definition at line 117 of file fast_region_plane_detector_jeanette.cpp.
double fast_plane_detection::FastRegionPlaneDetector::X_ [private] |
Definition at line 127 of file fast_region_plane_detector.cpp.
double fast_plane_detection::FastRegionPlaneDetector::Y [private] |
Definition at line 118 of file fast_region_plane_detector_jeanette.cpp.
double fast_plane_detection::FastRegionPlaneDetector::Y_ [private] |
Definition at line 128 of file fast_region_plane_detector.cpp.
double fast_plane_detection::FastRegionPlaneDetector::Z [private] |
Definition at line 119 of file fast_region_plane_detector_jeanette.cpp.
double fast_plane_detection::FastRegionPlaneDetector::Z_ [private] |
Definition at line 129 of file fast_region_plane_detector.cpp.