Classes | Public Member Functions | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes
tedusar_box_detection::BoxDetectionNode Class Reference

#include <box_detection_node.h>

List of all members.

Classes

struct  Box
struct  Parameters

Public Member Functions

 BoxDetectionNode ()
template<>
bool getParameter (ros::NodeHandle &private_nh, const std::string &key, Eigen::Vector3f &value)

Private Types

typedef pcl::PointXYZ PclPoint
typedef pcl::PointCloud< PclPointPclPointCloud

Private Member Functions

void boxDetectionActionGoalCallback ()
void boxDetectionActionPreemptCallback ()
void clusterizeCloud (const PclPointCloud::ConstPtr &cloud, std::vector< pcl::PointIndices > &cluster_indices)
void downsampleCloud (const PclPointCloud::ConstPtr &cloud, PclPointCloud &cloud_filtered)
void extractPlane (const PclPointCloud::ConstPtr &cloud, const pcl::PointIndices::ConstPtr &inliers, PclPointCloud &cloud_plane, PclPointCloud &cloud_rest)
bool fitBox (const PclPointCloud::ConstPtr &cloud, Box &box)
void fitPlane (const PclPointCloud::ConstPtr &cloud, pcl::PointIndices::Ptr &inliers)
void loadParameters ()
void planePublisherTimerCallback (const ros::TimerEvent &)
void pointCloudCallback (const sensor_msgs::PointCloud2ConstPtr &msg)
void publishActionFeedback (const Box &box)
void publishClusterCloud (const PclPointCloud::ConstPtr &cloud)
void publishCollisionObject (const Box &box)
void publishVisualizationMarker (const Box &box)

Static Private Member Functions

template<typename T >
static void getOptionalParameter (ros::NodeHandle &private_nh, const std::string &key, T &value, T default_value)
template<typename T >
static bool getParameter (ros::NodeHandle &private_nh, const std::string &key, T &value)
template<typename T >
static void getRequiredParameter (ros::NodeHandle &private_nh, const std::string &key, T &value)

Private Attributes

unsigned int box_counter_
actionlib::SimpleActionServer
< tedusar_box_detection_msgs::BoxDetectionAction > 
box_detection_as_
std::vector< Boxboxes_
ros::Time detection_timeout_time_
ros::NodeHandle nh_
Parameters parameters_
sensor_msgs::PointCloud plane_cloud_
ros::Publisher plane_cloud_publisher_
float plane_intensity_
ros::Timer plane_publisher_timer_
ros::Publisher planning_scene_publisher_
ros::Subscriber point_cloud_subscriber_
tf::TransformListener tf_listener_
ros::Publisher visualization_marker_publisher_

Detailed Description

Definition at line 65 of file box_detection_node.h.


Member Typedef Documentation

typedef pcl::PointXYZ tedusar_box_detection::BoxDetectionNode::PclPoint [private]

Definition at line 71 of file box_detection_node.h.

Definition at line 72 of file box_detection_node.h.


Constructor & Destructor Documentation

Definition at line 67 of file box_detection_node.cpp.


Member Function Documentation

Definition at line 172 of file box_detection_node.cpp.

Definition at line 208 of file box_detection_node.cpp.

void tedusar_box_detection::BoxDetectionNode::clusterizeCloud ( const PclPointCloud::ConstPtr &  cloud,
std::vector< pcl::PointIndices > &  cluster_indices 
) [private]

Definition at line 362 of file box_detection_node.cpp.

void tedusar_box_detection::BoxDetectionNode::downsampleCloud ( const PclPointCloud::ConstPtr &  cloud,
PclPointCloud cloud_filtered 
) [private]

Definition at line 354 of file box_detection_node.cpp.

void tedusar_box_detection::BoxDetectionNode::extractPlane ( const PclPointCloud::ConstPtr &  cloud,
const pcl::PointIndices::ConstPtr &  inliers,
PclPointCloud cloud_plane,
PclPointCloud cloud_rest 
) [private]

Definition at line 337 of file box_detection_node.cpp.

bool tedusar_box_detection::BoxDetectionNode::fitBox ( const PclPointCloud::ConstPtr &  cloud,
Box box 
) [private]

Definition at line 376 of file box_detection_node.cpp.

void tedusar_box_detection::BoxDetectionNode::fitPlane ( const PclPointCloud::ConstPtr &  cloud,
pcl::PointIndices::Ptr &  inliers 
) [private]

Definition at line 321 of file box_detection_node.cpp.

template<typename T >
void tedusar_box_detection::BoxDetectionNode::getOptionalParameter ( ros::NodeHandle private_nh,
const std::string &  key,
T &  value,
default_value 
) [static, private]

Definition at line 136 of file box_detection_node.cpp.

template<typename T >
bool tedusar_box_detection::BoxDetectionNode::getParameter ( ros::NodeHandle private_nh,
const std::string &  key,
T &  value 
) [static, private]

Definition at line 145 of file box_detection_node.cpp.

template<>
bool tedusar_box_detection::BoxDetectionNode::getParameter ( ros::NodeHandle private_nh,
const std::string &  key,
Eigen::Vector3f &  value 
)

Definition at line 150 of file box_detection_node.cpp.

template<typename T >
void tedusar_box_detection::BoxDetectionNode::getRequiredParameter ( ros::NodeHandle private_nh,
const std::string &  key,
T &  value 
) [static, private]

Definition at line 126 of file box_detection_node.cpp.

Definition at line 94 of file box_detection_node.cpp.

Definition at line 315 of file box_detection_node.cpp.

void tedusar_box_detection::BoxDetectionNode::pointCloudCallback ( const sensor_msgs::PointCloud2ConstPtr &  msg) [private]

Definition at line 215 of file box_detection_node.cpp.

Definition at line 491 of file box_detection_node.cpp.

void tedusar_box_detection::BoxDetectionNode::publishClusterCloud ( const PclPointCloud::ConstPtr &  cloud) [private]

Definition at line 435 of file box_detection_node.cpp.

Definition at line 450 of file box_detection_node.cpp.

Definition at line 472 of file box_detection_node.cpp.


Member Data Documentation

Definition at line 144 of file box_detection_node.h.

actionlib::SimpleActionServer<tedusar_box_detection_msgs::BoxDetectionAction> tedusar_box_detection::BoxDetectionNode::box_detection_as_ [private]

Definition at line 133 of file box_detection_node.h.

Definition at line 141 of file box_detection_node.h.

Definition at line 140 of file box_detection_node.h.

Definition at line 131 of file box_detection_node.h.

Definition at line 132 of file box_detection_node.h.

Definition at line 142 of file box_detection_node.h.

Definition at line 136 of file box_detection_node.h.

Definition at line 143 of file box_detection_node.h.

Definition at line 137 of file box_detection_node.h.

Definition at line 138 of file box_detection_node.h.

Definition at line 135 of file box_detection_node.h.

Definition at line 134 of file box_detection_node.h.

Definition at line 139 of file box_detection_node.h.


The documentation for this class was generated from the following files:


tedusar_box_detection
Author(s):
autogenerated on Wed Aug 26 2015 16:30:42