Public Member Functions | Private Slots | Private Member Functions | Private Attributes | List of all members
Dashboard Class Reference

The Dashboard class provides functionality for the autogenerated ui header. More...

#include "pses_dashboard/dashboard.h"

Inheritance diagram for Dashboard:
Inheritance graph
[legend]

Public Member Functions

 Dashboard (ros::NodeHandle *nh, QWidget *parent=0)
 Dashboard constructor. More...
 
void keyPressEvent (QKeyEvent *event)
 Callback function in case of a key event. More...
 
virtual ~Dashboard ()
 Dashboard default destructor. More...
 

Private Slots

void cameraSelect (int index)
 This function gets called whenever the camera mode changed. More...
 
void centerSteeringClicked ()
 This function gets called whenever the center steering button has been clicked. More...
 
void maxLeftSteeringClicked ()
 This function gets called whenever the max left steering button has been clicked. More...
 
void maxRightSteeringClicked ()
 This function gets called whenever the max right steering button has been clicked. More...
 
void maxSpeedClicked ()
 This function gets called whenever the max speed button has been clicked. More...
 
void minSpeedClicked ()
 This function gets called whenever the min speed button has been clicked. More...
 
void modeSelect (int index)
 This function gets called whenever a mode has been selected. More...
 
void pollNodeHandle ()
 This function gets called whenever the polling timer runs out. More...
 
void toggleDAQ ()
 This function gets called whenever the daq toggle button has been pressed. More...
 
void toggleKinect ()
 This function gets called whenever the kinect toggle button has been pressed. More...
 
void toggleMotor ()
 This function gets called whenever the motor toggle button has been pressed. More...
 
void toggleUS ()
 This function gets called whenever the us toggle button has been pressed. More...
 
void valueChangedSpeed (int value)
 This function gets called whenever the speed slider changed. More...
 
void valueChangedSteering (int value)
 This function gets called whenever the steering slider changed. More...
 
void zeroSpeedClicked ()
 This function gets called whenever the zero speed button has been clicked. More...
 

Private Member Functions

void callGetCarIdServide ()
 Get the id from the ucboard. More...
 
void callGetFirmwareServide ()
 Get the firmware version from the ucboard. More...
 
void callGetSidServide ()
 Get the session id from the ucboard. More...
 
void cameraCallback (const image_msg::ConstPtr &img)
 This function gets called whenever a message has been published to the color image topic. More...
 
void configureVideoFeed ()
 Set up video feed based on launch parameters. More...
 
void connectGuiSignals ()
 Register gui relevant callbacks e.g. buttons, silders etc. More...
 
void depthCallback (const image_msg::ConstPtr &img)
 This function gets called whenever a message has been published to the depth image topic. More...
 
void driveBatteryCallback (const battery_msg::ConstPtr &vdBat)
 This function gets called whenever a message has been published to the drive battery topic. More...
 
void fetchStartupParameters ()
 Get all available launch parameters. More...
 
void hallCntCallback (const uint8_msg::ConstPtr &hallCnt)
 This function gets called whenever a message has been published to the hall count topic. More...
 
void hallDt8Callback (const float64_msg::ConstPtr &hallDt8)
 This function gets called whenever a message has been published to the hall dt 8 topic. More...
 
void hallDtCallback (const float64_msg::ConstPtr &hallDt)
 This function gets called whenever a message has been published to the hall dt topic. More...
 
void imuCallback (const imu_msg::ConstPtr &imu)
 This function gets called whenever a message has been published to the imu topic. More...
 
void initTopicPollingTimer ()
 Ininit ros topic polling timer. More...
 
void magneticCallback (const magnetic_msg::ConstPtr &magnetic)
 This function gets called whenever a message has been published to the magnetic field topic. More...
 
void odomCallback (const odom_msg::ConstPtr &odom)
 This function gets called whenever a message has been published to the odometry topic. More...
 
void reconfigureSpeedSlider ()
 Reconfigure the gui (e.g. speed slider) according to launch paramters. More...
 
void registerRosTopics ()
 Register all published/subscribed ros topics. More...
 
void systemBatteryCallback (const battery_msg::ConstPtr &vsBat)
 This function gets called whenever a message has been published to the system battery topic. More...
 
