Public Member Functions | Private Attributes | List of all members
stdr_gui::CRobotVisualisation Class Reference

Implements the functionalities of the robot visualization widget. Inherits form QWidget and Ui_robotVisualization (auto created from ui file) More...

#include <stdr_robot_visualization.h>

Inheritance diagram for stdr_gui::CRobotVisualisation:
Inheritance graph
[legend]

Public Member Functions

void closeEvent (QCloseEvent *event)
 Called when the close event is triggered. More...
 
 CRobotVisualisation (QString name, float resolution)
 Default contructor. More...
 
void destruct (void)
 Destroys the visualizer. More...
 
bool getActive (void)
 Returns true if the visualizer is active. More...
 
int getInternalImageSize (void)
 Returns the internal image size. More...
 
void setCurrentPose (geometry_msgs::Pose2D pose)
 Sets the robot's current pose. More...
 
void setCurrentSpeed (std::vector< float > msg)
 Sets the robot's current speed. More...
 
void setImage (QImage img)
 Sets the image to be shown. More...
 
 ~CRobotVisualisation (void)
 Default destructor. More...
 

Private Attributes

bool active_
 < True if the visualizer is active More...
 
QImage internal_image_
 A void image. More...
 
QString name_
 
float resolution_
 The image to draw into. More...
 
QImage void_image_
 The robot frame id. More...
 

Detailed Description

Implements the functionalities of the robot visualization widget. Inherits form QWidget and Ui_robotVisualization (auto created from ui file)

Definition at line 38 of file stdr_robot_visualization.h.

Constructor & Destructor Documentation

stdr_gui::CRobotVisualisation::CRobotVisualisation ( QString  name,
float  resolution 
)

Default contructor.

Parameters
name[QString] Robot frame id
resolution[float] Map resolution
Returns
void

Definition at line 32 of file stdr_robot_visualization.cpp.

stdr_gui::CRobotVisualisation::~CRobotVisualisation ( void  )

Default destructor.

Returns
void

Definition at line 52 of file stdr_robot_visualization.cpp.

Member Function Documentation

void stdr_gui::CRobotVisualisation::closeEvent ( QCloseEvent *  event)

Called when the close event is triggered.

Parameters
event[QCloseEvent*] The close event
Returns
void

Definition at line 75 of file stdr_robot_visualization.cpp.

void stdr_gui::CRobotVisualisation::destruct ( void  )

Destroys the visualizer.

Returns
void

Definition at line 61 of file stdr_robot_visualization.cpp.

bool stdr_gui::CRobotVisualisation::getActive ( void  )

Returns true if the visualizer is active.

Returns
bool

Definition at line 85 of file stdr_robot_visualization.cpp.

int stdr_gui::CRobotVisualisation::getInternalImageSize ( void  )

Returns the internal image size.

Returns
int : Width of the internal image
void stdr_gui::CRobotVisualisation::setCurrentPose ( geometry_msgs::Pose2D  pose)

Sets the robot's current pose.

Parameters
pose[geometry_msgs::Pose2D] the robot pose
Returns
void

Definition at line 107 of file stdr_robot_visualization.cpp.

void stdr_gui::CRobotVisualisation::setCurrentSpeed ( std::vector< float >  msg)

Sets the robot's current speed.

Parameters
msg[std::vector<float>] the robot speeds
Returns
void
Parameters
msg[std::pair<float,float>] the robot speeds
Returns
void

Definition at line 122 of file stdr_robot_visualization.cpp.

void stdr_gui::CRobotVisualisation::setImage ( QImage  img)

Sets the image to be shown.

Parameters
img[QImage] The drawn image
Returns
void

Definition at line 95 of file stdr_robot_visualization.cpp.

Member Data Documentation

bool stdr_gui::CRobotVisualisation::active_
private

< True if the visualizer is active

The map resolution

Definition at line 45 of file stdr_robot_visualization.h.

QImage stdr_gui::CRobotVisualisation::internal_image_
private

A void image.

Definition at line 49 of file stdr_robot_visualization.h.

QString stdr_gui::CRobotVisualisation::name_
private

Definition at line 53 of file stdr_robot_visualization.h.

float stdr_gui::CRobotVisualisation::resolution_
private

The image to draw into.

Definition at line 47 of file stdr_robot_visualization.h.

QImage stdr_gui::CRobotVisualisation::void_image_
private

The robot frame id.

Definition at line 51 of file stdr_robot_visualization.h.


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


stdr_gui
Author(s): Manos Tsardoulias
autogenerated on Mon Jun 10 2019 15:15:17