Public Slots | Signals | Public Member Functions | Static Public Attributes | Private Member Functions | Private Attributes | List of all members
stdr_gui::CRobotCreatorConnector Class Reference

Implements the high level functionalities of the robot creator widget. Inherits form QObject. More...

#include <stdr_robot_creator_connector.h>

Inheritance diagram for stdr_gui::CRobotCreatorConnector:
Inheritance graph
[legend]

Public Slots

void getRobotFromYaml (void)
 Called when the load robot button. More...
 
void loadRobot (void)
 Called when the load robot in map button is clicked. More...
 
void saveRobot (void)
 Called when the save robot button is clicked. More...
 
void treeItemClicked (QTreeWidgetItem *item, int column)
 Called when a tree item is clicked. More...
 
void updateCO2Sensor (void)
 Called when the update button of the properties widget is clicked. More...
 
void updateCO2SensorOpen (void)
 Called when the refresh button of the properties widget is clicked. More...
 
void updateFootprintPoint (void)
 Called when the update button of the footprint widget is clicked. More...
 
void updateFootprintPointOpen (void)
 Called when the refresh button of the properties widget is clicked. More...
 
void updateKinematicModel (void)
 Called when the update button of the kinematic model widget is clicked. More...
 
void updateLaser (void)
 Called when the update button of the properties widget is clicked. More...
 
void updateLaserOpen (void)
 Called when the refresh button of the properties widget is clicked. More...
 
void updateRfidAntenna (void)
 Called when the update button of the properties widget is clicked. More...
 
void updateRfidAntennaOpen (void)
 Called when the update button of the properties widget is clicked. More...
 
void updateRobot (void)
 Called when the update button of the properties widget is clicked. More...
 
void updateRobotOpen (void)
 Called when the refresh button of the properties widget is clicked. More...
 
void updateSonar (void)
 Called when the update button of the properties widget is clicked. More...
 
void updateSonarOpen (void)
 Called when the refresh button of the properties widget is clicked. More...
 
void updateSoundSensor (void)
 Called when the update button of the properties widget is clicked. More...
 
void updateSoundSensorOpen (void)
 Called when the refresh button of the properties widget is clicked. More...
 
void updateThermalSensor (void)
 Called when the update button of the properties widget is clicked. More...
 
void updateThermalSensorOpen (void)
 Called when the refresh button of the properties widget is clicked. More...
 

Signals

void loadRobotPressed (stdr_msgs::RobotMsg newRobotMsg)
 Emitted when the "load robot in map" button is pressed. More...
 
void saveRobotPressed (stdr_msgs::RobotMsg newRobotMsg, QString file_name)
 Emitted to save the robot in a yaml file. More...
 

Public Member Functions

void addCO2Sensor (void)
 Adds a co2 sensor in the new robot. More...
 
void addCO2Sensor (stdr_msgs::CO2SensorMsg rmsg)
 Adds a co2 sensor in the new robot. More...
 
void addFootprintPoint (void)
 Adds a footprint point in the new robot. More...
 
void addFootprintPoint (geometry_msgs::Point pt)
 Adds a footprint point in the new robot. More...
 
void addLaser (void)
 Adds a laser sensor in the new robot. More...
 
void addLaser (stdr_msgs::LaserSensorMsg lmsg)
 Adds a specific laser sensor in the new robot. More...
 
void addRfidAntenna (void)
 Adds an rfid antenna sensor in the new robot. More...
 
void addRfidAntenna (stdr_msgs::RfidSensorMsg rmsg)
 Adds an rfid antenna sensor in the new robot. More...
 
void addSonar (void)
 Adds a sonar sensor in the new robot. More...
 
void addSonar (stdr_msgs::SonarSensorMsg smsg)
 Adds a specific sonar sensor in the new robot. More...
 
void addSoundSensor (void)
 Adds a sound sensor in the new robot. More...
 
void addSoundSensor (stdr_msgs::SoundSensorMsg rmsg)
 Adds a sound sensor in the new robot. More...
 
void addThermalSensor (void)
 Adds a thermal sensor in the new robot. More...
 
void addThermalSensor (stdr_msgs::ThermalSensorMsg rmsg)
 Adds a thermal sensor in the new robot. More...
 
 CRobotCreatorConnector (int argc, char **argv)
 Default contructor. More...
 
