sick_ldmrs_make_organized.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2016, DFKI GmbH
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 DFKI GmbH 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  * Authors:
30  * Martin Günther <martin.guenther@dfki.de>
31  * Jochen Sprickerhof <ros@jochen.sprickerhof.de>
32  *
33  */
34 
35 #include <ros/ros.h>
36 
38 
39 #include <sensor_msgs/PointCloud2.h>
41 #include <pcl/point_cloud.h>
42 
44 typedef pcl::PointCloud<PointT> PointCloudT;
45 
47 
48 double start_angle_;
49 double end_angle_;
51 
52 void callback(const sensor_msgs::PointCloud2::ConstPtr& pc)
53 {
54 
55  PointCloudT::Ptr cloud = boost::make_shared<PointCloudT>();
56  pcl::fromROSMsg(*pc, *cloud);
57 
58  size_t height = 8; // 8 layers
59  size_t width = round((start_angle_ - end_angle_) / angular_resolution_) + 1;
60 
61  PointT invalid;
62  invalid.x = invalid.y = invalid.z = std::numeric_limits<float>::quiet_NaN();
63  PointCloudT::Ptr cloud_out = boost::make_shared<PointCloudT>(width, height, invalid);
64  cloud_out->is_dense = false;
65 
66  for (size_t i = 0; i < cloud->size(); i++)
67  {
68  const PointT &p = cloud->points[i];
69  int col = round((atan2(p.y, p.x) - end_angle_) / angular_resolution_);
70  int row = p.layer;
71 
72  if (col < 0 || col >= width || row < 0 || row >= height)
73  {
74  ROS_ERROR("Invalid coordinates: (%d, %d) is outside (0, 0)..(%zu, %zu)!", col, row, width, height);
75  continue;
76  }
77  (*cloud_out)[row * width + col] = p;
78  }
79 
80  sensor_msgs::PointCloud2::Ptr msg = boost::make_shared<sensor_msgs::PointCloud2>();
81  pcl::toROSMsg(*cloud_out, *msg);
82  msg->header = pc->header;
83  pub.publish(msg);
84 }
85 
86 int main(int argc, char **argv)
87 {
88  ros::init(argc, argv, "sick_ldmrs_make_organized");
89  ros::NodeHandle nh;
90  ros::NodeHandle private_nh("~");
91 
92  start_angle_ = private_nh.param("start_angle", 0.872664625997);
93  end_angle_ = private_nh.param("end_angle", -1.0471975512);
94  angular_resolution_ = private_nh.param("angular_resolution", 0.125 * M_PI / 180.0);
95 
96  ros::Subscriber sub = nh.subscribe("cloud", 1, callback);
97  pub = nh.advertise<sensor_msgs::PointCloud2>("organized", 1);
98 
99  ros::spin();
100 
101  return 0;
102 }
msg
void publish(const boost::shared_ptr< M > &message) const
ros::Publisher pub
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
ROSCPP_DECL void spin(Spinner &spinner)
double angular_resolution_
double start_angle_
bool param(const std::string &param_name, T &param_val, const T &default_val) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void callback(const sensor_msgs::PointCloud2::ConstPtr &pc)
sick_ldmrs_msgs::SICK_LDMRS_Point PointT
int main(int argc, char **argv)
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
double end_angle_
#define ROS_ERROR(...)
pcl::PointCloud< PointT > PointCloudT


sick_ldmrs_tools
Author(s): Martin Günther , Jochen Sprickerhof
autogenerated on Sun Oct 25 2020 03:33:58