Skip to content

Commit 81b472e

Browse files
author
Paul Bovbel
committed
Move pointcloud_to_laserscan to new repository
0 parents  commit 81b472e

File tree

9 files changed

+623
-0
lines changed

9 files changed

+623
-0
lines changed

CHANGELOG.rst

Lines changed: 49 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,49 @@
1+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
2+
Changelog for package pointcloud_to_laserscan
3+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
4+
5+
1.2.7 (2015-06-08)
6+
------------------
7+
8+
* Cleanup pointcloud_to_laserscan launch files
9+
* Contributors: Paul Bovbel
10+
11+
1.2.6 (2015-02-04)
12+
------------------
13+
* Fix default value for concurrency
14+
* Fix multithreaded lazy pub sub
15+
* Contributors: Paul Bovbel
16+
17+
1.2.5 (2015-01-20)
18+
------------------
19+
* Switch to tf_sensor_msgs for transform
20+
* Set parameters in sample launch files to default
21+
* Add tolerance parameter
22+
* Contributors: Paul Bovbel
23+
24+
1.2.4 (2015-01-15)
25+
------------------
26+
* Remove stray dependencies
27+
* Refactor with tf2 and message filters
28+
* Remove roslaunch check
29+
* Fix regressions
30+
* Refactor to allow debug messages from node and nodelet
31+
* Contributors: Paul Bovbel
32+
33+
1.2.3 (2015-01-10)
34+
------------------
35+
* add launch tests
36+
* refactor naming and fix nodelet export
37+
* set default target frame to empty
38+
* clean up package.xml
39+
* Contributors: Paul Bovbel
40+
41+
1.2.2 (2014-10-25)
42+
------------------
43+
* clean up package.xml
44+
* Fix header reference
45+
* Fix flow
46+
* Fix pointer assertion
47+
* Finalize pointcloud to laserscan
48+
* Initial pointcloud to laserscan commit
49+
* Contributors: Paul Bovbel

CMakeLists.txt

Lines changed: 45 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,45 @@
1+
cmake_minimum_required(VERSION 2.8.3)
2+
project(pointcloud_to_laserscan)
3+
4+
find_package(catkin REQUIRED COMPONENTS
5+
message_filters
6+
nodelet
7+
roscpp
8+
sensor_msgs
9+
tf2
10+
tf2_ros
11+
tf2_sensor_msgs
12+
)
13+
14+
catkin_package(
15+
INCLUDE_DIRS include
16+
LIBRARIES pointcloud_to_laserscan
17+
CATKIN_DEPENDS roscpp message_filters nodelet sensor_msgs tf2 tf2_ros
18+
)
19+
20+
include_directories(
21+
include
22+
${catkin_INCLUDE_DIRS}
23+
)
24+
25+
add_library(pointcloud_to_laserscan src/pointcloud_to_laserscan_nodelet.cpp)
26+
target_link_libraries(pointcloud_to_laserscan ${catkin_LIBRARIES})
27+
28+
add_executable(pointcloud_to_laserscan_node src/pointcloud_to_laserscan_node.cpp)
29+
target_link_libraries(pointcloud_to_laserscan_node pointcloud_to_laserscan ${catkin_LIBRARIES})
30+
31+
install(TARGETS pointcloud_to_laserscan pointcloud_to_laserscan_node
32+
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
33+
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
34+
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION})
35+
36+
install(DIRECTORY include/${PROJECT_NAME}/
37+
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
38+
)
39+
install(FILES nodelets.xml
40+
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
41+
)
42+
43+
install(DIRECTORY launch
44+
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
45+
)
Lines changed: 96 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,96 @@
1+
/*
2+
* Software License Agreement (BSD License)
3+
*
4+
* Copyright (c) 2010-2012, 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 Willow Garage, Inc. 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+
37+
/*
38+
* Author: Paul Bovbel
39+
*/
40+
41+
#ifndef POINTCLOUD_TO_LASERSCAN_POINTCLOUD_TO_LASERSCAN_NODELET
42+
#define POINTCLOUD_TO_LASERSCAN_POINTCLOUD_TO_LASERSCAN_NODELET
43+
44+
#include "ros/ros.h"
45+
#include "boost/thread/mutex.hpp"
46+
47+
#include "nodelet/nodelet.h"
48+
#include "tf2_ros/buffer.h"
49+
#include "tf2_ros/message_filter.h"
50+
#include "message_filters/subscriber.h"
51+
#include "sensor_msgs/PointCloud2.h"
52+
53+
54+
namespace pointcloud_to_laserscan
55+
{
56+
typedef tf2_ros::MessageFilter<sensor_msgs::PointCloud2> MessageFilter;
57+
/**
58+
* Class to process incoming pointclouds into laserscans. Some initial code was pulled from the defunct turtlebot
59+
* pointcloud_to_laserscan implementation.
60+
*/
61+
class PointCloudToLaserScanNodelet : public nodelet::Nodelet
62+
{
63+
64+
public:
65+
PointCloudToLaserScanNodelet();
66+
67+
private:
68+
virtual void onInit();
69+
70+
void cloudCb(const sensor_msgs::PointCloud2ConstPtr &cloud_msg);
71+
void failureCb(const sensor_msgs::PointCloud2ConstPtr &cloud_msg,
72+
tf2_ros::filter_failure_reasons::FilterFailureReason reason);
73+
74+
void connectCb();
75+
76+
void disconnectCb();
77+
78+
ros::NodeHandle nh_, private_nh_;
79+
ros::Publisher pub_;
80+
boost::mutex connect_mutex_;
81+
82+
tf2_ros::Buffer tf2_;
83+
message_filters::Subscriber<sensor_msgs::PointCloud2> sub_;
84+
boost::shared_ptr<MessageFilter> message_filter_;
85+
86+
// ROS Parameters
87+
unsigned int input_queue_size_;
88+
std::string target_frame_;
89+
double tolerance_;
90+
double min_height_, max_height_, angle_min_, angle_max_, angle_increment_, scan_time_, range_min_, range_max_;
91+
bool use_inf_;
92+
};
93+
94+
} // pointcloud_to_laserscan
95+
96+
#endif // POINTCLOUD_TO_LASERSCAN_POINTCLOUD_TO_LASERSCAN_NODELET