void deleteTreeNode (QTreeWidgetItem *item)
 Deletes a specific tree item and it's children recursively. More...
 
void drawCO2Sensors (void)
 Draws the robot's rfid antennas. More...
 
void drawLasers (void)
 Draws the robot's lasers. More...
 
void drawRfidAntennas (void)
 Draws the robot's rfid antennas. More...
 
void drawRobot (void)
 Draws a robot. More...
 
void drawSonars (void)
 Draws the robot's sonars. More...
 
void drawSoundSensors (void)
 Draws the robot's rfid antennas. More...
 
void drawThermalSensors (void)
 Draws the robot's rfid antennas. More...
 
void editCO2Sensor (QTreeWidgetItem *item)
 Edits a specific co2 sensor based on a tree item. \ Initiates the co2 sensor editor widget. More...
 
void editFootprintPoint (QTreeWidgetItem *item)
 Edits a specific footprint point based on a tree item. Initiates the footprint editor widget. More...
 
void editLaser (QTreeWidgetItem *item)
 Edits a specific laser sensor based on a tree item. Initiates the laser sensor editor widget. More...
 
void editRfid (QTreeWidgetItem *item)
 Edits a specific rfid antenna sensor based on a tree item. Initiates the rfid antenna sensor editor widget. More...
 
void editRobot (void)
 Shows the edit robot widget. More...
 
void editSonar (QTreeWidgetItem *item)
 Edits a specific sonar sensor based on a tree item. Initiates the sonar sensor editor widget. More...
 
void editSoundSensor (QTreeWidgetItem *item)
 Edits a specific sound sensor based on a tree item. \ Initiates the sound sensor editor widget. More...
 
void editThermalSensor (QTreeWidgetItem *item)
 Edits a specific thermal sensor based on a tree item. \ Initiates the thermal sensor editor widget. More...
 
void eraseCO2Sensor (QTreeWidgetItem *item)
 Erases a specific co2 sensor based on a tree item. More...
 
void eraseFootprintPoint (QTreeWidgetItem *item)
 Erases a footprint point in the new robot. More...
 
void eraseLaser (QTreeWidgetItem *item)
 Erases a specific laser sensor based on a tree item. More...
 
void eraseRfid (QTreeWidgetItem *item)
 Erases a specific rfid antenna sensor based on a tree item. More...
 
void eraseSonar (QTreeWidgetItem *item)
 Erases a specific sonar sensor based on a tree item. More...
 
void eraseSoundSensor (QTreeWidgetItem *item)
 Erases a specific sound sensor based on a tree item. More...
 
void eraseThermalSensor (QTreeWidgetItem *item)
 Erases a specific thermal sensor based on a tree item. More...
 
stdr_msgs::RobotMsg getNewRobot (void)
 Returns the created robot. More...
 
void initialise (void)
 Initializes the robot creator. More...
 
void loadCO2Sensor (QTreeWidgetItem *item)
 Loads a specific co2 sensor from a file. More...
 
void loadLaser (QTreeWidgetItem *item)
 Loads a specific laser sensor from a file. More...
 
void loadRfidAntenna (QTreeWidgetItem *item)
 Loads a specific rfid reader sensor from a file. More...
 
void loadSonar (QTreeWidgetItem *item)
 Loads a specific sonar sensor from a file. More...
 
void loadSoundSensor (QTreeWidgetItem *item)
 Loads a specific sound sensor from a file. More...
 
void loadThermalSensor (QTreeWidgetItem *item)
 Loads a specific thermal sensor from a file. More...
 
void saveCO2Sensor (QTreeWidgetItem *item)
 Saves a specific co2 sensor in a file. More...
 
void saveLaser (QTreeWidgetItem *item)
 Saves a specific laser sensor in a file. More...
 
void saveRfidAntenna (QTreeWidgetItem *item)
 Saves a specific rfid reader sensor in a file. More...
 
void saveSonar (QTreeWidgetItem *item)
 Saves a specific sonar sensor in a file. More...
 
void saveSoundSensor (QTreeWidgetItem *item)
 Saves a specific sound sensor in a file. More...
 
void saveThermalSensor (QTreeWidgetItem *item)
 Saves a specific thermal sensor in a file. More...
 
int searchCO2Sensor (QString frameId)
 Returns the ID of an co2 sensor. More...
 
int searchLaser (QString frameId)
 Returns the ID of a laser sensor. More...
 
