forked from gazebosim/gz-sensors
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathLogicalCameraSensor.hh
130 lines (106 loc) · 4.4 KB
/
LogicalCameraSensor.hh
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
/*
* Copyright (C) 2019 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/
#ifndef GZ_SENSORS_LOGICALCAMERASENSOR_HH_
#define GZ_SENSORS_LOGICALCAMERASENSOR_HH_
#include <map>
#include <memory>
#include <string>
#include <sdf/sdf.hh>
#include <gz/utils/SuppressWarning.hh>
#include <gz/math/Angle.hh>
#include <gz/msgs/logical_camera_image.pb.h>
#include "gz/sensors/config.hh"
#include "gz/sensors/Export.hh"
#include "gz/sensors/logical_camera/Export.hh"
#include "gz/sensors/Sensor.hh"
namespace gz
{
namespace sensors
{
// Inline bracket to help doxygen filtering.
inline namespace GZ_SENSORS_VERSION_NAMESPACE {
//
/// \brief forward declarations
class LogicalCameraSensorPrivate;
/// \brief Logical Camera Sensor Class
///
/// A logical camera reports locations of objects. This camera finds models
/// within the sensor's frustum and publishes information about the models
/// on the sensor's topic.
class GZ_SENSORS_LOGICAL_CAMERA_VISIBLE LogicalCameraSensor
: public Sensor
{
/// \brief constructor
public: LogicalCameraSensor();
/// \brief destructor
public: virtual ~LogicalCameraSensor();
/// \brief Load the sensor with SDF parameters.
/// \param[in] _sdf SDF Sensor parameters.
/// \return true if loading was successful
public: virtual bool Load(sdf::ElementPtr _sdf) override;
/// \brief Initialize values in the sensor
/// \return True on success
public: virtual bool Init() override;
using Sensor::Update;
/// \brief Force the sensor to generate data
/// \param[in] _now The current time
/// \return true if the update was successfull
public: virtual bool Update(
const std::chrono::steady_clock::duration &_now) override;
/// \brief Get the near distance. This is the distance from the
/// frustum's vertex to the closest plane.
/// \return Near distance.
public: double Near() const;
/// \brief Get the far distance. This is the distance from the
/// frustum's vertex to the farthest plane.
/// \return Far distance.
public: double Far() const;
/// \brief Set the models currently in the world
/// \param[in] _models A map of model names to their world pose.
public: void SetModelPoses(std::map<std::string, math::Pose3d> &&_models);
/// \brief Get the horizontal field of view. The field of view is the
/// angle between the frustum's vertex and the edges of the near or far
/// plane. This value represents the horizontal angle.
/// \return The field of view.
public: gz::math::Angle HorizontalFOV() const;
/// \brief Get the aspect ratio, which is the width divided by height
/// of the near or far planes.
/// \return The frustum's aspect ratio.
public: double AspectRatio() const;
/// \brief Check if there are any subscribers
/// \return True if there are subscribers, false otherwise
public: virtual bool HasConnections() const override;
/// \brief Check if there are any image subscribers
/// \return True if there are image subscribers, false otherwise
public: virtual bool HasImageConnections() const;
/// \brief Check if there are any frustum subscribers
/// \return True if there are info subscribers, false otherwise
public: virtual bool HasFrustumConnections() const;
/// \brief Get the latest image. An image is an instance of
/// msgs::LogicalCameraImage, which contains a list of detected models.
/// \return List of detected models.
public: msgs::LogicalCameraImage Image() const;
GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief Data pointer for private data
/// \internal
private: std::unique_ptr<LogicalCameraSensorPrivate> dataPtr;
GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
}
#endif