#include <stdr_gui_controller.h>
Public Slots | |
void | co2PlaceSet (QPoint p) |
Gets the point at which the new CO2 source is placed. Connects to the CMapConnector::co2PlaceSet signal. More... | |
void | co2SensorVisibilityClicked (QString robotName, QString co2SensorName) |
Informs CGuiController that a CO2Sensor visibility status has \ been clicked. Connects to the CInfoConnector::co2SensorVisibilityClicked\ signal. More... | |
void | itemClicked (QPoint p, Qt::MouseButton b) |
Informs CGuiController that click has performed in the map. Connects to the CMapConnector::itemClicked signal. More... | |
void | laserVisibilityClicked (QString robotName, QString laserName) |
Informs CGuiController that a laser visibility status has been clicked. Connects to the CInfoConnector::laserVisibilityClicked signal. More... | |
void | laserVisualizerClicked (QString robotName, QString laserName) |
Informs CGuiController that a laser visualizer has been clicked. Connects to the CInfoConnector::laserVisualizerClicked signal. More... | |
void | loadCo2Pressed (void) |
Informs CGuiController that a CO2 source is going to be placed in the environment. Connects to the CGuiConnector::loadCo2Pressed signal. More... | |
void | loadRfidPressed (void) |
Informs CGuiController that an RFID is going to be placed in the environment. Connects to the CGuiConnector::loadRfidPressed signal. More... | |
void | loadRobotFromFilePressed (stdr_msgs::RobotMsg newRobotMsg) |
Informs CGuiController that a robot is loaded from a yaml file. Connects to the CGuiConnector::robotFromFile signal. More... | |
void | loadRobotPressed (stdr_msgs::RobotMsg newRobotMsg) |
Loads a robot from robot creator into map. Connects to the CGuiConnector::CRobotCreatorConnector::loadRobotPressed signal. More... | |
void | loadSoundPressed (void) |
Informs CGuiController that a sound source is going to be placed in the environment. Connects to the CGuiConnector::loadSoundPressed signal. More... | |
void | loadThermalPressed (void) |
Informs CGuiController that a thermal source is going to be placed in the environment. Connects to the CGuiConnector::loadThermalPressed signal. More... | |
void | rfidPlaceSet (QPoint p) |
Gets the point at which the new RFID tag is placed. Connects to the CMapConnector::robotPlaceSet signal. More... | |
void | rfidReaderVisibilityClicked (QString robotName, QString rfidReaderName) |
Informs CGuiController that a rfidReader visibility status has \ been clicked. Connects to the CInfoConnector::rfidReaderVisibilityClicked\ signal. More... | |
void | robotPlaceSet (QPoint p) |
Gets the point at which the new robot is placed. Connects to the CMapConnector::robotPlaceSet signal. More... | |
void | robotReplaceSet (QPoint p, std::string robotName) |
Informs CGuiController about the new pose of a robot. Connects to the CMapConnector::robotReplaceSet signal. More... | |
void | robotVisibilityClicked (QString robotName) |
Informs CGuiController that a robot visibility status has been clicked. Connects to the CInfoConnector::robotVisibilityClicked signal. More... | |
void | robotVisualizerClicked (QString robotName) |
Informs CGuiController that a robot visualizer has been clicked. Connects to the CInfoConnector::robotVisualizerClicked signal. More... | |
void | saveRobotPressed (stdr_msgs::RobotMsg newRobotMsg, QString file_name) |
Saves the robot in a yaml file. Connects to the CGuiConnector::CRobotCreatorConnector::saveRobotPressed signal. More... | |
void | sonarVisibilityClicked (QString robotName, QString sonarName) |
Informs CGuiController that a sonar visibility status has been clicked. Connects to the CInfoConnector::sonarVisibilityClicked signal. More... | |
void | sonarVisualizerClicked (QString robotName, QString sonarName) |
Informs CGuiController that a sonar visualizer has been clicked. Connects to the CInfoConnector::sonarVisualizerClicked signal. More... | |
void | soundPlaceSet (QPoint p) |
Gets the point at which the new sound source is placed. Connects to the CMapConnector::soundPlaceSet signal. More... | |
void | soundSensorVisibilityClicked (QString robotName, QString soundSensorName) |
Informs CGuiController that a sound Sensor visibility status has \ been clicked. Connects to the CInfoConnector::soundSensorVisibilityClicked\ signal. More... | |
void | thermalPlaceSet (QPoint p) |
Gets the point at which the new thermal source is placed. Connects to the CMapConnector::thermalPlaceSet signal. More... | |
void | thermalSensorVisibilityClicked (QString robotName, QString thermalSensorName) |
Informs CGuiController that a Thermal Sensor visibility status has \ been clicked. Connects to the CInfoConnector::thermalSensorVisibilityClicked\ signal. More... | |
void | updateMapInternal (void) |
Updates the map to be shown in GUI. Connects to the timeout signal of timer_. More... | |
void | zoomInPressed (QPoint p) |
Performs zoom in when the button is pressed. Connects to the CMapConnector::zoomInPressed signal. More... | |
void | zoomOutPressed (QPoint p) |
Performs zoom out when the button is pressed. Connects to the CMapConnector::zoomOutPressed signal. More... | |
Signals | |
void | replaceRobot (std::string robotFrameId) |
Is emitted when a robot is going to be re-placed. Connects to the CMapConnector::waitForReplace slot. More... | |
void | setCO2SensorVisibility (QString robotName, QString co2SensorName, char vs) |
Is emitted when a CO2 sensor's visibility status is going to be \ changed. Connects to the CInfoConnector::setCO2SensorVisibility slot. More... | |
void | setLaserVisibility (QString robotName, QString laserName, char vs) |
Is emitted when a laser's visibility status is going to be changed. Connects to the CInfoConnector::setLaserVisibility slot. More... | |
void | setRfidReaderVisibility (QString robotName, QString rfidReaderName, char vs) |
Is emitted when a rfid sensor's visibility status is going to be \ changed. Connects to the CInfoConnector::setRfidReaderVisibility slot. More... | |
void | setRobotVisibility (QString robotName, char vs) |
Is emitted when a robot's visibility status is going to be changed. Connects to the CInfoConnector::setRobotVisibility slot. More... | |
void | setSonarVisibility (QString robotName, QString sonarName, char vs) |
Is emitted when a sonar's visibility status is going to be changed. Connects to the CInfoConnector::setSonarVisibility slot. More... | |
void | setSoundSensorVisibility (QString robotName, QString soundSensorName, char vs) |
Is emitted when a sound sensor's visibility status is going to be \ changed. Connects to the CInfoConnector::setSoundSensorVisibility slot. More... | |
void | setThermalSensorVisibility (QString robotName, QString thermalSensorName, char vs) |
Is emitted when a thermal sensor's visibility status is going to be \ changed. Connects to the CInfoConnector::setThermalSensorVisibility slot. More... | |
void | waitForCo2Pose (void) |
Is emitted when a new CO2 source is going to be placed. Connects to the CMapConnector::waitForCo2Pose slot. More... | |
void | waitForRfidPose (void) |
Is emitted when a new rfid tag is going to be placed. Connects to the CMapConnector::waitForRfidPose slot. More... | |
void | waitForRobotPose (void) |
Is emitted when a new robot is going to be placed. Connects to the CMapConnector::waitForPlace slot. More... | |
void | waitForSoundPose (void) |
Is emitted when a new sound source is going to be placed. Connects to the CMapConnector::waitForSOundPose slot. More... | |
void | waitForThermalPose (void) |
Is emitted when a new thermal source is going to be placed. Connects to the CMapConnector::waitForThermalPose slot. More... | |
Public Member Functions | |
CGuiController (int argc, char **argv) | |
Default contructor. More... | |
void | cleanupVisualizers (const stdr_msgs::RobotIndexedVectorMsg &msg) |
Dumps all visualizers that connect to robots not existent in the input argument message. More... | |
bool | init () |
Initializes the ROS spin and Qt threads. More... | |
void | initializeCommunications (void) |
Initializes the Qt event connections and ROS subscribers and publishers. More... | |
void | receiveCO2Sources (const stdr_msgs::CO2SourceVector &msg) |
Receives the existent co2 sources. More... | |
void | receiveMap (const nav_msgs::OccupancyGrid &msg) |
Receives the occupancy grid map from stdr_server. Connects to "map" ROS topic. More... | |
void | receiveRfids (const stdr_msgs::RfidTagVector &msg) |
Receives the existent rfid tags. More... | |
void | receiveRobots (const stdr_msgs::RobotIndexedVectorMsg &msg) |
Receives the robots from stdr_server. Connects to "stdr_server/active_robots" ROS topic. More... | |
void | receiveSoundSources (const stdr_msgs::SoundSourceVector &msg) |
Receives the existent sound sources. More... | |
void | receiveThermalSources (const stdr_msgs::ThermalSourceVector &msg) |
Receives the existent thermal sources. More... | |
void | setupWidgets (void) |
Sets up the main window widgets. More... | |
~CGuiController (void) | |
Default destructor. More... | |
Private Types | |
typedef std::map< QString, CGuiCo2Source >::iterator | Co2SourcesIterator |
typedef std::map< QString, CLaserVisualisation * >::iterator | LaserVisIterator |
typedef std::map< QString, CGuiRfidTag >::iterator | RfidTagIterator |
typedef std::map< QString, CRobotVisualisation * >::iterator | RobotVisIterator |
typedef std::map< QString, CSonarVisualisation * >::iterator | SonarVisIterator |
typedef std::map< QString, CGuiSoundSource >::iterator | SoundSourcesIterator |
typedef std::map< QString, CGuiThermalSource >::iterator | ThermalSourcesIterator |
Number of input arguments. More... | |
Private Member Functions | |
stdr_msgs::LaserSensorMsg | getLaserDescription (QString robotName, QString laserName) |
Returns a stdr_msgs::LaserSensorMsg message from robot and laser name. More... | |
stdr_msgs::SonarSensorMsg | getSonarDescription (QString robotName, QString sonarName) |
Returns a stdr_msgs::SonarSensorMsg message from robot and sonar name. More... | |
Private Attributes | |
stdr_msgs::RobotIndexedVectorMsg | all_robots_ |
Timer for the drawing event. More... | |
int | argc_ |
Input arguments. More... | |
char ** | argv_ |
Prevents concurrent map writing. More... | |
stdr_msgs::CO2SourceVector | co2_source_pure_ |
CO2 sources in the environment. More... | |
std::map< QString, CGuiCo2Source > | co2_sources_ |
Sound sources in the environment. More... | |
ros::Subscriber | co2_sources_subscriber_ |
ROS subscriber for thermal sources. More... | |
ros::ServiceClient | delete_co2_source_client_ |
Service client for inserting a new thermal source. More... | |
ros::ServiceClient | delete_rfid_tag_client_ |
Service client for inserting a new co2 source. More... | |
ros::ServiceClient | delete_sound_source_client_ |
ros::ServiceClient | delete_thermal_source_client_ |
Service client for inserting a new sound source. More... | |
QTime | elapsed_time_ |
QIcon for move robot (pop-up menu) More... | |
CGuiConnector | gui_connector_ |
Object of CInfoConnector. More... | |
QIcon | icon_delete_ |
QImage created one time, containing the OGM. More... | |
QIcon | icon_move_ |
QIcon for delete robot (pop-up menu) More... | |
CInfoConnector | info_connector_ |
Object of CMapConnector. More... | |
QImage | initial_map_ |
QImage that initiates as initial_map and the elements are painted on it. More... | |
std::map< QString, CLaserVisualisation * > | laser_visualizers_ |
Sonar visualizers. More... | |
tf::TransformListener | listener_ |
The occypancy grid map. More... | |
CMapConnector | map_connector_ |
bool | map_initialized_ |
All the robots server has. More... | |
bool | map_lock_ |
Prevents actions before map initializes. More... | |
nav_msgs::OccupancyGrid | map_msg_ |
Robot handler from stdr_robot. More... | |
ros::Subscriber | map_subscriber_ |
ROS subscriber to get all robots. More... | |
std::set< std::string > | my_robots_ |
Laser visualizers. More... | |
ros::NodeHandle | n_ |
ROS tf transform listener. More... | |
ros::ServiceClient | new_co2_source_client_ |
Service client for deleting a co2 source. More... | |
ros::ServiceClient | new_rfid_tag_client_ |
Service client for deleting a rfid tag. More... | |
ros::ServiceClient | new_sound_source_client_ |
Service client for deleting a sound source. More... | |
ros::ServiceClient | new_thermal_source_client_ |
Service client for deleting a thermal source. More... | |
std::vector< CGuiRobot > | registered_robots_ |
Robots created from the specific GUI instance. More... | |
stdr_msgs::RfidTagVector | rfid_tag_pure_ |
Thermal sources in the environment. More... | |
std::map< QString, CGuiRfidTag > | rfid_tags_ |
The original rfid vector. More... | |
ros::Subscriber | rfids_subscriber_ |
ROS subscriber for co2 sources. More... | |
std::string | robot_following_ |
Service client for inserting a new rfid tag. More... | |
stdr_robot::HandleRobot | robot_handler_ |
All robots in "raw" form. More... | |
ros::Subscriber | robot_subscriber_ |
ROS subscriber for rfids. More... | |
std::map< QString, CRobotVisualisation * > | robot_visualizers_ |
RFID tags in the environment. More... | |
QImage | running_map_ |
Object of CGuiConnector. More... | |
std::map< QString, CSonarVisualisation * > | sonar_visualizers_ |
Robot visualizers. More... | |
stdr_msgs::SoundSourceVector | sound_source_pure_ |
Sound sources in the environment. More... | |
std::map< QString, CGuiSoundSource > | sound_sources_ |
ROS subscriber for occupancy grid map. More... | |
ros::Subscriber | sound_sources_subscriber_ |
The ROS node handle. More... | |
stdr_msgs::ThermalSourceVector | thermal_source_pure_ |
CO2 sources in the environment. More... | |
std::map< QString, CGuiThermalSource > | thermal_sources_ |
The original vector. More... | |
ros::Subscriber | thermal_sources_subscriber_ |
ROS subscriber for sound sources. More... | |
QTimer * | timer_ |
Elapsed time from the experiment's start. More... | |
Definition at line 56 of file stdr_gui_controller.h.
|
private |
Definition at line 71 of file stdr_gui_controller.h.
|
private |
Definition at line 65 of file stdr_gui_controller.h.
|
private |
Definition at line 70 of file stdr_gui_controller.h.
|
private |
Definition at line 69 of file stdr_gui_controller.h.
|
private |
Definition at line 67 of file stdr_gui_controller.h.
|
private |
Definition at line 72 of file stdr_gui_controller.h.
|
private |
Number of input arguments.
Definition at line 74 of file stdr_gui_controller.h.
stdr_gui::CGuiController::CGuiController | ( | int | argc, |
char ** | argv | ||
) |
Default contructor.
argc | [int] Number of input arguments |
argv | [char **] Input arguments |
Definition at line 42 of file stdr_gui_controller.cpp.
stdr_gui::CGuiController::~CGuiController | ( | void | ) |
void stdr_gui::CGuiController::cleanupVisualizers | ( | const stdr_msgs::RobotIndexedVectorMsg & | msg | ) |
Dumps all visualizers that connect to robots not existent in the input argument message.
msg | [const stdr_msgs::RobotIndexedVectorMsg&] The robots message |
Definition at line 664 of file stdr_gui_controller.cpp.
|
slot |
Gets the point at which the new CO2 source is placed. Connects to the CMapConnector::co2PlaceSet signal.
Gets the point at which the new CO2 source is placed. Connects to the\ CMapConnector::co2PlaceSet signal.
p | [QPoint] The event point in the OGM |
< Getting co2 source id
Definition at line 859 of file stdr_gui_controller.cpp.
|
slot |
Informs CGuiController that a CO2Sensor visibility status has \ been clicked. Connects to the CInfoConnector::co2SensorVisibilityClicked\ signal.
Informs CGuiController that a co2 sensor visibility status has \ been clicked. Connects to the CInfoConnector::CO2SensorVisibilityClicked\ signal.
robotName | [QString] Frame id of the robot |
co2SensorName | [QString] Frame id of the co2 sensor |
Definition at line 1590 of file stdr_gui_controller.cpp.
|
private |
Returns a stdr_msgs::LaserSensorMsg message from robot and laser name.
robotName | [QString] Frame id of the robot |
laserName | [QString] Frame id of the laser |
Definition at line 1155 of file stdr_gui_controller.cpp.
|
private |
Returns a stdr_msgs::SonarSensorMsg message from robot and sonar name.
robotName | [QString] Frame id of the robot |
sonarName | [QString] Frame id of the sonar |
robotName | [QString] Frame id of the robot |
sonarName | [QString] Frame id of the sonar |
Definition at line 1184 of file stdr_gui_controller.cpp.
bool stdr_gui::CGuiController::init | ( | void | ) |
Initializes the ROS spin and Qt threads.
Definition at line 349 of file stdr_gui_controller.cpp.
void stdr_gui::CGuiController::initializeCommunications | ( | void | ) |
Initializes the Qt event connections and ROS subscribers and publishers.
< Rfid related
< CO2 related
< Thermal related
< Sound related
Definition at line 80 of file stdr_gui_controller.cpp.
|
slot |
Informs CGuiController that click has performed in the map. Connects to the CMapConnector::itemClicked signal.
p | [QPoint] The event point in map |
b | [Qt::MouseButton] The mouse button used to trigger the event |
< To avoid crashes as rfid_tags_ changes size
< To avoid crashes as rfid_tags_ changes size
< To avoid crashes as rfid_tags_ changes size
< To avoid crashes as rfid_tags_ changes size
Definition at line 1286 of file stdr_gui_controller.cpp.
|
slot |
Informs CGuiController that a laser visibility status has been clicked. Connects to the CInfoConnector::laserVisibilityClicked signal.
robotName | [QString] Frame id of the robot |
laserName | [QString] Frame id of the laser |
Definition at line 1523 of file stdr_gui_controller.cpp.
|
slot |
Informs CGuiController that a laser visualizer has been clicked. Connects to the CInfoConnector::laserVisualizerClicked signal.
robotName | [QString] Frame id of the robot |
laserName | [QString] Frame id of the laser |
Definition at line 1213 of file stdr_gui_controller.cpp.
|
slot |
Informs CGuiController that a CO2 source is going to be placed in the environment. Connects to the CGuiConnector::loadCo2Pressed signal.
Definition at line 609 of file stdr_gui_controller.cpp.
|
slot |
Informs CGuiController that an RFID is going to be placed in the environment. Connects to the CGuiConnector::loadRfidPressed signal.
Definition at line 583 of file stdr_gui_controller.cpp.
|
slot |
Informs CGuiController that a robot is loaded from a yaml file. Connects to the CGuiConnector::robotFromFile signal.
newRobotMsg | [stdr_msgs::RobotMsg] The robot to be put in the map |
Definition at line 568 of file stdr_gui_controller.cpp.
|
slot |
Loads a robot from robot creator into map. Connects to the CGuiConnector::CRobotCreatorConnector::loadRobotPressed signal.
newRobotMsg | [stdr_msgs::RobotMsg] The robot to be put in the map |
Definition at line 554 of file stdr_gui_controller.cpp.
|
slot |
Informs CGuiController that a sound source is going to be placed in the environment. Connects to the CGuiConnector::loadSoundPressed signal.
Definition at line 622 of file stdr_gui_controller.cpp.
|
slot |
Informs CGuiController that a thermal source is going to be placed in the environment. Connects to the CGuiConnector::loadThermalPressed signal.
Definition at line 596 of file stdr_gui_controller.cpp.
void stdr_gui::CGuiController::receiveCO2Sources | ( | const stdr_msgs::CO2SourceVector & | msg | ) |
Receives the existent co2 sources.
msg | [const stdr_msgs::CO2SourceVector&] The CO2 source message |
Definition at line 391 of file stdr_gui_controller.cpp.
void stdr_gui::CGuiController::receiveMap | ( | const nav_msgs::OccupancyGrid & | msg | ) |
Receives the occupancy grid map from stdr_server. Connects to "map" ROS topic.
Receives the occupancy grid map from stdr_server. Connects to "map" \ ROS topic.
msg | [const nav_msgs::OccupancyGrid&] The OGM message |
Definition at line 475 of file stdr_gui_controller.cpp.
void stdr_gui::CGuiController::receiveRfids | ( | const stdr_msgs::RfidTagVector & | msg | ) |
Receives the existent rfid tags.
msg | [const stdr_msgs::RfidTagVector&] The rfid tags message |
Definition at line 365 of file stdr_gui_controller.cpp.
void stdr_gui::CGuiController::receiveRobots | ( | const stdr_msgs::RobotIndexedVectorMsg & | msg | ) |
Receives the robots from stdr_server. Connects to "stdr_server/active_robots" ROS topic.
msg | [const stdr_msgs::RobotIndexedVectorMsg&] The robots message |
Definition at line 726 of file stdr_gui_controller.cpp.
void stdr_gui::CGuiController::receiveSoundSources | ( | const stdr_msgs::SoundSourceVector & | msg | ) |
Receives the existent sound sources.
msg | [const stdr_msgs::SoundSourceVector&] The sound source message |
Definition at line 446 of file stdr_gui_controller.cpp.
void stdr_gui::CGuiController::receiveThermalSources | ( | const stdr_msgs::ThermalSourceVector & | msg | ) |
Receives the existent thermal sources.
msg | [const stdr_msgs::ThermalSourceVector&] The thermal source message |
Definition at line 418 of file stdr_gui_controller.cpp.
|
signal |
Is emitted when a robot is going to be re-placed. Connects to the CMapConnector::waitForReplace slot.
robotFrameId | [std::string] The frame id of the robot to be re-placed |
|
slot |
Gets the point at which the new RFID tag is placed. Connects to the CMapConnector::robotPlaceSet signal.
Gets the point at which the new RFID tag is placed. Connects to \ the CMapConnector::robotPlaceSet signal.
p | [QPoint] The event point in the OGM |
< Getting RFID tag id
Definition at line 809 of file stdr_gui_controller.cpp.
|
slot |
Informs CGuiController that a rfidReader visibility status has \ been clicked. Connects to the CInfoConnector::rfidReaderVisibilityClicked\ signal.
robotName | [QString] Frame id of the robot |
rfidReaderName | [QString] Frame id of the rfidReader |
Definition at line 1569 of file stdr_gui_controller.cpp.
|
slot |
Gets the point at which the new robot is placed. Connects to the CMapConnector::robotPlaceSet signal.
p | [QPoint] The event point in the OGM |
Definition at line 764 of file stdr_gui_controller.cpp.
|
slot |
Informs CGuiController about the new pose of a robot. Connects to the CMapConnector::robotReplaceSet signal.
p | [QPoint] The event point in map |
robotName | [std::string] The frame id of the re-placed robot |
Definition at line 1488 of file stdr_gui_controller.cpp.
|
slot |
Informs CGuiController that a robot visibility status has been clicked. Connects to the CInfoConnector::robotVisibilityClicked signal.
robotName | [QString] Frame id of the robot |
Definition at line 1655 of file stdr_gui_controller.cpp.
|
slot |
Informs CGuiController that a robot visualizer has been clicked. Connects to the CInfoConnector::robotVisualizerClicked signal.
robotName | [QString] Frame id of the robot |
Definition at line 1264 of file stdr_gui_controller.cpp.
|
slot |
Saves the robot in a yaml file. Connects to the CGuiConnector::CRobotCreatorConnector::saveRobotPressed signal.
Saves the robot in a file. Connects to the CGuiConnector::CRobotCreatorConnector::saveRobotPressed signal.
newRobotMsg | [stdr_msgs::RobotMsg] The robot to be saved |
file_name | [QString] The yaml file for the robot to be saved |
newRobotMsg | [stdr_msgs::RobotMsg] The robot to be saved |
file_name | [QString] The file for the robot to be saved |
Definition at line 535 of file stdr_gui_controller.cpp.
|
signal |
Is emitted when a CO2 sensor's visibility status is going to be \ changed. Connects to the CInfoConnector::setCO2SensorVisibility slot.
robotName | [QString] The frame id of the robot containing the specific co2 reader |
co2SensorName | [QString] The frame id of the CO2 sensor |
vs | [char] The new visibility status |
|
signal |
Is emitted when a laser's visibility status is going to be changed. Connects to the CInfoConnector::setLaserVisibility slot.
robotName | [QString] The frame id of the robot containing the specific laser |
laserName | [QString] The frame id of the laser |
vs | [char] The new visibility status |
|
signal |
Is emitted when a rfid sensor's visibility status is going to be \ changed. Connects to the CInfoConnector::setRfidReaderVisibility slot.
robotName | [QString] The frame id of the robot containing the specific rfid reader |
rfidReaderName | [QString] The frame id of the rfidReader |
vs | [char] The new visibility status |
|
signal |
Is emitted when a robot's visibility status is going to be changed. Connects to the CInfoConnector::setRobotVisibility slot.
robotName | [QString] The frame id of the robot |
vs | [char] The new visibility status |
|
signal |
Is emitted when a sonar's visibility status is going to be changed. Connects to the CInfoConnector::setSonarVisibility slot.
robotName | [QString] The frame id of the robot containing the specific sonar |
sonarName | [QString] The frame id of the laser |
vs | [char] The new visibility status |
|
signal |
Is emitted when a sound sensor's visibility status is going to be \ changed. Connects to the CInfoConnector::setSoundSensorVisibility slot.
robotName | [QString] The frame id of the robot containing the specific sensor |
soundSensorName | [QString] The frame id of the sound sensor |
vs | [char] The new visibility status |
|
signal |
Is emitted when a thermal sensor's visibility status is going to be \ changed. Connects to the CInfoConnector::setThermalSensorVisibility slot.
robotName | [QString] The frame id of the robot containing the specific sensor |
thermalSensorName | [QString] The frame id of the thermal sensor |
vs | [char] The new visibility status |
void stdr_gui::CGuiController::setupWidgets | ( | void | ) |
Sets up the main window widgets.
Definition at line 323 of file stdr_gui_controller.cpp.
|
slot |
Informs CGuiController that a sonar visibility status has been clicked. Connects to the CInfoConnector::sonarVisibilityClicked signal.
robotName | [QString] Frame id of the robot |
sonarName | [QString] Frame id of the sonar |
Definition at line 1546 of file stdr_gui_controller.cpp.
|
slot |
Informs CGuiController that a sonar visualizer has been clicked. Connects to the CInfoConnector::sonarVisualizerClicked signal.
robotName | [QString] Frame id of the robot |
sonarName | [QString] Frame id of the sonar |
Definition at line 1239 of file stdr_gui_controller.cpp.
|
slot |
Gets the point at which the new sound source is placed. Connects to the CMapConnector::soundPlaceSet signal.
Gets the point at which the new sound source is placed. Connects to the\ CMapConnector::soundPlaceSet signal.
p | [QPoint] The event point in the OGM |
< Getting source id
Definition at line 958 of file stdr_gui_controller.cpp.
|
slot |
Informs CGuiController that a sound Sensor visibility status has \ been clicked. Connects to the CInfoConnector::soundSensorVisibilityClicked\ signal.
Informs CGuiController that a sound sensor visibility status has \ been clicked. Connects to the CInfoConnector::soundSensorVisibilityClicked\ signal.
robotName | [QString] Frame id of the robot |
soundSensorName | [QString] Frame id of the sound sensor |
Definition at line 1633 of file stdr_gui_controller.cpp.
|
slot |
Gets the point at which the new thermal source is placed. Connects to the CMapConnector::thermalPlaceSet signal.
Gets the point at which the new thermal source is placed. Connects to the\ CMapConnector::thermalPlaceSet signal.
p | [QPoint] The event point in the OGM |
< Getting source id
Definition at line 908 of file stdr_gui_controller.cpp.
|
slot |
Informs CGuiController that a Thermal Sensor visibility status has \ been clicked. Connects to the CInfoConnector::thermalSensorVisibilityClicked\ signal.
Informs CGuiController that a thermal sensor visibility status has \ been clicked. Connects to the CInfoConnector::thermalSensorVisibilityClicked\ signal.
robotName | [QString] Frame id of the robot |
thermalSensorName | [QString] Frame id of the thermal sensor |
Definition at line 1611 of file stdr_gui_controller.cpp.
|
slot |
Updates the map to be shown in GUI. Connects to the timeout signal of timer_.
<------------------------— Check if all visualisers are active
Definition at line 1006 of file stdr_gui_controller.cpp.
|
signal |
Is emitted when a new CO2 source is going to be placed. Connects to the CMapConnector::waitForCo2Pose slot.
|
signal |
Is emitted when a new rfid tag is going to be placed. Connects to the CMapConnector::waitForRfidPose slot.
|
signal |
Is emitted when a new robot is going to be placed. Connects to the CMapConnector::waitForPlace slot.
|
signal |
Is emitted when a new sound source is going to be placed. Connects to the CMapConnector::waitForSOundPose slot.
|
signal |
Is emitted when a new thermal source is going to be placed. Connects to the CMapConnector::waitForThermalPose slot.
|
slot |
Performs zoom in when the button is pressed. Connects to the CMapConnector::zoomInPressed signal.
p | [QPoint] The event point in the OGM |
Definition at line 636 of file stdr_gui_controller.cpp.
|
slot |
Performs zoom out when the button is pressed. Connects to the CMapConnector::zoomOutPressed signal.
p | [QPoint] The event point in the OGM |
Definition at line 650 of file stdr_gui_controller.cpp.
|
private |
Timer for the drawing event.
Definition at line 138 of file stdr_gui_controller.h.
|
private |
Input arguments.
Definition at line 77 of file stdr_gui_controller.h.
|
private |
Prevents concurrent map writing.
Definition at line 79 of file stdr_gui_controller.h.
|
private |
CO2 sources in the environment.
Definition at line 107 of file stdr_gui_controller.h.
|
private |
Sound sources in the environment.
Definition at line 109 of file stdr_gui_controller.h.
|
private |
ROS subscriber for thermal sources.
Definition at line 122 of file stdr_gui_controller.h.
|
private |
Service client for inserting a new thermal source.
Definition at line 193 of file stdr_gui_controller.h.
|
private |
Service client for inserting a new co2 source.
Definition at line 188 of file stdr_gui_controller.h.
|
private |
Definition at line 203 of file stdr_gui_controller.h.
|
private |
Service client for inserting a new sound source.
Definition at line 198 of file stdr_gui_controller.h.
|
private |
QIcon for move robot (pop-up menu)
Definition at line 143 of file stdr_gui_controller.h.
|
private |
Object of CInfoConnector.
Definition at line 156 of file stdr_gui_controller.h.
|
private |
QImage created one time, containing the OGM.
Definition at line 148 of file stdr_gui_controller.h.
|
private |
QIcon for delete robot (pop-up menu)
Definition at line 146 of file stdr_gui_controller.h.
|
private |
Object of CMapConnector.
Definition at line 158 of file stdr_gui_controller.h.
|
private |
QImage that initiates as initial_map and the elements are painted on it.
Definition at line 151 of file stdr_gui_controller.h.
|
private |
Sonar visualizers.
Definition at line 92 of file stdr_gui_controller.h.
|
private |
The occypancy grid map.
Definition at line 130 of file stdr_gui_controller.h.
|
private |
Definition at line 160 of file stdr_gui_controller.h.
|
private |
All the robots server has.
Definition at line 84 of file stdr_gui_controller.h.
|
private |
Prevents actions before map initializes.
Definition at line 82 of file stdr_gui_controller.h.
|
private |
Robot handler from stdr_robot.
Definition at line 133 of file stdr_gui_controller.h.
|
private |
ROS subscriber to get all robots.
Definition at line 116 of file stdr_gui_controller.h.
|
private |
Laser visualizers.
Definition at line 89 of file stdr_gui_controller.h.
|
private |
ROS tf transform listener.
Definition at line 128 of file stdr_gui_controller.h.
|
private |
Service client for deleting a co2 source.
Definition at line 191 of file stdr_gui_controller.h.
|
private |
Service client for deleting a rfid tag.
Definition at line 186 of file stdr_gui_controller.h.
|
private |
Service client for deleting a sound source.
Definition at line 201 of file stdr_gui_controller.h.
|
private |
Service client for deleting a thermal source.
Definition at line 196 of file stdr_gui_controller.h.
|
private |
Robots created from the specific GUI instance.
Definition at line 87 of file stdr_gui_controller.h.
|
private |
Thermal sources in the environment.
Definition at line 101 of file stdr_gui_controller.h.
|
private |
The original rfid vector.
Definition at line 99 of file stdr_gui_controller.h.
|
private |
ROS subscriber for co2 sources.
Definition at line 120 of file stdr_gui_controller.h.
|
private |
Service client for inserting a new rfid tag.
Definition at line 183 of file stdr_gui_controller.h.
|
private |
All robots in "raw" form.
Definition at line 136 of file stdr_gui_controller.h.
|
private |
ROS subscriber for rfids.
Definition at line 118 of file stdr_gui_controller.h.
|
private |
RFID tags in the environment.
Definition at line 96 of file stdr_gui_controller.h.
|
private |
Object of CGuiConnector.
Definition at line 153 of file stdr_gui_controller.h.
|
private |
Robot visualizers.
Definition at line 94 of file stdr_gui_controller.h.
|
private |
Sound sources in the environment.
Definition at line 111 of file stdr_gui_controller.h.
|
private |
ROS subscriber for occupancy grid map.
Definition at line 113 of file stdr_gui_controller.h.
|
private |
The ROS node handle.
Definition at line 126 of file stdr_gui_controller.h.
|
private |
CO2 sources in the environment.
Definition at line 103 of file stdr_gui_controller.h.
|
private |
The original vector.
Definition at line 105 of file stdr_gui_controller.h.
|
private |
ROS subscriber for sound sources.
Definition at line 124 of file stdr_gui_controller.h.
|
private |
Elapsed time from the experiment's start.
Definition at line 141 of file stdr_gui_controller.h.