sick_ldmrs_make_organized.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2016, DFKI GmbH
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of DFKI GmbH nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  *
00029  *      Authors:
00030  *         Martin Günther <martin.guenther@dfki.de>
00031  *         Jochen Sprickerhof <ros@jochen.sprickerhof.de>
00032  *
00033  */
00034 
00035 #include <ros/ros.h>
00036 
00037 #include <pcl_conversions/pcl_conversions.h>
00038 
00039 #include <sensor_msgs/PointCloud2.h>
00040 #include <sick_ldmrs_msgs/sick_ldmrs_point_type.h>
00041 #include <pcl/point_cloud.h>
00042 
00043 typedef sick_ldmrs_msgs::SICK_LDMRS_Point PointT;
00044 typedef pcl::PointCloud<PointT> PointCloudT;
00045 
00046 ros::Publisher pub;
00047 
00048 double start_angle_;
00049 double end_angle_;
00050 double angular_resolution_;
00051 
00052 void callback(const sensor_msgs::PointCloud2::ConstPtr& pc)
00053 {
00054 
00055   PointCloudT::Ptr cloud = boost::make_shared<PointCloudT>();
00056   pcl::fromROSMsg(*pc, *cloud);
00057 
00058   size_t height = 8;   // 8 layers
00059   size_t width = round((start_angle_ - end_angle_) / angular_resolution_) + 1;
00060 
00061   PointT invalid;
00062   invalid.x = invalid.y = invalid.z = std::numeric_limits<float>::quiet_NaN();
00063   PointCloudT::Ptr cloud_out = boost::make_shared<PointCloudT>(width, height, invalid);
00064   cloud_out->is_dense = false;
00065 
00066   for (size_t i = 0; i < cloud->size(); i++)
00067   {
00068     const PointT &p = cloud->points[i];
00069     int col = round((atan2(p.y, p.x) - end_angle_) / angular_resolution_);
00070     int row = p.layer;
00071 
00072     if (col < 0 || col >= width || row < 0 || row >= height)
00073     {
00074       ROS_ERROR("Invalid coordinates: (%d, %d) is outside (0, 0)..(%zu, %zu)!", col, row, width, height);
00075       continue;
00076     }
00077     (*cloud_out)[row * width + col] = p;
00078   }
00079 
00080   sensor_msgs::PointCloud2::Ptr msg = boost::make_shared<sensor_msgs::PointCloud2>();
00081   pcl::toROSMsg(*cloud_out, *msg);
00082   msg->header = pc->header;
00083   pub.publish(msg);
00084 }
00085 
00086 int main(int argc, char **argv)
00087 {
00088   ros::init(argc, argv, "sick_ldmrs_make_organized");
00089   ros::NodeHandle nh;
00090   ros::NodeHandle private_nh("~");
00091 
00092   start_angle_ = private_nh.param("start_angle", 0.872664625997);
00093   end_angle_ = private_nh.param("end_angle", -1.0471975512);
00094   angular_resolution_ = private_nh.param("angular_resolution", 0.125 * M_PI / 180.0);
00095 
00096   ros::Subscriber sub = nh.subscribe("cloud", 1, callback);
00097   pub = nh.advertise<sensor_msgs::PointCloud2>("organized", 1);
00098 
00099   ros::spin();
00100 
00101   return 0;
00102 }


sick_ldmrs_tools
Author(s): Martin Günther , Jochen Sprickerhof
autogenerated on Mon Aug 14 2017 02:35:43