Project

General

Profile

Statistics
| Branch: | Revision:

root / rgbdslam / src / ros_service_ui.h @ 9240aaa3

History | View | Annotate | Download (3.17 KB)

1 9240aaa3 Alex
/* This file is part of RGBDSLAM.
2
 * 
3
 * RGBDSLAM is free software: you can redistribute it and/or modify
4
 * it under the terms of the GNU General Public License as published by
5
 * the Free Software Foundation, either version 3 of the License, or
6
 * (at your option) any later version.
7
 * 
8
 * RGBDSLAM is distributed in the hope that it will be useful,
9
 * but WITHOUT ANY WARRANTY; without even the implied warranty of
10
 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
11
 * GNU General Public License for more details.
12
 * 
13
 * You should have received a copy of the GNU General Public License
14
 * along with RGBDSLAM.  If not, see <http://www.gnu.org/licenses/>.
15
 */
16
#ifndef ROS_UI_H
17
#define ROS_UI_H
18
19
#include <QMainWindow>
20
#include <QGridLayout>
21
#include "glviewer.h"
22
#include "parameter_server.h"
23
#include <QObject>
24
#include "rgbdslam/rgbdslam_ros_ui.h"
25
#include "rgbdslam/rgbdslam_ros_ui_b.h"
26
#include "rgbdslam/rgbdslam_ros_ui_f.h"
27
28
class QAction;
29
30
///Headless version of the Graphical_UI
31
///works with service-calls and offers the possibility to run rgbdslam without a GUI
32
class RosUi: public QObject{
33
    Q_OBJECT
34
35
public:
36
    RosUi(const char* service_namespace);
37
38
    ///a service-client for all methods not needing an argument: {reset, quick_save, save_all, save_individual, send_all, delete_frame}
39
    bool services(rgbdslam::rgbdslam_ros_ui::Request  &req, rgbdslam::rgbdslam_ros_ui::Response &res);
40
    ///a service-client for all methods with bool as argument: {pause, record}
41
    bool services_b(rgbdslam::rgbdslam_ros_ui_b::Request  &req, rgbdslam::rgbdslam_ros_ui_b::Response &res);
42
    ///a service-client for changing the maximal depth of a point: {set_max}
43
    bool services_f(rgbdslam::rgbdslam_ros_ui_f::Request  &req, rgbdslam::rgbdslam_ros_ui_f::Response &res);
44
Q_SIGNALS:
45
    ///User selected to reset the graph
46
    void reset(); 
47
    ///User selected to start or resume processing
48
    void togglePause();
49
    ///User selected to start or resume bag recording
50
    void toggleBagRecording();
51
    ///User wants the next frame to be processed
52
    void getOneFrame();
53
    ///User wants the last node to be removed from the graph
54
    void deleteLastFrame();
55
    void sendAllClouds(); ///< Signifies the sending of the whole model
56
    ///User wants the current world model to be saved to a pcd-file or ply file
57
    void saveAllClouds(QString filename);
58
    ///User wants the current world model to be saved to one pcd-file per node
59
    void saveIndividualClouds(QString file_basename);
60
    void setMaxDepth(float max_depth);
61
    ///User wants logfiles of the trajectory estimate (and ground truth if available)
62
    void saveTrajectory(QString);
63
    void optimizeGraph();
64
     
65
public Q_SLOTS:
66
    void sendFinished();
67
68
private:
69
    void resetCmd();
70
    void sendAll();
71
    void setMax(float val);
72
    void saveAll();
73
    void saveIndividual();
74
    void quickSaveAll();
75
    void pause(bool);
76
    void bagRecording(bool);
77
    void getOneFrameCmd();
78
    void deleteLastFrameCmd();
79
private:
80
    void createActions(const char* service_namespace);
81
    bool pause_on;
82
    QString filename;
83
    bool record_on;
84
    ros::ServiceServer server;
85
    ros::ServiceServer server_b;
86
    ros::ServiceServer server_f;
87
};
88
89
#endif