Public Member Functions | |
ObstaclesDetectionOld () | |
virtual | ~ObstaclesDetectionOld () |
Private Member Functions | |
void | callback (const sensor_msgs::PointCloud2ConstPtr &cloudMsg) |
virtual void | onInit () |
Private Attributes | |
ros::Subscriber | cloudSub_ |
double | clusterRadius_ |
std::string | frameId_ |
double | groundNormalAngle_ |
ros::Publisher | groundPub_ |
double | maxGroundHeight_ |
double | maxObstaclesHeight_ |
int | minClusterSize_ |
int | normalKSearch_ |
ros::Publisher | obstaclesPub_ |
bool | optimizeForCloseObjects_ |
ros::Publisher | projObstaclesPub_ |
double | projVoxelSize_ |
bool | segmentFlatObstacles_ |
tf::TransformListener | tfListener_ |
bool | waitForTransform_ |
Definition at line 50 of file obstacles_detection_old.cpp.
Definition at line 53 of file obstacles_detection_old.cpp.
virtual rtabmap_ros::ObstaclesDetectionOld::~ObstaclesDetectionOld | ( | ) | [inline, virtual] |
Definition at line 67 of file obstacles_detection_old.cpp.
void rtabmap_ros::ObstaclesDetectionOld::callback | ( | const sensor_msgs::PointCloud2ConstPtr & | cloudMsg | ) | [inline, private] |
Definition at line 110 of file obstacles_detection_old.cpp.
virtual void rtabmap_ros::ObstaclesDetectionOld::onInit | ( | ) | [inline, private, virtual] |
Implements nodelet::Nodelet.
Definition at line 71 of file obstacles_detection_old.cpp.
Definition at line 351 of file obstacles_detection_old.cpp.
double rtabmap_ros::ObstaclesDetectionOld::clusterRadius_ [private] |
Definition at line 336 of file obstacles_detection_old.cpp.
std::string rtabmap_ros::ObstaclesDetectionOld::frameId_ [private] |
Definition at line 333 of file obstacles_detection_old.cpp.
double rtabmap_ros::ObstaclesDetectionOld::groundNormalAngle_ [private] |
Definition at line 335 of file obstacles_detection_old.cpp.
Definition at line 347 of file obstacles_detection_old.cpp.
double rtabmap_ros::ObstaclesDetectionOld::maxGroundHeight_ [private] |
Definition at line 339 of file obstacles_detection_old.cpp.
double rtabmap_ros::ObstaclesDetectionOld::maxObstaclesHeight_ [private] |
Definition at line 338 of file obstacles_detection_old.cpp.
int rtabmap_ros::ObstaclesDetectionOld::minClusterSize_ [private] |
Definition at line 337 of file obstacles_detection_old.cpp.
int rtabmap_ros::ObstaclesDetectionOld::normalKSearch_ [private] |
Definition at line 334 of file obstacles_detection_old.cpp.
Definition at line 348 of file obstacles_detection_old.cpp.
bool rtabmap_ros::ObstaclesDetectionOld::optimizeForCloseObjects_ [private] |
Definition at line 342 of file obstacles_detection_old.cpp.
Definition at line 349 of file obstacles_detection_old.cpp.
double rtabmap_ros::ObstaclesDetectionOld::projVoxelSize_ [private] |
Definition at line 343 of file obstacles_detection_old.cpp.
bool rtabmap_ros::ObstaclesDetectionOld::segmentFlatObstacles_ [private] |
Definition at line 340 of file obstacles_detection_old.cpp.
Definition at line 345 of file obstacles_detection_old.cpp.
bool rtabmap_ros::ObstaclesDetectionOld::waitForTransform_ [private] |
Definition at line 341 of file obstacles_detection_old.cpp.