Public Member Functions | Static Public Member Functions | List of all members
gazebo::rendering::DynamicLines Class Reference

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

#include <rendering/rendering.hh>

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

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 const Ogre::String & getMovableType () const
 Overridden function from Ogre's base class. 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...
 
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 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...
 
- Public Member Functions inherited from gazebo::rendering::DynamicRenderable
 DynamicRenderable ()
 Constructor. More...
 
virtual ~DynamicRenderable ()
 Virtual destructor. More...
 
virtual Ogre::Real getBoundingRadius () const
 Implementation of Ogre::SimpleRenderable. More...
 
std::string GetMovableType () const
 Get type of movable. More...
 
RenderOpType GetOperationType () const
 Get the render operation type. 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...
 
void SetOperationType (RenderOpType _opType)
 Set the render operation type. More...
 

Static Public Member Functions

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

Additional Inherited Members

- Protected Member Functions inherited from gazebo::rendering::DynamicRenderable
void PrepareHardwareBuffers (size_t _vertexCount, size_t _indexCount)
 Prepares the hardware buffers for the requested vertex and index counts. More...
 
- Protected Attributes inherited from gazebo::rendering::DynamicRenderable
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

gazebo::rendering::DynamicLines::DynamicLines ( RenderOpType  _opType = RENDERING_LINE_STRIP)

Constructor.

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

Destructor.

Member Function Documentation

void gazebo::rendering::DynamicLines::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 gazebo::rendering::DynamicLines::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 gazebo::rendering::DynamicLines::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 gazebo::rendering::DynamicLines::Clear ( )

Remove all points from the point list.

static std::string gazebo::rendering::DynamicLines::GetMovableType ( )
static

Get type of movable.

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

Overridden function from Ogre's base class.

Returns
Returns "gazebo::ogredynamicslines"
math::Vector3 gazebo::rendering::DynamicLines::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 gazebo::rendering::DynamicLines::GetPointCount ( ) const

Return the total number of points in the point list.

Returns
Number of points
ignition::math::Vector3d gazebo::rendering::DynamicLines::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 gazebo::rendering::DynamicLines::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 gazebo::rendering::DynamicLines::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 gazebo::rendering::DynamicLines::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 gazebo::rendering::DynamicLines::Update ( )

Call this to update the hardware buffer after making changes.


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