All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Groups Pages
Public Member Functions | 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, Scene *_scene, bool _autoRender=true)
 Constructor.
 
virtual ~GpuLaser ()
 Destructor.
 
template<typename T >
event::ConnectionPtr ConnectNewLaserFrame (T _subscriber)
 Connect to a laser frame signal.
 
void CreateLaserTexture (const std::string &_textureName)
 Create the texture which is used to render laser data.
 
void DisconnectNewLaserFrame (event::ConnectionPtr &_c)
 Disconnect from a laser frame signal.
 
void Fini ()
 Finalize the camera.
 
virtual const float * GetLaserData ()
 All things needed to get back z buffer for laser data.
 
void Init ()
 Initialize the camera.
 
void Load (sdf::ElementPtr &_sdf)
 Load the camera with a set of parmeters.
 
void Load ()
 Load the camera with default parmeters.
 
virtual void notifyRenderSingleObject (Ogre::Renderable *_rend, const Ogre::Pass *_p, const Ogre::AutoParamDataSource *_s, const Ogre::LightList *_ll, bool _supp)
 
virtual void PostRender ()
 Render the camera.
 
void SetParentSensor (sensors::GpuRaySensor *_parent)
 Set the parent sensor.
 
void SetRangeCount (unsigned int _w, unsigned int _h=1)
 Set the number of laser samples in the width and height.
 
- Public Member Functions inherited from gazebo::rendering::Camera
 Camera (const std::string &_namePrefix, Scene *_scene, bool _autoRender=true)
 Constructor.
 
virtual ~Camera ()
 Destructor.
 
void AttachToVisual (const std::string &_visualName, bool _inheritOrientation, double _minDist=0.0, double _maxDist=0.0)
 Attach the camera to a scene node.
 
template<typename T >
event::ConnectionPtr ConnectNewImageFrame (T _subscriber)
 Connect a to the new image signal.
 
void CreateRenderTexture (const std::string &_textureName)
 Set the render target.
 
void DisconnectNewImageFrame (event::ConnectionPtr &_c)
 Disconnect from an image frame.
 
void EnableSaveFrame (bool _enable)
 Enable or disable saving.
 
void Fini ()
 Finalize the camera.
 
float GetAspectRatio () const
 Get the apect ratio.
 
virtual float GetAvgFPS ()
 Get the average FPS.
 
void GetCameraToViewportRay (int _screenx, int _screeny, math::Vector3 &_origin, math::Vector3 &_dir)
 Get a world space ray as cast from the camera through the viewport.
 
math::Vector3 GetDirection () const
 Get the camera's direction vector.
 
double GetFarClip ()
 Get the far clip distance.
 
math::Angle GetHFOV () const
 Get the camera FOV (horizontal)
 
size_t GetImageByteSize () const
 Get the image size in bytes.
 
virtual const unsigned char * GetImageData (unsigned int i=0)
 Get a pointer to the image data.
 
unsigned int GetImageDepth () const
 Get the depth of the image.
 
std::string GetImageFormat () const
 Get the height of the image.
 
unsigned int GetImageHeight () const
 Get the height of the image.
 
unsigned int GetImageWidth () const
 Get the width of the image.
 
bool GetInitialized () const
 Returns true if initialized.
 
common::Time GetLastRenderWallTime ()
 Get the last time the camera was rendered.
 
std::string GetName () const
 Get the camera's name.
 
double GetNearClip ()
 Get the near clip distance.
 
Ogre::Camera * GetOgreCamera () const
 Get a pointer to the ogre camera.
 
Ogre::Texture * GetRenderTexture () const
 Get the render texture.
 
math::Vector3 GetRight ()
 Get the viewport right vector.
 
SceneGetScene () const
 Get the scene this camera is in.
 
Ogre::SceneNode * GetSceneNode () const
 Get the camera's scene node.
 
unsigned int GetTextureHeight () const
 Get the height of the off-screen render texture.
 
unsigned int GetTextureWidth () const
 Get the width of the off-screen render texture.
 
virtual unsigned int GetTriangleCount ()
 Get the triangle count.
 
math::Vector3 GetUp ()
 Get the viewport up vector.
 
math::Angle GetVFOV () const
 Get the camera FOV (vertical)
 
Ogre::Viewport * GetViewport () const
 Get a pointer to the Ogre::Viewport.
 
unsigned int GetViewportHeight () const
 Get the viewport height in pixels.
 
unsigned int GetViewportWidth () const
 Get the viewport width in pixels.
 
unsigned int GetWindowId () const
 Get the ID of the window this camera is rendering into.
 
bool GetWorldPointOnPlane (int _x, int _y, const math::Plane &_plane, math::Vector3 &_result)
 Get point on a plane.
 
math::Pose GetWorldPose ()
 Get the global pose of the camera.
 
math::Vector3 GetWorldPosition () const
 Get the camera position in the world.
 
math::Quaternion GetWorldRotation () const
 Get the camera's orientation in the world.
 
double GetZValue (int _x, int _y)
 Get the Z-buffer value at the given image coordinate.
 
void Init ()
 Initialize the camera.
 
bool IsInitialized () const
 Return true if the camera has been initialized.
 
bool IsVisible (VisualPtr _visual)
 Return true if the visual is within the camera's view frustum.
 
bool IsVisible (const std::string &_visualName)
 Return true if the visual is within the camera's view frustum.
 
void Load (sdf::ElementPtr _sdf)
 Load the camera with a set of parmeters.
 
void Load ()
 Load the camera with default parmeters.
 
virtual bool MoveToPosition (const math::Pose &_pose, double _time)
 Move the camera to a position.
 
bool MoveToPositions (const std::vector< math::Pose > &_pts, double _time, boost::function< void()> _onComplete=NULL)
 Move the camera to a series of positions.
 
