9 #ifndef QTCTRL_ROS_NODE 10 #define QTCTRL_ROS_NODE 15 #include <QStringListModel> 24 #include <nav_msgs/Odometry.h> 27 using namespace ::ros::console::levels;
97 void newOdometry(
const nav_msgs::Odometry::ConstPtr& odom);
123 : ROS_argc(argc), ROS_argv(argv), motion_ctrl(NULL) {}
135 bool connected()
const {
return (motion_ctrl != NULL); }
142 { ros::init(ROS_argc, ROS_argv,
"qt_ctrl");
ROSsetup(ctrl); }
152 void init(
const std::string &master_url,
153 const std::string &host_url,
Controller& ctrl);
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];
179 void log(
const LogLevel &level,
const std::string &msg);
189 #endif // QTCTRL_ROS_NODE ros::Subscriber odom_subscriber
ROS object used to get the odometry.
Controller is the abstract class inherited by all the implemented controllers.
::ros::console::Level LogLevel
Log severity levels, comming from ROS::console.
void init(Controller &ctrl)
Connects to ROS server with main arguments.
void loggingUpdated()
Signals the GUI for log's update.
void newOdometry(const nav_msgs::Odometry::ConstPtr &odom)
Sends the odometry data to the controller.
QStringListModel log_model
Qt object used to show the logs in the GUI.
std::string worldCommandFile(const bool empty=true)
File name for the script starting the simulation.
int ROS_argc
Main arguments' count, forwarded to ROS.
QStringListModel & loggingModel()
The Qt object used to show the logs.
ROSnode(const int argc, char **argv)
The constructor requires main()'s arguments (they can be forwarded to ROS).
Controller * motion_ctrl
A pointer to the controller of the motion.
bool connected() const
Indicates whether the node is connected to ROS.
void ROSsetup(Controller &ctrl)
Common part of the two initialisation methods.
void log(const LogLevel &level, const std::string &msg)
Writes a message at given level in the log.
void run()
Main loop of the process (on a separate thread).
ros::Publisher cmd_publisher
ROS object used to send the velocities.
void end()
Stops ROS if it has been started.
Controller abstract class.
char ** ROS_argv
Main arguments' values, forwarded to ROS.
ROS node, getting sensors data and sending commands.