DynamicLines Class Reference

Class for drawing lines that can change. More...

#include <rendering/rendering.hh>

Inherits DynamicRenderable.

Public Member Functions

 DynamicLines (RenderOpType _opType=RENDERING_LINE_STRIP)
 Constructor. More...
 
virtual ~DynamicLines ()
 Destructor. More...
 
void AddPoint (const math::Vector3 &_pt, const common::Color &_color=common::Color::White) GAZEBO_DEPRECATED(7.0)
 Add a point to the point list. More...
 
void AddPoint (const ignition::math::Vector3d &_pt, const common::Color &_color=common::Color::White)
 Add a point to the point list. More...
 
void AddPoint (double _x, double _y, double _z, const common::Color &_color=common::Color::White)
 Add a point to the point list. More...
 
void Clear ()
 Remove all points from the point list. More...
 
virtual Ogre::Real getBoundingRadius () const
 Implementation of Ogre::SimpleRenderable. More...
 
virtual const Ogre::String & getMovableType () const
 Overridden function from Ogre's base class. More...
 
std::string GetMovableType () const
 Get type of movable. More...
 
RenderOpType GetOperationType () const
 Get the render operation type. More...
 
math::Vector3 GetPoint (unsigned int _index) const GAZEBO_DEPRECATED(7.0)
 Return the location of an existing point in the point list. More...
 
unsigned int GetPointCount () const
 Return the total number of points in the point list. More...
 
virtual Ogre::Real getSquaredViewDepth (const Ogre::Camera *_cam) const
 Implementation of Ogre::SimpleRenderable. More...
 
void Init (RenderOpType _opType, bool _useIndices=false)
 Initializes the dynamic renderable. More...
 
ignition::math::Vector3d Point (const unsigned int _index) const
 Return the location of an existing point in the point list. More...
 
void SetColor (unsigned int _index, const common::Color &_color)
 Change the color of an existing point in the point list. More...
 
void SetOperationType (RenderOpType _opType)
 Set the render operation type. More...
 
void SetPoint (unsigned int _index, const math::Vector3 &_value) GAZEBO_DEPRECATED(7.0)
 Change the location of an existing point in the point list. More...
 
void SetPoint (const unsigned int _index, const ignition::math::Vector3d &_value)
 Change the location of an existing point in the point list. More...
 
void Update ()
 Call this to update the hardware buffer after making changes. More...
 

Static Public Member Functions

static std::string GetMovableType ()
 Get type of movable. More...
 

Protected Member Functions

void PrepareHardwareBuffers (size_t _vertexCount, size_t _indexCount)
 Prepares the hardware buffers for the requested vertex and index counts. More...
 

Protected Attributes

size_t indexBufferCapacity
 Maximum capacity of the currently allocated index buffer. More...
 
size_t vertexBufferCapacity
 Maximum capacity of the currently allocated vertex buffer. More...
 

Detailed Description

Class for drawing lines that can change.

Constructor & Destructor Documentation

Constructor.

Parameters
[in]_opTypeThe type of Line
virtual ~DynamicLines ( )
virtual

Destructor.

Member Function Documentation

void AddPoint ( const math::Vector3 _pt,
const common::Color _color = common::Color::White 
)

Add a point to the point list.

Parameters
[in]_ptmath::Vector3 point
[in]_colorcommon::Color Point color
Deprecated:
See function that accepts ignition::math parameters
void AddPoint ( const ignition::math::Vector3d &  _pt,
const common::Color _color = common::Color::White 
)

Add a point to the point list.

Parameters
[in]_ptignition::math::Vector3d point
[in]_colorcommon::Color Point color
void AddPoint ( double  _x,
double  _y,
double  _z,
const common::Color _color = common::Color::White 
)

Add a point to the point list.

Parameters
[in]_xX position
[in]_yY position
[in]_zZ position
[in]_colorcommon::Color Point color
void Clear ( )

Remove all points from the point list.

virtual Ogre::Real getBoundingRadius ( ) const
virtualinherited

