Public Member Functions | Private Attributes
DoorHandleDetector Class Reference

This class detects the door handle in 3D point clouds. More...

#include <handle_detector.h>

List of all members.

Public Member Functions

void cloudCallback (const PointCloudType::ConstPtr &msg)
 DoorHandleDetector ()
bool doorHandleRansac (const PointCloudType &cloud, PointCloudType &handle_cloud, Eigen::Vector3f &door_normal, double &plane_distance_to_origin)
 Assumption: Clouds are in a frame where Z is vertical (up or down does not matter)
void estimateDoorHandle (const PointCloudType &cloud, PointCloudType &handle_cloud)
 computes angle, stores slope and intercept
bool serviceCallback (door_perception_msgs::DoorStateSrv::Request &request, door_perception_msgs::DoorStateSrv::Response &response)
bool switchActive (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
bool switchInactive (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)

Private Attributes

bool active_
tf::TransformBroadcaster br_
message_filters::Subscriber
< PointCloudType
cloud_sub_
PointCloudType cropping_polygon_
ros::Publisher door_cloud_publisher_
std::string door_frame_
double door_radius_
door_perception_msgs::DoorState door_state_msg_
ros::Publisher door_state_publisher_
ros::ServiceServer door_state_service_
std::string filter_polygon_filename_
ros::Publisher handle_cloud_publisher_
ros::Publisher handle_pose_pub_
ros::NodeHandle node_
ros::ServiceServer service_off_
ros::ServiceServer service_on_
tf::MessageFilter
< PointCloudType > * 
tf_filter_
tf::TransformListener tfListener_
ros::Publisher vis_pub_

Detailed Description

This class detects the door handle in 3D point clouds.

This class projects the point cloud into the (tf) door frame (settable via parameter) and crops it to remove the (physical) door frame. It then determines the door plane via RANSAC and assumes the outlying points to be the handle.

Definition at line 25 of file handle_detector.h.


Constructor & Destructor Documentation

Definition at line 23 of file handle_detector.cpp.


Member Function Documentation

void DoorHandleDetector::cloudCallback ( const PointCloudType::ConstPtr &  msg)

Definition at line 58 of file handle_detector.cpp.

bool DoorHandleDetector::doorHandleRansac ( const PointCloudType cloud,
PointCloudType handle_cloud,
Eigen::Vector3f door_normal,
double &  plane_distance_to_origin 
)

Assumption: Clouds are in a frame where Z is vertical (up or down does not matter)

Definition at line 115 of file handle_detector.cpp.

computes angle, stores slope and intercept

Definition at line 209 of file handle_detector.cpp.

Definition at line 305 of file handle_detector.cpp.

bool DoorHandleDetector::switchActive ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
)

Definition at line 287 of file handle_detector.cpp.

bool DoorHandleDetector::switchInactive ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
)

Definition at line 295 of file handle_detector.cpp.


Member Data Documentation

Definition at line 53 of file handle_detector.h.

Definition at line 52 of file handle_detector.h.

Definition at line 40 of file handle_detector.h.

Definition at line 51 of file handle_detector.h.

Definition at line 41 of file handle_detector.h.

std::string DoorHandleDetector::door_frame_ [private]

Definition at line 49 of file handle_detector.h.

Definition at line 55 of file handle_detector.h.

Definition at line 56 of file handle_detector.h.

Definition at line 43 of file handle_detector.h.

Definition at line 48 of file handle_detector.h.

Definition at line 54 of file handle_detector.h.

Definition at line 42 of file handle_detector.h.

Definition at line 45 of file handle_detector.h.

Definition at line 37 of file handle_detector.h.

Definition at line 47 of file handle_detector.h.

Definition at line 46 of file handle_detector.h.

Definition at line 50 of file handle_detector.h.

Definition at line 38 of file handle_detector.h.

Definition at line 44 of file handle_detector.h.


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


door_perception
Author(s): Felix Endres
autogenerated on Wed Dec 26 2012 16:03:53