int searchRfid (QString frameId)
 Returns the ID of an rfid antenna sensor. More...
 
int searchSonar (QString frameId)
 Returns the ID of a sonar sensor. More...
 
int searchSoundSensor (QString frameId)
 Returns the ID of a sound sensor. More...
 
int searchThermalSensor (QString frameId)
 Returns the ID of a thermal sensor. More...
 
void setInitialPose (float x, float y)
 Sets the robot's initial pose. More...
 
void setNewRobot (stdr_msgs::RobotMsg msg)
 Sets the created robot. More...
 
void updateCO2SensorTree (QTreeWidgetItem *item, stdr_msgs::CO2SensorMsg l)
 Updates a tree item with a specific co2 sensor. More...
 
void updateLaserTree (QTreeWidgetItem *item, stdr_msgs::LaserSensorMsg l)
 Updates a tree item with a specific laser sensor. More...
 
void updateRfidTree (QTreeWidgetItem *item, stdr_msgs::RfidSensorMsg l)
 Updates a tree item with a specific rfid reader sensor. More...
 
void updateRobotPreview (void)
 Updates the robot's preview. More...
 
void updateRobotTree (void)
 Updates the robot's tree widget. More...
 
void updateSonarTree (QTreeWidgetItem *item, stdr_msgs::SonarSensorMsg l)
 Updates a tree item with a specific sonar sensor. More...
 
void updateSoundSensorTree (QTreeWidgetItem *item, stdr_msgs::SoundSensorMsg l)
 Updates a tree item with a specific sound sensor. More...
 
void updateThermalSensorTree (QTreeWidgetItem *item, stdr_msgs::ThermalSensorMsg l)
 Updates a tree item with a specific thermal sensor. More...
 
 ~CRobotCreatorConnector (void)
 Default destructor. More...
 

Static Public Attributes

static int co2_sensors_number = -1
 
static int laser_number = -1
 < Number of laser sensors More...
 
static int rfid_number = -1
 
static int sonar_number = -1
 Number of rfid antenna sensors. More...
 
static int sound_sensors_number = -1
 
static int thermal_sensors_number = -1
 

Private Member Functions

void showMessage (QString msg)
 Pops up a message box with a specific message. More...
 

Private Attributes

int argc_
 < Number of input arguments More...
 
char ** argv_
 Variable that holds the proportion coefficient for the visualization of robot creator image. More...
 
float climax_
 Object of CRobotCreatorLoader. More...
 
unsigned int co2_sensor_hightlight_id_
 
QTreeWidgetItem * current_co2_sensor_
 
QTreeWidgetItem * current_footprint_point_
 
QTreeWidgetItem * current_laser_
 Tree item of the currently clicked sonar. More...
 
QTreeWidgetItem * current_rfid_
 
QTreeWidgetItem * current_sonar_
 Tree item of the currently clicked rfid. More...
 
QTreeWidgetItem * current_sound_sensor_
 Tree item of the currently clicked footprint point. More...
 
QTreeWidgetItem * current_thermal_sensor_
 
unsigned int laser_hightlight_id_
 Current sonar for highlight. More...
 
CRobotCreatorLoader loader_
 Container of the new robot message. More...
 
stdr_msgs::RobotMsg new_robot_msg_
 Current laser for highlight. More...
 
unsigned int rfid_antenna_hightlight_id_
 Current rfid antenna for highlight. More...
 
unsigned int sonar_hightlight_id_
 Current rfid antenna for highlight. More...
 
unsigned int sound_sensor_hightlight_id_
 Tree item of the currently clicked laser. More...
 
unsigned int thermal_sensor_hightlight_id_
 

Detailed Description

Implements the high level functionalities of the robot creator widget. Inherits form QObject.

Definition at line 37 of file stdr_robot_creator_connector.h.

Constructor & Destructor Documentation

stdr_gui::CRobotCreatorConnector::CRobotCreatorConnector ( int  argc,
char **  argv 
)

Default contructor.

Parameters
argc[int] Number of input arguments
argv[char**] Input arguments
Returns
void

Definition at line 40 of file stdr_robot_creator_connector.cpp.

stdr_gui::CRobotCreatorConnector::~CRobotCreatorConnector ( void  )

Default destructor.

Returns
void

Definition at line 128 of file stdr_robot_creator_connector.cpp.

Member Function Documentation

