GPU based laser distance sensor. More...
#include <rendering/rendering.hh>
Public Member Functions | |
GpuLaser (const std::string &_namePrefix, ScenePtr _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. | |
virtual void | Fini () |
Finalize the camera. | |
double | GetCameraCount () const |
Get the number of cameras required. | |
double | GetCosHorzFOV () const |
Get Cos Horz field-of-view. | |
double | GetCosVertFOV () const |
Get Cos Vert field-of-view. | |
double | GetFarClip () const |
Get far clip. | |
double | GetHorzFOV () const |
Get the horizontal field of view of the laser sensor. | |
double | GetHorzHalfAngle () const |
Get (horizontal_max_angle + horizontal_min_angle) * 0.5. | |
const float * | GetLaserData () |
All things needed to get back z buffer for laser data. | |
double | GetNearClip () const |
Get near clip. | |
double | GetRayCountRatio () const |
Get the ray count ratio (equivalent to aspect ratio) | |
double | GetVertFOV () const |
Get the vertical field-of-view. | |
double | GetVertHalfAngle () const |
Get (vertical_max_angle + vertical_min_angle) * 0.5. | |
virtual void | Init () |
Initialize the camera. | |
bool | IsHorizontal () const |
Gets if sensor is horizontal. | |
virtual void | Load (sdf::ElementPtr &_sdf) |
virtual 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 () |
Post render. | |
void | SetCameraCount (double _cameraCount) |
Set the number of cameras required. | |
void | SetCosHorzFOV (double _chfov) |
Set the Cos Horz FOV. | |
void | SetCosVertFOV (double _cvfov) |
Set the Cos Horz FOV. | |
void | SetFarClip (double _far) |
Set the far clip distance. | |
void | SetHorzFOV (double _hfov) |
Set the horizontal fov. | |
void | SetHorzHalfAngle (double _angle) |
Set the horizontal half angle. | |
void | SetIsHorizontal (bool _horizontal) |
Set sensor horizontal or vertical. | |
void | SetNearClip (double _near) |
Set the near clip distance. | |
void | SetRangeCount (unsigned int _w, unsigned int _h=1) |
Set the number of laser samples in the width and height. | |
void | SetRayCountRatio (double _rayCountRatio) |
Sets the ray count ratio (equivalen to aspect ratio) | |
void | SetVertFOV (double _vfov) |
Set the vertical fov. | |
void | SetVertHalfAngle (double _angle) |
Set the vertical half angle. | |
Public Member Functions inherited from gazebo::rendering::Camera | |
Camera (const std::string &_namePrefix, ScenePtr _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 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. | |
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 string representation of the image format. | |
virtual unsigned int | GetImageHeight () const |
Get the height of the image. | |
virtual unsigned int | GetImageWidth () const |
Get the width of the image. | |
bool | GetInitialized () const |
Return true if the camera has been 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::SceneNode * | GetPitchNode () const |
Get the camera's pitch scene node. | |
double | GetRenderRate () const |
Get the render Hz rate. | |
Ogre::Texture * | GetRenderTexture () const |
Get the render texture. | |
math::Vector3 | GetRight () |
Get the viewport right vector. | |
ScenePtr | GetScene () const |
Get the scene this camera is in. | |
Ogre::SceneNode * | GetSceneNode () const |
Get the camera's scene node. | |
std::string | GetScreenshotPath () const |
Get the path to saved screenshots. | |
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. | |
bool | IsAnimating () const |
Return true if the camera is moving due to an animation. | |
bool | IsInitialized () const GAZEBO_DEPRECATED(1.5) |
Deprecated. | |
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. | |
virtual void | Load (sdf::ElementPtr _sdf) |
Load the camera with a set of parmeters. | |
virtual bool | MoveToPosition (const math::Pose &_pose, double _time) |
Move the camera to a position (this is an animated motion). | |
bool | MoveToPositions (const std::vector< math::Pose > &_pts, double _time, boost::function< void()> _onComplete=NULL) |
Move the camera to a series of poses (this is an animated motion). | |
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 | SetCaptureDataOnce () |
Capture data once and save to disk. | |
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 (ScenePtr _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 () |
Protected Attributes | |
unsigned int | cameraCount |
Number of cameras needed to generate the rays. | |
double | chfov |
Cos horizontal field-of-view. | |
double | cvfov |
Cos vertical field-of-view. | |
double | far |
Far clip plane. | |
double | hfov |
Horizontal field-of-view. | |
double | horzHalfAngle |
Horizontal half angle. | |
bool | isHorizontal |
True if the sensor is horizontal only. | |
double | near |
Near clip plane. | |
double | rayCountRatio |
Ray count ratio. | |
double | vertHalfAngle |
Vertical half angle. | |
double | vfov |
Vertical field-of-view. | |
Protected Attributes inherited from gazebo::rendering::Camera | |
Ogre::AnimationState * | animState |
Animation state, used to animate the camera. | |
unsigned char * | bayerFrameBuffer |
Buffer for a bayer image frame. | |
Ogre::Camera * | camera |
The OGRE camera. | |
bool | captureData |
True to capture frames into an image buffer. | |
bool | captureDataOnce |
True to capture a frame once and save to disk. | |
std::vector< event::ConnectionPtr > | connections |
The camera's event connections. | |
int | imageFormat |
Format for saving images. | |
int | imageHeight |
Save image height. | |
int | imageWidth |
Save image width. | |
bool | initialized |
True if initialized. | |
common::Time | lastRenderWallTime |
Time the last frame was rendered. | |
std::string | name |
Name of the camera. | |
bool | newData |
True if new data is available. | |
event::EventT< void(const unsigned char *, unsigned int, unsigned int, unsigned int, const std::string &)> | newImageFrame |
Event triggered when a new frame is generated. | |
boost::function< void()> | onAnimationComplete |
User callback for when an animation completes. | |
Ogre::SceneNode * | pitchNode |
Scene nod that controls camera pitch. | |
common::Time | prevAnimTime |
Previous time the camera animation was updated. | |
Ogre::RenderTarget * | renderTarget |
Target that renders frames. | |
Ogre::Texture * | renderTexture |
Texture that receives results from rendering. | |
std::list< msgs::Request > | requests |
List of requests. | |
unsigned int | saveCount |
Number of saved frames. | |
unsigned char * | saveFrameBuffer |
ScenePtr | scene |
Pointer to the scene. | |
Ogre::SceneNode * | sceneNode |
Scene node that controls camera position. | |
std::string | screenshotPath |
Path to saved screenshots. | |
sdf::ElementPtr | sdf |
Camera's SDF values. | |
unsigned int | textureHeight |
Height of the render texture. | |
unsigned int | textureWidth |
Width of the render texture. | |
Ogre::Viewport * | viewport |
Viewport the ogre camera uses. | |
unsigned int | windowId |
ID of the window that the camera is attached to. |
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 void | AnimationComplete () |
Internal function used to indicate that an animation has completed. | |
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. | |
void | ReadPixelBuffer () |
Read image data from pixel buffer. | |
virtual void | RenderImpl () |
Implementation of the render call. | |
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. |
GPU based laser distance sensor.
gazebo::rendering::GpuLaser::GpuLaser | ( | const std::string & | _namePrefix, |
ScenePtr | _scene, | ||
bool | _autoRender = true |
||
) |
Constructor.
[in] | _namePrefix | Unique prefix name for the camera. |
[in] | _scene | Scene that will contain the camera |
[in] | _autoRender | Almost everyone should leave this as true. |
|
virtual |
Destructor.
|
inline |
Connect to a laser frame signal.
[in] | _subscriber | Callback that is called when a new image is generated |
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.
[in] | _textureName | Name of the new texture. |
|
inline |
Disconnect from a laser frame signal.
[in] | _c | The connection to disconnect |
References gazebo::event::EventT< T >::Disconnect().
|
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.
double gazebo::rendering::GpuLaser::GetCosHorzFOV | ( | ) | const |
Get Cos Horz field-of-view.
double gazebo::rendering::GpuLaser::GetCosVertFOV | ( | ) | const |
Get Cos Vert field-of-view.
double gazebo::rendering::GpuLaser::GetFarClip | ( | ) | const |
Get far clip.
double gazebo::rendering::GpuLaser::GetHorzFOV | ( | ) | const |
Get the horizontal field of view of the laser sensor.
double gazebo::rendering::GpuLaser::GetHorzHalfAngle | ( | ) | const |
Get (horizontal_max_angle + horizontal_min_angle) * 0.5.
const float* gazebo::rendering::GpuLaser::GetLaserData | ( | ) |
All things needed to get back z buffer for laser data.
double gazebo::rendering::GpuLaser::GetNearClip | ( | ) | const |
Get near clip.
double gazebo::rendering::GpuLaser::GetRayCountRatio | ( | ) | const |
Get the ray count ratio (equivalent to aspect ratio)
double gazebo::rendering::GpuLaser::GetVertFOV | ( | ) | const |
Get the vertical field-of-view.
double gazebo::rendering::GpuLaser::GetVertHalfAngle | ( | ) | const |
Get (vertical_max_angle + vertical_min_angle) * 0.5.
|
virtual |
Initialize the camera.
Reimplemented from gazebo::rendering::Camera.
bool gazebo::rendering::GpuLaser::IsHorizontal | ( | ) | const |
Gets if sensor is horizontal.
|
virtual |
|
virtual |
Load the camera with default parmeters.
Reimplemented from gazebo::rendering::Camera.
|
virtual |
|
virtual |
void gazebo::rendering::GpuLaser::SetCameraCount | ( | double | _cameraCount | ) |
Set the number of cameras required.
[in] | _cameraCount | The number of cameras required to generate the rays |
void gazebo::rendering::GpuLaser::SetCosHorzFOV | ( | double | _chfov | ) |
Set the Cos Horz FOV.
[in] | _chfov | Cos Horz FOV |
void gazebo::rendering::GpuLaser::SetCosVertFOV | ( | double | _cvfov | ) |
Set the Cos Horz FOV.
[in] | _cvfov | Cos Horz FOV |
void gazebo::rendering::GpuLaser::SetFarClip | ( | double | _far | ) |
Set the far clip distance.
[in] | _far | far clip distance |
void gazebo::rendering::GpuLaser::SetHorzFOV | ( | double | _hfov | ) |
Set the horizontal fov.
[in] | _hfov | horizontal fov |
void gazebo::rendering::GpuLaser::SetHorzHalfAngle | ( | double | _angle | ) |
Set the horizontal half angle.
[in] | _angle | horizontal half angle |
void gazebo::rendering::GpuLaser::SetIsHorizontal | ( | bool | _horizontal | ) |
Set sensor horizontal or vertical.
[in] | _horizontal | True if horizontal, false if not |
void gazebo::rendering::GpuLaser::SetNearClip | ( | double | _near | ) |
Set the near clip distance.
[in] | _near | near clip distance |
void gazebo::rendering::GpuLaser::SetRangeCount | ( | unsigned int | _w, |
unsigned int | _h = 1 |
||
) |
Set the number of laser samples in the width and height.
[in] | _w | Number of samples in the horizontal sweep |
[in] | _h | Number of samples in the vertical sweep |
void gazebo::rendering::GpuLaser::SetRayCountRatio | ( | double | _rayCountRatio | ) |
Sets the ray count ratio (equivalen to aspect ratio)
[in] | _rayCountRatio | ray count ratio (equivalent to aspect ratio) |
void gazebo::rendering::GpuLaser::SetVertFOV | ( | double | _vfov | ) |
Set the vertical fov.
[in] | _vfov | vertical fov |
void gazebo::rendering::GpuLaser::SetVertHalfAngle | ( | double | _angle | ) |
Set the vertical half angle.
[in] | _angle | vertical half angle |
|
protected |
Number of cameras needed to generate the rays.
|
protected |
Cos horizontal field-of-view.
|
protected |
Cos vertical field-of-view.
|
protected |
Far clip plane.
|
protected |
Horizontal field-of-view.
|
protected |
Horizontal half angle.
|
protected |
True if the sensor is horizontal only.
|
protected |
Near clip plane.
|
protected |
Ray count ratio.
|
protected |
Vertical half angle.
|
protected |
Vertical field-of-view.