Public Member Functions | Protected Attributes | List of all members
gazebo::rendering::GpuLaser Class Reference

GPU based laser distance sensor. More...

#include <rendering/rendering.hh>

Inheritance diagram for gazebo::rendering::GpuLaser:
Inheritance graph
[legend]

Public Member Functions

 GpuLaser (const std::string &_namePrefix, ScenePtr _scene, const bool _autoRender=true)
 Constructor. More...
 
virtual ~GpuLaser ()
 Destructor. More...
 
unsigned int CameraCount () const
 Get the number of cameras required. More...
 
event::ConnectionPtr ConnectNewLaserFrame (std::function< void(const float *_frame, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)> _subscriber)
 Connect to a laser frame signal. More...
 
double CosHorzFOV () const
 Get Cos Horz field-of-view. More...
 
double CosVertFOV () const
 Get Cos Vert field-of-view. More...
 
void CreateLaserTexture (const std::string &_textureName)
 Create the texture which is used to render laser data. More...
 
void DisconnectNewLaserFrame (event::ConnectionPtr &_c)
 Disconnect from a laser frame signal. More...
 
double FarClip () const
 Get far clip. More...
 
virtual void Fini ()
 Finalize the camera. More...
 
double GetCameraCount () const GAZEBO_DEPRECATED(7.0)
 Get the number of cameras required. More...
 
double GetCosHorzFOV () const GAZEBO_DEPRECATED(7.0)
 Get Cos Horz field-of-view. More...
 
double GetCosVertFOV () const GAZEBO_DEPRECATED(7.0)
 Get Cos Vert field-of-view. More...
 
double GetFarClip () const GAZEBO_DEPRECATED(7.0)
 Get far clip. More...
 
double GetHorzFOV () const GAZEBO_DEPRECATED(7.0)
 Get the horizontal field of view of the laser sensor. More...
 
double GetHorzHalfAngle () const GAZEBO_DEPRECATED(7.0)
 Get (horizontal_max_angle + horizontal_min_angle) * 0.5. More...
 
const float * GetLaserData () GAZEBO_DEPRECATED(7.0)
 All things needed to get back z buffer for laser data. More...
 
double GetNearClip () const GAZEBO_DEPRECATED(7.0)
 Get near clip. More...
 
double GetRayCountRatio () const GAZEBO_DEPRECATED(7.0)
 Get the ray count ratio (equivalent to aspect ratio) More...
 
double GetVertFOV () const GAZEBO_DEPRECATED(7.0)
 Get the vertical field-of-view. More...
 
double GetVertHalfAngle () const GAZEBO_DEPRECATED(7.0)
 Get (vertical_max_angle + vertical_min_angle) * 0.5. More...
 
double HorzFOV () const
 Get the horizontal field of view of the laser sensor. More...
 
double HorzHalfAngle () const
 Get (horizontal_max_angle + horizontal_min_angle) * 0.5. More...
 
virtual void Init ()
 Initialize the camera. More...
 
bool IsHorizontal () const
 Gets if sensor is horizontal. More...
 
const float * LaserData () const
 All things needed to get back z buffer for laser data. More...
 
virtual void Load (sdf::ElementPtr _sdf)
 Load the camera with a set of parmeters. More...
 
virtual void Load ()
 Load the camera with default parmeters. More...
 
double NearClip () const
 Get near clip. More...
 
virtual void notifyRenderSingleObject (Ogre::Renderable *_rend, const Ogre::Pass *_p, const Ogre::AutoParamDataSource *_s, const Ogre::LightList *_ll, bool _supp)
 
virtual void PostRender ()
 Post render. More...
 
double RayCountRatio () const
 Get the ray count ratio (equivalent to aspect ratio) More...
 
void SetCameraCount (const unsigned int _cameraCount)
 Set the number of cameras required. More...
 
void SetCosHorzFOV (const double _chfov)
 Set the Cos Horz FOV. More...
 
void SetCosVertFOV (const double _cvfov)
 Set the Cos Horz FOV. More...
 
void SetFarClip (const double _far)
 Set the far clip distance. More...
 
void SetHorzFOV (const double _hfov)
 Set the horizontal fov. More...
 
void SetHorzHalfAngle (const double _angle)
 Set the horizontal half angle. More...
 
void SetIsHorizontal (const bool _horizontal)
 Set sensor horizontal or vertical. More...
 
void SetNearClip (const double _near)
 Set the near clip distance. More...
 
