#include <hector_barrel_detection.h>
Definition at line 47 of file hector_barrel_detection.h.
typedef boost::shared_ptr<image_geometry::PinholeCameraModel> barrel_detection::BarrelDetection::CameraModelPtr [private] |
Definition at line 59 of file hector_barrel_detection.h.
Definition at line 4 of file hector_barrel_detection.cpp.
barrel_detection::BarrelDetection::~BarrelDetection | ( | ) | [virtual] |
Definition at line 32 of file hector_barrel_detection.cpp.
void barrel_detection::BarrelDetection::findCylinder | ( | const sensor_msgs::PointCloud2::ConstPtr & | pc_msg, |
float | xKey, | ||
float | yKey | ||
) | [protected] |
Definition at line 184 of file hector_barrel_detection.cpp.
void barrel_detection::BarrelDetection::imageCallback | ( | const sensor_msgs::ImageConstPtr & | img, |
const sensor_msgs::CameraInfoConstPtr & | info | ||
) | [protected] |
Definition at line 35 of file hector_barrel_detection.cpp.
void barrel_detection::BarrelDetection::PclCallback | ( | const sensor_msgs::PointCloud2::ConstPtr & | pc_msg | ) | [protected] |
Definition at line 180 of file hector_barrel_detection.cpp.
int barrel_detection::BarrelDetection::b_max [private] |
Definition at line 83 of file hector_barrel_detection.h.
int barrel_detection::BarrelDetection::b_min [private] |
Definition at line 82 of file hector_barrel_detection.h.
Definition at line 65 of file hector_barrel_detection.h.
Definition at line 63 of file hector_barrel_detection.h.
sensor_msgs::PointCloud2::ConstPtr barrel_detection::BarrelDetection::current_pc_msg_ [private] |
Definition at line 76 of file hector_barrel_detection.h.
Definition at line 73 of file hector_barrel_detection.h.
int barrel_detection::BarrelDetection::g_max [private] |
Definition at line 81 of file hector_barrel_detection.h.
int barrel_detection::BarrelDetection::g_min [private] |
Definition at line 80 of file hector_barrel_detection.h.
Definition at line 62 of file hector_barrel_detection.h.
Definition at line 66 of file hector_barrel_detection.h.
Definition at line 69 of file hector_barrel_detection.h.
pcl::PassThrough<pcl::PointXYZ> barrel_detection::BarrelDetection::pass_ [private] |
Definition at line 71 of file hector_barrel_detection.h.
Definition at line 74 of file hector_barrel_detection.h.
Definition at line 61 of file hector_barrel_detection.h.
Definition at line 64 of file hector_barrel_detection.h.
Definition at line 67 of file hector_barrel_detection.h.
int barrel_detection::BarrelDetection::r_max [private] |
Definition at line 79 of file hector_barrel_detection.h.
int barrel_detection::BarrelDetection::r_min [private] |
Definition at line 78 of file hector_barrel_detection.h.
Eigen::Affine3d barrel_detection::BarrelDetection::to_map_ [private] |
Definition at line 70 of file hector_barrel_detection.h.
Definition at line 68 of file hector_barrel_detection.h.