scan_to_cloud_converter.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2010, 2011, Ivan Dryanovski, William Morris
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 the CCNY Robotics Lab 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 
00030 #include "scan_to_cloud_converter/scan_to_cloud_converter.h"
00031 
00032 namespace scan_tools {
00033 
00034 ScanToCloudConverter::ScanToCloudConverter(ros::NodeHandle nh, ros::NodeHandle nh_private):
00035   nh_(nh),
00036   nh_private_(nh_private)
00037 {
00038   ROS_INFO("Starting ScanToCloudConverter");
00039 
00040   invalid_point_.x = std::numeric_limits<float>::quiet_NaN();
00041   invalid_point_.y = std::numeric_limits<float>::quiet_NaN();
00042   invalid_point_.z = std::numeric_limits<float>::quiet_NaN();
00043 
00044   cloud_publisher_ = nh_.advertise<PointCloudT>(
00045     "cloud", 1); 
00046   scan_subscriber_ = nh_.subscribe(
00047     "scan", 1, &ScanToCloudConverter::scanCallback, this);
00048 }
00049 
00050 ScanToCloudConverter::~ScanToCloudConverter()
00051 {
00052   ROS_INFO("Destroying ScanToCloudConverter");
00053 }
00054 
00055 void ScanToCloudConverter::scanCallback(const sensor_msgs::LaserScan::ConstPtr& scan_msg)
00056 {
00057   PointCloudT::Ptr cloud_msg =
00058     boost::shared_ptr<PointCloudT>(new PointCloudT());
00059 
00060   cloud_msg->points.resize(scan_msg->ranges.size());
00061 
00062   for (unsigned int i = 0; i < scan_msg->ranges.size(); ++i)
00063   {
00064     PointT& p = cloud_msg->points[i];
00065     float range = scan_msg->ranges[i];
00066     if (range > scan_msg->range_min && range < scan_msg->range_max)
00067     {
00068       float angle = scan_msg->angle_min + i*scan_msg->angle_increment;
00069 
00070       p.x = range * cos(angle);
00071       p.y = range * sin(angle);
00072       p.z = 0.0;
00073     }
00074     else
00075       p = invalid_point_;
00076   }
00077 
00078   cloud_msg->width = scan_msg->ranges.size();
00079   cloud_msg->height = 1;
00080   cloud_msg->is_dense = false; //contains nans
00081   cloud_msg->header = scan_msg->header;
00082 
00083   cloud_publisher_.publish(cloud_msg);
00084 }
00085 
00086 } //namespace scan_tools


scan_to_cloud_converter
Author(s): Ivan Dryanovski
autogenerated on Fri Jan 3 2014 11:55:29