obstacle_detection_alg_node.cpp
Go to the documentation of this file.
00001 #include "obstacle_detection_alg_node.h"
00002 
00003 ObstacleDetectionAlgNode::ObstacleDetectionAlgNode(void) :
00004   algorithm_base::IriBaseAlgorithm<ObstacleDetectionAlgorithm>()
00005 {
00006   //init class attributes if necessary
00007   //this->loop_rate_ = 2;//in [Hz]
00008 
00009   // [init publishers]
00010   this->pub_cloud_publisher_ = this->public_node_handle_.advertise<sensor_msgs::PointCloud2>("pub_cloud", 100);
00011   
00012   // [init subscribers]
00013   this->cloud_raw_subscriber_ = this->public_node_handle_.subscribe("cloud_raw", 100, &ObstacleDetectionAlgNode::cloud_raw_callback, this);
00014   
00015   // [init services]
00016   
00017   // [init clients]
00018   
00019   // [init action servers]
00020   
00021   // [init action clients]
00022 }
00023 
00024 ObstacleDetectionAlgNode::~ObstacleDetectionAlgNode(void)
00025 {
00026   // [free dynamic memory]
00027 }
00028 
00029 void ObstacleDetectionAlgNode::mainNodeThread(void)
00030 {
00031   // [fill msg structures]
00032   //this->PointCloud2_msg.data = my_var;
00033   
00034   // [fill srv structure and make request to the server]
00035   
00036   // [fill action structure and make request to the action server]
00037 
00038   // [publish messages]
00039  // this->pub_cloud_publisher_.publish(this->PointCloud2_msg_);
00040 }
00041 
00042 /*  [subscriber callbacks] */
00043 void ObstacleDetectionAlgNode::cloud_raw_callback(const sensor_msgs::PointCloud2::ConstPtr& msg) 
00044 { 
00045   ROS_INFO("ObstacleDetectionAlgNode::cloud_raw_callback: New Message Received"); 
00046 
00047   //use appropiate mutex to shared variables if necessary 
00048   //this->alg_.lock(); 
00049   this->cloud_raw_mutex_.enter(); 
00050   this->alg_.pcl_camera= *msg;
00051   //std::cout << msg->data << std::endl; 
00052    this->pub_cloud_publisher_.publish(this->alg_.getPCLfiltered());
00053   //unlock previously blocked shared variables 
00054   //this->alg_.unlock(); 
00055   this->cloud_raw_mutex_.exit(); 
00056 }
00057 
00058 /*  [service callbacks] */
00059 
00060 /*  [action callbacks] */
00061 
00062 /*  [action requests] */
00063 
00064 void ObstacleDetectionAlgNode::node_config_update(Config &config, uint32_t level)
00065 {
00066   this->alg_.lock();
00067 
00068   this->alg_.unlock();
00069 }
00070 
00071 void ObstacleDetectionAlgNode::addNodeDiagnostics(void)
00072 {
00073 }
00074 
00075 /* main function */
00076 int main(int argc,char *argv[])
00077 {
00078   return algorithm_base::main<ObstacleDetectionAlgNode>(argc, argv, "obstacle_detection_alg_node");
00079 }


iri_obstacle_detection
Author(s): irojas
autogenerated on Fri Dec 6 2013 20:48:37