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 // msgs
43 #include <geometry_msgs/Point.h>
44 #include <geometry_msgs/Quaternion.h>
45 #include <sensor_msgs/PointCloud2.h>
46 
48 {
49  DEPTH_CAMERA = 0,
51 };
52 
53 namespace observation
54 {
55 
56 // Measurement Reading
58 {
59  /*****************************************************************************/
60  MeasurementReading() : _cloud(new sensor_msgs::PointCloud2())
61  /*****************************************************************************/
62  {
63  }
64 
65  /*****************************************************************************/
66  MeasurementReading(geometry_msgs::Point& origin, sensor_msgs::PointCloud2 cloud, \
67  double obstacle_range, double min_z, double max_z, double vFOV, \
68  double vFOVPadding, double hFOV, double decay_acceleration, bool marking, \
69  bool clearing, ModelType model_type) :
70  /*****************************************************************************/
71  _origin(origin), \
72  _cloud(new sensor_msgs::PointCloud2(cloud)), \
73  _obstacle_range_in_m(obstacle_range), \
74  _min_z_in_m(min_z), \
75  _max_z_in_m(max_z), \
76  _vertical_fov_in_rad(vFOV), \
77  _vertical_fov_padding_in_m(vFOVPadding), \
78  _horizontal_fov_in_rad(hFOV), \
79  _decay_acceleration(decay_acceleration), \
80  _marking(marking), \
81  _clearing(clearing), \
82  _model_type(model_type)
83  {
84  }
85 
86  /*****************************************************************************/
87  MeasurementReading(sensor_msgs::PointCloud2 cloud, double obstacle_range) :
88  /*****************************************************************************/
89  _cloud(new sensor_msgs::PointCloud2(cloud)), \
90  _obstacle_range_in_m(obstacle_range)
91  {
92  }
93 
94  /*****************************************************************************/
96  /*****************************************************************************/
97  _origin(obs._origin), \
98  _cloud(new sensor_msgs::PointCloud2(*(obs._cloud))), \
100  _min_z_in_m(obs._min_z_in_m), \
101  _max_z_in_m(obs._max_z_in_m), \
105  _marking(obs._marking), \
106  _clearing(obs._clearing), \
107  _orientation(obs._orientation), \
110  {
111  }
112 
113  geometry_msgs::Point _origin;
114  geometry_msgs::Quaternion _orientation;
115  sensor_msgs::PointCloud2::Ptr _cloud;
120 
121 };
122 
123 } // end namespace
124 
125 #endif // MEASUREMENT_READING_H_
observation::MeasurementReading::_clearing
double _clearing
Definition: measurement_reading.h:118
observation::MeasurementReading::_horizontal_fov_in_rad
double _horizontal_fov_in_rad
Definition: measurement_reading.h:117
observation::MeasurementReading::MeasurementReading
MeasurementReading(geometry_msgs::Point &origin, sensor_msgs::PointCloud2 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)
Definition: measurement_reading.h:66
observation::MeasurementReading::_marking
double _marking
Definition: measurement_reading.h:118
observation::MeasurementReading::MeasurementReading
MeasurementReading()
Definition: measurement_reading.h:60
observation
Definition: measurement_reading.h:53
observation::MeasurementReading::_origin
geometry_msgs::Point _origin
Definition: measurement_reading.h:113
observation::MeasurementReading::MeasurementReading
MeasurementReading(const MeasurementReading &obs)
Definition: measurement_reading.h:95
observation::MeasurementReading::_cloud
sensor_msgs::PointCloud2::Ptr _cloud
Definition: measurement_reading.h:115
observation::MeasurementReading::_min_z_in_m
double _min_z_in_m
Definition: measurement_reading.h:116
DEPTH_CAMERA
@ DEPTH_CAMERA
Definition: measurement_reading.h:86
observation::MeasurementReading
Definition: measurement_reading.h:57
THREE_DIMENSIONAL_LIDAR
@ THREE_DIMENSIONAL_LIDAR
Definition: measurement_reading.h:87
observation::MeasurementReading::_obstacle_range_in_m
double _obstacle_range_in_m
Definition: measurement_reading.h:116
observation::MeasurementReading::_vertical_fov_padding_in_m
double _vertical_fov_padding_in_m
Definition: measurement_reading.h:117
observation::MeasurementReading::_vertical_fov_in_rad
double _vertical_fov_in_rad
Definition: measurement_reading.h:117
observation::MeasurementReading::_orientation
geometry_msgs::Quaternion _orientation
Definition: measurement_reading.h:114
ModelType
ModelType
Definition: measurement_reading.h:47
sensor_msgs
observation::MeasurementReading::_decay_acceleration
double _decay_acceleration
Definition: measurement_reading.h:118
observation::MeasurementReading::_max_z_in_m
double _max_z_in_m
Definition: measurement_reading.h:116
observation::MeasurementReading::_model_type
ModelType _model_type
Definition: measurement_reading.h:119


spatio_temporal_voxel_layer
Author(s):
autogenerated on Wed Aug 16 2023 02:10:02