void stdr_gui::CRobotCreatorConnector::addCO2Sensor ( void  )

Adds a co2 sensor in the new robot.

Definition at line 1056 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::addCO2Sensor ( stdr_msgs::CO2SensorMsg  smsg)

Adds a co2 sensor in the new robot.

Returns
void

Definition at line 1347 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::addFootprintPoint ( void  )

Adds a footprint point in the new robot.

Returns
void

Definition at line 499 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::addFootprintPoint ( geometry_msgs::Point  pt)

Adds a footprint point in the new robot.

Returns
void

Definition at line 478 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::addLaser ( void  )

Adds a laser sensor in the new robot.

Returns
void

Definition at line 640 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::addLaser ( stdr_msgs::LaserSensorMsg  lmsg)

Adds a specific laser sensor in the new robot.

Parameters
lmsg[stdr_msgs::LaserSensorMsg] The laser sensor to be added
Returns
void

Definition at line 737 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::addRfidAntenna ( void  )

Adds an rfid antenna sensor in the new robot.

Returns
void

Definition at line 981 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::addRfidAntenna ( stdr_msgs::RfidSensorMsg  smsg)

Adds an rfid antenna sensor in the new robot.

Parameters
rmsg[stdr_msgs::RfidSensorMsg] The rfid antenna sensor message
Returns
void
void

Definition at line 1283 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::addSonar ( void  )

Adds a sonar sensor in the new robot.

Returns
void

Definition at line 816 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::addSonar ( stdr_msgs::SonarSensorMsg  smsg)

Adds a specific sonar sensor in the new robot.

Parameters
smsg[stdr_msgs::SonarSensorMsg] The sonar sensor to be added
Returns
void

Definition at line 907 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::addSoundSensor ( void  )

Adds a sound sensor in the new robot.

Definition at line 1206 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::addSoundSensor ( stdr_msgs::SoundSensorMsg  smsg)

Adds a sound sensor in the new robot.

Returns
void

Definition at line 1475 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::addThermalSensor ( void  )

Adds a thermal sensor in the new robot.

Definition at line 1131 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::addThermalSensor ( stdr_msgs::ThermalSensorMsg  smsg)

Adds a thermal sensor in the new robot.

Returns
void

Definition at line 1411 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::deleteTreeNode ( QTreeWidgetItem *  item)

Deletes a specific tree item and it's children recursively.

Parameters
item[QTreeWidgetItem*] The item to be erased
Returns
void

Definition at line 4331 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::drawCO2Sensors ( void  )

Draws the robot's rfid antennas.

Definition at line 4770 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::drawLasers ( void  )

Draws the robot's lasers.

Returns
void

Definition at line 4627 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::drawRfidAntennas ( void  )

Draws the robot's rfid antennas.

Returns
void

Definition at line 4727 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::drawRobot ( void  )

Draws a robot.

Draws a circular robot.

Returns
void

Definition at line 4549 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::drawSonars ( void  )

Draws the robot's sonars.

Returns
void

Definition at line 4679 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::drawSoundSensors ( void  )

Draws the robot's rfid antennas.

Returns
void

Definition at line 4856 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::drawThermalSensors ( void  )

Draws the robot's rfid antennas.

Returns
void

Definition at line 4812 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::editCO2Sensor ( QTreeWidgetItem *  item)

Edits a specific co2 sensor based on a tree item. \ Initiates the co2 sensor editor widget.

Definition at line 2301 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::editFootprintPoint ( QTreeWidgetItem *  item)

Edits a specific footprint point based on a tree item. Initiates the footprint editor widget.

Parameters
item[QTreeWidgetItem*] Tree item that holds the specific footprint point
Returns
void

Definition at line 1640 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::editLaser ( QTreeWidgetItem *  item)

Edits a specific laser sensor based on a tree item. Initiates the laser sensor editor widget.

Parameters
item[QTreeWidgetItem*] Tree item that holds the specific laser sensor
Returns
void

Definition at line 1678 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::editRfid ( QTreeWidgetItem *  item)

Edits a specific rfid antenna sensor based on a tree item. Initiates the rfid antenna sensor editor widget.

Parameters
item[QTreeWidgetItem*] Tree item that holds the specific rfid antenna sensor
Returns
void

Definition at line 2258 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::editRobot ( void  )

Shows the edit robot widget.

Returns
void

