measurement_reading.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement
4  *
5  * Copyright (c) 2018, Simbe Robotics, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Simbe Robotics, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: Steve Macenski (steven.macenski@simberobotics.com)
36  * Purpose: Measurement reading structure containing info needed for marking
37  * and frustum clearing.
38  *********************************************************************/
39 
40 #ifndef MEASUREMENT_READING_H_
41 #define MEASUREMENT_READING_H_
42 // PCL
43 #include <pcl/point_cloud.h>
44 #include <pcl_ros/point_cloud.h>
45 // msgs
46 #include <geometry_msgs/Point.h>
47 #include <geometry_msgs/Quaternion.h>
48 
50 {
53 };
54 
55 namespace observation
56 {
57 
58 // Measurement Reading
60 {
61  /*****************************************************************************/
63  /*****************************************************************************/
64  {
65  }
66 
67  /*****************************************************************************/
68  MeasurementReading(geometry_msgs::Point& origin, pcl::PointCloud<pcl::PointXYZ> cloud, \
69  double obstacle_range, double min_z, double max_z, double vFOV,
70  double vFOVPadding, double hFOV, double decay_acceleration, bool marking,
71  bool clearing, ModelType model_type) :
72  /*****************************************************************************/
73  _origin(origin), \
74  _cloud(new pcl::PointCloud<pcl::PointXYZ>(cloud)), \
75  _obstacle_range_in_m(obstacle_range), \
76  _min_z_in_m(min_z), \
77  _max_z_in_m(max_z), \
78  _vertical_fov_in_rad(vFOV), \
79  _vertical_fov_padding_in_m(vFOVPadding), \
80  _horizontal_fov_in_rad(hFOV), \
81  _decay_acceleration(decay_acceleration), \
82  _marking(marking), \
83  _clearing(clearing), \
84  _model_type(model_type)
85  {
86  }
87 
88  /*****************************************************************************/
89  MeasurementReading(pcl::PointCloud<pcl::PointXYZ> cld, double obstacle_range) :
90  _cloud(new pcl::PointCloud<pcl::PointXYZ>(cld)),
91  _obstacle_range_in_m(obstacle_range)
92  /*****************************************************************************/
93  {
94  }
95 
96  /*****************************************************************************/
98  /*****************************************************************************/
99  _origin(obs._origin), \
100  _cloud(new pcl::PointCloud<pcl::PointXYZ>(*(obs._cloud))), \
102  _min_z_in_m(obs._min_z_in_m), \
103  _max_z_in_m(obs._max_z_in_m), \
107  _marking(obs._marking), \
108  _clearing(obs._clearing), \
109  _orientation(obs._orientation), \
112  {
113  }
114 
115  geometry_msgs::Point _origin;
116  geometry_msgs::Quaternion _orientation;
117  pcl::PointCloud<pcl::PointXYZ>::Ptr _cloud;
122 
123 };
124 
125 } // end namespace
126 
127 #endif // MEASUREMENT_READING_H_
pcl::PointCloud< pcl::PointXYZ >::Ptr _cloud
sensor_msgs::PointCloud2 PointCloud
MeasurementReading(geometry_msgs::Point &origin, pcl::PointCloud< pcl::PointXYZ > cloud, double obstacle_range, double min_z, double max_z, double vFOV, double vFOVPadding, double hFOV, double decay_acceleration, bool marking, bool clearing, ModelType model_type)
MeasurementReading(pcl::PointCloud< pcl::PointXYZ > cld, double obstacle_range)
MeasurementReading(const MeasurementReading &obs)
geometry_msgs::Quaternion _orientation


spatio_temporal_voxel_layer
Author(s):
autogenerated on Sat Dec 21 2019 04:06:19