Public Slots | Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | List of all members
rqt_human_radar::RadarCanvas Class Reference

#include <RadarCanvas.hpp>

Inheritance diagram for rqt_human_radar::RadarCanvas:
Inheritance graph
[legend]

Public Slots

void showId ()
 Reading the user preference about showing or not people ID. More...
 
void updatePixelPerMeter ()
 Updating the pixel-per-meter value. More...
 

Public Member Functions

 RadarCanvas (QWidget *parent, Ui::RadarTabs *ui)
 Constructor. More...
 
virtual ~RadarCanvas ()
 Destructor. More...
 

Protected Member Functions

void mousePressEvent (QMouseEvent *event) override
 overriding the mousePressEvent virtual function More...
 
void paintEvent (QPaintEvent *event) override
 overriding the paintEvent virtual function. More...
 
void resizeEvent (QResizeEvent *event) override
 overriding the resizeEvent virtual function. More...
 

Private Member Functions

bool inScreen (double &x, double &y) const
 returns whether or not a point is inside the canvas. More...
 
void updateArcsToDraw ()
 updates the number of arcs to draw. More...
 

Private Attributes

QFont anglesFont_
 
int arcsToDraw_
 
QBrush evenBrush_
 
QFont font_
 
hri::HRIListener hriListener_
 
std::string idClicked_
 
QBrush oddBrush_
 
std::string package_
 
std::map< std::string, QPolygon > peoplePosition_
 
bool personImageFound
 
std::string personSvgFile_
 
int pixelPerMeter_
 
QPen rangePen_
 
std::string referenceFrame_
 
QImage robotImage_
 
std::string robotImageFile_
 
bool robotImageFound
 
Qt::CheckState showIdValue_
 
QSvgRenderer svgRenderer_
 
bool svgRendererInitialized_
 
tf::TransformListener tfListener_
 
QTimer * timer_
 
Ui::RadarTabs * ui_
 
geometry_msgs::Vector3Stamped versor_
 
QWidget * widget_
 
double xOffset_
 
double yOffset_
 

Detailed Description

Definition at line 43 of file RadarCanvas.hpp.

Constructor & Destructor Documentation

◆ RadarCanvas()

rqt_human_radar::RadarCanvas::RadarCanvas ( QWidget *  parent,
Ui::RadarTabs *  ui 
)

Constructor.

Definition at line 33 of file RadarCanvas.cpp.

◆ ~RadarCanvas()

rqt_human_radar::RadarCanvas::~RadarCanvas ( )
virtual

Destructor.

Definition at line 105 of file RadarCanvas.cpp.

Member Function Documentation

◆ inScreen()

bool rqt_human_radar::RadarCanvas::inScreen ( double &  x,
double &  y 
) const
private

returns whether or not a point is inside the canvas.

Definition at line 371 of file RadarCanvas.cpp.

◆ mousePressEvent()

void rqt_human_radar::RadarCanvas::mousePressEvent ( QMouseEvent *  event)
overrideprotected

overriding the mousePressEvent virtual function

Inherited from QWidget. Stores the id of the person icon the user has clicked on, if any.

Definition at line 362 of file RadarCanvas.cpp.

◆ paintEvent()

void rqt_human_radar::RadarCanvas::paintEvent ( QPaintEvent *  event)
overrideprotected

overriding the paintEvent virtual function.

Inherited from QWidget. Paints the entire radar canvas.

Definition at line 108 of file RadarCanvas.cpp.

◆ resizeEvent()

void rqt_human_radar::RadarCanvas::resizeEvent ( QResizeEvent *  event)
overrideprotected

overriding the resizeEvent virtual function.

Inherited from QWidget. Updates some painting parameters according to the new size of the window.

Definition at line 345 of file RadarCanvas.cpp.

◆ showId

void rqt_human_radar::RadarCanvas::showId ( )
slot

Reading the user preference about showing or not people ID.

The preference is expressed in settings, through a tick-box. Currently, person ID = <body_id>

Definition at line 357 of file RadarCanvas.cpp.

◆ updateArcsToDraw()

void rqt_human_radar::RadarCanvas::updateArcsToDraw ( )
private

updates the number of arcs to draw.

The numbers of arcs to draw is defined by the current size of the canvas.

Definition at line 375 of file RadarCanvas.cpp.

◆ updatePixelPerMeter

void rqt_human_radar::RadarCanvas::updatePixelPerMeter ( )
slot

Updating the pixel-per-meter value.