Definition at line 4261 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::editSonar ( QTreeWidgetItem *  item)

Edits a specific sonar sensor based on a tree item. Initiates the sonar sensor editor widget.

Parameters
item[QTreeWidgetItem*] Tree item that holds the specific sonar sensor
Returns
void

Definition at line 2205 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::editSoundSensor ( QTreeWidgetItem *  item)

Edits a specific sound sensor based on a tree item. \ Initiates the sound sensor editor widget.

Definition at line 2384 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::editThermalSensor ( QTreeWidgetItem *  item)

Edits a specific thermal sensor based on a tree item. \ Initiates the thermal sensor editor widget.

Definition at line 2344 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::eraseCO2Sensor ( QTreeWidgetItem *  item)

Erases a specific co2 sensor based on a tree item.

Definition at line 1592 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::eraseFootprintPoint ( QTreeWidgetItem *  item)

Erases a footprint point in the new robot.

Returns
void

Definition at line 525 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::eraseLaser ( QTreeWidgetItem *  item)

Erases a specific laser sensor based on a tree item.

Parameters
item[QTreeWidgetItem*] Tree item that holds the specific laser sensor
Returns
void

Definition at line 1541 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::eraseRfid ( QTreeWidgetItem *  item)

Erases a specific rfid antenna sensor based on a tree item.

Parameters
item[QTreeWidgetItem*] Tree item that holds the specific rfid antenna sensor
Returns
void

Definition at line 1577 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::eraseSonar ( QTreeWidgetItem *  item)

Erases a specific sonar sensor based on a tree item.

Parameters
item[QTreeWidgetItem*] Tree item that holds the specific sonar sensor
Returns
void

Definition at line 1559 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::eraseSoundSensor ( QTreeWidgetItem *  item)

Erases a specific sound sensor based on a tree item.

Definition at line 1622 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::eraseThermalSensor ( QTreeWidgetItem *  item)

Erases a specific thermal sensor based on a tree item.

Definition at line 1607 of file stdr_robot_creator_connector.cpp.

stdr_msgs::RobotMsg stdr_gui::CRobotCreatorConnector::getNewRobot ( void  )

Returns the created robot.

Returns
stdr_msgs::RobotMsg : The new robot

Definition at line 4992 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::getRobotFromYaml ( void  )
slot

Called when the load robot button.

Returns
void

< Not a valid filename

Definition at line 4918 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::initialise ( void  )

Initializes the robot creator.

Returns
void

Definition at line 137 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::loadCO2Sensor ( QTreeWidgetItem *  item)

Loads a specific co2 sensor from a file.

Definition at line 2076 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::loadLaser ( QTreeWidgetItem *  item)

Loads a specific laser sensor from a file.

Parameters
item[QTreeWidgetItem*] The tree item that holds the laser sensor
Returns
void

Definition at line 1944 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::loadRfidAntenna ( QTreeWidgetItem *  item)

Loads a specific rfid reader sensor from a file.

Loads a specific rfid antenna sensor from a file.

Parameters
item[QTreeWidgetItem*] The tree item that holds the sensor
Returns
void

Definition at line 2034 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::loadRobot ( void  )
slot

Called when the load robot in map button is clicked.

Returns
void

Definition at line 4970 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::loadRobotPressed ( stdr_msgs::RobotMsg  newRobotMsg)
signal

Emitted when the "load robot in map" button is pressed.

Parameters
newRobotMsg[stdr_msgs::RobotMsg] The new robot to be placed in the map
Returns
void
void stdr_gui::CRobotCreatorConnector::loadSonar ( QTreeWidgetItem *  item)

Loads a specific sonar sensor from a file.

Parameters
item[QTreeWidgetItem*] The tree item that holds the sonar sensor
Returns
void

Definition at line 1989 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::loadSoundSensor ( QTreeWidgetItem *  item)

Loads a specific sound sensor from a file.

Definition at line 2160 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::loadThermalSensor ( QTreeWidgetItem *  item)

Loads a specific thermal sensor from a file.

Definition at line 2118 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::saveCO2Sensor ( QTreeWidgetItem *  item)

Saves a specific co2 sensor in a file.

Definition at line 1842 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::saveLaser ( QTreeWidgetItem *  item)

Saves a specific laser sensor in a file.

Parameters
item[QTreeWidgetItem*] The tree item that holds the laser sensor
Returns
void