void SetRangeCount (const unsigned int _w, const unsigned int _h=1)
 Set the number of laser samples in the width and height. More...
 
void SetRayCountRatio (const double _rayCountRatio)
 Sets the ray count ratio (equivalen to aspect ratio) More...
 
void SetVertFOV (const double _vfov)
 Set the vertical fov. More...
 
void SetVertHalfAngle (const double _angle)
 Set the vertical half angle. More...
 
double VertFOV () const
 Get the vertical field-of-view. More...
 
double VertHalfAngle () const
 Get (vertical_max_angle + vertical_min_angle) * 0.5. More...
 
- Public Member Functions inherited from gazebo::rendering::Camera
 Camera (const std::string &_namePrefix, ScenePtr _scene, bool _autoRender=true)
 Constructor. More...
 
virtual ~Camera ()
 Destructor. More...
 
float AspectRatio () const
 Get the apect ratio. More...
 
void AttachToVisual (const std::string &_visualName, const bool _inheritOrientation, const double _minDist=0.0, const double _maxDist=0.0)
 Attach the camera to a scene node. More...
 
void AttachToVisual (uint32_t _id, const bool _inheritOrientation, const double _minDist=0.0, const double _maxDist=0.0)
 Attach the camera to a scene node. More...
 
virtual float AvgFPS () const
 Get the average FPS. More...
 
void CameraToViewportRay (const int _screenx, const int _screeny, ignition::math::Vector3d &_origin, ignition::math::Vector3d &_dir) const
 Get a world space ray as cast from the camera through the viewport. More...
 
bool CaptureData () const
 Return the value of this->captureData. More...
 
event::ConnectionPtr ConnectNewImageFrame (std::function< void(const unsigned char *, unsigned int, unsigned int, unsigned int, const std::string &)> _subscriber)
 Connect to the new image signal. More...
 
void CreateRenderTexture (const std::string &_textureName)
 Set the render target. More...
 
ignition::math::Vector3d Direction () const
 Get the camera's direction vector. More...
 
void DisconnectNewImageFrame (event::ConnectionPtr &_c)
 Disconnect from an image frame. More...
 
void EnableSaveFrame (const bool _enable)
 Enable or disable saving. More...
 
double FarClip () const
 Get the far clip distance. More...
 
float GetAspectRatio () const GAZEBO_DEPRECATED(7.0)
 Get the apect ratio. More...
 
virtual float GetAvgFPS () const GAZEBO_DEPRECATED(7.0)
 Get the average FPS. More...
 
void GetCameraToViewportRay (int _screenx, int _screeny, math::Vector3 &_origin, math::Vector3 &_dir) GAZEBO_DEPRECATED(7.0)
 Get a world space ray as cast from the camera through the viewport. More...
 
bool GetCaptureData () const GAZEBO_DEPRECATED(7.0)
 Return the value of this->captureData. More...
 
math::Vector3 GetDirection () const GAZEBO_DEPRECATED(7.0)
 Get the camera's direction vector. More...
 
DistortionPtr GetDistortion () const GAZEBO_DEPRECATED(7.0)
 Get the distortion model of this camera. More...
 
double GetFarClip () GAZEBO_DEPRECATED(7.0)
 Get the far clip distance. More...
 
math::Angle GetHFOV () const GAZEBO_DEPRECATED(7.0)
 Get the camera FOV (horizontal) More...
 
size_t GetImageByteSize () const GAZEBO_DEPRECATED(7.0)
 Get the image size in bytes. More...
 
virtual const unsigned char * GetImageData (unsigned int i=0) GAZEBO_DEPRECATED(7.0)
 Get a pointer to the image data. More...
 
unsigned int GetImageDepth () const GAZEBO_DEPRECATED(7.0)
 Get the depth of the image. More...
 
std::string GetImageFormat () const GAZEBO_DEPRECATED(7.0)
 Get the string representation of the image format. More...
 
virtual unsigned int GetImageHeight () const GAZEBO_DEPRECATED(7.0)
 Get the height of the image. More...
 
virtual unsigned int GetImageWidth () const GAZEBO_DEPRECATED(7.0)
 Get the width of the image. More...
 
bool GetInitialized () const GAZEBO_DEPRECATED(7.0)
 Return true if the camera has been initialized. More...
 
common::Time GetLastRenderWallTime () GAZEBO_DEPRECATED(7.0)
 Get the last time the camera was rendered. More...
 
std::string GetName () const GAZEBO_DEPRECATED(7.0)
 Get the camera's unscoped name. More...
 
