CParam.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 Team
00032  *  http://www.iav.com
00033  *
00034  */
00035 
00036 
00037 #ifndef CPARAM
00038 #define CPARAM
00039 
00040 #include <stdlib.h>
00041 #include <sstream>
00042 #include <math.h>
00043 #include <limits.h>
00044 
00045 #include <tf/transform_broadcaster.h>
00046 #include <tf/tf.h>
00047 #include <tf/transform_listener.h>
00048 
00049 #include "../include/LSParam.h"
00050 
00051 namespace iav_depthimage_to_laserscan
00052 {
00053 
00054   /*
00055   * These Class contains all the parameters of the camera(s), that must to be initialized. 
00056   * 
00057   * Furthermore had the method init_parameter, that is used to stablish the geometrical limits of the image through
00058   * a max and min height.
00059   *
00060   * The class had methods and some parameters for the frames of every camera, from the creation to the
00061   * updating of a frame. 
00062   */
00063   class CParam
00064   {
00065   public:
00066 
00067           CParam();
00068           ~CParam();
00069 
00070           void init_parameter(CParam& Param, LSParam& laserParam, float height_max, float height_min);
00071 
00072           void createTF(std::string header, std::string child);
00073 
00074           // Camera Variables
00075           double cam_AOV_h;    // Horizontal angle of view
00076           double cam_AOV_v;    // Vertical angle of view
00077           double cam_yaw;      // Yaw is positive leftwards. 
00078           double cam_pitch;    // Pitch is positive downward. 
00079           double cam_offset;   // Offset (short distance) between camera and laser
00080 
00081           int cam_image_width; // Image width
00082           int cam_image_height; // Image height
00083           int* cam_index; // Index for the correct depth points (pre calculated)
00084           double cam_focal_length_x; // Focal length in x
00085           double cam_focal_length_y; // Focal length in y
00086           std::string cam_frame_id; // Camera header.frame_id
00087 
00088           // Auxiliaries to limit the "angle of view" of the laser
00089           float* cam_max_distances; // Max. distances limits within the area bounded by height_max and height_min
00090           float* cam_min_distances; // Min. distances limits within the area bounded by height_max and height_min
00091           float* cam_cos_h; // Calculating a cosine for each point in horizontal
00092           float* cam_cos_v; // Calculating a cosine for each point in vertical  
00093           float* cam_sin_v; // Calculating a sine for each point in vertical
00094 
00095           geometry_msgs::TransformStamped* m_tf; //< Contains the TF
00096 
00097   };
00098 
00099 }; //iav_depthimage_to_laserscan
00100 
00101 #endif


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