void usfCallback (const range_msg::ConstPtr &usf)
 This function gets called whenever a message has been published to the front ultra sonic range topic. More...
 
void uslCallback (const range_msg::ConstPtr &usl)
 This function gets called whenever a message has been published to the left ultra sonic range topic. More...
 
void usrCallback (const range_msg::ConstPtr &usr)
 This function gets called whenever a message has been published to the right ultra sonic range topic. More...
 

Private Attributes

int bwdSgn
 
ros::Subscriber cameraSub
 
ros::Subscriber depthSub
 
double distanceTravelled
 
int fwdSgn
 
std::string getCarIdService
 
std::string getFirmwareService
 
std::string getSidService
 
ros::Subscriber hallCntSub
 
std::string hallCntTopic
 
ros::Subscriber hallDt8Sub
 
std::string hallDt8Topic
 
ros::Subscriber hallDtSub
 
std::string hallDtTopic
 
std::string imageColorTopic
 
std::string imageDepthTopic
 
ros::Subscriber imuSub
 
std::string imuTopic
 
int leftSgn
 
ros::Subscriber magneticSub
 
std::string magneticTopic
 
int maxForwardSpeed
 
int maxLeftSteering
 
int maxReverseSpeed
 
int maxRightSteering
 
string_msg mode
 
ros::Publisher modeControl
 
std::string modeControlTopic
 
ros::Publisher motorCommand
 
std::string motorCommandTopic
 
int16_msg motorMessage
 
ros::NodeHandle * nh
 
ros::Subscriber odomSub
 
std::string odomTopic
 
int rightSgn
 
int speedStep
 
ros::Publisher steeringCommand
 
std::string steeringCommandTopic
 
int16_msg steeringMessage
 
int steeringStep
 
QTimer * timer
 
std::string toggleDAQService
 
std::string toggleKinectService
 
std::string toggleMotorService
 
std::string toggleUSService
 
Ui::Dashboard * ui
 
ros::Subscriber usfSub
 
std::string usfTopic
 
ros::Subscriber uslSub
 
std::string uslTopic
 
ros::Subscriber usrSub
 
std::string usrTopic
 
ros::Subscriber vdBatSub
 
std::string vdBatTopic
 
std::string videoFeedMode
 
ros::Subscriber vsBatSub
 
std::string vsBatTopic
 
double x
 
double y
 
double z
 

Detailed Description

The Dashboard class provides functionality for the autogenerated ui header.

This class implements the means for the GUI to interface ROS functionality, i.e. publishing and subscribing to topics as well as call ROS services. The Dashboard GUI is meant to be used in combination with the pses_ucbridge or the pses_simulation package, since its build around the pses robot functionality.

Definition at line 218 of file dashboard.h.

Constructor & Destructor Documentation

Dashboard::Dashboard ( ros::NodeHandle *  nh,
QWidget *  parent = 0 
)
explicit

Dashboard constructor.

Parameters
[in]nhros::NodeHandle object needed to interact with the ros framework.
[in]parentoptional parameter to signal if this is a sub widget of another ui container.

Definition at line 9 of file dashboard.cpp.

Dashboard::~Dashboard ( )
virtual

Dashboard default destructor.

Definition at line 36 of file dashboard.cpp.

Member Function Documentation

void Dashboard::callGetCarIdServide ( )
private

Get the id from the ucboard.

Definition at line 352 of file dashboard.cpp.

void Dashboard::callGetFirmwareServide ( )
private

Get the firmware version from the ucboard.

Definition at line 335 of file dashboard.cpp.

void Dashboard::callGetSidServide ( )
private

Get the session id from the ucboard.

Definition at line 369 of file dashboard.cpp.

void Dashboard::cameraCallback ( const image_msg::ConstPtr &  img)
private

This function gets called whenever a message has been published to the color image topic.

It decides how to display the revceived data.

Definition at line 504 of file dashboard.cpp.

void Dashboard::cameraSelect ( int  index)
privateslot

This function gets called whenever the camera mode changed.

It subscribes to the selected camera topic and displays its output.

Definition at line 705 of file dashboard.cpp.

void Dashboard::centerSteeringClicked ( )
privateslot

This function gets called whenever the center steering button has been clicked.

It published zero on the steering level topic.

Definition at line 790 of file dashboard.cpp.

void Dashboard::configureVideoFeed ( )
private