launch/sample_node.launch

Lines changed: 40 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,40 @@
1+
<?xml version="1.0"?>
2+
3+
<launch>
4+
5+
<arg name="camera" default="camera" />
6+
7+
<!-- start sensor-->
8+
<include file="$(find openni2_launch)/launch/openni2.launch">
9+
<arg name="camera" default="$(arg camera)"/>
10+
</include>
11+
12+
<!-- run pointcloud_to_laserscan node -->
13+
<node pkg="pointcloud_to_laserscan" type="pointcloud_to_laserscan_node" name="pointcloud_to_laserscan">
14+
15+
<remap from="cloud_in" to="$(arg camera)/depth_registered/points_processed"/>
16+
<remap from="scan" to="$(arg camera)/scan"/>
17+
<rosparam>
18+
target_frame: camera_link # Leave empty to output scan in the pointcloud frame
19+
transform_tolerance: 0.01
20+
min_height: 0.0
21+
max_height: 1.0
22+
23+
angle_min: -1.5708 # -M_PI/2
24+
angle_max: 1.5708 # M_PI/2
25+
angle_increment: 0.087 # M_PI/360.0
26+
scan_time: 0.3333
27+
range_min: 0.45
28+
range_max: 4.0
29+
use_inf: true
30+
31+
# Concurrency level, affects number of pointclouds queued for processing and number of threads used
32+
# 0 : Detect number of cores
33+
# 1 : Single threaded
34+
# 2->inf : Parallelism level
35+
concurrency_level: 1
36+
</rosparam>
37+
38+
</node>
39+
40+
</launch>

launch/sample_nodelet.launch

Lines changed: 40 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,40 @@
1+
<?xml version="1.0"?>
2+
3+
<launch>
4+
5+
<arg name="camera" default="camera" />
6+
7+
<!-- start sensor-->
8+
<include file="$(find openni2_launch)/launch/openni2.launch">
9+
<arg name="camera" default="$(arg camera)"/>
10+
</include>
11+
12+
<!-- push pointcloud_to_laserscan nodelet into sensor's nodelet manager-->
13+
<node pkg="nodelet" type="nodelet" name="pointcloud_to_laserscan" args="load pointcloud_to_laserscan/pointcloud_to_laserscan_nodelet $(arg camera)_nodelet_manager">
14+
15+
<remap from="cloud_in" to="$(arg camera)/depth_registered/points_processed"/>
16+
<remap from="scan" to="$(arg camera)/scan"/>
17+
<rosparam>
18+
target_frame: camera_link # Leave empty to output scan in the pointcloud frame
19+
transform_tolerance: 0.01
20+
min_height: 0.0
21+
max_height: 1.0
22+
23+
angle_min: -1.5708 # -M_PI/2
24+
angle_max: 1.5708 # M_PI/2
25+
angle_increment: 0.087 # M_PI/360.0
26+
scan_time: 0.3333
27+
range_min: 0.45
28+
range_max: 4.0
29+
use_inf: true
30+
31+
# Concurrency level, affects number of pointclouds queued for processing, thread number governed by nodelet manager
32+
# 0 : Detect number of cores
33+
# 1 : Single threaded
34+
# 2->inf : Parallelism level
35+
concurrency_level: 1
36+
</rosparam>
37+
38+
</node>
39+
40+
</launch>