double GetNearClip () GAZEBO_DEPRECATED(7.0)
 Get the near clip distance. More...
 
Ogre::Camera * GetOgreCamera () const GAZEBO_DEPRECATED(7.0)
 Get a pointer to the ogre camera. More...
 
std::string GetProjectionType () const GAZEBO_DEPRECATED(7.0)
 Return the projection type as a string. More...
 
double GetRenderRate () const GAZEBO_DEPRECATED(7.0)
 Get the render Hz rate. More...
 
Ogre::Texture * GetRenderTexture () const GAZEBO_DEPRECATED(7.0)
 Get the render texture. More...
 
math::Vector3 GetRight () GAZEBO_DEPRECATED(7.0)
 Get the viewport right vector. More...
 
ScenePtr GetScene () const
 Get the scene this camera is in. More...
 
Ogre::SceneNode * GetSceneNode () const GAZEBO_DEPRECATED(7.0)
 Get the camera's scene node. More...
 
std::string GetScopedName () const GAZEBO_DEPRECATED(7.0)
 Get the camera's scoped name (scene_name::camera_name) More...
 
std::string GetScreenshotPath () const GAZEBO_DEPRECATED(7.0)
 Get the path to saved screenshots. More...
 
unsigned int GetTextureHeight () const GAZEBO_DEPRECATED(7.0)
 Get the height of the off-screen render texture. More...
 
unsigned int GetTextureWidth () const GAZEBO_DEPRECATED(7.0)
 Get the width of the off-screen render texture. More...
 
virtual unsigned int GetTriangleCount () const GAZEBO_DEPRECATED(7.0)
 Get the triangle count. More...
 
math::Vector3 GetUp () GAZEBO_DEPRECATED(7.0)
 Get the viewport up vector. More...
 
math::Angle GetVFOV () const GAZEBO_DEPRECATED(7.0)
 Get the camera FOV (vertical) More...
 
Ogre::Viewport * GetViewport () const GAZEBO_DEPRECATED(7.0)
 Get a pointer to the Ogre::Viewport. More...
 
unsigned int GetViewportHeight () const GAZEBO_DEPRECATED(7.0)
 Get the viewport height in pixels. More...
 
unsigned int GetViewportWidth () const GAZEBO_DEPRECATED(7.0)
 Get the viewport width in pixels. More...
 
unsigned int GetWindowId () const GAZEBO_DEPRECATED(7.0)
 Get the ID of the window this camera is rendering into. More...
 
bool GetWorldPointOnPlane (int _x, int _y, const math::Plane &_plane, math::Vector3 &_result) GAZEBO_DEPRECATED(7.0)
 Get point on a plane. More...
 
math::Pose GetWorldPose () const GAZEBO_DEPRECATED(7.0)
 Get the world pose. More...
 
math::Vector3 GetWorldPosition () const GAZEBO_DEPRECATED(7.0)
 Get the camera position in the world. More...
 
math::Quaternion GetWorldRotation () const GAZEBO_DEPRECATED(7.0)
 Get the camera's orientation in the world. More...
 
double GetZValue (int _x, int _y) GAZEBO_DEPRECATED(7.0)
 Get the Z-buffer value at the given image coordinate. More...
 
ignition::math::Angle HFOV () const
 Get the camera FOV (horizontal) More...
 
size_t ImageByteSize () const
 Get the image size in bytes. More...
 
virtual const unsigned char * ImageData (const unsigned int i=0) const
 Get a pointer to the image data. More...
 
unsigned int ImageDepth () const
 Get the depth of the image. More...
 
std::string ImageFormat () const
 Get the string representation of the image format. More...
 
virtual unsigned int ImageHeight () const
 Get the height of the image. More...
 
virtual unsigned int ImageWidth () const
 Get the width of the image. More...
 
bool Initialized () const
 Return true if the camera has been initialized. More...
 
bool IsAnimating () const
 Return true if the camera is moving due to an animation. More...
 
bool IsVisible (VisualPtr _visual)
 Return true if the visual is within the camera's view frustum. More...
 
bool IsVisible (const std::string &_visualName)
 Return true if the visual is within the camera's view frustum. More...
 
common::Time LastRenderWallTime () const
 Get the last time the camera was rendered. More...
 
DistortionPtr LensDistortion () const
 Get the distortion model of this camera. More...
 
