window.hpp
Go to the documentation of this file.
1 
9 #ifndef QTCTRL_GUI
10 #define QTCTRL_GUI
11 
12 
13 #include <QMainWindow>
14 #include <QMenuBar>
15 #include <QToolBar>
16 #include <QAction>
17 #include <QListView>
18 #include <QEvent>
19 #include <model/thread.hpp>
20 #include <ctrl/smoothPath.hpp>
21 #include <gui/ctrlWdgt.hpp>
22 #include <gui/display.hpp>
23 
24 // State class is used as parameters in this GUI's slots.
25 // This macro is needed before the call to qRegisterMetaType in
26 // the constructor.
27 Q_DECLARE_METATYPE(State)
28 
29 
41 class QtCtrlGUI : public QMainWindow {
42  Q_OBJECT // This macro is needed to handle graphical events
43 
45  static const double time_step;
46 
49  QMenuBar menu_bar;
50 
53  QMenu app_menu;
54 
57  QMenu help_menu;
58 
64  QToolBar tool_bar;
65 
69 
72  QAction about_action;
73 
76 
79  QAction about_Qt_action;
80 
81 
84 
88 
91 
95 
99 
102  QListView logs;
103 
104  void readSettings();
105  void writeSettings();
106 
110  void connectCtrl() {
111  connect( controller, SIGNAL( stateUpdated(const State&) ),
112  this, SLOT( updateState(const State&) ) );
113  connect( controller,
114  SIGNAL( commandsUpdated(const double&, const double&) ),
115  this, SLOT( updateCommands(const double&, const double&)
116  ) );
117  }
118 
119 public:
130  QtCtrlGUI(const int argc, char** argv, QWidget *parent = 0);
131 
133  // Freeing the Qt widget pointer is OK, the other one generates
134  // a segmentation fault (?!?).
135  ~QtCtrlGUI() { if ( ROS_server.isRunning() ) ROS_server.stop();
136  delete ctrl_wdgt; /* delete controller; */ }
137 
139  const MotionModel& motionModel() const { return motion_model; }
140 
144  void newTrajectory(const std::list<State*>& trajectory)
145  { display.addTrajectory(trajectory); }
146 
147 protected Q_SLOTS:
156  void closeEvent(QCloseEvent* event) {
157  if ( ctrl_node.connected() )
158  // simplified version of buttonStartStop()
159  { ctrl_node.end(); ROS_server.stop(); }
160  writeSettings(); QMainWindow::closeEvent(event);
161  qApp->closeAllWindows();
162  }
163 
171  void keyPressEvent(QKeyEvent* event)
172  { ctrl_wdgt->keyPressed(event); }
173 
181  void keyReleaseEvent(QKeyEvent* event)
182  { ctrl_wdgt->keyReleased(event); }
183 
184 private Q_SLOTS:
188  void threadError(const int error, const QString& program);
189 
191  void actionAbout();
192 
194  void buttonStartStop();
195 
197  void updateLogging() { logs.scrollToBottom(); }
198 
201  void updateState(const State& state)
202  { ctrl_wdgt->updateState(state); display.updateState(state); }
203 
206  { display.addTrajectory( ( (SmoothPathCtrl*)(controller) )
207  ->getAimedTrajectory() ); }
208 
213  void updateCommands(const double& trans_vel, const double& rot_vel)
214  { ctrl_wdgt->updateCommands(trans_vel, rot_vel);
215  display.updateCommands(trans_vel, rot_vel); }
216 
217 }; // end of class QtCtrlGUI
218 
219 #endif // QTCTRL_GUI
ROSnode ctrl_node
The ROS node at the center of this GUI.
Definition: window.hpp:90
Controller is the abstract class inherited by all the implemented controllers.
Definition: controller.hpp:28
QMenuBar menu_bar
The menu bar of this GUI.
Definition: window.hpp:49
Oriented point reaching controller class using a smooth path generator.
void updateState(const State &state)
Update the display of the state.
Definition: window.hpp:201
void updateLogging()
Method activated when this GUI&#39;s log view is updated.
Definition: window.hpp:197
QMenu app_menu
The actions&#39; menu of this GUI.
Definition: window.hpp:53
void updateState(const State &state)
Update the display of the state.
Definition: display.cpp:85
ROSserver ROS_server
The instance used to start a ROS server, if needed.
Definition: window.hpp:75
const MotionModel & motionModel() const
The motion model of the controlled robot.
Definition: window.hpp:139
QToolBar tool_bar
The tool bar of this GUI.
Definition: window.hpp:64
void updateCommands(const double &trans_vel, const double &rot_vel)
Update the display of the controller&#39;s commands.
Definition: window.hpp:213
virtual void updateState(const State &state)=0
Update the display of the odometry.
QMenu help_menu
The help menu of this GUI.
Definition: window.hpp:57
This abstract class is inherited by all those containing a Qt widget intended to show the controller&#39;...
Definition: ctrlWdgt.hpp:24
void connectCtrl()
Connects the controller signals to this class&#39; methods.
Definition: window.hpp:110
ControlWidget * ctrl_wdgt
The widget showing the controller&#39;s velocities can also change.
Definition: window.hpp:94
void keyPressed(QKeyEvent *event)
Handles Quit/eXit shortcuts.
Definition: ctrlWdgt.hpp:69
static const double time_step
The default time step.
Definition: window.hpp:45
void newTrajectory(const std::list< State * > &trajectory)
Adds a trajectory to the motion display.
Definition: window.hpp:144
Qt widget displaying data for qt_ctrl.
void stop()
Stops the ROS server (and the thread&#39;s execution).
Definition: thread.hpp:60
This class defines a state, i.e. a configuration and its (translation and rotation) velocities...
Definition: state.hpp:22
Controller * controller
The controller of the ROS node can change.
Definition: window.hpp:87
bool connected() const
Indicates whether the node is connected to ROS.
Definition: ROS_node.hpp:135
SmoothPathCtrl aims at reaching an oriented point with the robot, using a smooth path generator...
Definition: smoothPath.hpp:26
Qt based thread for qt_ctrl package.
QAction about_action
The Qt action starting a dialog box about Qt Ctrl.
Definition: window.hpp:72
void keyReleaseEvent(QKeyEvent *event)
When a key is released, it is transmitted to the control widget.
Definition: window.hpp:181
void keyPressEvent(QKeyEvent *event)
All key press events are transmitted to the control widget.
Definition: window.hpp:171
Qt based control widget for qt_ctrl.
This class defines a motion model, with the motion limits.
Definition: motion.hpp:28
~QtCtrlGUI()
Freeing the allocated pointer.
Definition: window.hpp:135
MotionModel motion_model
The motion model of the controlled robot.
Definition: window.hpp:83
virtual void updateCommands(const double &trans_vel, const double &rot_vel)=0
Update the display of the ROS node.
DataWidget display
The data display widget of the ROS node.
Definition: window.hpp:98
void updateTrajectory()
Update the display of the .
Definition: window.hpp:205
This class is a Qt widget which displays the data (odometry and commands) of the controller.
Definition: display.hpp:25
QAction about_Qt_action
The Qt action starting a dialog box about Qt.
Definition: window.hpp:79
This class is the Qt main window of qt_ctrl package.
Definition: window.hpp:41
QAction start_stop_action
The Qt action starting the ROS node.
Definition: window.hpp:68
void updateCommands(const double &trans_vel, const double &rot_vel)
Update the display of the controller&#39;s commands.
Definition: display.cpp:105
This class is used to start a ROS server.
Definition: thread.hpp:21
void end()
Stops ROS if it has been started.
Definition: ROS_node.cpp:17
QListView logs
The Qt list view showing the logs of the ROS node.
Definition: window.hpp:102
void keyReleased(QKeyEvent *)
Key release can be handled by inheritors.
Definition: ctrlWdgt.hpp:75
void closeEvent(QCloseEvent *event)
The closing method of QMainWindow is surcharged to save settings before closing.
Definition: window.hpp:156
void addTrajectory(const std::list< State * > &trajectory)
Adds a trajectory to the motion display.
Definition: display.hpp:116
ROS node, getting sensors data and sending commands.
Definition: ROS_node.hpp:42


qt_ctrl
Author(s): Alexis Scheuer
autogenerated on Wed Dec 16 2020 15:51:32