#include <plane_transform.h>
Public Member Functions | |
| bool | getPlane (fast_plane_detection::Plane &plane) |
| PlaneTransform (const sensor_msgs::CameraInfo &camera_info, float baseline, float up_direction) | |
| void | setParameters (float alpha, float beta, float d, int min_x, int max_x, int min_y, int max_y, std_msgs::Header header) |
| ~PlaneTransform () | |
Private Member Functions | |
| fast_plane_detection::Plane | constructPlaneMsg (const sensor_msgs::PointCloud &plane_limits, const std::vector< double > &coeffs, const tf::Transform &plane_trans) |
| std::vector< double > | convertTo3DPlane (const sensor_msgs::CameraInfo &camera_info, float alpha, float beta, float d) |
| void | get3DPlanePoint (int u, int v, Point &p) |
| void | get3DTableLimits (sensor_msgs::PointCloud &plane_limits) |
| tf::Transform | getPlaneTransform (const std::vector< double > &coeffs, double up_direction) |
| bool | transformPlanePoints (const tf::Transform &plane_trans, sensor_msgs::PointCloud &plane_limits) |
Private Attributes | |
| float | alpha_ |
| float | baseline_ |
| float | beta_ |
| sensor_msgs::CameraInfo | camera_info_ |
| float | d_ |
| std_msgs::Header | header_ |
| tf::TransformListener | listener |
| int | max_x_ |
| int | max_y_ |
| int | min_x_ |
| int | min_y_ |
| float | up_direction_ |
Definition at line 47 of file plane_transform.h.
| fast_plane_detection::PlaneTransform::PlaneTransform | ( | const sensor_msgs::CameraInfo & | camera_info, | |
| float | baseline, | |||
| float | up_direction | |||
| ) |
Definition at line 38 of file plane_transform.cpp.
| fast_plane_detection::PlaneTransform::~PlaneTransform | ( | ) |
Definition at line 45 of file plane_transform.cpp.
| Plane fast_plane_detection::PlaneTransform::constructPlaneMsg | ( | const sensor_msgs::PointCloud & | plane_limits, | |
| const std::vector< double > & | coeffs, | |||
| const tf::Transform & | plane_trans | |||
| ) | [private] |
Definition at line 215 of file plane_transform.cpp.
| std::vector< double > fast_plane_detection::PlaneTransform::convertTo3DPlane | ( | const sensor_msgs::CameraInfo & | camera_info, | |
| float | alpha, | |||
| float | beta, | |||
| float | d | |||
| ) | [private] |
Definition at line 93 of file plane_transform.cpp.
| void fast_plane_detection::PlaneTransform::get3DPlanePoint | ( | int | u, | |
| int | v, | |||
| Point & | p | |||
| ) | [private] |
Definition at line 271 of file plane_transform.cpp.
| void fast_plane_detection::PlaneTransform::get3DTableLimits | ( | sensor_msgs::PointCloud & | plane_limits | ) | [private] |
Definition at line 255 of file plane_transform.cpp.
| bool fast_plane_detection::PlaneTransform::getPlane | ( | fast_plane_detection::Plane & | plane | ) |
Definition at line 68 of file plane_transform.cpp.
| tf::Transform fast_plane_detection::PlaneTransform::getPlaneTransform | ( | const std::vector< double > & | coeffs, | |
| double | up_direction | |||
| ) | [private] |
Definition at line 140 of file plane_transform.cpp.
| void fast_plane_detection::PlaneTransform::setParameters | ( | float | alpha, | |
| float | beta, | |||
| float | d, | |||
| int | min_x, | |||
| int | max_x, | |||
| int | min_y, | |||
| int | max_y, | |||
| std_msgs::Header | header | |||
| ) |
Definition at line 48 of file plane_transform.cpp.
| bool fast_plane_detection::PlaneTransform::transformPlanePoints | ( | const tf::Transform & | plane_trans, | |
| sensor_msgs::PointCloud & | plane_limits | |||
| ) | [private] |
Definition at line 179 of file plane_transform.cpp.
float fast_plane_detection::PlaneTransform::alpha_ [private] |
Definition at line 92 of file plane_transform.h.
float fast_plane_detection::PlaneTransform::baseline_ [private] |
Definition at line 89 of file plane_transform.h.
float fast_plane_detection::PlaneTransform::beta_ [private] |
Definition at line 92 of file plane_transform.h.
sensor_msgs::CameraInfo fast_plane_detection::PlaneTransform::camera_info_ [private] |
Definition at line 87 of file plane_transform.h.
float fast_plane_detection::PlaneTransform::d_ [private] |
Definition at line 92 of file plane_transform.h.
std_msgs::Header fast_plane_detection::PlaneTransform::header_ [private] |
Definition at line 97 of file plane_transform.h.
tf::TransformListener fast_plane_detection::PlaneTransform::listener [private] |
Definition at line 99 of file plane_transform.h.
int fast_plane_detection::PlaneTransform::max_x_ [private] |
Definition at line 94 of file plane_transform.h.
int fast_plane_detection::PlaneTransform::max_y_ [private] |
Definition at line 95 of file plane_transform.h.
int fast_plane_detection::PlaneTransform::min_x_ [private] |
Definition at line 94 of file plane_transform.h.
int fast_plane_detection::PlaneTransform::min_y_ [private] |
Definition at line 95 of file plane_transform.h.
float fast_plane_detection::PlaneTransform::up_direction_ [private] |
Definition at line 90 of file plane_transform.h.