Definition at line 1736 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::saveRfidAntenna ( QTreeWidgetItem *  item)

Saves a specific rfid reader sensor in a file.

Parameters
item[QTreeWidgetItem*] The tree item that holds the sensor
Returns
void

Definition at line 1808 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::saveRobot ( void  )
slot

Called when the save robot button is clicked.

Returns
void

Definition at line 4901 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::saveRobotPressed ( stdr_msgs::RobotMsg  newRobotMsg,
QString  file_name 
)
signal

Emitted to save the robot in a yaml file.

Parameters
newRobotMsg[stdr_msgs::RobotMsg] The new robot to be saved
file_name[QString] The file name for the robot description to be saved
Returns
void
void stdr_gui::CRobotCreatorConnector::saveSonar ( QTreeWidgetItem *  item)

Saves a specific sonar sensor in a file.

Parameters
item[QTreeWidgetItem*] The tree item that holds the sonar sensor
Returns
void

Definition at line 1772 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::saveSoundSensor ( QTreeWidgetItem *  item)

Saves a specific sound sensor in a file.

Definition at line 1908 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::saveThermalSensor ( QTreeWidgetItem *  item)

Saves a specific thermal sensor in a file.

Definition at line 1875 of file stdr_robot_creator_connector.cpp.

int stdr_gui::CRobotCreatorConnector::searchCO2Sensor ( QString  frameId)

Returns the ID of an co2 sensor.

Parameters
frameId[QString] The frame id of the co2 sensor
Returns
int

Definition at line 2476 of file stdr_robot_creator_connector.cpp.

int stdr_gui::CRobotCreatorConnector::searchLaser ( QString  frameId)

Returns the ID of a laser sensor.

Parameters
frameId[QString] The frame id of the laser sensor
Returns
int

Definition at line 2426 of file stdr_robot_creator_connector.cpp.

int stdr_gui::CRobotCreatorConnector::searchRfid ( QString  frameId)

Returns the ID of an rfid antenna sensor.

Parameters
frameId[QString] The frame id of the rfid antenna sensor
Returns
int

Definition at line 2460 of file stdr_robot_creator_connector.cpp.

int stdr_gui::CRobotCreatorConnector::searchSonar ( QString  frameId)

Returns the ID of a sonar sensor.

Parameters
frameId[QString] The frame id of the sonar sensor
Returns
int

Definition at line 2443 of file stdr_robot_creator_connector.cpp.

int stdr_gui::CRobotCreatorConnector::searchSoundSensor ( QString  frameId)

Returns the ID of a sound sensor.

Parameters
frameId[QString] The frame id of the sound sensor
Returns
int

Definition at line 2508 of file stdr_robot_creator_connector.cpp.

int stdr_gui::CRobotCreatorConnector::searchThermalSensor ( QString  frameId)

Returns the ID of a thermal sensor.

Parameters
frameId[QString] The frame id of the thermal sensor
Returns
int

Definition at line 2492 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::setInitialPose ( float  x,
float  y 
)

Sets the robot's initial pose.

Parameters
x[float] x coordinate
y[float] y coordinate
Returns
void

Definition at line 4982 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::setNewRobot ( stdr_msgs::RobotMsg  msg)

Sets the created robot.

Parameters
msg[stdr_msgs::RobotMsg] The new robot
Returns
void

Definition at line 5002 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::showMessage ( QString  msg)
private

Pops up a message box with a specific message.

Parameters
msg[QString] Message to be shown
Returns
void

Definition at line 5012 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::treeItemClicked ( QTreeWidgetItem *  item,
int  column 
)
slot

Called when a tree item is clicked.

Parameters
item[QTreeWidgetItem *] The item clicked
column[int] The column clicked
Returns
void

< Laser clicked

< Robot edit clicked

Definition at line 189 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::updateCO2Sensor ( void  )
slot

Called when the update button of the properties widget is clicked.

< Rfid antenna angle span

< Orientation

Definition at line 3611 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::updateCO2SensorOpen ( void  )
slot

Called when the refresh button of the properties widget is clicked.

< Rfid antenna orientation

Definition at line 3989 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::updateCO2SensorTree ( QTreeWidgetItem *  item,
stdr_msgs::CO2SensorMsg  l 
)

Updates a tree item with a specific co2 sensor.

Definition at line 3375 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::updateFootprintPoint ( void  )
slot

