assemble_image_and_pointcloud_alg_node.cpp
Go to the documentation of this file.
00001 #include "assemble_image_and_pointcloud_alg_node.h"
00002 
00003 AssembleImageAndPointcloudAlgNode::AssembleImageAndPointcloudAlgNode(void) :
00004   algorithm_base::IriBaseAlgorithm<AssembleImageAndPointcloudAlgorithm>(), b_pcl_(true), b_img_(true)
00005 {
00006   //init class attributes if necessary
00007   //this->loop_rate_ = 2;//in [Hz]
00008 
00009   // [init publishers]
00010   this->output_publisher_ = this->public_node_handle_.advertise<sensor_msgs::PointCloud2>("output", 10);
00011   
00012   // [init subscribers]
00013   this->pointcloud_subscriber_ = this->public_node_handle_.subscribe("pointcloud", 10, &AssembleImageAndPointcloudAlgNode::pointcloud_callback, this);
00014   this->image_subscriber_ = this->public_node_handle_.subscribe("image", 10, &AssembleImageAndPointcloudAlgNode::image_callback, this);
00015   
00016   // [init services]
00017   
00018   // [init clients]
00019   
00020   // [init action servers]
00021   
00022   // [init action clients]
00023 }
00024 
00025 AssembleImageAndPointcloudAlgNode::~AssembleImageAndPointcloudAlgNode(void)
00026 {
00027   // [free dynamic memory]
00028 }
00029 
00030 void AssembleImageAndPointcloudAlgNode::assembleImageAndPointCloud(void)
00031 {
00032     if ((!b_pcl_) && (!b_img_)){ 
00033         if (output_publisher_.getNumSubscribers () > 0){
00034             if ((cloud2_->height != image_->height) && (cloud2_->width != image_->width)){
00035                 ROS_ERROR("AssembleImageAndPointCloudAlgNode::assembleImageAndPointCloud: Input data have different size");
00036             } else {
00037                 // PointCloud_msg_ re-definition
00038                 PointCloud2_msg_.header.frame_id = cloud2_->header.frame_id;
00039                 PointCloud2_msg_.header.stamp    = cloud2_->header.stamp;
00040                 PointCloud2_msg_.height          = cloud2_->height;
00041                 PointCloud2_msg_.width           = cloud2_->width;
00042                 PointCloud2_msg_.fields.resize (4);
00043                 PointCloud2_msg_.fields[0].name = "x";
00044                 PointCloud2_msg_.fields[1].name = "y";
00045                 PointCloud2_msg_.fields[2].name = "z";
00046                 PointCloud2_msg_.fields[3].name = "intensity";
00047                 unsigned int offset = 0;
00048                 for (size_t s = 0; s < PointCloud2_msg_.fields.size (); ++s, offset += 4)
00049                 {
00050                     PointCloud2_msg_.fields[s].offset   = offset;
00051                     PointCloud2_msg_.fields[s].count    = 1;
00052                     PointCloud2_msg_.fields[s].datatype = sensor_msgs::PointField::FLOAT32;
00053                 }
00054                 PointCloud2_msg_.point_step = offset;
00055                 PointCloud2_msg_.row_step   = PointCloud2_msg_.point_step * PointCloud2_msg_.width;
00056                 PointCloud2_msg_.data.resize (PointCloud2_msg_.row_step   * PointCloud2_msg_.height);
00057                 PointCloud2_msg_.is_dense   = true;
00058 
00059                 int index = 0;
00060                 for (unsigned int v = 0; v < PointCloud2_msg_.height; ++v){
00061                     for (unsigned int u = 0; u < PointCloud2_msg_.width; ++u, ++index){
00062                         float *cstep = (float*)&cloud2_->data[(index) * cloud2_->point_step];
00063                         float *pstep = (float*)&PointCloud2_msg_.data[(index) * PointCloud2_msg_.point_step];
00064                         //unsigned int *image_data = (unsigned int *)&image_->data[index];
00065                         pstep[0] = cstep[0];
00066                         pstep[1] = cstep[1];
00067                         pstep[2] = cstep[2];
00068                         pstep[3] = image_->data[index];
00069                     }
00070                 }
00071                 output_publisher_.publish(PointCloud2_msg_);
00072             }
00073             b_pcl_ = b_img_ = true;
00074         }
00075     }
00076 }
00077 
00078 
00079 void AssembleImageAndPointcloudAlgNode::mainNodeThread(void)
00080 {
00081   // [fill msg structures]
00082   //this->PointCloud2_msg_.data = my_var;
00083   
00084   // [fill srv structure and make request to the server]
00085   
00086   // [fill action structure and make request to the action server]
00087 
00088   // [publish messages]
00089   //  output_publisher_.publish(PointCloud2_msg_);
00090 }
00091 
00092 /*  [subscriber callbacks] */
00093 void AssembleImageAndPointcloudAlgNode::pointcloud_callback(const sensor_msgs::PointCloud2::ConstPtr& msg) 
00094 { 
00095   //ROS_INFO("AssembleImageAndPointcloudAlgNode::pointcloud_callback: New Message Received"); 
00096 
00097   //use appropiate mutex to shared variables if necessary 
00098   //alg_.lock(); 
00099   //pointcloud_mutex_.enter(); 
00100 
00101   cloud2_ = msg;
00102   b_pcl_ = false;
00103   assembleImageAndPointCloud();
00104 
00105   //std::cout << msg->data << std::endl; 
00106 
00107   //unlock previously blocked shared variables 
00108   //alg_.unlock(); 
00109   //pointcloud_mutex_.exit(); 
00110 }
00111 
00112 void AssembleImageAndPointcloudAlgNode::image_callback(const sensor_msgs::Image::ConstPtr& msg) 
00113 { 
00114   //ROS_INFO("AssembleImageAndPointcloudAlgNode::image_callback: New Message Received"); 
00115 
00116   //use appropiate mutex to shared variables if necessary 
00117   //alg_.lock(); 
00118   //image_mutex_.enter(); 
00119 
00120   image_ = msg;
00121   b_img_ = false;
00122   assembleImageAndPointCloud();
00123   
00124   //std::cout << msg->data << std::endl; 
00125 
00126   //unlock previously blocked shared variables 
00127   //alg_.unlock(); 
00128   //image_mutex_.exit(); 
00129 }
00130 
00131 /*  [service callbacks] */
00132 
00133 /*  [action callbacks] */
00134 
00135 /*  [action requests] */
00136 
00137 void AssembleImageAndPointcloudAlgNode::node_config_update(Config &config, uint32_t level)
00138 {
00139   this->alg_.lock();
00140 
00141   this->alg_.unlock();
00142 }
00143 
00144 void AssembleImageAndPointcloudAlgNode::addNodeDiagnostics(void)
00145 {
00146 }
00147 
00148 /* main function */
00149 int main(int argc,char *argv[])
00150 {
00151   return algorithm_base::main<AssembleImageAndPointcloudAlgNode>(argc, argv, "assemble_image_and_pointcloud_alg_node");
00152 }


iri_assemble_image_and_pointcloud
Author(s): Sergi Foix
autogenerated on Fri Dec 6 2013 21:41:29