virtual bool MoveToPosition (const math::Pose &_pose, double _time) GAZEBO_DEPRECATED(7.0)
 Move the camera to a position (this is an animated motion). More...
 
virtual bool MoveToPosition (const ignition::math::Pose3d &_pose, const double _time)
 Move the camera to a position (this is an animated motion). More...
 
bool MoveToPositions (const std::vector< math::Pose > &_pts, double _time, std::function< void()> _onComplete=NULL) GAZEBO_DEPRECATED(7.0)
 Move the camera to a series of poses (this is an animated motion). More...
 
bool MoveToPositions (const std::vector< ignition::math::Pose3d > &_pts, const double _time, std::function< void()> _onComplete=NULL)
 Move the camera to a series of poses (this is an animated motion). More...
 
std::string Name () const
 Get the camera's unscoped name. More...
 
double NearClip () const
 Get the near clip distance. More...
 
Ogre::Camera * OgreCamera () const
 Get a pointer to the ogre camera. More...
 
Ogre::Viewport * OgreViewport () const
 Get a pointer to the Ogre::Viewport. More...
 
void Pitch (const math::Angle &_angle, Ogre::Node::TransformSpace _relativeTo=Ogre::Node::TS_LOCAL) GAZEBO_DEPRECATED(7.0)
 Rotate the camera around the y-axis. More...
 
void Pitch (const ignition::math::Angle &_angle, ReferenceFrame _relativeTo=RF_LOCAL)
 Rotate the camera around the y-axis. More...
 
std::string ProjectionType () const
 Return the projection type as a string. More...
 
void Render (const bool _force=false)
 Render the camera. More...
 
double RenderRate () const
 Get the render Hz rate. More...
 
Ogre::Texture * RenderTexture () const
 Get the render texture. More...
 
ignition::math::Vector3d Right () const
 Get the viewport right vector. More...
 
void Roll (const math::Angle &_angle, Ogre::Node::TransformSpace _relativeTo=Ogre::Node::TS_LOCAL) GAZEBO_DEPRECATED(7.0)
 Rotate the camera around the x-axis. More...
 
void Roll (const ignition::math::Angle &_angle, ReferenceFrame _relativeTo=RF_LOCAL)
 Rotate the camera around the x-axis. More...
 
bool SaveFrame (const std::string &_filename)
 Save the last frame to disk. More...
 
Ogre::SceneNode * SceneNode () const
 Get the camera's scene node. More...
 
std::string ScopedName () const
 Get the camera's scoped name (scene_name::camera_name) More...
 
std::string ScreenshotPath () const
 Get the path to saved screenshots. More...
 
void SetAspectRatio (float _ratio)
 Set the aspect ratio. More...
 
void SetCaptureData (const bool _value)
 Set whether to capture data. More...
 
void SetCaptureDataOnce ()
 Capture data once and save to disk. More...
 
virtual void SetClipDist (const float _near, const float _far)
 Set the clip distances. More...
 
void SetHFOV (math::Angle _angle) GAZEBO_DEPRECATED(7.0)
 Set the camera FOV (horizontal) More...
 
void SetHFOV (const ignition::math::Angle &_angle)
 Set the camera FOV (horizontal) More...
 
void SetImageHeight (const unsigned int _h)
 Set the image height. More...
 
void SetImageSize (const unsigned int _w, const unsigned int _h)
 Set the image size. More...
 
void SetImageWidth (const unsigned int _w)
 Set the image height. More...
 
void SetName (const std::string &_name)
 Set the camera's name. More...
 
virtual bool SetProjectionType (const std::string &_type)
 Set the type of projection used by the camera. More...
 
void SetRenderRate (const double _hz)
 Set the render Hz rate. More...
 
virtual void SetRenderTarget (Ogre::RenderTarget *_target)
 Set the camera's render target. More...
 
void SetSaveFramePathname (const std::string &_pathname)
 Set the save frame pathname. More...
 
void SetScene (ScenePtr _scene)
 Set the scene this camera is viewing. More...
 
void SetSceneNode (Ogre::SceneNode *_node)
 Set the camera's scene node. More...
 
void SetWindowId (unsigned int _windowId)
 
virtual void SetWorldPose (const math::Pose &_pose) GAZEBO_DEPRECATED(7.0)
 Set the global pose of the camera. More...
 
virtual void SetWorldPose (const ignition::math::Pose3d &_pose)
 Set the global pose of the camera. More...
 
void SetWorldPosition (const math::Vector3 &_pos) GAZEBO_DEPRECATED(7.0)
 Set the world position. More...
 
