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
00007
00008
00009
00010 this->output_publisher_ = this->public_node_handle_.advertise<sensor_msgs::PointCloud2>("output", 10);
00011
00012
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
00017
00018
00019
00020
00021
00022
00023 }
00024
00025 AssembleImageAndPointcloudAlgNode::~AssembleImageAndPointcloudAlgNode(void)
00026 {
00027
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
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
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
00082
00083
00084
00085
00086
00087
00088
00089
00090 }
00091
00092
00093 void AssembleImageAndPointcloudAlgNode::pointcloud_callback(const sensor_msgs::PointCloud2::ConstPtr& msg)
00094 {
00095
00096
00097
00098
00099
00100
00101 cloud2_ = msg;
00102 b_pcl_ = false;
00103 assembleImageAndPointCloud();
00104
00105
00106
00107
00108
00109
00110 }
00111
00112 void AssembleImageAndPointcloudAlgNode::image_callback(const sensor_msgs::Image::ConstPtr& msg)
00113 {
00114
00115
00116
00117
00118
00119
00120 image_ = msg;
00121 b_img_ = false;
00122 assembleImageAndPointCloud();
00123
00124
00125
00126
00127
00128
00129 }
00130
00131
00132
00133
00134
00135
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
00149 int main(int argc,char *argv[])
00150 {
00151 return algorithm_base::main<AssembleImageAndPointcloudAlgNode>(argc, argv, "assemble_image_and_pointcloud_alg_node");
00152 }