Set up video feed based on launch parameters.

Definition at line 386 of file dashboard.cpp.

void Dashboard::connectGuiSignals ( )
private

Register gui relevant callbacks e.g. buttons, silders etc.

Definition at line 415 of file dashboard.cpp.

void Dashboard::depthCallback ( const image_msg::ConstPtr &  img)
private

This function gets called whenever a message has been published to the depth image topic.

It decides how to display the revceived data.

Definition at line 511 of file dashboard.cpp.

void Dashboard::driveBatteryCallback ( const battery_msg::ConstPtr &  vdBat)
private

This function gets called whenever a message has been published to the drive battery topic.

It decides how to display the revceived data.

Definition at line 494 of file dashboard.cpp.

void Dashboard::fetchStartupParameters ( )
private

Get all available launch parameters.

Definition at line 38 of file dashboard.cpp.

void Dashboard::hallCntCallback ( const uint8_msg::ConstPtr &  hallCnt)
private

This function gets called whenever a message has been published to the hall count topic.

It decides how to display the revceived data.

Definition at line 479 of file dashboard.cpp.

void Dashboard::hallDt8Callback ( const float64_msg::ConstPtr &  hallDt8)
private

This function gets called whenever a message has been published to the hall dt 8 topic.

It decides how to display the revceived data.

Definition at line 489 of file dashboard.cpp.

void Dashboard::hallDtCallback ( const float64_msg::ConstPtr &  hallDt)
private

This function gets called whenever a message has been published to the hall dt topic.

It decides how to display the revceived data.

Definition at line 484 of file dashboard.cpp.

void Dashboard::imuCallback ( const imu_msg::ConstPtr &  imu)
private

This function gets called whenever a message has been published to the imu topic.

It decides how to display the revceived data.

Definition at line 447 of file dashboard.cpp.

void Dashboard::initTopicPollingTimer ( )
private

Ininit ros topic polling timer.

This is needed in case of prolonged inactivity from topics.

Definition at line 440 of file dashboard.cpp.

void Dashboard::keyPressEvent ( QKeyEvent *  event)

Callback function in case of a key event.

This function decides what to do in case of a pressed key event.

Parameters
[in]eventsignals what key has been pressed

Definition at line 569 of file dashboard.cpp.

void Dashboard::magneticCallback ( const magnetic_msg::ConstPtr &  magnetic)
private

This function gets called whenever a message has been published to the magnetic field topic.

It decides how to display the revceived data.

Definition at line 457 of file dashboard.cpp.

void Dashboard::maxLeftSteeringClicked ( )
privateslot

This function gets called whenever the max left steering button has been clicked.

It published the max left steering on the steering level topic.

Definition at line 770 of file dashboard.cpp.

void Dashboard::maxRightSteeringClicked ( )
privateslot

This function gets called whenever the max right steering button has been clicked.

It published the max right steering on the steering level topic.

Definition at line 780 of file dashboard.cpp.

void Dashboard::maxSpeedClicked ( )
privateslot

This function gets called whenever the max speed button has been clicked.

It published the max forward speed on the motor level topic.

Definition at line 740 of file dashboard.cpp.

void Dashboard::minSpeedClicked ( )
privateslot

This function gets called whenever the min speed button has been clicked.

It published the max reverse speed on the motor level topic.

Definition at line 750 of file dashboard.cpp.

void Dashboard::modeSelect ( int  index)
privateslot

This function gets called whenever a mode has been selected.

It published the selected mode on a mode selection topic.

Definition at line 698 of file dashboard.cpp.

void Dashboard::odomCallback ( const odom_msg::ConstPtr &  odom)
private

This function gets called whenever a message has been published to the odometry topic.

It decides how to display the revceived data.

Definition at line 532 of file dashboard.cpp.

void Dashboard::pollNodeHandle ( )
privateslot

This function gets called whenever the polling timer runs out.

It polls the queues of subscribed/published ros topics.

Definition at line 644 of file dashboard.cpp.

void Dashboard::reconfigureSpeedSlider ( )
private

Reconfigure the gui (e.g. speed slider) according to launch paramters.

Definition at line 286 of file dashboard.cpp.

void Dashboard::registerRosTopics ( )
private

Register all published/subscribed ros topics.