void SetWorldPosition (const ignition::math::Vector3d &_pos)
 Set the world position. More...
 
void SetWorldRotation (const math::Quaternion &_quat) GAZEBO_DEPRECATED(7.0)
 Set the world orientation. More...
 
void SetWorldRotation (const ignition::math::Quaterniond &_quat)
 Set the world orientation. More...
 
void ShowWireframe (const bool _s)
 Set whether to view the world in wireframe. More...
 
unsigned int TextureHeight () const
 Get the height of the off-screen render texture. More...
 
unsigned int TextureWidth () const
 Get the width of the off-screen render texture. More...
 
void ToggleShowWireframe ()
 Toggle whether to view the world in wireframe. More...
 
void TrackVisual (const std::string &_visualName)
 Set the camera to track a scene node. More...
 
void Translate (const math::Vector3 &_direction) GAZEBO_DEPRECATED(7.0)
 Translate the camera. More...
 
void Translate (const ignition::math::Vector3d &_direction)
 Translate the camera. More...
 
virtual unsigned int TriangleCount () const
 Get the triangle count. More...
 
ignition::math::Vector3d Up () const
 Get the viewport up vector. More...
 
virtual void Update ()
 
ignition::math::Angle VFOV () const
 Get the camera FOV (vertical) More...
 
unsigned int ViewportHeight () const
 Get the viewport height in pixels. More...
 
unsigned int ViewportWidth () const
 Get the viewport width in pixels. More...
 
unsigned int WindowId () const
 Get the ID of the window this camera is rendering into. More...
 
bool WorldPointOnPlane (const int _x, const int _y, const ignition::math::Planed &_plane, ignition::math::Vector3d &_result)
 Get point on a plane. More...
 
ignition::math::Pose3d WorldPose () const
 Get the world pose. More...
 
ignition::math::Vector3d WorldPosition () const
 Get the camera position in the world. More...
 
ignition::math::Quaterniond WorldRotation () const
 Get the camera's orientation in the world. More...
 
void Yaw (const math::Angle &_angle, Ogre::Node::TransformSpace _relativeTo=Ogre::Node::TS_WORLD) GAZEBO_DEPRECATED(7.0)
 Rotate the camera around the z-axis. More...
 
void Yaw (const ignition::math::Angle &_angle, ReferenceFrame _relativeTo=RF_WORLD)
 Rotate the camera around the z-axis. More...
 
double ZValue (const int _x, const int _y)
 Get the Z-buffer value at the given image coordinate. More...
 

Protected Attributes

unsigned int cameraCount
 Number of cameras needed to generate the rays. More...
 
double chfov
 Cos horizontal field-of-view. More...
 
double cvfov
 Cos vertical field-of-view. More...
 
double farClip
 Far clip plane. More...
 
double hfov
 Horizontal field-of-view. More...
 
double horzHalfAngle
 Horizontal half angle. More...
 
bool isHorizontal
 True if the sensor is horizontal only. More...
 
double nearClip
 Near clip plane. More...
 
double rayCountRatio
 Ray count ratio. More...
 
double vertHalfAngle
 Vertical half angle. More...
 
double vfov
 Vertical field-of-view. More...
 
- Protected Attributes inherited from gazebo::rendering::Camera
Ogre::AnimationState * animState
 Animation state, used to animate the camera. More...
 
unsigned char * bayerFrameBuffer
 Buffer for a bayer image frame. More...
 
Ogre::Camera * camera
 The OGRE camera. More...
 
bool captureData
 True to capture frames into an image buffer. More...
 
bool captureDataOnce
 True to capture a frame once and save to disk. More...
 
std::vector< event::ConnectionPtrconnections
 The camera's event connections. More...
 
int imageFormat
 Format for saving images. More...
 
int imageHeight
 Save image height. More...
 
int imageWidth
 Save image width. More...
 
bool initialized
 True if initialized. More...
 
common::Time lastRenderWallTime
 Time the last frame was rendered. More...
 
std::string name
 Name of the camera. More...
 
bool newData
 True if new data is available. More...
 
event::EventT< void(const
unsigned char *, unsigned int,
unsigned int, unsigned int,
const std::string &)> 
newImageFrame
 Event triggered when a new frame is generated. More...
 
std::function< void()> onAnimationComplete
 User callback for when an animation completes. More...
 
common::Time prevAnimTime
 Previous time the camera animation was updated. More...
 
