Skip to content

Commit 8e471f4

Browse files
committed
Merge pull request #2 from jspricke/point_cloud2_assembler
New point_cloud2_assembler for PointCloud2 input
2 parents e9507cc + d4d7d8c commit 8e471f4

File tree

2 files changed

+94
-0
lines changed

2 files changed

+94
-0
lines changed

CMakeLists.txt

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,8 @@ rosbuild_add_executable(laser_scan_assembler src/laser_scan_assembler.cpp)
1717
rosbuild_link_boost(laser_scan_assembler system signals)
1818
rosbuild_add_executable(point_cloud_assembler src/point_cloud_assembler.cpp)
1919
rosbuild_link_boost(point_cloud_assembler signals)
20+
rosbuild_add_executable(point_cloud2_assembler src/point_cloud2_assembler.cpp)
21+
rosbuild_link_boost(point_cloud2_assembler signals)
2022

2123
rosbuild_add_executable(../test/dummy_scan_producer test/dummy_scan_producer.cpp)
2224
rosbuild_link_boost(../test/dummy_scan_producer thread signals)

src/point_cloud2_assembler.cpp

Lines changed: 92 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,92 @@
1+
/*********************************************************************
2+
* Software License Agreement (BSD License)
3+
*
4+
* Copyright (c) 2008, Willow Garage, Inc.
5+
* All rights reserved.
6+
*
7+
* Redistribution and use in source and binary forms, with or without
8+
* modification, are permitted provided that the following conditions
9+
* are met:
10+
*
11+
* * Redistributions of source code must retain the above copyright
12+
* notice, this list of conditions and the following disclaimer.
13+
* * Redistributions in binary form must reproduce the above
14+
* copyright notice, this list of conditions and the following
15+
* disclaimer in the documentation and/or other materials provided
16+
* with the distribution.
17+
* * Neither the name of the Willow Garage nor the names of its
18+
* contributors may be used to endorse or promote products derived
19+
* from this software without specific prior written permission.
20+
*
21+
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22+
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23+
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24+
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25+
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26+
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27+
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28+
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29+
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30+
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31+
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32+
* POSSIBILITY OF SUCH DAMAGE.
33+
*********************************************************************/
34+
35+
36+
#include "laser_assembler/base_assembler.h"
37+
#include <sensor_msgs/point_cloud_conversion.h>
38+
39+
using namespace std ;
40+
41+
namespace laser_assembler
42+
{
43+
44+
/**
45+
* \brief Maintains a history of incremental point clouds (usually from laser scans) and generates a point cloud upon request
46+
* \todo Clean up the doxygen part of this header
47+
* params
48+
* * (Several params are inherited from BaseAssemblerSrv)
49+
*/
50+
class PointCloud2Assembler : public BaseAssembler<sensor_msgs::PointCloud2>
51+
{
52+
public:
53+
PointCloud2Assembler() : BaseAssembler<sensor_msgs::PointCloud2>("max_clouds")
54+
{
55+
56+
}
57+
58+
~PointCloud2Assembler()
59+
{
60+
61+
}
62+
63+
unsigned int GetPointsInScan(const sensor_msgs::PointCloud2& scan)
64+
{
65+
return (scan.width * scan.height);
66+
}
67+
68+
void ConvertToCloud(const string& fixed_frame_id, const sensor_msgs::PointCloud2& scan_in, sensor_msgs::PointCloud& cloud_out)
69+
{
70+
sensor_msgs::PointCloud cloud_in;
71+
sensor_msgs::convertPointCloud2ToPointCloud(scan_in, cloud_in);
72+
tf_->transformPointCloud(fixed_frame_id, cloud_in, cloud_out) ;
73+
return ;
74+
}
75+
76+
private:
77+
78+
};
79+
80+
}
81+
82+
using namespace laser_assembler ;
83+
84+
int main(int argc, char **argv)
85+
{
86+
ros::init(argc, argv, "point_cloud_assembler");
87+
PointCloud2Assembler pc_assembler;
88+
pc_assembler.start("cloud");
89+
ros::spin();
90+
91+
return 0;
92+
}

0 commit comments

Comments
 (0)