void Render ()
 Render the camera.
 
void RotatePitch (math::Angle _angle)
 Rotate the camera around the pitch axis.
 
void RotateYaw (math::Angle _angle)
 Rotate the camera around the yaw axis.
 
bool SaveFrame (const std::string &_filename)
 Save the last frame to disk.
 
void SetAspectRatio (float _ratio)
 Set the aspect ratio.
 
void SetCaptureData (bool _value)
 Set whether to capture data.
 
void SetClipDist (float _near, float _far)
 Set the clip distances.
 
void SetHFOV (math::Angle _angle)
 Set the camera FOV (horizontal)
 
void SetImageHeight (unsigned int _h)
 Set the image height.
 
void SetImageSize (unsigned int _w, unsigned int _h)
 Set the image size.
 
void SetImageWidth (unsigned int _w)
 Set the image height.
 
void SetName (const std::string &_name)
 Set the camera's name.
 
void SetRenderRate (double _hz)
 Set the render Hz rate.
 
virtual void SetRenderTarget (Ogre::RenderTarget *_target)
 Set the camera's render target.
 
void SetSaveFramePathname (const std::string &_pathname)
 Set the save frame pathname.
 
void SetScene (Scene *_scene)
 Set the scene this camera is viewing.
 
void SetSceneNode (Ogre::SceneNode *_node)
 Set the camera's scene node.
 
void SetWindowId (unsigned int _windowId)
 
virtual void SetWorldPose (const math::Pose &_pose)
 Set the global pose of the camera.
 
void SetWorldPosition (const math::Vector3 &_pos)
 Set the world position.
 
void SetWorldRotation (const math::Quaternion &_quat)
 Set the world orientation.
 
void ShowWireframe (bool _s)
 Set whether to view the world in wireframe.
 
void ToggleShowWireframe ()
 Toggle whether to view the world in wireframe.
 
void TrackVisual (const std::string &_visualName)
 Set the camera to track a scene node.
 
void Translate (const math::Vector3 &_direction)
 Translate the camera.
 
virtual void Update ()
 

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)
 Calculate image byte size base on a few parameters.
 
static bool SaveFrame (const unsigned char *_image, unsigned int _width, unsigned int _height, int _depth, const std::string &_format, const std::string &_filename)
 Save a frame using an image buffer.
 
- Protected Member Functions inherited from gazebo::rendering::Camera
virtual bool AttachToVisualImpl (const std::string &_name, bool _inheritOrientation, double _minDist=0, double _maxDist=0)
 Attach the camera to a scene node.
 
virtual bool AttachToVisualImpl (VisualPtr _visual, bool _inheritOrientation, double _minDist=0, double _maxDist=0)
 Attach the camera to a visual.
 
std::string GetFrameFilename ()
 Get the next frame filename based on SDF parameters.
 
bool TrackVisualImpl (const std::string &_visualName)
 Implementation of the Camera::TrackVisual call.
 
virtual bool TrackVisualImpl (VisualPtr _visual)
 Set the camera to track a scene node.
 
- Protected Attributes inherited from gazebo::rendering::Camera
Ogre::AnimationState * animState
 
unsigned char * bayerFrameBuffer
 
Ogre::Camera * camera
 
bool captureData
 
std::vector< event::ConnectionPtrconnections
 
int imageFormat
 
int imageHeight
 
int imageWidth
 
bool initialized
 
common::Time lastRenderWallTime
 
std::string name
 
bool newData
 
event::EventT< void(const
unsigned char *, unsigned int,
unsigned int, unsigned int,
const std::string &)> 
newImageFrame
 
boost::function< void()> onAnimationComplete
 
Ogre::SceneNode * pitchNode
 
common::Time prevAnimTime
 
Ogre::RenderTarget * renderTarget
 
Ogre::Texture * renderTexture
 
std::list< msgs::Request > requests
 
unsigned int saveCount
 
unsigned char * saveFrameBuffer
 
Scenescene
 
Ogre::SceneNode * sceneNode
 
sdf::ElementPtr sdf
 
unsigned int textureHeight
 
unsigned int textureWidth
 
Ogre::Viewport * viewport
 
unsigned int windowId
 

Detailed Description

GPU based laser distance sensor.

This is the base class for all cameras.

Constructor & Destructor Documentation

gazebo::rendering::GpuLaser::GpuLaser ( const std::string &  _namePrefix,
Scene _scene,
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

template<typename T >
event::ConnectionPtr gazebo::rendering::GpuLaser::ConnectNewLaserFrame ( _subscriber)
inline

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.

References gazebo::event::EventT< T >::Connect().

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)
inline

Disconnect from a laser frame signal.

Parameters
[in]_cThe connection to disconnect

References gazebo::event::EventT< T >::Disconnect().

void gazebo::rendering::GpuLaser::Fini ( )

Finalize the camera.

virtual const float* gazebo::rendering::GpuLaser::GetLaserData ( )
virtual

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

Returns
Array of laser data
void gazebo::rendering::GpuLaser::Init ( )

Initialize the camera.

void gazebo::rendering::GpuLaser::Load ( sdf::ElementPtr _sdf)

Load the camera with a set of parmeters.

Parameters
[in]_sdfThe SDF camera info
void gazebo::rendering::GpuLaser::Load ( )

Load the camera with default parmeters.

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

Render the camera.

Reimplemented from gazebo::rendering::Camera.

void gazebo::rendering::GpuLaser::SetParentSensor ( sensors::GpuRaySensor _parent)

Set the parent sensor.

Parameters
[in]_parentPointer to a sensors::GpuRaySensor
void gazebo::rendering::GpuLaser::SetRangeCount ( unsigned int  _w,
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

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