nodelets.xml

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,11 @@
1+
<library path="lib/libpointcloud_to_laserscan">
2+
3+
<class name="pointcloud_to_laserscan/pointcloud_to_laserscan_nodelet"
4+
type="pointcloud_to_laserscan::PointCloudToLaserScanNodelet"
5+
base_class_type="nodelet::Nodelet">
6+
<description>
7+
Nodelet to convert sensor_msgs/PointCloud2 to sensor_msgs/LaserScans.
8+
</description>
9+
</class>
10+
11+
</library>

package.xml

Lines changed: 37 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,37 @@
1+
<?xml version="1.0"?>
2+
<package>
3+
<name>pointcloud_to_laserscan</name>
4+
<version>1.2.7</version>
5+
<description>Converts a 3D Point Cloud into a 2D laser scan. This is useful for making devices like the Kinect appear like a laser scanner for 2D-based algorithms (e.g. laser-based SLAM).</description>
6+
7+
<maintainer email="[email protected]">Paul Bovbel</maintainer>
8+
<author>Tully Foote</author>
9+
10+
<license>BSD</license>
11+
12+
<url type="website">http://ros.org/wiki/perception_pcl</url>
13+
<url type="bugtracker">https://github.com/ros-perception/perception_pcl/issues</url>
14+
<url type="repository">https://github.com/ros-perception/perception_pcl</url>
15+
16+
<buildtool_depend>catkin</buildtool_depend>
17+
18+
<build_depend>message_filters</build_depend>
19+
<build_depend>nodelet</build_depend>
20+
<build_depend>roscpp</build_depend>
21+
<build_depend>sensor_msgs</build_depend>
22+
<build_depend>tf2</build_depend>
23+
<build_depend>tf2_ros</build_depend>
24+
<build_depend>tf2_sensor_msgs</build_depend>
25+
26+
<run_depend>message_filters</run_depend>
27+
<run_depend>nodelet</run_depend>
28+
<run_depend>roscpp</run_depend>
29+
<run_depend>sensor_msgs</run_depend>
30+
<run_depend>tf2</run_depend>
31+
<run_depend>tf2_ros</run_depend>
32+
<run_depend>tf2_sensor_msgs</run_depend>
33+
34+
<export>
35+
<nodelet plugin="${prefix}/nodelets.xml"/>
36+
</export>
37+
</package>
Lines changed: 65 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,65 @@
1+
/*
2+
* Software License Agreement (BSD License)
3+
*
4+
* Copyright (c) 2010-2012, 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 Willow Garage, Inc. 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+
37+
/*
38+
* Author: Paul Bovbel
39+
*/
40+
41+
#include <ros/ros.h>
42+
#include <nodelet/loader.h>
43+
44+
int main(int argc, char **argv){
45+
ros::init(argc, argv, "pointcloud_to_laserscan_node");
46+
ros::NodeHandle private_nh("~");
47+
int concurrency_level;
48+
private_nh.param<int>("concurrency_level", concurrency_level, 0);
49+
50+
nodelet::Loader nodelet;
51+
nodelet::M_string remap(ros::names::getRemappings());
52+
nodelet::V_string nargv;
53+
std::string nodelet_name = ros::this_node::getName();
54+
nodelet.load(nodelet_name, "pointcloud_to_laserscan/pointcloud_to_laserscan_nodelet", remap, nargv);
55+
56+
boost::shared_ptr<ros::MultiThreadedSpinner> spinner;
57+
if(concurrency_level) {
58+
spinner.reset(new ros::MultiThreadedSpinner(concurrency_level));
59+
}else{
60+
spinner.reset(new ros::MultiThreadedSpinner());
61+
}
62+
spinner->spin();
63+
return 0;
64+
65+
}

0 commit comments

Comments
 (0)