Implementation of Ogre::SimpleRenderable.

Returns
The bounding radius
static std::string GetMovableType ( )
static

Get type of movable.

Returns
This returns "gazebo::dynamiclines"
virtual const Ogre::String& getMovableType ( ) const
virtual

Overridden function from Ogre's base class.

Returns
Returns "gazebo::ogredynamicslines"
std::string GetMovableType ( ) const
inherited

Get type of movable.

Returns
This returns "gazebo::DynamicRenderable"
RenderOpType GetOperationType ( ) const
inherited

Get the render operation type.

Returns
The render operation type.
math::Vector3 GetPoint ( unsigned int  _index) const

Return the location of an existing point in the point list.

Parameters
[in]_indexNumber of the point to return
Returns
math::Vector3 value of the point
Deprecated:
See function that returns an ignition::math object
Exceptions
Throwsan gazebo::common::Exception if the _index is out of bounds
unsigned int GetPointCount ( ) const

Return the total number of points in the point list.

Returns
Number of points
virtual Ogre::Real getSquaredViewDepth ( const Ogre::Camera *  _cam) const
virtualinherited

Implementation of Ogre::SimpleRenderable.

Parameters
[in]_camPointer to the Ogre camera that views the renderable.
Returns
The squared depth in the Camera's view
void Init ( RenderOpType  _opType,
bool  _useIndices = false 
)
inherited

Initializes the dynamic renderable.

Remarks
This function should only be called once. It initializes the render operation, and calls the abstract function CreateVertexDeclaration().
Parameters
[in]_opTypeThe type of render operation to perform.
[in]_useIndicesSpecifies whether to use indices to determine the vertices to use as input.
ignition::math::Vector3d Point ( const unsigned int  _index) const

Return the location of an existing point in the point list.

Parameters
[in]_indexNumber of the point to return
Returns
ignition::math::Vector3d value of the point. A vector of [IGN_DBL_INF, IGN_DBL_INF, IGN_DBL_INF] is returned when then the _index is out of bounds. IGN_DBL_INF==std::numeric_limits<double>::infinity()
void PrepareHardwareBuffers ( size_t  _vertexCount,
size_t  _indexCount 
)
protectedinherited

Prepares the hardware buffers for the requested vertex and index counts.

Remarks
This function must be called before locking the buffers in fillHardwareBuffers(). It guarantees that the hardware buffers are large enough to hold at least the requested number of vertices and indices (if using indices). The buffers are possibly reallocated to achieve this.
The vertex and index count in the render operation are set to
the values of vertexCount and indexCount respectively.
Parameters
[in]_vertexCountThe number of vertices the buffer must hold.
[in]_indexCountThe number of indices the buffer must hold. This parameter is ignored if not using indices.
void SetColor ( unsigned int  _index,
const common::Color _color 
)

Change the color of an existing point in the point list.

Parameters
[in]_indexIndex of the point to set
[in]_colorcommon::Color Pixelcolor color to set the point to
void SetOperationType ( RenderOpType  _opType)
inherited

Set the render operation type.

Parameters
[in]_opTypeThe type of render operation to perform.
void SetPoint ( unsigned int  _index,
const math::Vector3 _value 
)

Change the location of an existing point in the point list.

Parameters
[in]_indexIndex of the point to set
[in]_valuemath::Vector3 value to set the point to
Deprecated:
See function that accepts ignition::math parameters
void SetPoint ( const unsigned int  _index,
const ignition::math::Vector3d &  _value 
)

Change the location of an existing point in the point list.

Parameters
[in]_indexIndex of the point to set
[in]_valueignition::math::Vector3d value to set the point to
void Update ( )

Call this to update the hardware buffer after making changes.

Member Data Documentation

size_t indexBufferCapacity
protectedinherited

Maximum capacity of the currently allocated index buffer.

size_t vertexBufferCapacity
protectedinherited

Maximum capacity of the currently allocated vertex buffer.


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