#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. | |
void | co2SensorVisibilityClicked (QString robotName, QString co2SensorName) |
Informs CGuiController that a CO2Sensor visibility status has \ been clicked. Connects to the CInfoConnector::co2SensorVisibilityClicked\ signal. | |
void | itemClicked (QPoint p, Qt::MouseButton b) |
Informs CGuiController that click has performed in the map. Connects to the CMapConnector::itemClicked signal. | |
void | laserVisibilityClicked (QString robotName, QString laserName) |
Informs CGuiController that a laser visibility status has been clicked. Connects to the CInfoConnector::laserVisibilityClicked signal. | |
void | laserVisualizerClicked (QString robotName, QString laserName) |
Informs CGuiController that a laser visualizer has been clicked. Connects to the CInfoConnector::laserVisualizerClicked signal. | |
void | loadCo2Pressed (void) |
Informs CGuiController that a CO2 source is going to be placed in the environment. Connects to the CGuiConnector::loadCo2Pressed signal. | |
void | loadRfidPressed (void) |
Informs CGuiController that an RFID is going to be placed in the environment. Connects to the CGuiConnector::loadRfidPressed signal. | |
void | loadRobotFromFilePressed (stdr_msgs::RobotMsg newRobotMsg) |
Informs CGuiController that a robot is loaded from a yaml file. Connects to the CGuiConnector::robotFromFile signal. | |
void | loadRobotPressed (stdr_msgs::RobotMsg newRobotMsg) |
Loads a robot from robot creator into map. Connects to the CGuiConnector::CRobotCreatorConnector::loadRobotPressed signal. | |
void | loadSoundPressed (void) |
Informs CGuiController that a sound source is going to be placed in the environment. Connects to the CGuiConnector::loadSoundPressed signal. | |
void | loadThermalPressed (void) |
Informs CGuiController that a thermal source is going to be placed in the environment. Connects to the CGuiConnector::loadThermalPressed signal. | |
void | rfidPlaceSet (QPoint p) |
Gets the point at which the new RFID tag is placed. Connects to the CMapConnector::robotPlaceSet signal. | |
void | rfidReaderVisibilityClicked (QString robotName, QString rfidReaderName) |
Informs CGuiController that a rfidReader visibility status has \ been clicked. Connects to the CInfoConnector::rfidReaderVisibilityClicked\ signal. | |
void | robotPlaceSet (QPoint p) |
Gets the point at which the new robot is placed. Connects to the CMapConnector::robotPlaceSet signal. | |
void | robotReplaceSet (QPoint p, std::string robotName) |
Informs CGuiController about the new pose of a robot. Connects to the CMapConnector::robotReplaceSet signal. | |
void | robotVisibilityClicked (QString robotName) |
Informs CGuiController that a robot visibility status has been clicked. Connects to the CInfoConnector::robotVisibilityClicked signal. | |
void | robotVisualizerClicked (QString robotName) |
Informs CGuiController that a robot visualizer has been clicked. Connects to the CInfoConnector::robotVisualizerClicked signal. | |
void | saveRobotPressed (stdr_msgs::RobotMsg newRobotMsg, QString file_name) |
Saves the robot in a yaml file. Connects to the CGuiConnector::CRobotCreatorConnector::saveRobotPressed signal. | |
void | sonarVisibilityClicked (QString robotName, QString sonarName) |
Informs CGuiController that a sonar visibility status has been clicked. Connects to the CInfoConnector::sonarVisibilityClicked signal. | |
void | sonarVisualizerClicked (QString robotName, QString sonarName) |
Informs CGuiController that a sonar visualizer has been clicked. Connects to the CInfoConnector::sonarVisualizerClicked signal. | |
void | soundPlaceSet (QPoint p) |
Gets the point at which the new sound source is placed. Connects to the CMapConnector::soundPlaceSet signal. | |
void | soundSensorVisibilityClicked (QString robotName, QString soundSensorName) |
Informs CGuiController that a sound Sensor visibility status has \ been clicked. Connects to the CInfoConnector::soundSensorVisibilityClicked\ signal. | |
void | thermalPlaceSet (QPoint p) |
Gets the point at which the new thermal source is placed. Connects to the CMapConnector::thermalPlaceSet signal. | |
void | thermalSensorVisibilityClicked (QString robotName, QString thermalSensorName) |
Informs CGuiController that a Thermal Sensor visibility status has \ been clicked. Connects to the CInfoConnector::thermalSensorVisibilityClicked\ signal. | |
void | updateMapInternal (void) |
Updates the map to be shown in GUI. Connects to the timeout signal of timer_. | |
void | zoomInPressed (QPoint p) |
Performs zoom in when the button is pressed. Connects to the CMapConnector::zoomInPressed signal. | |
void | zoomOutPressed (QPoint p) |
Performs zoom out when the button is pressed. Connects to the CMapConnector::zoomOutPressed signal. | |
Signals | |
void | replaceRobot (std::string robotFrameId) |
Is emitted when a robot is going to be re-placed. Connects to the CMapConnector::waitForReplace slot. | |
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. | |
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. | |
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. | |
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. | |
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. | |
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. | |
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. | |
void | waitForCo2Pose (void) |
Is emitted when a new CO2 source is going to be placed. Connects to the CMapConnector::waitForCo2Pose slot. | |
void | waitForRfidPose (void) |
Is emitted when a new rfid tag is going to be placed. Connects to the CMapConnector::waitForRfidPose slot. | |
void | waitForRobotPose (void) |
Is emitted when a new robot is going to be placed. Connects to the CMapConnector::waitForPlace slot. | |
void | waitForSoundPose (void) |
Is emitted when a new sound source is going to be placed. Connects to the CMapConnector::waitForSOundPose slot. | |
void | waitForThermalPose (void) |
Is emitted when a new thermal source is going to be placed. Connects to the CMapConnector::waitForThermalPose slot. | |
Public Member Functions | |
CGuiController (int argc, char **argv) | |
Default contructor. | |
void | cleanupVisualizers (const stdr_msgs::RobotIndexedVectorMsg &msg) |
Dumps all visualizers that connect to robots not existent in the input argument message. | |
bool | init () |
Initializes the ROS spin and Qt threads. | |
void | initializeCommunications (void) |
Initializes the Qt event connections and ROS subscribers and publishers. | |
void | receiveCO2Sources (const stdr_msgs::CO2SourceVector &msg) |
Receives the existent co2 sources. | |
void | receiveMap (const nav_msgs::OccupancyGrid &msg) |
Receives the occupancy grid map from stdr_server. Connects to "map" ROS topic. | |
void | receiveRfids (const stdr_msgs::RfidTagVector &msg) |
Receives the existent rfid tags. | |
void | receiveRobots (const stdr_msgs::RobotIndexedVectorMsg &msg) |
Receives the robots from stdr_server. Connects to "stdr_server/active_robots" ROS topic. | |
void | receiveSoundSources (const stdr_msgs::SoundSourceVector &msg) |
Receives the existent sound sources. | |
void | receiveThermalSources (const stdr_msgs::ThermalSourceVector &msg) |
Receives the existent thermal sources. | |
void | setupWidgets (void) |
Sets up the main window widgets. | |
~CGuiController (void) | |
Default destructor. | |
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. | |
Private Member Functions | |
stdr_msgs::LaserSensorMsg | getLaserDescription (QString robotName, QString laserName) |
Returns a stdr_msgs::LaserSensorMsg message from robot and laser name. | |
stdr_msgs::SonarSensorMsg | getSonarDescription (QString robotName, QString sonarName) |
Returns a stdr_msgs::SonarSensorMsg message from robot and sonar name. | |
Private Attributes | |
stdr_msgs::RobotIndexedVectorMsg | all_robots_ |
Timer for the drawing event. | |
int | argc_ |
Input arguments. | |
char ** | argv_ |
Prevents concurrent map writing. | |
stdr_msgs::CO2SourceVector | co2_source_pure_ |
CO2 sources in the environment. | |
std::map< QString, CGuiCo2Source > | co2_sources_ |
Sound sources in the environment. | |
ros::Subscriber | co2_sources_subscriber_ |
ROS subscriber for thermal sources. | |
ros::ServiceClient | delete_co2_source_client_ |
Service client for inserting a new thermal source. | |
ros::ServiceClient | delete_rfid_tag_client_ |
Service client for inserting a new co2 source. | |
ros::ServiceClient | delete_sound_source_client_ |
ros::ServiceClient | delete_thermal_source_client_ |
Service client for inserting a new sound source. | |
QTime | elapsed_time_ |
QIcon for move robot (pop-up menu) | |
CGuiConnector | gui_connector_ |
Object of CInfoConnector. | |
QIcon | icon_delete_ |
QImage created one time, containing the OGM. | |
QIcon | icon_move_ |
QIcon for delete robot (pop-up menu) | |
CInfoConnector | info_connector_ |
Object of CMapConnector. | |
QImage | initial_map_ |
QImage that initiates as initial_map and the elements are painted on it. | |
std::map< QString, CLaserVisualisation * > | laser_visualizers_ |
Sonar visualizers. | |
tf::TransformListener | listener_ |
The occypancy grid map. | |
CMapConnector | map_connector_ |
bool | map_initialized_ |
All the robots server has. | |
bool | map_lock_ |
Prevents actions before map initializes. | |
nav_msgs::OccupancyGrid | map_msg_ |
Robot handler from stdr_robot. | |
ros::Subscriber | map_subscriber_ |
ROS subscriber to get all robots. | |
std::set< std::string > | my_robots_ |
Laser visualizers. | |
ros::NodeHandle | n_ |
ROS tf transform listener. | |
ros::ServiceClient | new_co2_source_client_ |
Service client for deleting a co2 source. | |
ros::ServiceClient | new_rfid_tag_client_ |
Service client for deleting a rfid tag. | |
ros::ServiceClient | new_sound_source_client_ |
Service client for deleting a sound source. | |
ros::ServiceClient | new_thermal_source_client_ |
Service client for deleting a thermal source. | |
std::vector< CGuiRobot > | registered_robots_ |
Robots created from the specific GUI instance. | |
stdr_msgs::RfidTagVector | rfid_tag_pure_ |
Thermal sources in the environment. | |
std::map< QString, CGuiRfidTag > | rfid_tags_ |
The original rfid vector. | |
ros::Subscriber | rfids_subscriber_ |
ROS subscriber for co2 sources. | |
std::string | robot_following_ |
Service client for inserting a new rfid tag. | |
stdr_robot::HandleRobot | robot_handler_ |
All robots in "raw" form. | |
ros::Subscriber | robot_subscriber_ |
ROS subscriber for rfids. | |
std::map< QString, CRobotVisualisation * > | robot_visualizers_ |
RFID tags in the environment. | |
QImage | running_map_ |
Object of CGuiConnector. | |
std::map< QString, CSonarVisualisation * > | sonar_visualizers_ |
Robot visualizers. | |
stdr_msgs::SoundSourceVector | sound_source_pure_ |
Sound sources in the environment. | |
std::map< QString, CGuiSoundSource > | sound_sources_ |
ROS subscriber for occupancy grid map. | |
ros::Subscriber | sound_sources_subscriber_ |
The ROS node handle. | |
stdr_msgs::ThermalSourceVector | thermal_source_pure_ |
CO2 sources in the environment. | |
std::map< QString, CGuiThermalSource > | thermal_sources_ |
The original vector. | |
ros::Subscriber | thermal_sources_subscriber_ |
ROS subscriber for sound sources. | |
QTimer * | timer_ |
Elapsed time from the experiment's start. |
Definition at line 56 of file stdr_gui_controller.h.
typedef std::map<QString,CGuiCo2Source>::iterator stdr_gui::CGuiController::Co2SourcesIterator [private] |
Definition at line 71 of file stdr_gui_controller.h.
typedef std::map<QString,CLaserVisualisation *>::iterator stdr_gui::CGuiController::LaserVisIterator [private] |
Definition at line 65 of file stdr_gui_controller.h.
typedef std::map<QString,CGuiRfidTag>::iterator stdr_gui::CGuiController::RfidTagIterator [private] |
Definition at line 70 of file stdr_gui_controller.h.
typedef std::map<QString,CRobotVisualisation *>::iterator stdr_gui::CGuiController::RobotVisIterator [private] |
Definition at line 69 of file stdr_gui_controller.h.
typedef std::map<QString,CSonarVisualisation *>::iterator stdr_gui::CGuiController::SonarVisIterator [private] |
Definition at line 67 of file stdr_gui_controller.h.
typedef std::map<QString,CGuiSoundSource>::iterator stdr_gui::CGuiController::SoundSourcesIterator [private] |
Definition at line 72 of file stdr_gui_controller.h.
typedef std::map<QString,CGuiThermalSource>::iterator stdr_gui::CGuiController::ThermalSourcesIterator [private] |
Number of input arguments.
Definition at line 76 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.
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.
void stdr_gui::CGuiController::co2PlaceSet | ( | QPoint | p | ) | [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.
void stdr_gui::CGuiController::co2SensorVisibilityClicked | ( | QString | robotName, |
QString | co2SensorName | ||
) | [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.
stdr_msgs::LaserSensorMsg stdr_gui::CGuiController::getLaserDescription | ( | QString | robotName, |
QString | laserName | ||
) | [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.
stdr_msgs::SonarSensorMsg stdr_gui::CGuiController::getSonarDescription | ( | QString | robotName, |
QString | sonarName | ||
) | [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.
void stdr_gui::CGuiController::itemClicked | ( | QPoint | p, |
Qt::MouseButton | b | ||
) | [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.
void stdr_gui::CGuiController::laserVisibilityClicked | ( | QString | robotName, |
QString | laserName | ||
) | [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.
void stdr_gui::CGuiController::laserVisualizerClicked | ( | QString | robotName, |
QString | laserName | ||
) | [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.
void stdr_gui::CGuiController::loadCo2Pressed | ( | void | ) | [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.
void stdr_gui::CGuiController::loadRfidPressed | ( | void | ) | [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.
void stdr_gui::CGuiController::loadRobotFromFilePressed | ( | stdr_msgs::RobotMsg | newRobotMsg | ) | [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.
void stdr_gui::CGuiController::loadRobotPressed | ( | stdr_msgs::RobotMsg | newRobotMsg | ) | [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.
void stdr_gui::CGuiController::loadSoundPressed | ( | void | ) | [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.
void stdr_gui::CGuiController::loadThermalPressed | ( | void | ) | [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.
void stdr_gui::CGuiController::replaceRobot | ( | std::string | robotFrameId | ) | [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 |
void stdr_gui::CGuiController::rfidPlaceSet | ( | QPoint | p | ) | [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.
void stdr_gui::CGuiController::rfidReaderVisibilityClicked | ( | QString | robotName, |
QString | rfidReaderName | ||
) | [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.
void stdr_gui::CGuiController::robotPlaceSet | ( | QPoint | p | ) | [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.
void stdr_gui::CGuiController::robotReplaceSet | ( | QPoint | p, |
std::string | robotName | ||
) | [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.
void stdr_gui::CGuiController::robotVisibilityClicked | ( | QString | robotName | ) | [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.
void stdr_gui::CGuiController::robotVisualizerClicked | ( | QString | robotName | ) | [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.
void stdr_gui::CGuiController::saveRobotPressed | ( | stdr_msgs::RobotMsg | newRobotMsg, |
QString | file_name | ||
) | [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.
void stdr_gui::CGuiController::setCO2SensorVisibility | ( | QString | robotName, |
QString | co2SensorName, | ||
char | vs | ||
) | [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 |
void stdr_gui::CGuiController::setLaserVisibility | ( | QString | robotName, |
QString | laserName, | ||
char | vs | ||
) | [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 |
void stdr_gui::CGuiController::setRfidReaderVisibility | ( | QString | robotName, |
QString | rfidReaderName, | ||
char | vs | ||
) | [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 |
void stdr_gui::CGuiController::setRobotVisibility | ( | QString | robotName, |
char | vs | ||
) | [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 |
void stdr_gui::CGuiController::setSonarVisibility | ( | QString | robotName, |
QString | sonarName, | ||
char | vs | ||
) | [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 |
void stdr_gui::CGuiController::setSoundSensorVisibility | ( | QString | robotName, |
QString | soundSensorName, | ||
char | vs | ||
) | [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 |
void stdr_gui::CGuiController::setThermalSensorVisibility | ( | QString | robotName, |
QString | thermalSensorName, | ||
char | vs | ||
) | [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.
void stdr_gui::CGuiController::sonarVisibilityClicked | ( | QString | robotName, |
QString | sonarName | ||
) | [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.
void stdr_gui::CGuiController::sonarVisualizerClicked | ( | QString | robotName, |
QString | sonarName | ||
) | [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.
void stdr_gui::CGuiController::soundPlaceSet | ( | QPoint | p | ) | [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.
void stdr_gui::CGuiController::soundSensorVisibilityClicked | ( | QString | robotName, |
QString | soundSensorName | ||
) | [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.
void stdr_gui::CGuiController::thermalPlaceSet | ( | QPoint | p | ) | [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.
void stdr_gui::CGuiController::thermalSensorVisibilityClicked | ( | QString | robotName, |
QString | thermalSensorName | ||
) | [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.
void stdr_gui::CGuiController::updateMapInternal | ( | void | ) | [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.
void stdr_gui::CGuiController::waitForCo2Pose | ( | void | ) | [signal] |
Is emitted when a new CO2 source is going to be placed. Connects to the CMapConnector::waitForCo2Pose slot.
void stdr_gui::CGuiController::waitForRfidPose | ( | void | ) | [signal] |
Is emitted when a new rfid tag is going to be placed. Connects to the CMapConnector::waitForRfidPose slot.
void stdr_gui::CGuiController::waitForRobotPose | ( | void | ) | [signal] |
Is emitted when a new robot is going to be placed. Connects to the CMapConnector::waitForPlace slot.
void stdr_gui::CGuiController::waitForSoundPose | ( | void | ) | [signal] |
Is emitted when a new sound source is going to be placed. Connects to the CMapConnector::waitForSOundPose slot.
void stdr_gui::CGuiController::waitForThermalPose | ( | void | ) | [signal] |
Is emitted when a new thermal source is going to be placed. Connects to the CMapConnector::waitForThermalPose slot.
void stdr_gui::CGuiController::zoomInPressed | ( | QPoint | p | ) | [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.
void stdr_gui::CGuiController::zoomOutPressed | ( | QPoint | p | ) | [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.
stdr_msgs::RobotIndexedVectorMsg stdr_gui::CGuiController::all_robots_ [private] |
Timer for the drawing event.
Definition at line 140 of file stdr_gui_controller.h.
int stdr_gui::CGuiController::argc_ [private] |
Input arguments.
Definition at line 78 of file stdr_gui_controller.h.
char** stdr_gui::CGuiController::argv_ [private] |
Prevents concurrent map writing.
Definition at line 81 of file stdr_gui_controller.h.
stdr_msgs::CO2SourceVector stdr_gui::CGuiController::co2_source_pure_ [private] |
CO2 sources in the environment.
Definition at line 108 of file stdr_gui_controller.h.
std::map<QString,CGuiCo2Source> stdr_gui::CGuiController::co2_sources_ [private] |
Sound sources in the environment.
Definition at line 110 of file stdr_gui_controller.h.
ROS subscriber for thermal sources.
Definition at line 123 of file stdr_gui_controller.h.
Service client for inserting a new thermal source.
Definition at line 195 of file stdr_gui_controller.h.
Service client for inserting a new co2 source.
Definition at line 190 of file stdr_gui_controller.h.
Definition at line 203 of file stdr_gui_controller.h.
Service client for inserting a new sound source.
Definition at line 200 of file stdr_gui_controller.h.
QTime stdr_gui::CGuiController::elapsed_time_ [private] |
QIcon for move robot (pop-up menu)
Definition at line 145 of file stdr_gui_controller.h.
Object of CInfoConnector.
Definition at line 157 of file stdr_gui_controller.h.
QIcon stdr_gui::CGuiController::icon_delete_ [private] |
QImage created one time, containing the OGM.
Definition at line 150 of file stdr_gui_controller.h.
QIcon stdr_gui::CGuiController::icon_move_ [private] |
QIcon for delete robot (pop-up menu)
Definition at line 147 of file stdr_gui_controller.h.
Object of CMapConnector.
Definition at line 159 of file stdr_gui_controller.h.
QImage stdr_gui::CGuiController::initial_map_ [private] |
QImage that initiates as initial_map and the elements are painted on it.
Definition at line 152 of file stdr_gui_controller.h.
std::map<QString,CLaserVisualisation *> stdr_gui::CGuiController::laser_visualizers_ [private] |
Sonar visualizers.
Definition at line 93 of file stdr_gui_controller.h.
The occypancy grid map.
Definition at line 132 of file stdr_gui_controller.h.
Definition at line 160 of file stdr_gui_controller.h.
bool stdr_gui::CGuiController::map_initialized_ [private] |
All the robots server has.
Definition at line 86 of file stdr_gui_controller.h.
bool stdr_gui::CGuiController::map_lock_ [private] |
Prevents actions before map initializes.
Definition at line 83 of file stdr_gui_controller.h.
nav_msgs::OccupancyGrid stdr_gui::CGuiController::map_msg_ [private] |
Robot handler from stdr_robot.
Definition at line 135 of file stdr_gui_controller.h.
ROS subscriber to get all robots.
Definition at line 117 of file stdr_gui_controller.h.
std::set<std::string> stdr_gui::CGuiController::my_robots_ [private] |
Laser visualizers.
Definition at line 91 of file stdr_gui_controller.h.
ros::NodeHandle stdr_gui::CGuiController::n_ [private] |
ROS tf transform listener.
Definition at line 129 of file stdr_gui_controller.h.
Service client for deleting a co2 source.
Definition at line 192 of file stdr_gui_controller.h.
Service client for deleting a rfid tag.
Definition at line 187 of file stdr_gui_controller.h.
Service client for deleting a sound source.
Definition at line 202 of file stdr_gui_controller.h.
Service client for deleting a thermal source.
Definition at line 197 of file stdr_gui_controller.h.
std::vector<CGuiRobot> stdr_gui::CGuiController::registered_robots_ [private] |
Robots created from the specific GUI instance.
Definition at line 88 of file stdr_gui_controller.h.
stdr_msgs::RfidTagVector stdr_gui::CGuiController::rfid_tag_pure_ [private] |
Thermal sources in the environment.
Definition at line 102 of file stdr_gui_controller.h.
std::map<QString,CGuiRfidTag> stdr_gui::CGuiController::rfid_tags_ [private] |
The original rfid vector.
Definition at line 100 of file stdr_gui_controller.h.
ROS subscriber for co2 sources.
Definition at line 121 of file stdr_gui_controller.h.
std::string stdr_gui::CGuiController::robot_following_ [private] |
Service client for inserting a new rfid tag.
Definition at line 185 of file stdr_gui_controller.h.
All robots in "raw" form.
Definition at line 137 of file stdr_gui_controller.h.
ROS subscriber for rfids.
Definition at line 119 of file stdr_gui_controller.h.
std::map<QString,CRobotVisualisation *> stdr_gui::CGuiController::robot_visualizers_ [private] |
RFID tags in the environment.
Definition at line 98 of file stdr_gui_controller.h.
QImage stdr_gui::CGuiController::running_map_ [private] |
Object of CGuiConnector.
Definition at line 155 of file stdr_gui_controller.h.
std::map<QString,CSonarVisualisation *> stdr_gui::CGuiController::sonar_visualizers_ [private] |
Robot visualizers.
Definition at line 95 of file stdr_gui_controller.h.
stdr_msgs::SoundSourceVector stdr_gui::CGuiController::sound_source_pure_ [private] |
Sound sources in the environment.
Definition at line 112 of file stdr_gui_controller.h.
std::map<QString,CGuiSoundSource> stdr_gui::CGuiController::sound_sources_ [private] |
ROS subscriber for occupancy grid map.
Definition at line 115 of file stdr_gui_controller.h.
The ROS node handle.
Definition at line 127 of file stdr_gui_controller.h.
stdr_msgs::ThermalSourceVector stdr_gui::CGuiController::thermal_source_pure_ [private] |
CO2 sources in the environment.
Definition at line 104 of file stdr_gui_controller.h.
std::map<QString,CGuiThermalSource> stdr_gui::CGuiController::thermal_sources_ [private] |
The original vector.
Definition at line 106 of file stdr_gui_controller.h.
ROS subscriber for sound sources.
Definition at line 125 of file stdr_gui_controller.h.
QTimer* stdr_gui::CGuiController::timer_ [private] |
Elapsed time from the experiment's start.
Definition at line 142 of file stdr_gui_controller.h.