Ogre::RenderTarget * renderTarget
 Target that renders frames. More...
 
Ogre::Texture * renderTexture
 Texture that receives results from rendering. More...
 
std::list< msgs::Request > requests
 List of requests. More...
 
unsigned int saveCount
 Number of saved frames. More...
 
unsigned char * saveFrameBuffer
 Buffer for a single image frame. More...
 
ScenePtr scene
 Pointer to the scene. More...
 
Ogre::SceneNode * sceneNode
 Scene node that controls camera position and orientation. More...
 
std::string scopedName
 Scene scoped name of the camera. More...
 
std::string scopedUniqueName
 Scene scoped name of the camera with a unique ID. More...
 
std::string screenshotPath
 Path to saved screenshots. More...
 
sdf::ElementPtr sdf
 Camera's SDF values. More...
 
unsigned int textureHeight
 Height of the render texture. More...
 
unsigned int textureWidth
 Width of the render texture. More...
 
Ogre::Viewport * viewport
 Viewport the ogre camera uses. More...
 
unsigned int windowId
 ID of the window that the camera is attached to. More...
 

Additional Inherited Members

- Static Public Member Functions inherited from gazebo::rendering::Camera
static size_t GetImageByteSize (unsigned int _width, unsigned int _height, const std::string &_format) GAZEBO_DEPRECATED(7.0)
 Calculate image byte size base on a few parameters. More...
 
static size_t ImageByteSize (const unsigned int _width, const unsigned int _height, const std::string &_format)
 Calculate image byte size base on a few parameters. More...
 
static bool SaveFrame (const unsigned char *_image, const unsigned int _width, const unsigned int _height, const int _depth, const std::string &_format, const std::string &_filename)
 Save a frame using an image buffer. More...
 
- Protected Member Functions inherited from gazebo::rendering::Camera
virtual void AnimationComplete ()
 Internal function used to indicate that an animation has completed. More...
 
virtual bool AttachToVisualImpl (const std::string &_name, const bool _inheritOrientation, const double _minDist=0, const double _maxDist=0)
 Attach the camera to a scene node. More...
 
virtual bool AttachToVisualImpl (uint32_t _id, const bool _inheritOrientation, const double _minDist=0, const double _maxDist=0)
 Attach the camera to a scene node. More...
 
virtual bool AttachToVisualImpl (VisualPtr _visual, const bool _inheritOrientation, const double _minDist=0, const double _maxDist=0)
 Attach the camera to a visual. More...
 
std::string FrameFilename ()
 Get the next frame filename based on SDF parameters. More...
 
std::string GetFrameFilename () GAZEBO_DEPRECATED(7.0)
 Get the next frame filename based on SDF parameters. More...
 
void ReadPixelBuffer ()
 Read image data from pixel buffer. More...
 
bool TrackVisualImpl (const std::string &_visualName)
 Implementation of the Camera::TrackVisual call. More...
 
virtual bool TrackVisualImpl (VisualPtr _visual)
 Set the camera to track a scene node. More...
 
virtual void UpdateFOV ()
 Update the camera's field of view. More...
 

Detailed Description

GPU based laser distance sensor.

Constructor & Destructor Documentation

gazebo::rendering::GpuLaser::GpuLaser ( const std::string &  _namePrefix,
ScenePtr  _scene,
const bool  _autoRender = true 
)

Constructor.

Parameters
[in]_namePrefixUnique prefix name for the camera.
[in]_sceneScene that will contain the camera
[in]_autoRenderAlmost everyone should leave this as true.
virtual gazebo::rendering::GpuLaser::~GpuLaser ( )
virtual

Destructor.

Member Function Documentation

unsigned int gazebo::rendering::GpuLaser::CameraCount ( ) const

Get the number of cameras required.

Returns
Number of cameras needed to generate the rays
event::ConnectionPtr gazebo::rendering::GpuLaser::ConnectNewLaserFrame ( std::function< void(const float *_frame, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)>  _subscriber)

Connect to a laser frame signal.

Parameters
[in]_subscriberCallback that is called when a new image is generated
Returns
A pointer to the connection. This must be kept in scope.
double gazebo::rendering::GpuLaser::CosHorzFOV ( ) const

Get Cos Horz field-of-view.

Returns
2 * atan(tan(this->hfov/2) / cos(this->vfov/2))
double gazebo::rendering::GpuLaser::CosVertFOV ( ) const

Get Cos Vert field-of-view.

