zyonz_obtain_two_clustered_leaves_alg_node.cpp
Go to the documentation of this file.
00001 #include "zyonz_obtain_two_clustered_leaves_alg_node.h"
00002 
00003 ZyonzObtainTwoClusteredLeavesAlgNode::ZyonzObtainTwoClusteredLeavesAlgNode(void) :
00004   algorithm_base::IriBaseAlgorithm<ZyonzObtainTwoClusteredLeavesAlgorithm>()
00005 {
00006   //init class attributes if necessary
00007   //this->loop_rate_ = 2;//in [Hz]
00008 
00009   // [init publishers]
00010   cluster_a_img_publisher_ = public_node_handle_.advertise<sensor_msgs::Image>("cluster_a_img", 1);
00011   cluster_b_img_publisher_ = public_node_handle_.advertise<sensor_msgs::Image>("cluster_b_img", 1);
00012   cluster_a_publisher_ = public_node_handle_.advertise<sensor_msgs::PointCloud2>("cluster_a", 1);
00013   cluster_b_publisher_ = public_node_handle_.advertise<sensor_msgs::PointCloud2>("cluster_b", 1);
00014   
00015   // [init subscribers]
00016   
00017   // [init services]
00018   extract_clusters_server_ = public_node_handle_.advertiseService("extract_clusters", &ZyonzObtainTwoClusteredLeavesAlgNode::extract_clustersCallback, this);
00019   
00020   // [init clients]
00021   
00022   // [init action servers]
00023   
00024   // [init action clients]
00025 }
00026 
00027 ZyonzObtainTwoClusteredLeavesAlgNode::~ZyonzObtainTwoClusteredLeavesAlgNode(void)
00028 {
00029   // [free dynamic memory]
00030 }
00031 
00032 void ZyonzObtainTwoClusteredLeavesAlgNode::mainNodeThread(void)
00033 {
00034   // [fill msg structures]
00035   //this->Image_msg_.data = my_var;
00036   //this->PointCloud2_msg_.data = my_var;
00037   
00038   // [fill srv structure and make request to the server]
00039   
00040   // [fill action structure and make request to the action server]
00041 
00042   // [publish messages]
00043   // cluster_a_img_publisher_.publish(Image_msg_);
00044   // cluster_b_img_publisher_.publish(Image_msg_);
00045   // cluster_a_publisher_.publish(this->PointCloud2_msg_);
00046   // cluster_b_publisher_.publish(this->PointCloud2_msg_);
00047 }
00048 
00049 /*  [subscriber callbacks] */
00050 
00051 /*  [service callbacks] */
00052 bool ZyonzObtainTwoClusteredLeavesAlgNode::extract_clustersCallback(zyonz_obtain_two_clustered_leaves::ExtractClusters::Request &req, zyonz_obtain_two_clustered_leaves::ExtractClusters::Response &res) 
00053 {
00054   ROS_INFO("ZyonzObtainTwoClusteredLeavesAlgNode::extract_clustersCallback: New Request Received!"); 
00055 
00056   //use appropiate mutex to shared variables if necessary 
00057   alg_.lock(); 
00058   extract_clusters_mutex_.enter(); 
00059 
00060 //  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_Ptr;
00061 //  pcl::fromROSMsg(req.input, *cloud_Ptr);
00062   sensor_msgs::PointCloud2::ConstPtr point_cloud_ConstPtr;
00063   point_cloud_ConstPtr = boost::make_shared<sensor_msgs::PointCloud2>(req.input);
00064   
00065   if(!alg_.extract_clusters(point_cloud_ConstPtr))
00066   {
00067     ROS_INFO("ZyonzObtainTwoClusteredLeavesAlgNode::extract_clustersCallback: ERROR: alg is not on run mode yet!"); 
00068   }
00069 
00070   pcl::toROSMsg(*alg_.get_cluster_a(), res.cluster_a);
00071   pcl::toROSMsg(*alg_.get_cluster_b(), res.cluster_b);
00072   res.cluster_a_img = *alg_.get_cluster_a_img();
00073   res.cluster_b_img = *alg_.get_cluster_b_img();
00074 
00075   cluster_a_publisher_.publish(*alg_.get_cluster_a());
00076   cluster_b_publisher_.publish(*alg_.get_cluster_b());
00077   cluster_a_img_publisher_.publish(*alg_.get_cluster_a_img());
00078   cluster_b_img_publisher_.publish(*alg_.get_cluster_b_img());
00079   
00080   //unlock previously blocked shared variables 
00081   alg_.unlock(); 
00082   extract_clusters_mutex_.exit(); 
00083 
00084   return true; 
00085 }
00086 
00087 /*  [action callbacks] */
00088 
00089 /*  [action requests] */
00090 
00091 void ZyonzObtainTwoClusteredLeavesAlgNode::node_config_update(Config &config, uint32_t level)
00092 {
00093   this->alg_.lock();
00094 
00095   this->alg_.unlock();
00096 }
00097 
00098 void ZyonzObtainTwoClusteredLeavesAlgNode::addNodeDiagnostics(void)
00099 {
00100 }
00101 
00102 /* main function */
00103 int main(int argc,char *argv[])
00104 {
00105   return algorithm_base::main<ZyonzObtainTwoClusteredLeavesAlgNode>(argc, argv, "zyonz_obtain_two_clustered_leaves_alg_node");
00106 }


zyonz_obtain_two_clustered_leaves
Author(s): sfoix
autogenerated on Fri Dec 6 2013 20:35:16