Camera.hh
Go to the documentation of this file.
1/*
2 * Copyright 2019 Open Source Robotics Foundation
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *
16 */
17#ifndef SDF_CAMERA_HH_
18#define SDF_CAMERA_HH_
19
20#include <string>
21#include <ignition/math/Pose3.hh>
22#include <ignition/utils/ImplPtr.hh>
23
24#include <sdf/Error.hh>
25#include <sdf/Element.hh>
26#include <sdf/Noise.hh>
27#include <sdf/sdf_config.h>
28
29namespace sdf
30{
31 // Inline bracket to help doxygen filtering.
32 inline namespace SDF_VERSION_NAMESPACE {
36 enum class PixelFormatType
37 {
38 UNKNOWN_PIXEL_FORMAT = 0,
39 L_INT8,
40 L_INT16,
41 RGB_INT8,
42 RGBA_INT8,
43 BGRA_INT8,
44 RGB_INT16,
45 RGB_INT32,
46 BGR_INT8,
47 BGR_INT16,
48 BGR_INT32,
49 R_FLOAT16,
50 RGB_FLOAT16,
51 R_FLOAT32,
52 RGB_FLOAT32,
53 BAYER_RGGB8,
54 BAYER_BGGR8,
55 BAYER_GBRG8,
56 BAYER_GRBG8,
57 };
58
61 {
63 public: Camera();
64
68 public: bool operator==(const Camera &_alt) const;
69
74 public: bool operator!=(const Camera &_alt) const;
75
82 public: Errors Load(ElementPtr _sdf);
83
88 public: sdf::ElementPtr Element() const;
89
92 public: std::string Name() const;
93
96 public: void SetName(const std::string &_name);
97
100 public: ignition::math::Angle HorizontalFov() const;
101
104 public: void SetHorizontalFov(const ignition::math::Angle &_hfov);
105
108 public: uint32_t ImageWidth() const;
109
112 public: void SetImageWidth(uint32_t _width);
113
116 public: uint32_t ImageHeight() const;
117
120 public: void SetImageHeight(uint32_t _height);
121
126
129 public: void SetPixelFormat(PixelFormatType _format);
130
133 public: std::string PixelFormatStr() const;
134
137 public: void SetPixelFormatStr(const std::string &_fmt);
138
141 public: double DepthNearClip() const;
142
145 public: void SetDepthNearClip(double _near);
146
149 public: double DepthFarClip() const;
150
153 public: void SetDepthFarClip(double _far);
154
157 public: double NearClip() const;
158
161 public: void SetNearClip(double _near);
162
165 public: void SetHasDepthCamera(bool _camera);
166
169 public: bool HasDepthCamera() const;
170
175 public: void SetHasDepthNearClip(bool _near);
176
179 public: bool HasDepthNearClip() const;
180
185 public: void SetHasDepthFarClip(bool _far);
186
189 public: bool HasDepthFarClip() const;
190
193 public: double FarClip() const;
194
197 public: void SetFarClip(double _far);
198
202 public: void SetHasSegmentationType(bool _type);
203
206 public: bool HasSegmentationType() const;
207
210 public: const std::string &SegmentationType() const;
211
214 public: void SetSegmentationType(const std::string &_type);
215
219 public: void SetHasBoundingBoxType(bool _type);
220
223 public: bool HasBoundingBoxType() const;
224
227 public: const std::string &BoundingBoxType() const;
228
231 public: void SetBoundingBoxType(const std::string &_type);
232
235 public: bool SaveFrames() const;
236
239 public: void SetSaveFrames(bool _save);
240
243 public: const std::string &SaveFramesPath() const;
244
247 public: void SetSaveFramesPath(const std::string &_path);
248
251 public: const Noise &ImageNoise() const;
252
255 public: void SetImageNoise(const Noise &_noise);
256
259 public: double DistortionK1() const;
260
263 public: void SetDistortionK1(double _k1);
264
267 public: double DistortionK2() const;
268
271 public: void SetDistortionK2(double _k2);
272
275 public: double DistortionK3() const;
276
279 public: void SetDistortionK3(double _k3);
280
283 public: double DistortionP1() const;
284
287 public: void SetDistortionP1(double _p1);
288
291 public: double DistortionP2() const;
292
295 public: void SetDistortionP2(double _p2);
296
299 public: const ignition::math::Vector2d &DistortionCenter() const;
300
303 public: void SetDistortionCenter(const ignition::math::Vector2d &_center);
304
308 public: const ignition::math::Pose3d &RawPose() const;
309
313 public: void SetRawPose(const ignition::math::Pose3d &_pose);
314
319 public: const std::string &PoseRelativeTo() const;
320
325 public: void SetPoseRelativeTo(const std::string &_frame);
326
333 public: std::string LensType() const;
334
338 public: void SetLensType(const std::string &_type);
339
343 public: bool LensScaleToHfov() const;
344
348 public: void SetLensScaleToHfov(bool _scale);
349
352 public: double LensC1() const;
353
356 public: void SetLensC1(double _c1);
357
360 public: double LensC2() const;
361
364 public: void SetLensC2(double _c2);
365
368 public: double LensC3() const;
369
372 public: void SetLensC3(double _c3);
373
376 public: double LensFocalLength() const;
377
380 public: void SetLensFocalLength(double _f);
381
385 public: const std::string &LensFunction() const;
386
390 public: void SetLensFunction(const std::string &_fun);
391
395 public: ignition::math::Angle LensCutoffAngle() const;
396
400 public: void SetLensCutoffAngle(const ignition::math::Angle &_angle);
401
405 public: int LensEnvironmentTextureSize() const;
406
410 public: void SetLensEnvironmentTextureSize(int _size);
411
414 public: double LensIntrinsicsFx() const;
415
418 public: void SetLensIntrinsicsFx(double _fx);
419
422 public: double LensIntrinsicsFy() const;
423
426 public: void SetLensIntrinsicsFy(double _fy);
427
430 public: double LensIntrinsicsCx() const;
431
434 public: void SetLensIntrinsicsCx(double _cx);
435
438 public: double LensIntrinsicsCy() const;
439
442 public: void SetLensIntrinsicsCy(double _cy);
443
446 public: double LensIntrinsicsSkew() const;
447
450 public: void SetLensIntrinsicsSkew(double _s);
451
456 const std::string &_format);
457
461 public: static std::string ConvertPixelFormat(PixelFormatType _type);
462
465 public: uint32_t VisibilityMask() const;
466
469 public: void SetVisibilityMask(uint32_t _mask);
470
473 public: bool HasLensIntrinsics() const;
474
478 public: sdf::ElementPtr ToElement() const;
479
481 IGN_UTILS_IMPL_PTR(dataPtr)
482 };
483 }
484}
485
486#endif
Information about a monocular camera sensor.
Definition: Camera.hh:61
bool HasSegmentationType() const
Get whether the segmentation type was set.
double LensFocalLength() const
Get lens custom function focal length.
ignition::math::Angle HorizontalFov() const
Get the horizontal field of view in radians.
const Noise & ImageNoise() const
Get the image noise values.
uint32_t ImageHeight() const
Get the image height in pixels.
const std::string & BoundingBoxType() const
Get the boundingbox type.
double DepthFarClip() const
Get the far clip distance for the depth camera.
sdf::ElementPtr ToElement() const
Create and return an SDF element filled with data from this camera.
void SetLensEnvironmentTextureSize(int _size)
Set environment texture size.
bool HasDepthCamera() const
Get whether the depth camera was set.
double DistortionK3() const
Get the radial distortion coefficient k3.
void SetPoseRelativeTo(const std::string &_frame)
Set the name of the coordinate frame relative to which this object's pose is expressed.
void SetSaveFramesPath(const std::string &_path)
Set the path in which to save frames.
double DepthNearClip() const
Get the near clip distance for the depth camera.
void SetLensFunction(const std::string &_fun)
Set lens custom function.
const ignition::math::Vector2d & DistortionCenter() const
Get the distortion center or principal point.
void SetDistortionK2(double _k2)
Set the radial distortion coefficient k2.
bool LensScaleToHfov() const
Get lens scale to horizontal field of field.
static PixelFormatType ConvertPixelFormat(const std::string &_format)
Convert a string to a PixelFormatType.
Camera()
Constructor.
void SetImageHeight(uint32_t _height)
Set the image height in pixels.
double LensIntrinsicsCy() const
Get the lens Y principal point in pixels.
void SetLensC3(double _c3)
Set lens custom function angle offset constant.
void SetLensIntrinsicsFy(double _fy)
Set the lens Y focal length in pixels.
void SetHasSegmentationType(bool _type)
Set whether the segmentation type has been specified.
void SetLensIntrinsicsFx(double _fx)
Set the lens X focal length in pixels.
const std::string & SaveFramesPath() const
Get the path in which to save frames.
void SetDistortionP1(double _p1)
Set the tangential distortion coefficient p1.
double FarClip() const
Get the far clip distance.
double DistortionP1() const
Get the tangential distortion coefficient p1.
double LensIntrinsicsSkew() const
Get the lens XY axis skew.
static std::string ConvertPixelFormat(PixelFormatType _type)
Convert a PixelFormatType to a string.
const ignition::math::Pose3d & RawPose() const
Get the pose of the camer.
void SetName(const std::string &_name)
Set the name of the camera.
double DistortionP2() const
Get the tangential distortion coefficient p2.
void SetLensCutoffAngle(const ignition::math::Angle &_angle)
Set lens cutoff angle.
bool HasLensIntrinsics() const
Get whether or not the camera has instrinsics values set.
sdf::ElementPtr Element() const
Get a pointer to the SDF element that was used during load.
void SetDepthNearClip(double _near)
Set the near clip distance for the depth camera.
const std::string & LensFunction() const
Get lens custom function.
bool operator!=(const Camera &_alt) const
Return true this Camera object does not contain the same values as the passed in parameter.
int LensEnvironmentTextureSize() const
Get environment texture size.
void SetBoundingBoxType(const std::string &_type)
Set the boundingbox type.
void SetLensFocalLength(double _f)
Set lens custom function focal length.
void SetHorizontalFov(const ignition::math::Angle &_hfov)
Set the horizontal field of view in radians.
PixelFormatType PixelFormat() const
Get the pixel format.
void SetDistortionK3(double _k3)
Set the radial distortion coefficient k3.
uint32_t VisibilityMask() const
Get the visibility mask of a camera.
bool operator==(const Camera &_alt) const
Return true if both Camera objects contain the same values.
double LensC3() const
Get lens custom function angle offset constant.
void SetLensC2(double _c2)
Set lens custom function angular scaling constant.
bool HasDepthFarClip() const
Get whether the depth camera far clip distance was set.
void SetImageNoise(const Noise &_noise)
Set the noise values related to the image.
const std::string & PoseRelativeTo() const
Get the name of the coordinate frame relative to which this object's pose is expressed.
void SetFarClip(double _far)
Set the far clip distance.
void SetHasDepthFarClip(bool _far)
Set whether the depth camera far clip distance has been specified.
double DistortionK1() const
Get the radial distortion coefficient k1.
void SetHasBoundingBoxType(bool _type)
Set whether the boundingbox type has been specified.
void SetImageWidth(uint32_t _width)
Set the image width in pixels.
void SetPixelFormatStr(const std::string &_fmt)
Set the pixel format from a string.
double LensIntrinsicsFy() const
Get the lens Y focal length in pixels.
void SetSaveFrames(bool _save)
Set whether frames should be saved.
double LensIntrinsicsFx() const
Get the lens X focal length in pixels.
ignition::math::Angle LensCutoffAngle() const
Get lens cutoff angle.
bool HasDepthNearClip() const
Get whether the depth camera near clip distance was set.
double LensC2() const
Get lens custom function angular scaling constant.
std::string LensType() const
Get the lens type.
void SetDistortionK1(double _k1)
Set the radial distortion coefficient k1.
void SetVisibilityMask(uint32_t _mask)
Set the visibility mask of a camera.
double LensC1() const
Get lens custom function linear scaling constant.
void SetLensIntrinsicsCx(double _cx)
Set the lens X principal point in pixels.
double NearClip() const
Get the near clip distance.
void SetLensC1(double _c1)
Set lens custom function linear scaling constant.
void SetDepthFarClip(double _far)
Set the far clip distance for the depth camera.
bool SaveFrames() const
Get whether frames should be saved.
void SetHasDepthCamera(bool _camera)
Set whether the depth camera has been specified.
void SetNearClip(double _near)
Set the near clip distance.
const std::string & SegmentationType() const
Get the segmentation type.
void SetLensScaleToHfov(bool _scale)
Set lens scale to horizontal field of field.
Errors Load(ElementPtr _sdf)
Load the camera sensor based on an element pointer.
double DistortionK2() const
Get the radial distortion coefficient k2.
bool HasBoundingBoxType() const
Get whether the boundingbox type was set.
void SetDistortionP2(double _p2)
Set the tangential distortion coefficient p2.
double LensIntrinsicsCx() const
Get the lens X principal point in pixels.
void SetDistortionCenter(const ignition::math::Vector2d &_center)
Set the distortion center or principal point.
std::string PixelFormatStr() const
Get the pixel format as a string.
void SetHasDepthNearClip(bool _near)
Set whether the depth camera near clip distance has been specified.
void SetRawPose(const ignition::math::Pose3d &_pose)
Set the pose of the camera.
void SetLensIntrinsicsCy(double _cy)
Set the lens Y principal point in pixels.
void SetLensIntrinsicsSkew(double _s)
Set the lens XY axis skew.
void SetSegmentationType(const std::string &_type)
Set the segmentation type.
std::string Name() const
Get the name of the camera.
void SetLensType(const std::string &_type)
Set the lens type.
void SetPixelFormat(PixelFormatType _format)
Set the pixel format type.
uint32_t ImageWidth() const
Get the image width in pixels.
The Noise class contains information about a noise model, such as a Gaussian distribution.
Definition: Noise.hh:48
std::vector< Error > Errors
A vector of Error.
Definition: Types.hh:106
std::shared_ptr< Element > ElementPtr
Definition: Element.hh:54
PixelFormatType
The set of pixel formats.
Definition: Camera.hh:37
namespace for Simulation Description Format parser
Definition: Actor.hh:34
#define SDFORMAT_VISIBLE
Use to represent "symbol visible" if supported.
Definition: system_util.hh:41