ROS与QT语言入门教程-按钮发布消息
ROS与QT语言入门教程-按钮发布消息
说明:
- 在ROS QT GUI模板的基础上,实现按钮发布消息
ui界面
main_window.ui
文件:拖入一个按钮控件,将对象名改为sent_cmd
编写节点
qnode.hpp
头文件:
#include <std_msgs/String.h>
public:
QStringListModel* loggingModel_sub() { return &logging_model_sub; }
void log_sub( const LogLevel &level, const std::string &msg);
void Callback(const std_msgs::StringConstPtr &submsg);
void sent_cmd();
Q_SIGNALS:
void loggingUpdated_sub();
private:
ros::Subscriber chatter_subscriber;
QStringListModel logging_model_sub;
代码解释:
- 声明发布消息函数sent_cmd(),以及信号,订阅者
qnode.cpp
源码文件
bool QNode::init()
{
chatter_subscriber = n.subscribe("chatter", 1000, &QNode::Callback, this);
}
bool QNode::init(const std::string &master_url, const std::string &host_url)
{
chatter_subscriber = n.subscribe("chatter", 1000, &QNode::Callback, this);
}
void QNode::log_sub( const LogLevel &level, const std::string &msg)
{
logging_model_sub.insertRows(logging_model_sub.rowCount(),1);
std::stringstream logging_model_msg;
switch ( level ) {
case(Debug) : {
ROS_DEBUG_STREAM(msg);
logging_model_msg << "[DEBUG] [" << ros::Time::now() << "]: " << msg;
break;
}
case(Info) : {
ROS_INFO_STREAM(msg);
logging_model_msg << "[INFO] [" << ros::Time::now() << "]: " << msg;
break;
}
case(Warn) : {
ROS_WARN_STREAM(msg);
logging_model_msg << "[INFO] [" << ros::Time::now() << "]: " << msg;
break;
}
case(Error) : {
ROS_ERROR_STREAM(msg);
logging_model_msg << "[ERROR] [" << ros::Time::now() << "]: " << msg;
break;
}
case(Fatal) : {
ROS_FATAL_STREAM(msg);
logging_model_msg << "[FATAL] [" << ros::Time::now() << "]: " << msg;
break;
}
}
QVariant new_row(QString(logging_model_msg.str().c_str()));
logging_model_sub.setData(logging_model_sub.index(logging_model_sub.rowCount()-1),new_row);
Q_EMIT loggingUpdated_sub(); // used to readjust the scrollbar
}
void QNode::Callback(const std_msgs::StringConstPtr &submsg)
{
log_sub(Info, std::string("Success sub:")+submsg->data.c_str());
}
void QNode::sent_cmd()
{
if(ros::ok())
{
std_msgs::String msg;
std::stringstream ss;
ss << "clicked the button";
msg.data = ss.str();
chatter_publisher.publish(msg);
log(Info, std::string("I sent:"+msg.data));
ros::spinOnce();
}
}
代码解释
- 在初始化函数init()中,创建一个Subscriber,订阅名为chatter的话题,接受1000信息队列,注册回调函数Callback
- 日志输出
- 回调函数Callback(),接受到话题消息后,将接受到的信息打印出来
- 函数sent_cmd(),发布消息,以及循环等待回调函数
编写窗口
main_window.hpp
头文件:
public Q_SLOTS:
void updateLoggingView_sub();
void pub_cmd();
private:
QNode qnode;
代码解释:
声明日志更新函数和QNode对象main_window.cpp
源代码:
MainWindow::MainWindow(int argc, char** argv, QWidget *parent)
: QMainWindow(parent)
, qnode(argc,argv)
{
ui.view_logging_sub->setModel(qnode.loggingModel_sub());
QObject::connect(&qnode, SIGNAL(loggingUpdated_sub()), this, SLOT(updateLoggingView_sub()));
QObject::connect(ui.sent_cmd, SIGNAL(clicked()), this, SLOT(pub_cmd()));
}
void MainWindow::updateLoggingView_sub()
{
ui.view_logging_sub->scrollToBottom();
}
void MainWindow::pub_cmd()
{
qnode.sent_cmd();
}
代码解释
使用connect()函数将信号与槽进行连接
定义updateLoggingView_sub()函数,将QListView组件
MainWindow与QNode的连接,调用qnode的sent_cmd()函数
编译运行
参考资料
获取最新文章: 扫一扫右上角的二维码加入“创客智造”公众号