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 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498
|
/*
* Copyright 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 SDF_CAMERA_HH_
#define SDF_CAMERA_HH_
#include <string>
#include <ignition/math/Pose3.hh>
#include <sdf/Error.hh>
#include <sdf/Element.hh>
#include <sdf/Noise.hh>
#include <sdf/sdf_config.h>
namespace sdf
{
// Inline bracket to help doxygen filtering.
inline namespace SDF_VERSION_NAMESPACE {
//
// Forward declare private data class.
class CameraPrivate;
/// \enum PixelFormatType
/// \brief The set of pixel formats. This list should match
/// ignition::common::Image::PixelFormatType.
enum class PixelFormatType
{
UNKNOWN_PIXEL_FORMAT = 0,
L_INT8,
L_INT16,
RGB_INT8,
RGBA_INT8,
BGRA_INT8,
RGB_INT16,
RGB_INT32,
BGR_INT8,
BGR_INT16,
BGR_INT32,
R_FLOAT16,
RGB_FLOAT16,
R_FLOAT32,
RGB_FLOAT32,
BAYER_RGGB8,
BAYER_BGGR8,
BAYER_GBRG8,
BAYER_GRBG8,
};
/// \brief Information about a monocular camera sensor.
class SDFORMAT_VISIBLE Camera
{
/// \brief Constructor
public: Camera();
/// \brief Copy constructor
/// \param[in] _camera Camera to copy.
public: Camera(const Camera &_camera);
/// \brief Move constructor
/// \param[in] _camera Camera to move.
public: Camera(Camera &&_camera) noexcept;
/// \brief Destructor
public: virtual ~Camera();
/// \brief Assignment operator.
/// \param[in] _camera The camera to set values from.
/// \return *this
public: Camera &operator=(const Camera &_camera);
/// \brief Move assignment operator.
/// \param[in] _camera The camera to set values from.
/// \return *this
public: Camera &operator=(Camera &&_camera) noexcept;
/// \brief Return true if both Camera objects contain the same values.
/// \param[_in] _alt Camera value to compare.
/// \returen True if 'this' == _alt.
public: bool operator==(const Camera &_alt) const;
/// \brief Return true this Camera object does not contain the same
/// values as the passed in parameter.
/// \param[_in] _alt Camera value to compare.
/// \returen True if 'this' != _alt.
public: bool operator!=(const Camera &_alt) const;
/// \brief Load the camera sensor based on an element pointer.
/// This is *not* the usual entry point. Typical usage of the SDF DOM is
/// through the Root object.
/// \param[in] _sdf The SDF Element pointer
/// \return Errors, which is a vector of Error objects. Each Error includes
/// an error code and message. An empty vector indicates no error.
public: Errors Load(ElementPtr _sdf);
/// \brief Get a pointer to the SDF element that was used during
/// load.
/// \return SDF element pointer. The value will be nullptr if Load has
/// not been called.
public: sdf::ElementPtr Element() const;
/// \brief Get the name of the camera.
/// \return Name of the sensor.
public: std::string Name() const;
/// \brief Set the name of the camera.
/// \param[in] _name Name of the sensor.
public: void SetName(const std::string &_name);
/// \brief Get the horizontal field of view in radians.
/// \return The horizontal field of view in radians.
public: ignition::math::Angle HorizontalFov() const;
/// \brief Set the horizontal field of view in radians.
/// \param[in] _hfov The horizontal field of view in radians.
public: void SetHorizontalFov(const ignition::math::Angle &_hfov);
/// \brief Get the image width in pixels.
/// \return The image width in pixels.
public: uint32_t ImageWidth() const;
/// \brief Set the image width in pixels.
/// \param[in] _width The image width in pixels.
public: void SetImageWidth(uint32_t _width);
/// \brief Get the image height in pixels.
/// \return The image height in pixels.
public: uint32_t ImageHeight() const;
/// \brief Set the image height in pixels.
/// \param[in] _height The image height in pixels.
public: void SetImageHeight(uint32_t _height);
/// \brief Get the pixel format. This value is set from the <format>
/// element that is the child of <image>.
/// \return The pixel format.
public: PixelFormatType PixelFormat() const;
/// \brief Set the pixel format type.
/// \param[in] _format The image format.
public: void SetPixelFormat(PixelFormatType _format);
/// \brief Get the pixel format as a string.
/// \return The pixel format string.
public: std::string PixelFormatStr() const;
/// \brief Set the pixel format from a string.
/// \param[in] _fmt The pixel format string.
public: void SetPixelFormatStr(const std::string &_fmt);
/// \brief Get the near clip distance for the depth camera.
/// \return The near clip depth distance.
public: double DepthNearClip() const;
/// \brief Set the near clip distance for the depth camera.
/// \param[in] _near The near clip depth distance.
public: void SetDepthNearClip(double _near);
/// \brief Get the far clip distance for the depth camera.
/// \return The far clip depth distance.
public: double DepthFarClip() const;
/// \brief Set the far clip distance for the depth camera.
/// \param[in] _far The far clip depth distance.
public: void SetDepthFarClip(double _far);
/// \brief Get the near clip distance.
/// \return The near clip distance.
public: double NearClip() const;
/// \brief Set the near clip distance.
/// \param[in] _near The near clip distance.
public: void SetNearClip(double _near);
/// \brief Set whether the depth camera has been specified.
/// \param[in] _camera True if the depth camera has been set in the sdf.
public: void SetHasDepthCamera(bool _camera);
/// \brief Get whether the depth camera was set.
/// \return True if the depth camera was set.
public: bool HasDepthCamera() const;
/// \brief Set whether the depth camera near clip distance
/// has been specified.
/// \param[in] _camera True if the depth camera near clip distance
/// has been set in the sdf.
public: void SetHasDepthNearClip(bool _near);
/// \brief Get whether the depth camera near clip distance was set.
/// \return True if the depth camera near clip distance was set.
public: bool HasDepthNearClip() const;
/// \brief Set whether the depth camera far clip distance
/// has been specified.
/// \param[in] _camera True if the depth camera far clip distance
/// has been set in the sdf.
public: void SetHasDepthFarClip(bool _far);
/// \brief Get whether the depth camera far clip distance was set.
/// \return True if the depth camera far clip distance was set.
public: bool HasDepthFarClip() const;
/// \brief Get the far clip distance.
/// \return The far clip distance.
public: double FarClip() const;
/// \brief Set the far clip distance.
/// \param[in] _far The far clip distance.
public: void SetFarClip(double _far);
/// \brief Get whether frames should be saved.
/// \return True if image frames should be saved.
public: bool SaveFrames() const;
/// \brief Set whether frames should be saved.
/// \param[in] _save True if image frames should be saved.
public: void SetSaveFrames(bool _save);
/// \brief Get the path in which to save frames.
/// \return Path to save frames.
public: const std::string &SaveFramesPath() const;
/// \brief Set the path in which to save frames.
/// \param[in] _path Path to save frames.
public: void SetSaveFramesPath(const std::string &_path);
/// \brief Get the image noise values.
/// \return Noise values for the image.
public: const Noise &ImageNoise() const;
/// \brief Set the noise values related to the image.
/// \param[in] _noise Noise values for the image.
public: void SetImageNoise(const Noise &_noise);
/// \brief Get the radial distortion coefficient k1
/// \return _k1 The k1 radial distortion.
public: double DistortionK1() const;
/// \brief Set the radial distortion coefficient k1
/// \param[in] _k1 The k1 radial distortion.
public: void SetDistortionK1(double _k1);
/// \brief Get the radial distortion coefficient k2
/// \return _k2 The k2 radial distortion.
public: double DistortionK2() const;
/// \brief Set the radial distortion coefficient k2
/// \param[in] _k2 The k2 radial distortion.
public: void SetDistortionK2(double _k2);
/// \brief Get the radial distortion coefficient k3
/// \return _k3 The k3 radial distortion.
public: double DistortionK3() const;
/// \brief Set the radial distortion coefficient k3
/// \param[in] _k3 The k3 radial distortion.
public: void SetDistortionK3(double _k3);
/// \brief Get the tangential distortion coefficient p1
/// \return _p1 The p1 tangential distortion.
public: double DistortionP1() const;
/// \brief Set the tangential distortion coefficient p1
/// \param[in] _p1 The p1 tangential distortion.
public: void SetDistortionP1(double _p1);
/// \brief Get the tangential distortion coefficient p2
/// \return The p2 tangential distortion.
public: double DistortionP2() const;
/// \brief Set the tangential distortion coefficient p2
/// \return The p2 tangential distortion.
public: void SetDistortionP2(double _p2);
/// \brief Get the distortion center or principal point.
/// \return Distortion center or principal point.
public: const ignition::math::Vector2d &DistortionCenter() const;
/// \brief Set the distortion center or principal point.
/// \param[in] _center Distortion center or principal point.
public: void SetDistortionCenter(
const ignition::math::Vector2d &_center) const;
/// \brief Get the pose of the camer. This is the pose of the camera
/// as specified in SDF (<camera> <pose> ... </pose></camera>).
/// \return The pose of the link.
/// \deprecated See RawPose.
public: const ignition::math::Pose3d &Pose() const
SDF_DEPRECATED(9.0);
/// \brief Set the pose of the camera.
/// \sa const ignition::math::Pose3d &Pose() const
/// \param[in] _pose The new camera pose.
/// \deprecated See SetRawPose.
public: void SetPose(const ignition::math::Pose3d &_pose)
SDF_DEPRECATED(9.0);
/// \brief Get the pose of the camer. This is the pose of the camera
/// as specified in SDF (<camera> <pose> ... </pose></camera>).
/// \return The pose of the link.
public: const ignition::math::Pose3d &RawPose() const;
/// \brief Set the pose of the camera.
/// \sa const ignition::math::Pose3d &RawPose() const
/// \param[in] _pose The new camera pose.
public: void SetRawPose(const ignition::math::Pose3d &_pose);
/// \brief Get the name of the coordinate frame relative to which this
/// object's pose is expressed. An empty value indicates that the frame is
/// relative to the parent link.
/// \return The name of the pose relative-to frame.
public: const std::string &PoseRelativeTo() const;
/// \brief Set the name of the coordinate frame relative to which this
/// object's pose is expressed. An empty value indicates that the frame is
/// relative to the parent link.
/// \param[in] _frame The name of the pose relative-to frame.
public: void SetPoseRelativeTo(const std::string &_frame);
/// \brief Get the name of the coordinate frame in which this camera's
/// pose is expressed. A empty value indicates that the frame is the
/// parent link.
/// \return The name of the pose frame.
/// \deprecated See PoseRelativeTo.
public: const std::string &PoseFrame() const
SDF_DEPRECATED(9.0);
/// \brief Set the name of the coordinate frame in which this camera's
/// pose is expressed. A empty value indicates that the frame is the
/// parent link.
/// \param[in] _frame The name of the pose frame.
/// \deprecated See SetPoseRelativeTo.
public: void SetPoseFrame(const std::string &_frame)
SDF_DEPRECATED(9.0);
/// \brief Get the lens type. This is the type of the lens mapping.
/// Supported values are gnomonical, stereographic, equidistant,
/// equisolid_angle, orthographic, custom. For gnomonical (perspective)
/// projection, it is recommended to specify a horizontal_fov of less than
/// or equal to 90 degrees
/// \return The lens type.
public: std::string LensType() const;
/// \brief Set the lens type. Supported values are gnomonical,
/// stereographic, equidistant, equisolid_angle, orthographic, custom.
/// \param[in] _type The lens type.
public: void SetLensType(const std::string &_type);
/// \brief Get lens scale to horizontal field of field.
/// \return True if the image should be scaled to fit horizontal FOV,
/// otherwise it will be shown according to projection type parameters.
public: bool LensScaleToHfov() const;
/// \brief Set lens scale to horizontal field of field.
/// \param[in] _scale True if the image should be scaled to fit horizontal
/// FOV, otherwise it will be shown according to projection type parameters.
public: void SetLensScaleToHfov(bool _scale);
/// \brief Get lens custom function linear scaling constant.
/// \return The lens custom function linear scaling constant.
public: double LensC1() const;
/// \brief Set lens custom function linear scaling constant.
/// \param[in] _c1 The lens custom function linear scaling constant.
public: void SetLensC1(double _c1);
/// \brief Get lens custom function angular scaling constant.
/// \return The lens custom function angular scaling constant.
public: double LensC2() const;
/// \brief Set lens custom function angular scaling constant.
/// \param[in] _c2 The lens custom function angular scaling constant.
public: void SetLensC2(double _c2);
/// \brief Get lens custom function angle offset constant.
/// \return The lens custom function angle offset constant.
public: double LensC3() const;
/// \brief Set lens custom function angle offset constant.
/// \param[in] _c3 The lens custom function angle offset constant.
public: void SetLensC3(double _c3);
/// \brief Get lens custom function focal length.
/// \return The lens custom function focal length.
public: double LensFocalLength() const;
/// \brief Set lens custom function focal length.
/// \param[in] _f The lens custom function focal length.
public: void SetLensFocalLength(double _f);
/// \brief Get lens custom function. Possible values are 'sin', 'tan',
/// and 'id'.
/// \return The lens custom function.
public: const std::string &LensFunction() const;
/// \brief Set lens custom function.
/// \param[in] _fun The lens custom function. Possible values are 'sin',
/// 'tan', and 'id'.
public: void SetLensFunction(const std::string &_fun);
/// \brief Get lens cutoff angle. Everything outside of the specified
/// angle will be hidden.
/// \return The lens cutoff angle.
public: ignition::math::Angle LensCutoffAngle() const;
/// \brief Set lens cutoff angle. Everything outside of the specified
/// angle will be hidden.
/// \param[in] _angle The lens cutoff angle.
public: void SetLensCutoffAngle(const ignition::math::Angle &_angle);
/// \brief Get environment texture size. This is the resolution of the
/// environment cube map used to draw the world.
/// \return The lens environment texture size.
public: int LensEnvironmentTextureSize() const;
/// \brief Set environment texture size. This is the resolution of the
/// environment cube map used to draw the world.
/// \param[in] _size The lens environment texture size.
public: void SetLensEnvironmentTextureSize(int _size);
/// \brief Get the lens X focal length in pixels.
/// \return The lens X focal length in pixels.
public: double LensIntrinsicsFx() const;
/// \brief Set the lens X focal length in pixels.
/// \param[in] _fx The lens X focal length in pixels.
public: void SetLensIntrinsicsFx(double _fx);
/// \brief Get the lens Y focal length in pixels.
/// \return The lens Y focal length in pixels.
public: double LensIntrinsicsFy() const;
/// \brief Set the lens Y focal length in pixels.
/// \param[in] _fy The lens Y focal length in pixels.
public: void SetLensIntrinsicsFy(double _fy);
/// \brief Get the lens X principal point in pixels.
/// \return The lens X principal point in pixels.
public: double LensIntrinsicsCx() const;
/// \brief Set the lens X principal point in pixels.
/// \param[in] _cx The lens X principal point in pixels.
public: void SetLensIntrinsicsCx(double _cx);
/// \brief Get the lens Y principal point in pixels.
/// \return The lens Y principal point in pixels.
public: double LensIntrinsicsCy() const;
/// \brief Set the lens Y principal point in pixels.
/// \param[in] _cy The lens Y principal point in pixels.
public: void SetLensIntrinsicsCy(double _cy);
/// \brief Get the lens XY axis skew.
/// \return The lens XY axis skew.
public: double LensIntrinsicsSkew() const;
/// \brief Set the lens XY axis skew.
/// \param[in] _s The lens XY axis skew.
public: void SetLensIntrinsicsSkew(double _s);
/// \brief Convert a string to a PixelFormatType.
/// \param[in] _format String equivalent of a pixel format type to convert.
/// \return The matching PixelFormatType.
public: static PixelFormatType ConvertPixelFormat(
const std::string &_format);
/// \brief Convert a PixelFormatType to a string.
/// \param[in] _type Pixel format type to convert.
/// \return String equivalent of _type.
public: static std::string ConvertPixelFormat(PixelFormatType _type);
/// \brief Get the visibility mask of a camera
/// \return visibility mask
public: uint32_t VisibilityMask() const;
/// \brief Set the visibility mask of a camera
/// \param[in] _mask visibility mask
public: void SetVisibilityMask(uint32_t _mask);
/// \brief Private data pointer.
private: CameraPrivate *dataPtr = nullptr;
};
}
}
#endif
|