Utils.hh File Reference
#include <vector>#include <memory>#include <gz/math/Helpers.hh>#include <gz/math/AxisAlignedBox.hh>#include <gz/math/Vector2.hh>#include <gz/math/Vector3.hh>#include <gz/math/Pose3.hh>#include "gz/rendering/Camera.hh"#include "gz/rendering/config.hh"#include "gz/rendering/Export.hh"#include "gz/rendering/GraphicsAPI.hh"#include "gz/rendering/RayQuery.hh"#include "gz/rendering/Image.hh"Go to the source code of this file.
Namespaces | |
| namespace | gz |
| namespace | gz::rendering |
| Rendering classes and function useful in robot applications. | |
Functions | |
| Image | convertRGBToBayer (const Image &_image, PixelFormat _bayerFormat) |
| convert an RGB image data into bayer image data | |
| GraphicsAPI | defaultGraphicsAPI () |
| Convenience function to get the default graphics API based on current platform. | |
| gz::math::Matrix3d | projectionToCameraIntrinsic (const gz::math::Matrix4d &_projectionMatrix, double _width, double _height) |
| Convert a given camera projection matrix to an intrinsics matrix. Intrinsics matrix is different from the matrix returned by Camera::ProjectionMatrix(), which is used by OpenGL internally. The matrix returned contains the camera calibrated values. | |
| float | screenScalingFactor () |
| Get the screen scaling factor. This function always returns a value of 1.0 and will be marked as deprecated in the next release. | |
| math::Vector3d | screenToPlane (const math::Vector2i &_screenPos, const CameraPtr &_camera, const RayQueryPtr &_rayQuery, const float _offset=0.0) |
| Retrieve the point on a plane at z = 0 in the 3D scene hit by a ray cast from the given 2D screen coordinates. | |
| math::Vector3d | screenToScene (const math::Vector2i &_screenPos, const CameraPtr &_camera, const RayQueryPtr &_rayQuery, float _maxDistance=10.0) |
| Retrieve the first point on a surface in the 3D scene hit by a ray cast from the given 2D screen coordinates. | |
| math::Vector3d | screenToScene (const math::Vector2i &_screenPos, const CameraPtr &_camera, const RayQueryPtr &_rayQuery, RayQueryResult &_rayResult, float _maxDistance=10.0) |
| Retrieve the first point on a surface in the 3D scene hit by a ray cast from the given 2D screen coordinates. | |
| gz::math::AxisAlignedBox | transformAxisAlignedBox (const gz::math::AxisAlignedBox &_box, const gz::math::Pose3d &_pose) |
| Transform a bounding box. | |