Called when the update button of the footprint widget is clicked.

Returns
void

Definition at line 544 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::updateFootprintPointOpen ( void  )
slot

Called when the refresh button of the properties widget is clicked.

Returns
void

Definition at line 606 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::updateKinematicModel ( void  )
slot

Called when the update button of the kinematic model widget is clicked.

Returns
void

Definition at line 580 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::updateLaser ( void  )
slot

Called when the update button of the properties widget is clicked.

Returns
void

< Laser angle span

Definition at line 2661 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::updateLaserOpen ( void  )
slot

Called when the refresh button of the properties widget is clicked.

Returns
void

< Laser angle span

Definition at line 2825 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::updateLaserTree ( QTreeWidgetItem *  item,
stdr_msgs::LaserSensorMsg  l 
)

Updates a tree item with a specific laser sensor.

Parameters
item[QTreeWidgetItem*] The tree item that will be updated
l[stdr_msgs::LaserSensorMsg] The laser sensor message
Returns
void

Definition at line 2608 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::updateRfidAntenna ( void  )
slot

Called when the update button of the properties widget is clicked.

Returns
void

< Rfid antenna angle span

Definition at line 3509 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::updateRfidAntennaOpen ( void  )
slot

Called when the update button of the properties widget is clicked.

Called when the refresh button of the properties widget is clicked.

Returns
void

< Rfid antenna angle span

Definition at line 3889 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::updateRfidTree ( QTreeWidgetItem *  item,
stdr_msgs::RfidSensorMsg  l 
)

Updates a tree item with a specific rfid reader sensor.

Updates a tree item with a specific rfid antenna sensor.

Parameters
item[QTreeWidgetItem*] The tree item that will be updated
l[stdr_msgs::RfidSensorMsg] The rfid reader sensor message
Returns
void
Parameters
item[QTreeWidgetItem*] The tree item that will be updated
l[stdr_msgs::RfidSensorMsg] The rfid antenna sensor message
Returns
void

Definition at line 3331 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::updateRobot ( void  )
slot

Called when the update button of the properties widget is clicked.

Returns
void

Definition at line 4274 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::updateRobotOpen ( void  )
slot

Called when the refresh button of the properties widget is clicked.

Returns
void

Definition at line 4303 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::updateRobotPreview ( void  )

Updates the robot's preview.

Returns
void

Definition at line 4345 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::updateRobotTree ( void  )

Updates the robot's tree widget.

Returns
void

Definition at line 2524 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::updateSonar ( void  )
slot

Called when the update button of the properties widget is clicked.

Returns
void

< Sonar cone span

Definition at line 2988 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::updateSonarOpen ( void  )
slot

Called when the refresh button of the properties widget is clicked.

Returns
void

< Sonar cone span

Definition at line 3131 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::updateSonarTree ( QTreeWidgetItem *  item,
stdr_msgs::SonarSensorMsg  l 
)

Updates a tree item with a specific sonar sensor.

Parameters
item[QTreeWidgetItem*] The tree item that will be updated
l[stdr_msgs::SonarSensorMsg] The sonar sensor message
Returns
void

Definition at line 3275 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::updateSoundSensor ( void  )
slot

Called when the update button of the properties widget is clicked.

Definition at line 3795 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::updateSoundSensorOpen ( void  )
slot

Called when the refresh button of the properties widget is clicked.

< Angle span

Definition at line 4169 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::updateSoundSensorTree ( QTreeWidgetItem *  item,
stdr_msgs::SoundSensorMsg  l 
)

Updates a tree item with a specific sound sensor.

Definition at line 3463 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::updateThermalSensor ( void  )
slot

Called when the update button of the properties widget is clicked.

Definition at line 3703 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::updateThermalSensorOpen ( void  )
slot

Called when the refresh button of the properties widget is clicked.

< Angle span

Definition at line 4079 of file stdr_robot_creator_connector.cpp.

void stdr_gui::CRobotCreatorConnector::updateThermalSensorTree ( QTreeWidgetItem *  item,
stdr_msgs::ThermalSensorMsg  l 
)

Updates a tree item with a specific thermal sensor.

Definition at line 3419 of file stdr_robot_creator_connector.cpp.

Member Data Documentation

int stdr_gui::CRobotCreatorConnector::argc_
private

< Number of input arguments

Input arguments

