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