14 #include <ros/network.h> 16 #include <std_msgs/String.h> 18 #include "../include/%(package)s/qnode.hpp" 30 QNode::QNode(
int argc,
char** argv ) :
36 if(ros::isStarted()) {
38 ros::waitForShutdown();
45 if ( ! ros::master::check() ) {
56 bool QNode::init(
const std::string &master_url,
const std::string &host_url) {
57 std::map<std::string,std::string> remappings;
58 remappings[
"__master"] = master_url;
59 remappings[
"__hostname"] = host_url;
60 ros::init(remappings,
"%(package)s");
61 if ( ! ros::master::check() ) {
73 ros::Rate loop_rate(1);
79 ss <<
"hello world " << count;
82 log(
Info,std::string(
"I sent: ")+msg.data);
87 std::cout <<
"Ros shutdown, proceeding to close the gui." << std::endl;
94 std::stringstream logging_model_msg;
97 ROS_DEBUG_STREAM(msg);
98 logging_model_msg <<
"[DEBUG] [" << ros::Time::now() <<
"]: " << msg;
102 ROS_INFO_STREAM(msg);
103 logging_model_msg <<
"[INFO] [" << ros::Time::now() <<
"]: " << msg;
107 ROS_WARN_STREAM(msg);
108 logging_model_msg <<
"[INFO] [" << ros::Time::now() <<
"]: " << msg;
112 ROS_ERROR_STREAM(msg);
113 logging_model_msg <<
"[ERROR] [" << ros::Time::now() <<
"]: " << msg;
117 ROS_FATAL_STREAM(msg);
118 logging_model_msg <<
"[FATAL] [" << ros::Time::now() <<
"]: " << msg;
122 QVariant new_row(QString(logging_model_msg.str().c_str()));
void log(const LogLevel &level, const std::string &msg)
QStringListModel logging_model
ros::Publisher chatter_publisher