Public Slots | Signals | Public Member Functions | Private Member Functions | Private Attributes
RosUi Class Reference

Headless version of the Graphical_UI. More...

#include <ros_service_ui.h>

List of all members.

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 ()
 Trigger graph optimizer.
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 saveG2OGraph (QString filename)
 User wants the g2o graph saved.
void saveIndividualClouds (QString file_basename)
 User wants the current world model to be saved to one pcd-file per node.
void saveOctomapSig (QString filename)
 User wants the current world model to be saved to an octomap.
void saveTrajectory (QString)
 User wants logfiles of the trajectory estimate (and ground truth if available)
void sendAllClouds ()
void setMaxDepth (float max_depth)
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 floats, e.g., for changing the maximal depth of a point: {set_max}
bool services_s (rgbdslam::rgbdslam_ros_ui_s::Request &req, rgbdslam::rgbdslam_ros_ui_s::Response &res)
 a service-client for commands with string arguments, e.g. a filename

Private Member Functions

void pause (bool)
void toggleCloudStorage (bool)

Private Attributes

QString filename
bool pause_on
bool record_on
ros::ServiceServer server
ros::ServiceServer server_b
ros::ServiceServer server_f
ros::ServiceServer server_s

Detailed Description

Headless version of the Graphical_UI.

works with service-calls and offers the possibility to run rgbdslam without a GUI

Definition at line 33 of file ros_service_ui.h.


Constructor & Destructor Documentation

RosUi::RosUi ( const char *  service_namespace)

Definition at line 25 of file ros_service_ui.cpp.


Member Function Documentation

void RosUi::deleteLastFrame ( ) [signal]

User wants the last node to be removed from the graph.

void RosUi::getOneFrame ( ) [signal]

User wants the next frame to be processed.

void RosUi::optimizeGraph ( ) [signal]

Trigger graph optimizer.

void RosUi::pause ( bool  _pause_on) [private]

Definition at line 41 of file ros_service_ui.cpp.

void RosUi::reset ( ) [signal]

User selected to reset the graph.

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::saveG2OGraph ( QString  filename) [signal]

User wants the g2o graph saved.

void RosUi::saveIndividualClouds ( QString  file_basename) [signal]

User wants the current world model to be saved to one pcd-file per node.

void RosUi::saveOctomapSig ( QString  filename) [signal]

User wants the current world model to be saved to an octomap.

void RosUi::saveTrajectory ( QString  ) [signal]

User wants logfiles of the trajectory estimate (and ground truth if available)

void RosUi::sendAllClouds ( ) [signal]

Signifies the sending of the whole model

void RosUi::sendFinished ( ) [slot]

Definition at line 36 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 55 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 77 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 floats, e.g., for changing the maximal depth of a point: {set_max}

Definition at line 110 of file ros_service_ui.cpp.

bool RosUi::services_s ( rgbdslam::rgbdslam_ros_ui_s::Request &  req,
rgbdslam::rgbdslam_ros_ui_s::Response &  res 
)

a service-client for commands with string arguments, e.g. a filename

Definition at line 92 of file ros_service_ui.cpp.

void RosUi::setMaxDepth ( float  max_depth) [signal]
void RosUi::toggleCloudStorage ( bool  storage) [private]

Definition at line 124 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.


Member Data Documentation

QString RosUi::filename [private]

Definition at line 83 of file ros_service_ui.h.

bool RosUi::pause_on [private]

Definition at line 82 of file ros_service_ui.h.

bool RosUi::record_on [private]

Definition at line 84 of file ros_service_ui.h.

Definition at line 85 of file ros_service_ui.h.

Definition at line 86 of file ros_service_ui.h.

Definition at line 87 of file ros_service_ui.h.

Definition at line 88 of file ros_service_ui.h.


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


rgbdslam_v2
Author(s): Felix Endres, Juergen Hess, Nikolas Engelhard
autogenerated on Thu Jun 6 2019 21:49:45