45 #include <sensor_msgs/PointCloud.h>
49 #include <boost/bind/bind.hpp>
50 #include <boost/thread/mutex.hpp>
51 #include <boost/shared_ptr.hpp>
69 ROS_ERROR(
"No output frame specified for merging pointclouds");
111 sensor_msgs::PointCloud out;
120 std::copy(
cloud1_.points.begin(),
cloud1_.points.end(), out.points.begin());
124 for (
unsigned int i = 0 ; i <
cloud1_.channels.size() ; ++i)
125 for (
unsigned int j = 0 ; j <
cloud2_.channels.size() ; ++j)
130 unsigned int oc = out.channels.size();
131 out.channels.resize(oc + 1);
132 out.channels[oc].name =
cloud1_.channels[i].name;
133 out.channels[oc].values.resize(
cloud1_.channels[i].values.size() +
cloud2_.channels[j].values.size());
134 std::copy(
cloud1_.channels[i].values.begin(),
cloud1_.channels[i].values.end(), out.channels[oc].values.begin());
135 std::copy(
cloud2_.channels[j].values.begin(),
cloud2_.channels[j].values.end(), out.channels[oc].values.begin() +
cloud1_.channels[i].values.size());
145 void receiveCloud1(
const sensor_msgs::PointCloudConstPtr &cloud)
155 void receiveCloud2(
const sensor_msgs::PointCloudConstPtr &cloud)
165 void processCloud(
const sensor_msgs::PointCloudConstPtr &cloud, sensor_msgs::PointCloud &cloudOut)
190 sensor_msgs::PointCloud
cloud1_;
191 sensor_msgs::PointCloud
cloud2_;
198 int main(
int argc,
char **argv)
202 ROS_WARN(
"laser_assembler/merge_clouds is deprecated. You should instead be using 3dnav_pr2/merge_clouds");