door_handle_detector::HandleDetector Class Reference

#include <handle_detector.h>

List of all members.

Public Member Functions

bool detectHandleCloudSrv (door_handle_detector::DoorsDetectorCloud::Request &req, door_handle_detector::DoorsDetectorCloud::Response &resp)
bool detectHandleSrv (door_handle_detector::DoorsDetector::Request &req, door_handle_detector::DoorsDetector::Response &resp)
 This is the main service callback: it gets called whenever a request to find a new handle is given.
 HandleDetector ()
 ~HandleDetector ()

Public Attributes

ros::ServiceServer detect_cloud_srv_
ros::ServiceServer detect_srv_
ros::Publisher door_outliers_pub_
ros::Publisher handle_pol_pub_
ros::Publisher handle_reg_pub_
ros::Publisher vis_marker_pub_

Private Member Functions

void cloud_cb (const sensor_msgs::PointCloudConstPtr &cloud)
 Main point cloud callback.
bool detectHandle (const door_msgs::Door &door, sensor_msgs::PointCloud pointcloud, std::vector< door_msgs::Door > &result) const
void getDoorOutliers (const std::vector< int > &indices, const std::vector< int > &inliers, const std::vector< double > &coeff, const geometry_msgs::Polygon &polygon, const geometry_msgs::Polygon &polygon_tr, Eigen::Matrix4d transformation, std::vector< int > &outliers, sensor_msgs::PointCloud &pointcloud) const
 Select the door outliers that could represent a handle.
void getHandleCandidates (const std::vector< int > &indices, const std::vector< double > &coeff, const geometry_msgs::Polygon &polygon, const geometry_msgs::Polygon &polygon_tr, Eigen::Matrix4d transformation, std::vector< int > &handle_indices, sensor_msgs::PointCloud &pointcloud, geometry_msgs::PointStamped &viewpoint_cloud) const
 Select all points that could represent a handle, including the door.
void refineHandleCandidatesWithDoorOutliers (std::vector< int > &handle_indices, std::vector< int > &outliers, const geometry_msgs::Polygon &polygon, const std::vector< double > &coeff, const geometry_msgs::Point32 &door_axis, const door_msgs::Door &door_prior, sensor_msgs::PointCloud &pointcloud) const
 Refine the intensity/curvature handle indices with the door outliers.

Private Attributes

double distance_from_door_margin_
double euclidean_cluster_angle_tolerance_
double euclidean_cluster_distance_tolerance_
int euclidean_cluster_min_pts_
std::string fixed_frame_
int global_marker_id_
double handle_distance_door_max_threshold_
double handle_max_height_
double handle_min_height_
std::string input_cloud_topic_
int k_search_
double min_plane_pts_
ros::NodeHandle node_
ros::NodeHandle node_tilde_
unsigned int num_clouds_received_
std::string parameter_frame_
sensor_msgs::PointCloud pointcloud_
double sac_distance_threshold_
tf::TransformListener tf_
geometry_msgs::Point32 z_axis_

Detailed Description

Definition at line 60 of file handle_detector.h.


Constructor & Destructor Documentation

HandleDetector::HandleDetector (  ) 

Definition at line 43 of file handle_detector.cpp.

door_handle_detector::HandleDetector::~HandleDetector (  )  [inline]

Definition at line 64 of file handle_detector.h.


Member Function Documentation

void HandleDetector::cloud_cb ( const sensor_msgs::PointCloudConstPtr &  cloud  )  [private]

Main point cloud callback.

Definition at line 580 of file handle_detector.cpp.

bool HandleDetector::detectHandle ( const door_msgs::Door &  door,
sensor_msgs::PointCloud  pointcloud,
std::vector< door_msgs::Door > &  result 
) const [private]

Definition at line 86 of file handle_detector.cpp.

bool HandleDetector::detectHandleCloudSrv ( door_handle_detector::DoorsDetectorCloud::Request req,
door_handle_detector::DoorsDetectorCloud::Response resp 
)

Definition at line 571 of file handle_detector.cpp.

bool HandleDetector::detectHandleSrv ( door_handle_detector::DoorsDetector::Request req,
door_handle_detector::DoorsDetector::Response resp 
)

This is the main service callback: it gets called whenever a request to find a new handle is given.

Definition at line 554 of file handle_detector.cpp.

