ROS_node.hpp
Go to the documentation of this file.
1 
9 #ifndef QTCTRL_ROS_NODE
10 #define QTCTRL_ROS_NODE
11 
12 #include <string>
13 #include <fstream>
14 #include <QThread>
15 #include <QStringListModel>
16 #include <ctrl/controller.hpp>
17 // To workaround boost/qt4 problems that won't be bugfixed. Refer to
18 // https://bugreports.qt.io/browse/QTBUG-22829
19 #ifndef Q_MOC_RUN
20 #include <ros/ros.h>
21 #include <tf/tf.h>
22 //#include <boost/python.hpp>
23 #endif
24 #include <nav_msgs/Odometry.h> // odometry
25 
26 
27 using namespace ::ros::console::levels;
28 
42 class ROSnode : public QThread {
43  Q_OBJECT // This macro is needed to handle signals
44 
45  int ROS_argc;
46  char** ROS_argv;
47 
55 
60  ros::Publisher cmd_publisher;
61 
71  ros::Subscriber odom_subscriber;
72 
78  QStringListModel log_model;
79 
80  /* DOES NOT WORK
84  std::string world_command_file[2]; */
85 
92  void ROSsetup(Controller& ctrl);
93 
97  void newOdometry(const nav_msgs::Odometry::ConstPtr& odom);
98 
99 protected:
107  void run();
108 
109 public:
112  typedef ::ros::console::Level LogLevel;
113 
122  ROSnode(const int argc, char** argv)
123  : ROS_argc(argc), ROS_argv(argv), motion_ctrl(NULL) {}
124 
129  void end();
130 
135  bool connected() const { return (motion_ctrl != NULL); }
136 
141  void init(Controller& ctrl)
142  { ros::init(ROS_argc, ROS_argv, "qt_ctrl"); ROSsetup(ctrl); }
143 
152  void init(const std::string &master_url,
153  const std::string &host_url, Controller& ctrl);
154 
158  QStringListModel& loggingModel() { return log_model; }
159 
163  std::string worldCommandFile(const bool empty = true) {
164  // as the other method (cf ROSnode::ROSsetup) does not work...
165  static const std::string world_command_file[2]
166  = {"launch_empty_world.sh", "launch_world.sh"};
167  return world_command_file[empty ? 0 : 1];
168  }
169 
179  void log(const LogLevel &level, const std::string &msg);
180 
181 Q_SIGNALS: // this requires the Q_OBJECT macro
185  void loggingUpdated();
186 
187 }; // end of class ROSnode
188 
189 #endif // QTCTRL_ROS_NODE
ros::Subscriber odom_subscriber
ROS object used to get the odometry.
Definition: ROS_node.hpp:71
Controller is the abstract class inherited by all the implemented controllers.
Definition: controller.hpp:28
::ros::console::Level LogLevel
Log severity levels, comming from ROS::console.
Definition: ROS_node.hpp:112
void init(Controller &ctrl)
Connects to ROS server with main arguments.
Definition: ROS_node.hpp:141
void loggingUpdated()
Signals the GUI for log&#39;s update.
void newOdometry(const nav_msgs::Odometry::ConstPtr &odom)
Sends the odometry data to the controller.
Definition: ROS_node.cpp:64
QStringListModel log_model
Qt object used to show the logs in the GUI.
Definition: ROS_node.hpp:78
std::string worldCommandFile(const bool empty=true)
File name for the script starting the simulation.
Definition: ROS_node.hpp:163
int ROS_argc
Main arguments&#39; count, forwarded to ROS.
Definition: ROS_node.hpp:45
QStringListModel & loggingModel()
The Qt object used to show the logs.
Definition: ROS_node.hpp:158
ROSnode(const int argc, char **argv)
The constructor requires main()&#39;s arguments (they can be forwarded to ROS).
Definition: ROS_node.hpp:122
Controller * motion_ctrl
A pointer to the controller of the motion.
Definition: ROS_node.hpp:54
bool connected() const
Indicates whether the node is connected to ROS.
Definition: ROS_node.hpp:135
void ROSsetup(Controller &ctrl)
Common part of the two initialisation methods.
Definition: ROS_node.cpp:34
void log(const LogLevel &level, const std::string &msg)
Writes a message at given level in the log.
Definition: ROS_node.cpp:135
void run()
Main loop of the process (on a separate thread).
Definition: ROS_node.cpp:89
ros::Publisher cmd_publisher
ROS object used to send the velocities.
Definition: ROS_node.hpp:60
void end()
Stops ROS if it has been started.
Definition: ROS_node.cpp:17
Controller abstract class.
char ** ROS_argv
Main arguments&#39; values, forwarded to ROS.
Definition: ROS_node.hpp:46
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