前言
在使用ROS的过程中,我们常常需要使用复杂的编译源代码和相关的解析操作,才能单独对某一个任务进行启动。在修改时,也需要单独打开某个文件、编辑、保存,这个过程比较繁琐。这些数据信息均需要在终端中以字符的方式显示出来,键入命令同样需要在终端中输入字符命令,如果是用于较大的ROS工程,总不能所有调试工作,每改动一下参数都键入字符命令吧。为此人机交互界面氤氲而生,使用按钮,输入框等控件简化这一过程,并且使调试过程更加清晰明确,下方是一个人机交互界面的结构图:
整个软件被分为6个界面,主要部分为设置界面、建图导航界面、键盘控制界面、单点导航界面、巡航模式界面这六个界面。其中建图导航包含rviz组件,具备显示功能。整个软件还具备保存设置功能,只需第一次开机设置。下面我们对该界面以及运行流程进行详细介绍,并给出一系列较为实用的人机交互软件。
界面介绍
设置页面
设置界面,主要包括连接ros master,通过输入主机IP和从机IP来对机器人进行连接、设置启动功能按钮命令、自定义单点导航按钮名称、显示调试信息等模块。具体如下图所示:
该处需要预先通过ssh连接远端主机,然后点击界面中的connect按钮进入。下图中的命令可以在本地进行修改,以便于保存多幅地图,同时可以较好地替换一些可变参数。
此时已显示连接
MainWindow::MainWindow(int argc, char** argv, QWidget *parent)
: QMainWindow(parent)
, qnode(argc,argv)
{
ui.setupUi(this); // Calling this incidentally connects all ui's triggers to on_...() callbacks in this class.
//QObject::connect(ui.actionAbout_Qt, SIGNAL(triggered(bool)), qApp, SLOT(aboutQt())); // qApp is a global variable for the application
initUis();
//读取配置文件
ReadSettings();
setWindowIcon(QIcon(":/images/robot.png"));
setWindowFlags(Qt::FramelessWindowHint);//去掉标题栏
//QObject::connect(&qnode, SIGNAL(rosShutdown()), this, SLOT(close()));
/*********************
** Logging
**********************/
ui.view_logging->setModel(qnode.loggingModel());
/*********************
** 自动连接master
**********************/
if (m_autoConnect) {
on_button_connect_clicked(true);
}
//链接connect
connections();
}
下图为该软件的rviz示意图,并在当中加入了初始点设置,单点设置,多点设置以及返航点设置。同时单点选择出A01与上页中的A01相对应,并通过改名,可以较好地自定义按钮名称。同时在保存地图后,可以通过编辑地图可以有效的对地图上的一些杂点进行滤除。
该部分为RVIZ的核心代码,通过使用rviz容器,可以将rviz中的信息存储到UI当中。
#include "../include/cyrobot_monitor/qrviz.hpp"
QRviz::QRviz(QVBoxLayout *layout,QString node_name)
{
this->layout=layout;
this->nodename=node_name;
//创建rviz容器
render_panel_=new rviz::RenderPanel;
render_panel_->resize(900,900);
//向layout添加widget
layout->addWidget(render_panel_);
//初始化rviz控制对象
manager_=new rviz::VisualizationManager(render_panel_);
ROS_ASSERT(manager_!=NULL);
//获取当前rviz控制对象的 tool控制对象
tool_manager_=manager_->getToolManager();
ROS_ASSERT(tool_manager_!=NULL);
//初始化camera 这行代码实现放大 缩小 平移等操作
render_panel_->initialize(manager_->getSceneManager(),manager_);
manager_->initialize();
tool_manager_->initialize();
manager_->removeAllDisplays();
}
void QRviz::show(){
render_panel_->show();
}
void QRviz::hide(){
render_panel_->hide();
}
rviz::Display* RobotModel_=NULL;
//显示robotModel
void QRviz::Display_RobotModel(bool enable)
{
if(RobotModel_==NULL)
{
RobotModel_=manager_->createDisplay("rviz/RobotModel","Qrviz RobotModel",enable);
}
else{
delete RobotModel_;
RobotModel_=manager_->createDisplay("rviz/RobotModel","Qrviz RobotModel",enable);
}
}
//显示grid
void QRviz::Display_Grid(bool enable,QString Reference_frame,int Plan_Cell_count,QColor color)
{
if(grid_==NULL)
{
grid_ = manager_->createDisplay( "rviz/Grid", "adjustable grid", true );
ROS_ASSERT( grid_ != NULL );
// Configure the GridDisplay the way we like it.
grid_->subProp( "Line Style" )->setValue("Billboards");
grid_->subProp( "Color" )->setValue(color);
grid_->subProp( "Reference Frame" )->setValue(Reference_frame);
grid_->subProp("Plane Cell Count")->setValue(Plan_Cell_count);
}
else{
delete grid_;
grid_ = manager_->createDisplay( "rviz/Grid", "adjustable grid", true );
ROS_ASSERT( grid_ != NULL );
// Configure the GridDisplay the way we like it.
grid_->subProp( "Line Style" )->setValue("Billboards");
grid_->subProp( "Color" )->setValue(color);
grid_->subProp( "Reference Frame" )->setValue(Reference_frame);
grid_->subProp("Plane Cell Count")->setValue(Plan_Cell_count);
}
grid_->setEnabled(enable);
manager_->startUpdate();
}
//显示map
void QRviz::Display_Map(bool enable,QString topic,double Alpha,QString Color_Scheme)
{
if(!enable&&map_)
{
map_->setEnabled(false);
return ;
}
if(map_==NULL)
{
map_=manager_->createDisplay("rviz/Map","QMap",true);
ROS_ASSERT(map_);
map_->subProp("Topic")->setValue(topic);
map_->subProp("Alpha")->setValue(Alpha);
map_->subProp("Color Scheme")->setValue(Color_Scheme);
}
else{
ROS_ASSERT(map_);
qDebug()<<"asdasdasd:"<<topic<<Alpha;
delete map_;
map_=manager_->createDisplay("rviz/Map","QMap",true);
ROS_ASSERT(map_);
map_->subProp("Topic")->setValue(topic);
map_->subProp("Alpha")->setValue(Alpha);
map_->subProp("Color Scheme")->setValue(Color_Scheme);
}
map_->setEnabled(enable);
manager_->startUpdate();
}
void QRviz::Display_Polygon(bool enable,QString topic){
if(polygon_==NULL)
{
polygon_=manager_->createDisplay("rviz/Polygon","QPolygon",enable);
ROS_ASSERT(polygon_);
polygon_->subProp("Topic")->setValue(topic);
}
else{
delete polygon_;
polygon_=manager_->createDisplay("rviz/Polygon","QPolygon",enable);
ROS_ASSERT(polygon_);
polygon_->subProp("Topic")->setValue(topic);
}
polygon_->setEnabled(enable);
manager_->startUpdate();
}
//显示激光雷达
void QRviz::Display_LaserScan(bool enable,QString topic)
{
if(laser_==NULL)
{
laser_=manager_->createDisplay("rviz/LaserScan","QLaser",enable);
ROS_ASSERT(laser_);
laser_->subProp("Topic")->setValue(topic);
}
else{
delete laser_;
laser_=manager_->createDisplay("rviz/LaserScan","QLaser",enable);
ROS_ASSERT(laser_);
laser_->subProp("Topic")->setValue(topic);
}
laser_->setEnabled(enable);
manager_->startUpdate();
}
//设置全局显示
void QRviz::SetGlobalOptions(QString frame_name,QColor backColor,int frame_rate)
{
manager_->setFixedFrame(frame_name);
manager_->setProperty("Background Color",backColor);
manager_->setProperty("Frame Rate",frame_rate);
manager_->startUpdate();
}
下面是设置导航点和返航点的核心代码
导航点核心代码
//初始化rviz控制对象
manager_=new rviz::VisualizationManager(render_panel_);
//获取当前rviz控制对象的 tool控制对象
tool_manager_=manager_->getToolManager();
//设置机器人导航目标点
void QRviz::Set_Goal()
{
//添加工具
current_tool= tool_manager_->addTool("rviz/SetGoal");
//设置goal的话题
rviz::Property* pro= current_tool->getPropertyContainer();
pro->subProp("Topic")->setValue("/move_base_simple/goal");
//设置当前frame
manager_->setFixedFrame("map");
//设置当前使用的工具为SetGoal(实现在地图上标点)
tool_manager_->setCurrentTool( current_tool );
manager_->startUpdate();
}
//设置机器人导航初始位置
void QRviz::Set_Pos()
{
//获取设置Pos的工具
//添加工具
current_tool= tool_manager_->addTool("rviz/SetInitialPose");
//设置当前使用的工具为SetInitialPose(实现在地图上标点)
tool_manager_->setCurrentTool( current_tool );
manager_->startUpdate();
// tool_manager_->setCurrentTool()
}
返航点核心代码
//创建机器人位置订阅者及回调函数
ros::Subscriber pos_sub;
void poseCallback(const geometry_msgs::PoseWithCovarianceStamped& pos);
//订阅机器人位置
pos_sub=n.subscribe("amcl_pose",1000,&QNode::poseCallback,this);
//机器人位置话题的回调函数
void QNode::poseCallback(const geometry_msgs::PoseWithCovarianceStamped& pos)
{
emit position(pos.pose.pose.position.x,pos.pose.pose.position.y,pos.pose.pose.orientation.z,pos.pose.pose.orientation.w);
// qDebug()<<<<" "<<pos.pose.pose.position.y;
}
//刷新返航地点
void MainWindow::slot_set_return_point()
{
//更新ui返航点显示
ui.label_return_x->setText(ui.label_x->text());
ui.label_return_y->setText(ui.label_y->text());
ui.label_return_z->setText(ui.label_z->text());
ui.label_return_w->setText(ui.label_w->text());
//写入setting
QSettings settings("return-position", "cyrobot_monitor");
settings.setValue("x",ui.label_x->text());
settings.setValue("y",ui.label_y->text());
settings.setValue("z",ui.label_z->text());
settings.setValue("w",ui.label_w->text());
//发出声音提醒
if(media_player!=NULL)
{
delete media_player;
media_player=NULL;
}
media_player=new QSoundEffect;
media_player->setSource(QUrl::fromLocalFile("://media/refresh_return.wav"));
media_player->play();
}
//返航
void MainWindow::slot_return_point()
{
qnode.set_goal(ui.label_frame->text(),ui.label_return_x->text().toDouble(),ui.label_return_y->text().toDouble(),ui.label_return_z->text().toDouble(),ui.label_return_w->text().toDouble());
//声音提醒
if(media_player!=NULL)
{
delete media_player;
media_player=NULL;
}
media_player=new QSoundEffect;
media_player->setSource(QUrl::fromLocalFile("://media/start_return.wav"));
media_player->play();
}
该软件由于作者没有开源,为此在Github上找到了类似的项目,并针对性的进行解析,该软件主要由QT(C++)编写。目前作者提供了多个branch以供不同功能ROS机器人。
其他界面
ROS与Web的交互之roslibjs
ROS是现在应为最为广泛的机器人操作系统,为了将ROS与Web端的应用结合起来,ROS Web Tools社区开发了很多Web功能包,利用这些工具,我们能够在Web端实现对机器人的监测与控制。
文章介绍以下所需要的工具包:rosbridge_suite功能包,roslibjs,ros2djs,ros3djs。
● rosbridge_suite:实现Web浏览器与ROS之间的数据交互;
● roslibjs:实现了ROS中的部分功能,如Topic,Service,URDF等;
● ros2djs:提供了二维可视化的管理工具,可以用来在Web浏览器中显示二维地图;
● ros3djs:提供了三维可视化的管理工具,可以在Web端显示三维模型。
并给出了相关的示例代码以及解释(github—flask+pymysql + roslibjs)
ROS与Java的交互之rosbridge
android要与ROS通讯,一种是基于rosbridge,另一种是基于rosjava库。
rosjava库,这玩意儿类似于ROS官方支持的rospy roscpp等,也是ROS分布式计算平台的一种language binding。
以android_apps-kinetic为例,首先下载android_apps-kinetic工程
在导入Android Studio导入工程编译运行后,启动登入界面:
修改Master URI选择roscore的URI 点击CONNECT,则可进行地图导航
、
而对于rosbridge,则和上文的web端有些类似,通过Websocket以JSON格式的API为非ROS环境提供ROS通信支持,包括对Topic和Service的各种操作,这种通信方式轻量级,跨平台。个人比较建议使用rosbridge,因为ROSJava对ROS支持只到indigo版本!
rosbridge之前已经写过一版,这里不过多介绍,目前提供一些可用的代码:1、Android和ROS的通信介绍 2、实时控制导航 3、webapp控制turtlebot 4、realsence 双目摄像头数据传输