Definition at line 306 of file dashboard.cpp.

void Dashboard::systemBatteryCallback ( const battery_msg::ConstPtr &  vsBat)
private

This function gets called whenever a message has been published to the system battery topic.

It decides how to display the revceived data.

Definition at line 499 of file dashboard.cpp.

void Dashboard::toggleDAQ ( )
privateslot

This function gets called whenever the daq toggle button has been pressed.

It calls the ros::Service to toggle the daq.

Definition at line 686 of file dashboard.cpp.

void Dashboard::toggleKinect ( )
privateslot

This function gets called whenever the kinect toggle button has been pressed.

It calls the ros::Service to toggle the kinect power supply.

Definition at line 650 of file dashboard.cpp.

void Dashboard::toggleMotor ( )
privateslot

This function gets called whenever the motor toggle button has been pressed.

It calls the ros::Service to toggle the motor control.

Definition at line 674 of file dashboard.cpp.

void Dashboard::toggleUS ( )
privateslot

This function gets called whenever the us toggle button has been pressed.

It calls the ros::Service to toggle the ultra sonic range sensors.

Definition at line 662 of file dashboard.cpp.

void Dashboard::usfCallback ( const range_msg::ConstPtr &  usf)
private

This function gets called whenever a message has been published to the front ultra sonic range topic.

It decides how to display the revceived data.

Definition at line 474 of file dashboard.cpp.

void Dashboard::uslCallback ( const range_msg::ConstPtr &  usl)
private

This function gets called whenever a message has been published to the left ultra sonic range topic.

It decides how to display the revceived data.

Definition at line 469 of file dashboard.cpp.

void Dashboard::usrCallback ( const range_msg::ConstPtr &  usr)
private

This function gets called whenever a message has been published to the right ultra sonic range topic.

It decides how to display the revceived data.

Definition at line 464 of file dashboard.cpp.

void Dashboard::valueChangedSpeed ( int  value)
privateslot

This function gets called whenever the speed slider changed.

It published the selected speed on the motor level topic.

Definition at line 726 of file dashboard.cpp.

void Dashboard::valueChangedSteering ( int  value)
privateslot

This function gets called whenever the steering slider changed.

It published the selected speed on the steering level topic.

Definition at line 733 of file dashboard.cpp.

void Dashboard::zeroSpeedClicked ( )
privateslot

This function gets called whenever the zero speed button has been clicked.

It published zero on the motor level topic.

Definition at line 760 of file dashboard.cpp.

Member Data Documentation

int Dashboard::bwdSgn
private

The sign of a certain steering/driving direction.

Definition at line 385 of file dashboard.h.

ros::Subscriber Dashboard::cameraSub
private

Definition at line 397 of file dashboard.h.

ros::Subscriber Dashboard::depthSub
private

ros::Subscriber objects.

Definition at line 397 of file dashboard.h.

double Dashboard::distanceTravelled
private

Current travelled distance (only if odometry available)

Definition at line 391 of file dashboard.h.

int Dashboard::fwdSgn
private

Definition at line 385 of file dashboard.h.

std::string Dashboard::getCarIdService
private

Definition at line 377 of file dashboard.h.

std::string Dashboard::getFirmwareService
private

Definition at line 377 of file dashboard.h.

std::string Dashboard::getSidService
private

Definition at line 377 of file dashboard.h.

ros::Subscriber Dashboard::hallCntSub
private

Definition at line 397 of file dashboard.h.

std::string Dashboard::hallCntTopic
private

Definition at line 377 of file dashboard.h.

ros::Subscriber Dashboard::hallDt8Sub
private

Definition at line 397 of file dashboard.h.

std::string Dashboard::hallDt8Topic
private

Definition at line 377 of file dashboard.h.

ros::Subscriber Dashboard::hallDtSub
private

Definition at line 397 of file dashboard.h.

std::string Dashboard::hallDtTopic
private

Definition at line 377 of file dashboard.h.

std::string Dashboard::imageColorTopic
private

Definition at line 377 of file dashboard.h.

std::string Dashboard::imageDepthTopic
private

Definition at line 377 of file dashboard.h.

ros::Subscriber Dashboard::imuSub
private

Definition at line 397 of file dashboard.h.

std::string Dashboard::imuTopic
private

Definition at line 377 of file dashboard.h.

