Headless version of the Graphical_UI. More...
#include <ros_service_ui.h>
Public Slots | |
void | sendFinished () |
Signals | |
void | deleteLastFrame () |
User wants the last node to be removed from the graph. | |
void | getOneFrame () |
User wants the next frame to be processed. | |
void | optimizeGraph () |
void | reset () |
User selected to reset the graph. | |
void | saveAllClouds (QString filename) |
User wants the current world model to be saved to a pcd-file or ply file. | |
void | saveAllFeatures (QString filename) |
User wants the feature locations and descriptions saved to yaml or xml file. | |
void | saveIndividualClouds (QString file_basename) |
User wants the current world model to be saved to one pcd-file per node. | |
void | saveTrajectory (QString) |
User wants logfiles of the trajectory estimate (and ground truth if available) | |
void | sendAllClouds () |
void | setMaxDepth (float max_depth) |
void | toggleBagRecording () |
User selected to start or resume bag recording. | |
void | toggleMapping (bool) |
User selected to do SLAM or Localization only. | |
void | togglePause () |
User selected to start or resume processing. | |
Public Member Functions | |
RosUi (const char *service_namespace) | |
bool | services (rgbdslam::rgbdslam_ros_ui::Request &req, rgbdslam::rgbdslam_ros_ui::Response &res) |
a service-client for all methods not needing an argument: {reset, quick_save, save_all, save_individual, send_all, delete_frame} | |
bool | services_b (rgbdslam::rgbdslam_ros_ui_b::Request &req, rgbdslam::rgbdslam_ros_ui_b::Response &res) |
a service-client for all methods with bool as argument: {pause, record} | |
bool | services_f (rgbdslam::rgbdslam_ros_ui_f::Request &req, rgbdslam::rgbdslam_ros_ui_f::Response &res) |
a service-client for changing the maximal depth of a point: {set_max} | |
Private Member Functions | |
void | bagRecording (bool) |
void | createActions (const char *service_namespace) |
void | deleteLastFrameCmd () |
void | getOneFrameCmd () |
void | pause (bool) |
void | quickSaveAll () |
void | resetCmd () |
void | saveAll () |
void | saveFeatures () |
void | saveIndividual () |
void | sendAll () |
void | setMax (float val) |
void | toggleCloudStorage (bool) |
Private Attributes | |
QString | filename |
bool | pause_on |
bool | record_on |
ros::ServiceServer | server |
ros::ServiceServer | server_b |
ros::ServiceServer | server_f |
Headless version of the Graphical_UI.
works with service-calls and offers the possibility to run rgbdslam without a GUI
Definition at line 32 of file ros_service_ui.h.
RosUi::RosUi | ( | const char * | service_namespace | ) |
Definition at line 25 of file ros_service_ui.cpp.
void RosUi::bagRecording | ( | bool | _record_on | ) | [private] |
Definition at line 79 of file ros_service_ui.cpp.
void RosUi::createActions | ( | const char * | service_namespace | ) | [private] |
Definition at line 109 of file ros_service_ui.cpp.
void RosUi::deleteLastFrame | ( | ) | [signal] |
User wants the last node to be removed from the graph.
void RosUi::deleteLastFrameCmd | ( | ) | [private] |
Definition at line 74 of file ros_service_ui.cpp.
void RosUi::getOneFrame | ( | ) | [signal] |
User wants the next frame to be processed.
void RosUi::getOneFrameCmd | ( | ) | [private] |
Definition at line 69 of file ros_service_ui.cpp.
void RosUi::optimizeGraph | ( | ) | [signal] |
void RosUi::pause | ( | bool | _pause_on | ) | [private] |
Definition at line 92 of file ros_service_ui.cpp.
void RosUi::quickSaveAll | ( | ) | [private] |
Definition at line 37 of file ros_service_ui.cpp.
void RosUi::reset | ( | ) | [signal] |
User selected to reset the graph.
void RosUi::resetCmd | ( | ) | [private] |
Definition at line 31 of file ros_service_ui.cpp.
void RosUi::saveAll | ( | ) | [private] |
Definition at line 47 of file ros_service_ui.cpp.
void RosUi::saveAllClouds | ( | QString | filename | ) | [signal] |
User wants the current world model to be saved to a pcd-file or ply file.
void RosUi::saveAllFeatures | ( | QString | filename | ) | [signal] |
User wants the feature locations and descriptions saved to yaml or xml file.
void RosUi::saveFeatures | ( | ) | [private] |
Definition at line 42 of file ros_service_ui.cpp.
void RosUi::saveIndividual | ( | ) | [private] |
Definition at line 52 of file ros_service_ui.cpp.
void RosUi::saveIndividualClouds | ( | QString | file_basename | ) | [signal] |
User wants the current world model to be saved to one pcd-file per node.
void RosUi::saveTrajectory | ( | QString | ) | [signal] |
User wants logfiles of the trajectory estimate (and ground truth if available)
void RosUi::sendAll | ( | ) | [private] |
Definition at line 60 of file ros_service_ui.cpp.
void RosUi::sendAllClouds | ( | ) | [signal] |
Signifies the sending of the whole model
void RosUi::sendFinished | ( | ) | [slot] |
Definition at line 65 of file ros_service_ui.cpp.
bool RosUi::services | ( | rgbdslam::rgbdslam_ros_ui::Request & | req, |
rgbdslam::rgbdslam_ros_ui::Response & | res | ||
) |
a service-client for all methods not needing an argument: {reset, quick_save, save_all, save_individual, send_all, delete_frame}
Definition at line 117 of file ros_service_ui.cpp.
bool RosUi::services_b | ( | rgbdslam::rgbdslam_ros_ui_b::Request & | req, |
rgbdslam::rgbdslam_ros_ui_b::Response & | res | ||
) |
a service-client for all methods with bool as argument: {pause, record}
Definition at line 137 of file ros_service_ui.cpp.
bool RosUi::services_f | ( | rgbdslam::rgbdslam_ros_ui_f::Request & | req, |
rgbdslam::rgbdslam_ros_ui_f::Response & | res | ||
) |
a service-client for changing the maximal depth of a point: {set_max}
Definition at line 151 of file ros_service_ui.cpp.
void RosUi::setMax | ( | float | val | ) | [private] |
Definition at line 105 of file ros_service_ui.cpp.
void RosUi::setMaxDepth | ( | float | max_depth | ) | [signal] |
void RosUi::toggleBagRecording | ( | ) | [signal] |
User selected to start or resume bag recording.
void RosUi::toggleCloudStorage | ( | bool | storage | ) | [private] |
Definition at line 164 of file ros_service_ui.cpp.
void RosUi::toggleMapping | ( | bool | ) | [signal] |
User selected to do SLAM or Localization only.
void RosUi::togglePause | ( | ) | [signal] |
User selected to start or resume processing.
QString RosUi::filename [private] |
Definition at line 88 of file ros_service_ui.h.
bool RosUi::pause_on [private] |
Definition at line 87 of file ros_service_ui.h.
bool RosUi::record_on [private] |
Definition at line 89 of file ros_service_ui.h.
ros::ServiceServer RosUi::server [private] |
Definition at line 90 of file ros_service_ui.h.
ros::ServiceServer RosUi::server_b [private] |
Definition at line 91 of file ros_service_ui.h.
ros::ServiceServer RosUi::server_f [private] |
Definition at line 92 of file ros_service_ui.h.