DepthImage_to_Laserscan.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  * Copyright (c) 2015, IAV Automotive Engineering
00005  * All rights reserved.
00006  *
00007  * Redistribution and use in source and binary forms, with or without 
00008  * modification, are permitted provided that the following conditions are met:
00009  *
00010  * 1. Redistributions of source code must retain the above copyright notice, 
00011  *    this list of conditions and the following disclaimer.
00012  *
00013  * 2. Redistributions in binary form must reproduce the above copyright notice, 
00014  *    this list of conditions and the following disclaimer in the documentation 
00015  *    and/or other materials provided with the distribution.
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, 
00019  * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR 
00020  * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR 
00021  * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, 
00022  * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, 
00023  * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; 
00024  * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, 
00025  * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR 
00026  * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, 
00027  * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00028  *
00029  */
00030 /*
00031  *  IAV VI-A3
00032  *  http://www.iav.com
00033  *
00034  */
00035 
00036 
00037 #ifndef DEPTHIMAGE_TO_LASERSCAN
00038 #define DEPTHIMAGE_TO_LASERSCAN
00039 
00040 #include <ros/ros.h>
00041 #include <sensor_msgs/Image.h>
00042 #include <sensor_msgs/LaserScan.h>
00043 #include <sensor_msgs/image_encodings.h>
00044 
00045 #include "../include/CParam.h"
00046 
00047 namespace iav_depthimage_to_laserscan
00048 {
00049 
00050   /*
00051   * These Class creates a new parameter LaserScan (scan_msg) associated with the camera image and converts
00052   * the information of the depth image, that it is encoded, into a sensor_msgs::Laserscan.
00053   *
00054   * Then fill the ranges of the scan_msg with the points of the depth image msg using a method to project 
00055   * each pixel into a LaserScan angular increment. And when multiple points coorespond to a specific angular 
00056   * measurement, then the shortest range is used.
00057   */
00058   class DepthImage_to_Laserscan
00059   {
00060 
00061   public:
00062         
00063           DepthImage_to_Laserscan();
00064           ~DepthImage_to_Laserscan();
00065 
00066           sensor_msgs::LaserScanPtr convert_msg(const sensor_msgs::ImageConstPtr& depth_msg, const CParam& Param, const LSParam& lsparam);
00067 
00068   private:
00069 
00070           bool use_point(float new_value, float old_value, float range_min, float range_max);
00071 
00072           template<typename T>
00073           void convert_dtl(const sensor_msgs::ImageConstPtr& depth_msg, const CParam& Param, const LSParam& lsparam, const sensor_msgs::LaserScanPtr& scan_msg);
00074 
00075   };
00076 
00077 }; //iav_depthimage_to_laserscan
00078 
00079 #endif


iav_depthimage_to_laserscan
Author(s): Jan Obermueller
autogenerated on Thu Jun 6 2019 20:28:38