#include <ground_plane_finder.h>
Public Member Functions | |
bool | find (robot_calibration_msgs::CalibrationData *msg) |
GroundPlaneFinder (ros::NodeHandle &n) | |
Private Member Functions | |
void | cameraCallback (const sensor_msgs::PointCloud2 &cloud) |
bool | waitForCloud () |
Private Attributes | |
std::string | camera_sensor_name_ |
std::string | chain_sensor_name_ |
sensor_msgs::PointCloud2 | cloud_ |
DepthCameraInfoManager | depth_camera_manager_ |
double | max_z_ |
double | points_max_ |
ros::Publisher | publisher_ |
ros::Subscriber | subscriber_ |
bool | waiting_ |
Definition at line 29 of file ground_plane_finder.h.
Definition at line 29 of file ground_plane_finder.cpp.
void robot_calibration::GroundPlaneFinder::cameraCallback | ( | const sensor_msgs::PointCloud2 & | cloud | ) | [private] |
Definition at line 53 of file ground_plane_finder.cpp.
bool robot_calibration::GroundPlaneFinder::find | ( | robot_calibration_msgs::CalibrationData * | msg | ) | [virtual] |
Implements robot_calibration::FeatureFinder.
Definition at line 83 of file ground_plane_finder.cpp.
bool robot_calibration::GroundPlaneFinder::waitForCloud | ( | ) | [private] |
Definition at line 62 of file ground_plane_finder.cpp.
std::string robot_calibration::GroundPlaneFinder::camera_sensor_name_ [private] |
Definition at line 47 of file ground_plane_finder.h.
std::string robot_calibration::GroundPlaneFinder::chain_sensor_name_ [private] |
Definition at line 48 of file ground_plane_finder.h.
sensor_msgs::PointCloud2 robot_calibration::GroundPlaneFinder::cloud_ [private] |
Definition at line 44 of file ground_plane_finder.h.
Definition at line 45 of file ground_plane_finder.h.
double robot_calibration::GroundPlaneFinder::max_z_ [private] |
Definition at line 50 of file ground_plane_finder.h.
double robot_calibration::GroundPlaneFinder::points_max_ [private] |
Definition at line 49 of file ground_plane_finder.h.
Definition at line 41 of file ground_plane_finder.h.
Definition at line 40 of file ground_plane_finder.h.
bool robot_calibration::GroundPlaneFinder::waiting_ [private] |
Definition at line 43 of file ground_plane_finder.h.