Definition at line 44 of file stdr_robot_creator_connector.h.

char** stdr_gui::CRobotCreatorConnector::argv_
private

Variable that holds the proportion coefficient for the visualization of robot creator image.

Definition at line 46 of file stdr_robot_creator_connector.h.

float stdr_gui::CRobotCreatorConnector::climax_
private

Object of CRobotCreatorLoader.

Definition at line 49 of file stdr_robot_creator_connector.h.

unsigned int stdr_gui::CRobotCreatorConnector::co2_sensor_hightlight_id_
private

Definition at line 64 of file stdr_robot_creator_connector.h.

int stdr_gui::CRobotCreatorConnector::co2_sensors_number = -1
static

Definition at line 96 of file stdr_robot_creator_connector.h.

QTreeWidgetItem* stdr_gui::CRobotCreatorConnector::current_co2_sensor_
private

Definition at line 74 of file stdr_robot_creator_connector.h.

QTreeWidgetItem* stdr_gui::CRobotCreatorConnector::current_footprint_point_
private

Definition at line 78 of file stdr_robot_creator_connector.h.

QTreeWidgetItem* stdr_gui::CRobotCreatorConnector::current_laser_
private

Tree item of the currently clicked sonar.

Definition at line 69 of file stdr_robot_creator_connector.h.

QTreeWidgetItem* stdr_gui::CRobotCreatorConnector::current_rfid_
private

Definition at line 73 of file stdr_robot_creator_connector.h.

QTreeWidgetItem* stdr_gui::CRobotCreatorConnector::current_sonar_
private

Tree item of the currently clicked rfid.

Definition at line 71 of file stdr_robot_creator_connector.h.

QTreeWidgetItem* stdr_gui::CRobotCreatorConnector::current_sound_sensor_
private

Tree item of the currently clicked footprint point.

Definition at line 76 of file stdr_robot_creator_connector.h.

QTreeWidgetItem* stdr_gui::CRobotCreatorConnector::current_thermal_sensor_
private

Definition at line 75 of file stdr_robot_creator_connector.h.

unsigned int stdr_gui::CRobotCreatorConnector::laser_hightlight_id_
private

Current sonar for highlight.

Definition at line 58 of file stdr_robot_creator_connector.h.

int stdr_gui::CRobotCreatorConnector::laser_number = -1
static

< Number of laser sensors

Number of sonar sensors

Definition at line 91 of file stdr_robot_creator_connector.h.

CRobotCreatorLoader stdr_gui::CRobotCreatorConnector::loader_
private

Container of the new robot message.

Definition at line 52 of file stdr_robot_creator_connector.h.

stdr_msgs::RobotMsg stdr_gui::CRobotCreatorConnector::new_robot_msg_
private

Current laser for highlight.

Definition at line 55 of file stdr_robot_creator_connector.h.

unsigned int stdr_gui::CRobotCreatorConnector::rfid_antenna_hightlight_id_
private

Current rfid antenna for highlight.

Definition at line 62 of file stdr_robot_creator_connector.h.

int stdr_gui::CRobotCreatorConnector::rfid_number = -1
static

Definition at line 95 of file stdr_robot_creator_connector.h.

unsigned int stdr_gui::CRobotCreatorConnector::sonar_hightlight_id_
private

Current rfid antenna for highlight.

Definition at line 60 of file stdr_robot_creator_connector.h.

int stdr_gui::CRobotCreatorConnector::sonar_number = -1
static

Number of rfid antenna sensors.

Definition at line 93 of file stdr_robot_creator_connector.h.

unsigned int stdr_gui::CRobotCreatorConnector::sound_sensor_hightlight_id_
private

Tree item of the currently clicked laser.

Definition at line 66 of file stdr_robot_creator_connector.h.

int stdr_gui::CRobotCreatorConnector::sound_sensors_number = -1
static

Definition at line 98 of file stdr_robot_creator_connector.h.

unsigned int stdr_gui::CRobotCreatorConnector::thermal_sensor_hightlight_id_
private

Definition at line 65 of file stdr_robot_creator_connector.h.

int stdr_gui::CRobotCreatorConnector::thermal_sensors_number = -1
static

Definition at line 97 of file stdr_robot_creator_connector.h.


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


stdr_gui
Author(s): Manos Tsardoulias
autogenerated on Mon Jun 10 2019 15:15:17