scan_to_cloud_converter.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2010, 2011, Ivan Dryanovski, William Morris
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the CCNY Robotics Lab nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
31 
33 
34 namespace scan_tools {
35 
37  nh_(nh),
38  nh_private_(nh_private)
39 {
40  ROS_INFO("Starting ScanToCloudConverter");
41 
42  invalid_point_.x = std::numeric_limits<float>::quiet_NaN();
43  invalid_point_.y = std::numeric_limits<float>::quiet_NaN();
44  invalid_point_.z = std::numeric_limits<float>::quiet_NaN();
45 
47  "cloud", 1);
49  "scan", 1, &ScanToCloudConverter::scanCallback, this);
50 }
51 
53 {
54  ROS_INFO("Destroying ScanToCloudConverter");
55 }
56 
57 void ScanToCloudConverter::scanCallback(const sensor_msgs::LaserScan::ConstPtr& scan_msg)
58 {
59  PointCloudT::Ptr cloud_msg =
61 
62  cloud_msg->points.resize(scan_msg->ranges.size());
63 
64  for (unsigned int i = 0; i < scan_msg->ranges.size(); ++i)
65  {
66  PointT& p = cloud_msg->points[i];
67  float range = scan_msg->ranges[i];
68  if (range > scan_msg->range_min && range < scan_msg->range_max)
69  {
70  float angle = scan_msg->angle_min + i*scan_msg->angle_increment;
71 
72  p.x = range * cos(angle);
73  p.y = range * sin(angle);
74  p.z = 0.0;
75  }
76  else
77  p = invalid_point_;
78  }
79 
80  cloud_msg->width = scan_msg->ranges.size();
81  cloud_msg->height = 1;
82  cloud_msg->is_dense = false; //contains nans
83  pcl_conversions::toPCL(scan_msg->header, cloud_msg->header);
84 
85  cloud_publisher_.publish(cloud_msg);
86 }
87 
88 } //namespace scan_tools
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void scanCallback(const sensor_msgs::LaserScan::ConstPtr &scan_msg)
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
pcl::PointCloud< PointT > PointCloudT
#define ROS_INFO(...)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ScanToCloudConverter(ros::NodeHandle nh, ros::NodeHandle nh_private)
void toPCL(const ros::Time &stamp, pcl::uint64_t &pcl_stamp)


scan_to_cloud_converter
Author(s): Ivan Dryanovski, William Morris
autogenerated on Mon Jun 10 2019 15:08:55