Definition at line 351 of file RadarCanvas.cpp.

Member Data Documentation

◆ anglesFont_

QFont rqt_human_radar::RadarCanvas::anglesFont_
private

Definition at line 112 of file RadarCanvas.hpp.

◆ arcsToDraw_

int rqt_human_radar::RadarCanvas::arcsToDraw_
private

Definition at line 126 of file RadarCanvas.hpp.

◆ evenBrush_

QBrush rqt_human_radar::RadarCanvas::evenBrush_
private

Definition at line 111 of file RadarCanvas.hpp.

◆ font_

QFont rqt_human_radar::RadarCanvas::font_
private

Definition at line 112 of file RadarCanvas.hpp.

◆ hriListener_

hri::HRIListener rqt_human_radar::RadarCanvas::hriListener_
private

Definition at line 105 of file RadarCanvas.hpp.

◆ idClicked_

std::string rqt_human_radar::RadarCanvas::idClicked_
private

Definition at line 138 of file RadarCanvas.hpp.

◆ oddBrush_

QBrush rqt_human_radar::RadarCanvas::oddBrush_
private

Definition at line 111 of file RadarCanvas.hpp.

◆ package_

std::string rqt_human_radar::RadarCanvas::package_
private

Definition at line 117 of file RadarCanvas.hpp.

◆ peoplePosition_

std::map<std::string, QPolygon> rqt_human_radar::RadarCanvas::peoplePosition_
private

Definition at line 118 of file RadarCanvas.hpp.

◆ personImageFound

bool rqt_human_radar::RadarCanvas::personImageFound
private

Definition at line 116 of file RadarCanvas.hpp.

◆ personSvgFile_

std::string rqt_human_radar::RadarCanvas::personSvgFile_
private

Definition at line 117 of file RadarCanvas.hpp.

◆ pixelPerMeter_

int rqt_human_radar::RadarCanvas::pixelPerMeter_
private

Definition at line 124 of file RadarCanvas.hpp.

◆ rangePen_

QPen rqt_human_radar::RadarCanvas::rangePen_
private

Definition at line 110 of file RadarCanvas.hpp.

◆ referenceFrame_

std::string rqt_human_radar::RadarCanvas::referenceFrame_
private

Definition at line 141 of file RadarCanvas.hpp.

◆ robotImage_

QImage rqt_human_radar::RadarCanvas::robotImage_
private

Definition at line 115 of file RadarCanvas.hpp.

◆ robotImageFile_

std::string rqt_human_radar::RadarCanvas::robotImageFile_
private

Definition at line 117 of file RadarCanvas.hpp.

◆ robotImageFound

bool rqt_human_radar::RadarCanvas::robotImageFound
private

Definition at line 116 of file RadarCanvas.hpp.

◆ showIdValue_

Qt::CheckState rqt_human_radar::RadarCanvas::showIdValue_
private

Definition at line 128 of file RadarCanvas.hpp.

◆ svgRenderer_

QSvgRenderer rqt_human_radar::RadarCanvas::svgRenderer_
private

Definition at line 121 of file RadarCanvas.hpp.

◆ svgRendererInitialized_

bool rqt_human_radar::RadarCanvas::svgRendererInitialized_
private

Definition at line 122 of file RadarCanvas.hpp.

◆ tfListener_

tf::TransformListener rqt_human_radar::RadarCanvas::tfListener_
private

Definition at line 106 of file RadarCanvas.hpp.

◆ timer_

QTimer* rqt_human_radar::RadarCanvas::timer_
private

Definition at line 103 of file RadarCanvas.hpp.

◆ ui_

Ui::RadarTabs* rqt_human_radar::RadarCanvas::ui_
private

Definition at line 135 of file RadarCanvas.hpp.

◆ versor_

geometry_msgs::Vector3Stamped rqt_human_radar::RadarCanvas::versor_
private

Definition at line 107 of file RadarCanvas.hpp.

◆ widget_

QWidget* rqt_human_radar::RadarCanvas::widget_
private

Definition at line 134 of file RadarCanvas.hpp.

◆ xOffset_

double rqt_human_radar::RadarCanvas::xOffset_
private

Definition at line 131 of file RadarCanvas.hpp.

◆ yOffset_

double rqt_human_radar::RadarCanvas::yOffset_
private

Definition at line 131 of file RadarCanvas.hpp.


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


rqt_human_radar
Author(s): Lorenzo Ferrini
autogenerated on Fri Dec 16 2022 03:43:38