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 
23 #include <sdf/Error.hh>
24 #include <sdf/Element.hh>
25 #include <sdf/Noise.hh>
26 #include <sdf/sdf_config.h>
27 
28 namespace sdf
29 {
30  // Inline bracket to help doxygen filtering.
31  inline namespace SDF_VERSION_NAMESPACE {
32  //
33  // Forward declare private data class.
34  class CameraPrivate;
35 
39  enum class PixelFormatType
40  {
41  UNKNOWN_PIXEL_FORMAT = 0,
42  L_INT8,
43  L_INT16,
44  RGB_INT8,
45  RGBA_INT8,
46  BGRA_INT8,
47  RGB_INT16,
48  RGB_INT32,
49  BGR_INT8,
50  BGR_INT16,
51  BGR_INT32,
52  R_FLOAT16,
53  RGB_FLOAT16,
54  R_FLOAT32,
55  RGB_FLOAT32,
56  BAYER_RGGB8,
57  BAYER_BGGR8,
58  BAYER_GBRG8,
59  BAYER_GRBG8,
60  };
61 
64  {
66  public: Camera();
67 
70  public: Camera(const Camera &_camera);
71 
74  public: Camera(Camera &&_camera) noexcept;
75 
77  public: virtual ~Camera();
78 
82  public: Camera &operator=(const Camera &_camera);
83 
87  public: Camera &operator=(Camera &&_camera) noexcept;
88 
92  public: bool operator==(const Camera &_alt) const;
93 
98  public: bool operator!=(const Camera &_alt) const;
99 
106  public: Errors Load(ElementPtr _sdf);
107 
112  public: sdf::ElementPtr Element() const;
113 
116  public: std::string Name() const;
117 
120  public: void SetName(const std::string &_name);
121 
124  public: ignition::math::Angle HorizontalFov() const;
125 
128  public: void SetHorizontalFov(const ignition::math::Angle &_hfov);
129 
132  public: uint32_t ImageWidth() const;
133 
136  public: void SetImageWidth(uint32_t _width);
137 
140  public: uint32_t ImageHeight() const;
141 
144  public: void SetImageHeight(uint32_t _height);
145 
149  public: PixelFormatType PixelFormat() const;
150 
153  public: void SetPixelFormat(PixelFormatType _format);
154 
157  public: std::string PixelFormatStr() const;
158 
161  public: void SetPixelFormatStr(const std::string &_fmt);
162 
165  public: double DepthNearClip() const;
166 
169  public: void SetDepthNearClip(double _near);
170 
173  public: double DepthFarClip() const;
174 
177  public: void SetDepthFarClip(double _far);
178 
181  public: double NearClip() const;
182 
185  public: void SetNearClip(double _near);
186 
189  public: void SetHasDepthCamera(bool _camera);
190 
193  public: bool HasDepthCamera() const;
194 
199  public: void SetHasDepthNearClip(bool _near);
200 
203  public: bool HasDepthNearClip() const;
204 
209  public: void SetHasDepthFarClip(bool _far);
210 
213  public: bool HasDepthFarClip() const;
214 
217  public: double FarClip() const;
218 
221  public: void SetFarClip(double _far);
222 
225  public: bool SaveFrames() const;
226 
229  public: void SetSaveFrames(bool _save);
230 
233  public: const std::string &SaveFramesPath() const;
234 
237  public: void SetSaveFramesPath(const std::string &_path);
238 
241  public: const Noise &ImageNoise() const;
242 
245  public: void SetImageNoise(const Noise &_noise);
246 
249  public: double DistortionK1() const;
250 
253  public: void SetDistortionK1(double _k1);
254 
257  public: double DistortionK2() const;
258 
261  public: void SetDistortionK2(double _k2);
262 
265  public: double DistortionK3() const;
266 
269  public: void SetDistortionK3(double _k3);
270 
273  public: double DistortionP1() const;
274 
277  public: void SetDistortionP1(double _p1);
278 
281  public: double DistortionP2() const;
282 
285  public: void SetDistortionP2(double _p2);
286 
289  public: const ignition::math::Vector2d &DistortionCenter() const;
290 
293  public: void SetDistortionCenter(
294  const ignition::math::Vector2d &_center) const;
295 
300  public: const ignition::math::Pose3d &Pose() const
301  SDF_DEPRECATED(9.0);
302 
307  public: void SetPose(const ignition::math::Pose3d &_pose)
308  SDF_DEPRECATED(9.0);
309 
313  public: const ignition::math::Pose3d &RawPose() const;
314 
318  public: void SetRawPose(const ignition::math::Pose3d &_pose);
319 
324  public: const std::string &PoseRelativeTo() const;
325 
330  public: void SetPoseRelativeTo(const std::string &_frame);
331 
337  public: const std::string &PoseFrame() const
338  SDF_DEPRECATED(9.0);
339 
345  public: void SetPoseFrame(const std::string &_frame)
346  SDF_DEPRECATED(9.0);
347 
354  public: std::string LensType() const;
355 
359  public: void SetLensType(const std::string &_type);
360 
364  public: bool LensScaleToHfov() const;
365 
369  public: void SetLensScaleToHfov(bool _scale);
370 
373  public: double LensC1() const;
374 
377  public: void SetLensC1(double _c1);
378 
381  public: double LensC2() const;
382 
385  public: void SetLensC2(double _c2);
386 
389  public: double LensC3() const;
390 
393  public: void SetLensC3(double _c3);
394 
397  public: double LensFocalLength() const;
398 
401  public: void SetLensFocalLength(double _f);
402 
406  public: const std::string &LensFunction() const;
407 
411  public: void SetLensFunction(const std::string &_fun);
412 
416  public: ignition::math::Angle LensCutoffAngle() const;
417 
421  public: void SetLensCutoffAngle(const ignition::math::Angle &_angle);
422 
426  public: int LensEnvironmentTextureSize() const;
427 
431  public: void SetLensEnvironmentTextureSize(int _size);
432 
435  public: double LensIntrinsicsFx() const;
436 
439  public: void SetLensIntrinsicsFx(double _fx);
440 
443  public: double LensIntrinsicsFy() const;
444 
447  public: void SetLensIntrinsicsFy(double _fy);
448 
451  public: double LensIntrinsicsCx() const;
452 
455  public: void SetLensIntrinsicsCx(double _cx);
456 
459  public: double LensIntrinsicsCy() const;
460 
463  public: void SetLensIntrinsicsCy(double _cy);
464 
467  public: double LensIntrinsicsSkew() const;
468 
471  public: void SetLensIntrinsicsSkew(double _s);
472 
476  public: static PixelFormatType ConvertPixelFormat(
477  const std::string &_format);
478 
482  public: static std::string ConvertPixelFormat(PixelFormatType _type);
483 
486  public: uint32_t VisibilityMask() const;
487 
490  public: void SetVisibilityMask(uint32_t _mask);
491 
493  private: CameraPrivate *dataPtr = nullptr;
494  };
495  }
496 }
497 
498 #endif
Information about a monocular camera sensor.
Definition: Camera.hh:64
bool SaveFrames() const
Get whether frames should be saved.
bool operator!=(const Camera &_alt) const
Return true this Camera object does not contain the same values as the passed in parameter.
const ignition::math::Pose3d & Pose() const SDF_DEPRECATED(9.0)
Get the pose of the camer.
Errors Load(ElementPtr _sdf)
Load the camera sensor based on an element pointer.
double DistortionP2() const
Get the tangential distortion coefficient p2.
void SetImageHeight(uint32_t _height)
Set the image height in pixels.
void SetHasDepthNearClip(bool _near)
Set whether the depth camera near clip distance has been specified.
void SetDistortionCenter(const ignition::math::Vector2d &_center) const
Set the distortion center or principal point.
double DistortionP1() const
Get the tangential distortion coefficient p1.
virtual ~Camera()
Destructor.
PixelFormatType PixelFormat() const
Get the pixel format.
double DistortionK1() const
Get the radial distortion coefficient k1.
double DepthFarClip() const
Get the far clip distance for the depth camera.
void SetDistortionP1(double _p1)
Set the tangential distortion coefficient p1.
bool HasDepthCamera() const
Get whether the depth camera was set.
Camera(Camera &&_camera) noexcept
Move constructor.
uint32_t ImageHeight() const
Get the image height in pixels.
sdf::ElementPtr Element() const
Get a pointer to the SDF element that was used during load.
void SetHasDepthFarClip(bool _far)
Set whether the depth camera far clip distance has been specified.
double FarClip() const
Get the far clip distance.
void SetDistortionK2(double _k2)
Set the radial distortion coefficient k2.
const Noise & ImageNoise() const
Get the image noise values.
void SetHorizontalFov(const ignition::math::Angle &_hfov)
Set the horizontal field of view in radians.
void SetSaveFramesPath(const std::string &_path)
Set the path in which to save frames.
double DistortionK3() const
Get the radial distortion coefficient k3.
bool HasDepthNearClip() const
Get whether the depth camera near clip distance was set.
void SetPixelFormat(PixelFormatType _format)
Set the pixel format type.
double NearClip() const
Get the near clip distance.
void SetNearClip(double _near)
Set the near clip distance.
void SetDepthNearClip(double _near)
Set the near clip distance for the depth camera.
Camera & operator=(const Camera &_camera)
Assignment operator.
void SetFarClip(double _far)
Set the far clip distance.
Camera & operator=(Camera &&_camera) noexcept
Move assignment operator.
void SetImageNoise(const Noise &_noise)
Set the noise values related to the image.
uint32_t ImageWidth() const
Get the image width in pixels.
void SetDepthFarClip(double _far)
Set the far clip distance for the depth camera.
double DistortionK2() const
Get the radial distortion coefficient k2.
bool operator==(const Camera &_alt) const
Return true if both Camera objects contain the same values.
Camera(const Camera &_camera)
Copy constructor.
void SetHasDepthCamera(bool _camera)
Set whether the depth camera has been specified.
const std::string & SaveFramesPath() const
Get the path in which to save frames.
ignition::math::Angle HorizontalFov() const
Get the horizontal field of view in radians.
double DepthNearClip() const
Get the near clip distance for the depth camera.
const ignition::math::Vector2d & DistortionCenter() const
Get the distortion center or principal point.
void SetPixelFormatStr(const std::string &_fmt)
Set the pixel format from a string.
Camera()
Constructor.
void SetSaveFrames(bool _save)
Set whether frames should be saved.
void SetDistortionK1(double _k1)
Set the radial distortion coefficient k1.
void SetImageWidth(uint32_t _width)
Set the image width in pixels.
void SetDistortionP2(double _p2)
Set the tangential distortion coefficient p2.
std::string PixelFormatStr() const
Get the pixel format as a string.
std::string Name() const
Get the name of the camera.
void SetName(const std::string &_name)
Set the name of the camera.
bool HasDepthFarClip() const
Get whether the depth camera far clip distance was set.
void SetDistortionK3(double _k3)
Set the radial distortion coefficient k3.
The Noise class contains information about a noise model, such as a Gaussian distribution.
Definition: Noise.hh:50
std::vector< Error > Errors
A vector of Error.
Definition: Types.hh:89
PixelFormatType
The set of pixel formats.
Definition: Camera.hh:40
std::shared_ptr< Element > ElementPtr
Definition: Element.hh:53
class SDFORMAT_VISIBLE SDF_DEPRECATED(9.2) URDF2SDF
URDF to SDF converter.
Definition: parser_urdf.hh:40
namespace for Simulation Description Format parser
Definition: Actor.hh:33
#define SDFORMAT_VISIBLE
Use to represent "symbol visible" if supported.
Definition: system_util.hh:48