Gazebo Gazebo

API Reference

3.15.1

Provides buttons for the tape measure tool. More...

#include <TapeMeasure.hh>

Public Slots

double Distance ()
 Callback in Qt thread to get the distance to display in the gui window. More...
 
void OnMeasure ()
 Callback in Qt thread when the new measurement button is clicked. More...
 
void OnReset ()
 Callback in Qt thread when the reset button is clicked. More...
 

Signals

void newDistance ()
 Signal fired when a new tape measure distance is set. More...
 

Public Member Functions

 TapeMeasure ()
 Constructor. More...
 
 ~TapeMeasure () override
 Destructor. More...
 
void DeleteMarker (int _id)
 Deletes the marker with the provided id within the "tape_measure" namespace. More...
 
void DrawLine (int _id, gz::math::Vector3d &_startPoint, gz::math::Vector3d &_endPoint, gz::math::Color &_color)
 Draws a line marker. Called to display the line between the start and end point of the tape measure. More...
 
void DrawPoint (int _id, gz::math::Vector3d &_point, gz::math::Color &_color)
 Draws a point marker. Called to display the start and end point of the tape measure. More...
 
void LoadConfig (const tinyxml2::XMLElement *_pluginElem) override
 
void Measure ()
 Starts a new measurement. Erases any previous measurement in progress or already made. More...
 
void Reset ()
 Resets all of the relevant data for this plugin. Called when the user clicks the reset button and when the user starts a new measurement. More...
 

Protected Member Functions

bool eventFilter (QObject *_obj, QEvent *_event) override
 

Detailed Description

Provides buttons for the tape measure tool.

Constructor & Destructor Documentation

◆ TapeMeasure()

Constructor.

◆ ~TapeMeasure()

~TapeMeasure ( )
override

Destructor.

Member Function Documentation

◆ DeleteMarker()

void DeleteMarker ( int  _id)

Deletes the marker with the provided id within the "tape_measure" namespace.

Parameters
[in]_idThe id of the marker

◆ Distance

double Distance ( )
slot

Callback in Qt thread to get the distance to display in the gui window.

Returns
The distance between the start and end point of the measurement

◆ DrawLine()

void DrawLine ( int  _id,
gz::math::Vector3d _startPoint,
gz::math::Vector3d _endPoint,
gz::math::Color &  _color 
)

Draws a line marker. Called to display the line between the start and end point of the tape measure.

Parameters
[in]_idThe id of the marker
[in]_startPointThe x, y, z coordinates of the line start point
[in]_endPointThe x, y, z coordinates of the line end point
[in]_colorThe rgba color to set the marker

◆ DrawPoint()

void DrawPoint ( int  _id,
gz::math::Vector3d _point,
gz::math::Color &  _color 
)

Draws a point marker. Called to display the start and end point of the tape measure.

Parameters
[in]_idThe id of the marker
[in]_pointThe x, y, z coordinates of where to place the marker
[in]_colorThe rgba color to set the marker

◆ eventFilter()

bool eventFilter ( QObject *  _obj,
QEvent *  _event 
)
overrideprotected

◆ LoadConfig()

void LoadConfig ( const tinyxml2::XMLElement *  _pluginElem)
override

◆ Measure()

void Measure ( )

Starts a new measurement. Erases any previous measurement in progress or already made.

◆ newDistance

void newDistance ( )
signal

Signal fired when a new tape measure distance is set.

◆ OnMeasure

void OnMeasure ( )
slot

Callback in Qt thread when the new measurement button is clicked.

◆ OnReset

void OnReset ( )
slot

Callback in Qt thread when the reset button is clicked.

◆ Reset()

void Reset ( )

Resets all of the relevant data for this plugin. Called when the user clicks the reset button and when the user starts a new measurement.


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