int Dashboard::leftSgn
private

Definition at line 385 of file dashboard.h.

ros::Subscriber Dashboard::magneticSub
private

Definition at line 397 of file dashboard.h.

std::string Dashboard::magneticTopic
private

Definition at line 377 of file dashboard.h.

int Dashboard::maxForwardSpeed
private

Definition at line 383 of file dashboard.h.

int Dashboard::maxLeftSteering
private

Definition at line 383 of file dashboard.h.

int Dashboard::maxReverseSpeed
private

Definition at line 383 of file dashboard.h.

int Dashboard::maxRightSteering
private

Definition at line 383 of file dashboard.h.

string_msg Dashboard::mode
private

Current driving mode

Definition at line 390 of file dashboard.h.

ros::Publisher Dashboard::modeControl
private

Definition at line 395 of file dashboard.h.

std::string Dashboard::modeControlTopic
private

Definition at line 377 of file dashboard.h.

ros::Publisher Dashboard::motorCommand
private

Definition at line 395 of file dashboard.h.

std::string Dashboard::motorCommandTopic
private

Definition at line 377 of file dashboard.h.

int16_msg Dashboard::motorMessage
private

Current motor level

Definition at line 388 of file dashboard.h.

ros::NodeHandle* Dashboard::nh
private

Pointer to a ros::NodeHandle object.

Definition at line 376 of file dashboard.h.

ros::Subscriber Dashboard::odomSub
private

Definition at line 397 of file dashboard.h.

std::string Dashboard::odomTopic
private

Subscribed/Published topic names.

Definition at line 377 of file dashboard.h.

int Dashboard::rightSgn
private

Definition at line 385 of file dashboard.h.

int Dashboard::speedStep
private

Definition at line 383 of file dashboard.h.

ros::Publisher Dashboard::steeringCommand
private

ros::Publisher objects.

Definition at line 395 of file dashboard.h.

std::string Dashboard::steeringCommandTopic
private

Definition at line 377 of file dashboard.h.

int16_msg Dashboard::steeringMessage
private

Current steering level

Definition at line 389 of file dashboard.h.

int Dashboard::steeringStep
private

Gui parameter

Definition at line 383 of file dashboard.h.

QTimer* Dashboard::timer
private

Ros queue polling timer.

Definition at line 400 of file dashboard.h.

std::string Dashboard::toggleDAQService
private

Definition at line 377 of file dashboard.h.

std::string Dashboard::toggleKinectService
private

Definition at line 377 of file dashboard.h.

std::string Dashboard::toggleMotorService
private

Definition at line 377 of file dashboard.h.

std::string Dashboard::toggleUSService
private

Definition at line 377 of file dashboard.h.

Ui::Dashboard* Dashboard::ui
private

Pointer to the auto generated ui implementation.

Definition at line 375 of file dashboard.h.

ros::Subscriber Dashboard::usfSub
private

Definition at line 397 of file dashboard.h.

std::string Dashboard::usfTopic
private

Definition at line 377 of file dashboard.h.

ros::Subscriber Dashboard::uslSub
private

Definition at line 397 of file dashboard.h.

std::string Dashboard::uslTopic
private

Definition at line 377 of file dashboard.h.

ros::Subscriber Dashboard::usrSub
private

Definition at line 397 of file dashboard.h.

std::string Dashboard::usrTopic
private

Definition at line 377 of file dashboard.h.

ros::Subscriber Dashboard::vdBatSub
private

Definition at line 397 of file dashboard.h.

std::string Dashboard::vdBatTopic
private

Definition at line 377 of file dashboard.h.

std::string Dashboard::videoFeedMode
private

Selected video feed mode

Definition at line 387 of file dashboard.h.

ros::Subscriber Dashboard::vsBatSub
private

Definition at line 397 of file dashboard.h.

std::string Dashboard::vsBatTopic
private

Definition at line 377 of file dashboard.h.

double Dashboard::x
private

Definition at line 393 of file dashboard.h.

double Dashboard::y
private

Definition at line 393 of file dashboard.h.

double Dashboard::z
private

Current position (only if odometry available)

Definition at line 393 of file dashboard.h.


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


pses_dashboard
Author(s): Sebastian Ehmes
autogenerated on Sat Oct 28 2017 14:12:28