34 resolution_(resolution)
37 setWindowTitle(
name_);
43 QImage::Format_RGB32);
98 robotImage->setPixmap(
110 QString(
"\tx = ") + QString().setNum(pose.x) + QString(
" m"));
112 QString(
"\ty = ") + QString().setNum(pose.y) + QString(
" m"));
113 robotPoseTheta->setText(
114 QString(
"\ttheta = ") + QString().setNum(pose.theta) + QString(
" rad"));
124 robotSpeedLinear->setText(
125 QString(
"\tu_x = ") + QString().setNum(msg[0]) + QString(
" m/s"));
126 robotSpeedLinearY->setText(
127 QString(
"\tu_y = ") + QString().setNum(msg[1]) + QString(
" m/s"));
128 robotSpeedAngular->setText(
129 QString(
"\tw = ") + QString().setNum(msg[2]) + QString(
" rad/s"));
bool getActive(void)
Returns true if the visualizer is active.
QImage internal_image_
A void image.
void setCurrentSpeed(std::vector< float > msg)
Sets the robot's current speed.
void setCurrentPose(geometry_msgs::Pose2D pose)
Sets the robot's current pose.
void closeEvent(QCloseEvent *event)
Called when the close event is triggered.
QImage void_image_
The robot frame id.
void setImage(QImage img)
Sets the image to be shown.
CRobotVisualisation(QString name, float resolution)
Default contructor.
bool active_
< True if the visualizer is active
The main namespace for STDR GUI.
void destruct(void)
Destroys the visualizer.
~CRobotVisualisation(void)
Default destructor.