mesh_from_pointcloud_alg_node.cpp
Go to the documentation of this file.
00001 #include "mesh_from_pointcloud_alg_node.h"
00002 
00003 MeshFromPointcloudAlgNode::MeshFromPointcloudAlgNode(void) :
00004   algorithm_base::IriBaseAlgorithm<MeshFromPointcloudAlgorithm>()
00005 {
00006   //init class attributes if necessary
00007   //this->loop_rate_ = 2;//in [Hz]
00008 
00009   // [init publishers]
00010   
00011   // [init subscribers]
00012   
00013   // [init services]
00014   this->get_mesh_server_ = this->public_node_handle_.advertiseService("get_mesh", &MeshFromPointcloudAlgNode::get_meshCallback, this);
00015   
00016   // [init clients]
00017   
00018   // [init action servers]
00019   
00020   // [init action clients]
00021 }
00022 
00023 MeshFromPointcloudAlgNode::~MeshFromPointcloudAlgNode(void)
00024 {
00025   // [free dynamic memory]
00026 }
00027 
00028 void MeshFromPointcloudAlgNode::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 
00041 /*  [service callbacks] */
00042 bool MeshFromPointcloudAlgNode::get_meshCallback(iri_perception_msgs::PointCloud2ToMesh::Request &req, iri_perception_msgs::PointCloud2ToMesh::Response &res) 
00043 { 
00044     ROS_INFO("MeshFromPointcloudAlgNode::get_meshCallback: New Request Received!"); 
00045 
00046     //use appropiate mutex to shared variables if necessary 
00047     this->alg_.lock(); 
00048     this->get_mesh_mutex_.enter(); 
00049 
00050     sensor_msgs::PointCloud2::ConstPtr point_cloud_ConstPtr;
00051     point_cloud_ConstPtr = boost::make_shared<sensor_msgs::PointCloud2>(req.input);
00052 
00053     if(!alg_.compute_mesh(point_cloud_ConstPtr))
00054     {
00055         ROS_INFO("MeshFromPointcloudAlgNode::get_meshCallback: ERROR: alg is not on run mode yet.");
00056     }
00057     // TODO: There is not response right now
00058     // It would be great to return the mesh as a message or the url to the stored file.
00059     //res.mesh = *alg_.get_mesh();
00060 
00061     //unlock previously blocked shared variables 
00062     this->alg_.unlock(); 
00063     this->get_mesh_mutex_.exit(); 
00064 
00065     return true; 
00066 }
00067 
00068 /*  [action callbacks] */
00069 
00070 /*  [action requests] */
00071 
00072 void MeshFromPointcloudAlgNode::node_config_update(Config &config, uint32_t level)
00073 {
00074   this->alg_.lock();
00075 
00076   this->alg_.unlock();
00077 }
00078 
00079 void MeshFromPointcloudAlgNode::addNodeDiagnostics(void)
00080 {
00081 }
00082 
00083 /* main function */
00084 int main(int argc,char *argv[])
00085 {
00086   return algorithm_base::main<MeshFromPointcloudAlgNode>(argc, argv, "mesh_from_pointcloud_alg_node");
00087 }
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


iri_mesh_from_pointcloud
Author(s): Sergi Foix
autogenerated on Thu Mar 7 2013 11:30:06