Public Member Functions | Private Attributes | List of all members
SegmentationNode Class Reference

Public Member Functions

void doSegmentation ()
 doSegmentation thread for doing the segmentation More...
 
bool doSegmentation (cpf_segmentation_ros::DoSegmentation::Request &req, cpf_segmentation_ros::DoSegmentation::Response &res)
 doSegmentation service callback for synchronized processing More...
 
bool enablePublisher (cpf_segmentation_ros::EnablePublisher::Request &req, cpf_segmentation_ros::EnablePublisher::Response &resp)
 enablePublisher More...
 
void goalCB ()
 goalCB callback funtion for the new goal More...
 
void scan_callback (const sensor_msgs::PointCloud2ConstPtr &cloud_ptr)
 scan_callback More...
 
 SegmentationNode (ros::NodeHandle nh)
 

Private Attributes

actionlib::SimpleActionServer< cpf_segmentation_ros::DoSegmentationAction > actionServer_
 
pcl::PointCloud< PointT > cloud_
 
ros::ServiceServer doSegmentationSrv_
 
ros::ServiceServer enablePublisherSrv_
 
ros::NodeHandle nh_
 
ros::Subscriber pcl_sub_
 
bool publisherEnabled_
 
Segmentation segmentation
 
boost::thread * segmentation_thread
 
ros::Publisher segmented_pub_
 

Detailed Description

Definition at line 62 of file segmentation_ros_node.cpp.

Constructor & Destructor Documentation

SegmentationNode::SegmentationNode ( ros::NodeHandle  nh)
inline

Definition at line 64 of file segmentation_ros_node.cpp.

Member Function Documentation

void SegmentationNode::doSegmentation ( )
inline

doSegmentation thread for doing the segmentation

Parameters
cloud_ptr
Returns

Definition at line 141 of file segmentation_ros_node.cpp.

bool SegmentationNode::doSegmentation ( cpf_segmentation_ros::DoSegmentation::Request &  req,
cpf_segmentation_ros::DoSegmentation::Response &  res 
)
inline

doSegmentation service callback for synchronized processing

Parameters
reqthe input point cloud
resthe output point cloud
Returns
true if the service succeeded

Definition at line 191 of file segmentation_ros_node.cpp.

bool SegmentationNode::enablePublisher ( cpf_segmentation_ros::EnablePublisher::Request &  req,
cpf_segmentation_ros::EnablePublisher::Response &  resp 
)
inline

enablePublisher

Parameters
req
resp
Returns

Definition at line 178 of file segmentation_ros_node.cpp.

void SegmentationNode::goalCB ( )
inline

goalCB callback funtion for the new goal

Definition at line 129 of file segmentation_ros_node.cpp.

void SegmentationNode::scan_callback ( const sensor_msgs::PointCloud2ConstPtr &  cloud_ptr)
inline

scan_callback

Parameters
cloud_ptr

Definition at line 230 of file segmentation_ros_node.cpp.

Member Data Documentation

actionlib::SimpleActionServer<cpf_segmentation_ros::DoSegmentationAction> SegmentationNode::actionServer_
private

Definition at line 275 of file segmentation_ros_node.cpp.

pcl::PointCloud<PointT> SegmentationNode::cloud_
private

Definition at line 279 of file segmentation_ros_node.cpp.

ros::ServiceServer SegmentationNode::doSegmentationSrv_
private

Definition at line 271 of file segmentation_ros_node.cpp.

ros::ServiceServer SegmentationNode::enablePublisherSrv_
private

Definition at line 272 of file segmentation_ros_node.cpp.

ros::NodeHandle SegmentationNode::nh_
private

Definition at line 264 of file segmentation_ros_node.cpp.

ros::Subscriber SegmentationNode::pcl_sub_
private

Definition at line 268 of file segmentation_ros_node.cpp.

bool SegmentationNode::publisherEnabled_
private

Definition at line 283 of file segmentation_ros_node.cpp.

Segmentation SegmentationNode::segmentation
private

Definition at line 280 of file segmentation_ros_node.cpp.

boost::thread* SegmentationNode::segmentation_thread
private

Definition at line 277 of file segmentation_ros_node.cpp.

ros::Publisher SegmentationNode::segmented_pub_
private

Definition at line 267 of file segmentation_ros_node.cpp.


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


cpf_segmentation_ros
Author(s):
autogenerated on Mon Jun 10 2019 13:04:53