Returns
2 * atan(tan(this->vfov/2) / cos(this->hfov/2))
void gazebo::rendering::GpuLaser::CreateLaserTexture ( const std::string &  _textureName)

Create the texture which is used to render laser data.

Parameters
[in]_textureNameName of the new texture.
void gazebo::rendering::GpuLaser::DisconnectNewLaserFrame ( event::ConnectionPtr _c)

Disconnect from a laser frame signal.

Parameters
[in]_cThe connection to disconnect
double gazebo::rendering::GpuLaser::FarClip ( ) const

Get far clip.

Returns
far clip distance
virtual void gazebo::rendering::GpuLaser::Fini ( )
virtual

Finalize the camera.

This function is called before the camera is destructed

Reimplemented from gazebo::rendering::Camera.

double gazebo::rendering::GpuLaser::GetCameraCount ( ) const

Get the number of cameras required.

Returns
Number of cameras needed to generate the rays
Deprecated:
See CameraCount()
double gazebo::rendering::GpuLaser::GetCosHorzFOV ( ) const

Get Cos Horz field-of-view.

Returns
2 * atan(tan(this->hfov/2) / cos(this->vfov/2))
Deprecated:
See CosHorzFOV()
double gazebo::rendering::GpuLaser::GetCosVertFOV ( ) const

Get Cos Vert field-of-view.

Returns
2 * atan(tan(this->vfov/2) / cos(this->hfov/2))
Deprecated:
See CosVertFOV()
double gazebo::rendering::GpuLaser::GetFarClip ( ) const

Get far clip.

Returns
far clip distance
Deprecated:
See FarClip()
double gazebo::rendering::GpuLaser::GetHorzFOV ( ) const

Get the horizontal field of view of the laser sensor.

Returns
The horizontal field of view of the laser sensor.
Deprecated:
See HorzFOV()
double gazebo::rendering::GpuLaser::GetHorzHalfAngle ( ) const

Get (horizontal_max_angle + horizontal_min_angle) * 0.5.

Returns
(horizontal_max_angle + horizontal_min_angle) * 0.5
Deprecated:
See HorzHalfAngle()
const float* gazebo::rendering::GpuLaser::GetLaserData ( )

All things needed to get back z buffer for laser data.

Returns
Array of laser data.
Deprecated:
See LaserData()
double gazebo::rendering::GpuLaser::GetNearClip ( ) const

Get near clip.

Returns
near clip distance
Deprecated:
See NearClip()
double gazebo::rendering::GpuLaser::GetRayCountRatio ( ) const

Get the ray count ratio (equivalent to aspect ratio)

Returns
The ray count ratio (equivalent to aspect ratio)
Deprecated:
See RayCountRatio()
double gazebo::rendering::GpuLaser::GetVertFOV ( ) const

Get the vertical field-of-view.

Returns
The vertical field of view of the laser sensor.
Deprecated:
See VertFOV()
double gazebo::rendering::GpuLaser::GetVertHalfAngle ( ) const

Get (vertical_max_angle + vertical_min_angle) * 0.5.

Returns
(vertical_max_angle + vertical_min_angle) * 0.5
Deprecated:
See VertHalfAngle()
double gazebo::rendering::GpuLaser::HorzFOV ( ) const

Get the horizontal field of view of the laser sensor.

Returns
The horizontal field of view of the laser sensor.
double gazebo::rendering::GpuLaser::HorzHalfAngle ( ) const

Get (horizontal_max_angle + horizontal_min_angle) * 0.5.

Returns
(horizontal_max_angle + horizontal_min_angle) * 0.5
virtual void gazebo::rendering::GpuLaser::Init ( )
virtual

Initialize the camera.

Reimplemented from gazebo::rendering::Camera.

bool gazebo::rendering::GpuLaser::IsHorizontal ( ) const

Gets if sensor is horizontal.

Returns
True if horizontal, false if not
const float* gazebo::rendering::GpuLaser::LaserData ( ) const

All things needed to get back z buffer for laser data.

Returns
Array of laser data.
virtual void gazebo::rendering::GpuLaser::Load ( sdf::ElementPtr  _sdf)
virtual

Load the camera with a set of parmeters.

Parameters
[in]_sdfThe SDF camera info

Reimplemented from gazebo::rendering::Camera.

virtual void gazebo::rendering::GpuLaser::Load ( )
virtual

Load the camera with default parmeters.

Reimplemented from gazebo::rendering::Camera.

double gazebo::rendering::GpuLaser::NearClip ( ) const