void door_handle_detector::HandleDetector::getDoorOutliers ( const std::vector< int > &  indices,
const std::vector< int > &  inliers,
const std::vector< double > &  coeff,
const geometry_msgs::Polygon &  polygon,
const geometry_msgs::Polygon &  polygon_tr,
Eigen::Matrix4d  transformation,
std::vector< int > &  outliers,
sensor_msgs::PointCloud &  pointcloud 
) const [private]

Select the door outliers that could represent a handle.

Parameters:
indices a pointer to all the point indices
inliers a pointer to the point indices which are inliers for the door plane
coeff the door planar coefficients
polygon the polygonal bounds of the door
polygon_tr the polygonal bounds of the door in the X-Y plane
transformation the transformation between the door planar coefficients and the X-Y plane
outliers the resultant outliers
Note:
The following global parameters are used: cloud_tr_, viewpoint_cloud_ distance_from_door_margin_, euclidean_cluster_distance_tolerance_, euclidean_cluster_min_pts_
void door_handle_detector::HandleDetector::getHandleCandidates ( const std::vector< int > &  indices,
const std::vector< double > &  coeff,
const geometry_msgs::Polygon &  polygon,
const geometry_msgs::Polygon &  polygon_tr,
Eigen::Matrix4d  transformation,
std::vector< int > &  handle_indices,
sensor_msgs::PointCloud &  pointcloud,
geometry_msgs::PointStamped &  viewpoint_cloud 
) const [private]

Select all points that could represent a handle, including the door.

Parameters:
indices a pointer to all the point indices
coeff the door planar coefficients
polygon the polygonal bounds of the door
polygon_tr the polygonal bounds of the door in the X-Y plane
transformation the transformation between the door planar coefficients and the X-Y plane
handle_indices the resultant handle indices
Note:
In principle, this method could be fused with getDoorOutliers, but we want to keep them separate for now for debugging purposes
The following global parameters are used: cloud_tr_, viewpoint_cloud_
void door_handle_detector::HandleDetector::refineHandleCandidatesWithDoorOutliers ( std::vector< int > &  handle_indices,
std::vector< int > &  outliers,
const geometry_msgs::Polygon &  polygon,
const std::vector< double > &  coeff,
const geometry_msgs::Point32 &  door_axis,
const door_msgs::Door &  door_prior,
sensor_msgs::PointCloud &  pointcloud 
) const [private]

Refine the intensity/curvature handle indices with the door outliers.

Parameters:
handle_indices the handle indices
outliers the door outliers
polygon the polygonal bounds of the door
coeff the door planar coefficients
door_axis search for lines along this axis
Note:
The following global parameters are used: cloud_tr_ distance_from_door_margin_, euclidean_cluster_distance_tolerance_, euclidean_cluster_min_pts_

Member Data Documentation

Definition at line 72 of file handle_detector.h.

Definition at line 72 of file handle_detector.h.

Definition at line 167 of file handle_detector.h.

Definition at line 73 of file handle_detector.h.

Definition at line 164 of file handle_detector.h.

Definition at line 164 of file handle_detector.h.

Definition at line 165 of file handle_detector.h.

Definition at line 152 of file handle_detector.h.

Definition at line 169 of file handle_detector.h.

Definition at line 158 of file handle_detector.h.

Definition at line 161 of file handle_detector.h.

Definition at line 161 of file handle_detector.h.

Definition at line 73 of file handle_detector.h.

Definition at line 73 of file handle_detector.h.

Definition at line 152 of file handle_detector.h.

Definition at line 155 of file handle_detector.h.

Definition at line 167 of file handle_detector.h.

Definition at line 143 of file handle_detector.h.

Definition at line 143 of file handle_detector.h.

Definition at line 153 of file handle_detector.h.

Definition at line 152 of file handle_detector.h.

sensor_msgs::PointCloud door_handle_detector::HandleDetector::pointcloud_ [private]

Definition at line 146 of file handle_detector.h.

Definition at line 167 of file handle_detector.h.

tf::TransformListener door_handle_detector::HandleDetector::tf_ [private]

Definition at line 150 of file handle_detector.h.

Definition at line 73 of file handle_detector.h.

geometry_msgs::Point32 door_handle_detector::HandleDetector::z_axis_ [private]

Definition at line 147 of file handle_detector.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Defines


door_handle_detector
Author(s): Radu Bogdan Rusu, Marius
autogenerated on Fri Jan 11 09:42:08 2013