Get near clip.

Returns
near clip distance
virtual void gazebo::rendering::GpuLaser::notifyRenderSingleObject ( Ogre::Renderable *  _rend,
const Ogre::Pass *  _p,
const Ogre::AutoParamDataSource *  _s,
const Ogre::LightList *  _ll,
bool  _supp 
)
virtual
virtual void gazebo::rendering::GpuLaser::PostRender ( )
virtual

Post render.

Called afer the render signal.

Reimplemented from gazebo::rendering::Camera.

double gazebo::rendering::GpuLaser::RayCountRatio ( ) const

Get the ray count ratio (equivalent to aspect ratio)

Returns
The ray count ratio (equivalent to aspect ratio)
void gazebo::rendering::GpuLaser::SetCameraCount ( const unsigned int  _cameraCount)

Set the number of cameras required.

Parameters
[in]_cameraCountThe number of cameras required to generate the rays
void gazebo::rendering::GpuLaser::SetCosHorzFOV ( const double  _chfov)

Set the Cos Horz FOV.

Parameters
[in]_chfovCos Horz FOV
void gazebo::rendering::GpuLaser::SetCosVertFOV ( const double  _cvfov)

Set the Cos Horz FOV.

Parameters
[in]_cvfovCos Horz FOV
void gazebo::rendering::GpuLaser::SetFarClip ( const double  _far)

Set the far clip distance.

Parameters
[in]_farfar clip distance
void gazebo::rendering::GpuLaser::SetHorzFOV ( const double  _hfov)

Set the horizontal fov.

Parameters
[in]_hfovhorizontal fov
void gazebo::rendering::GpuLaser::SetHorzHalfAngle ( const double  _angle)

Set the horizontal half angle.

Parameters
[in]_anglehorizontal half angle
void gazebo::rendering::GpuLaser::SetIsHorizontal ( const bool  _horizontal)

Set sensor horizontal or vertical.

Parameters
[in]_horizontalTrue if horizontal, false if not
void gazebo::rendering::GpuLaser::SetNearClip ( const double  _near)

Set the near clip distance.

Parameters
[in]_nearnear clip distance
void gazebo::rendering::GpuLaser::SetRangeCount ( const unsigned int  _w,
const unsigned int  _h = 1 
)

Set the number of laser samples in the width and height.

Parameters
[in]_wNumber of samples in the horizontal sweep
[in]_hNumber of samples in the vertical sweep
void gazebo::rendering::GpuLaser::SetRayCountRatio ( const double  _rayCountRatio)

Sets the ray count ratio (equivalen to aspect ratio)

Parameters
[in]_rayCountRatioray count ratio (equivalent to aspect ratio)
void gazebo::rendering::GpuLaser::SetVertFOV ( const double  _vfov)

Set the vertical fov.

Parameters
[in]_vfovvertical fov
void gazebo::rendering::GpuLaser::SetVertHalfAngle ( const double  _angle)

Set the vertical half angle.

Parameters
[in]_anglevertical half angle
double gazebo::rendering::GpuLaser::VertFOV ( ) const

Get the vertical field-of-view.

Returns
The vertical field of view of the laser sensor.
double gazebo::rendering::GpuLaser::VertHalfAngle ( ) const

Get (vertical_max_angle + vertical_min_angle) * 0.5.

Returns
(vertical_max_angle + vertical_min_angle) * 0.5

Member Data Documentation

unsigned int gazebo::rendering::GpuLaser::cameraCount
protected

Number of cameras needed to generate the rays.

double gazebo::rendering::GpuLaser::chfov
protected

Cos horizontal field-of-view.

double gazebo::rendering::GpuLaser::cvfov
protected

Cos vertical field-of-view.

double gazebo::rendering::GpuLaser::farClip
protected

Far clip plane.

double gazebo::rendering::GpuLaser::hfov
protected

Horizontal field-of-view.

double gazebo::rendering::GpuLaser::horzHalfAngle
protected

Horizontal half angle.

bool gazebo::rendering::GpuLaser::isHorizontal
protected

True if the sensor is horizontal only.

double gazebo::rendering::GpuLaser::nearClip
protected

Near clip plane.

double gazebo::rendering::GpuLaser::rayCountRatio
protected

Ray count ratio.

double gazebo::rendering::GpuLaser::vertHalfAngle
protected

Vertical half angle.

double gazebo::rendering::GpuLaser::vfov
protected

Vertical field-of-view.


The documentation for this class was generated from the following file: