< >
Home » ROS探索总结 » ROS探索总结-36.Matlab中的ROS可视化应用

ROS探索总结-36.Matlab中的ROS可视化应用

ROS探索总结-36.Matlab中的ROS可视化应用

概要

  • MatLab有非常便捷的可视化编程,我们可以借助Matlab来制作一些小的可视化工具。在之前的博客中,使用rviz的插件功能实现过一个速度控制的小工具,今天就来探索研究如何用Matlab来实现类似的工具。

  • 本文使用的完整代码可见:github

一、了解Matlab的可视化编程

  • Matlab的可视化编程非常简单,首先在命令窗口中输入“guide”命令来启动可视化编程:

请输入图片描述

  • 然后选择默认的空窗口,点击“OK”,然后会出现如下的可视化编辑界面:

  • 在这个界面中,我们可以从左边的控件列表中选择创建按钮、编辑框等控件:

请输入图片描述

  • 创建控件后就可以编辑该控件的回调函数,从而实现该控件的对应功能。

二、创建界面

  • 了解了上边创建控件的基础知识,我们接下来就来动手做一个速度控制的界面。
    首先从左侧控件列表中选择一个“Edit Text”控件,然后在主窗口中点击并拖动鼠标来绘制控件的位置。

请输入图片描述

  • 现在控件的命名和默认内容不是我们想要的,双击控件,可以修改相应的属性。

请输入图片描述

这个输入控件是用来输入ROS_MASTER_URI的,同样的方法,我们再来创建一个输入框,用来输入topic name:

请输入图片描述

  • 接下来,我们需要创建一些按键,并且编辑按键的属性,最终的界面如下:

请输入图片描述

三、编辑控件回调函数

  • 界面我们已经设计完成了,接下来我们来编辑每个控件的功能,即回调函数。保存目前设计的界面,命名为myTeleop,在保存路径下,我们可以看到出现了一个.fig文件和一个.m文件,前者是界面设计,上一节已经实现,后者是这一节将要编辑的代码文件。在上一篇中我们已经讲到了Matlab中可用的一些ROS接口,这里的核心代码基本还上一篇类似,忘记的同学可以参考上一篇。

  • 1.设计全局变量

  • 考虑到该工具所应用的一些功能,我们首先在代码声明一些全局变量,方便不同回调函数的使用。

% 声明一些全局变量
% ROS Master URI和Topic name
global rosMasterUri
global teleopTopicName
 
rosMasterUri = 'http://192.168.1.202:11311';
teleopTopicName = '/cmd_vel';
 
% 机器人的运行速度
global leftVelocity
global rightVelocity
global forwardVelocity
global backwardVelocity
 
leftVelocity = 2;        % 角速度 (rad/s)
rightVelocity = -2;      % 角速度 (rad/s)
forwardVelocity = 2;     % 线速度 (m/s)
backwardVelocity = -2;   % 线速度 (m/s)
  • 2.URI输入框和Topic name输入框

  • 两个输入分别对应ROS_MASTER_URI和Topic name,在输入之后,我们需要将输入的字符串保存到全局变量当中,所对应的回调函数如下:

% 设置ROS Master URI
function URIEdit_Callback(hObject, eventdata, handles)
 
global rosMasterUri
rosMasterUri = get(hObject,'String')
 
% 设置Topic name
function TopicEdit_Callback(hObject, eventdata, handles)
 
global teleopTopicName
teleopTopicName = get(hObject,'String')
  • 3.建立连接和断开连接的按键

  • 建立连接的按键在点击之后需要初始化Matlab中的ros环境,并且和ROS master建立连接,还需要初始化速度指令的发布者。

  • 断开连接的按键在点击之后关闭Matlab中的ROS即可。

% 建立连接并初始化ROS publisher
function ConnectButton_Callback(hObject, eventdata, handles)
 
global rosMasterUri
global teleopTopicName
global robot
global velmsg
 
setenv('ROS_MASTER_URI',rosMasterUri)
rosinit
robot = rospublisher(teleopTopicName,'geometry_msgs/Twist');
velmsg = rosmessage(robot);
 
% 断开连接,关闭ROS
function DisconnectButton_Callback(hObject, eventdata, handles)
 
rosshutdown
  • 4.运动控制按键

  • 最后是四个控制前后左右的按键,按下对应的按键,就会发布相应的运动指令。

% 向前
function ForwardButton_Callback(hObject, eventdata, handles)
 
global velmsg
global robot
global teleopTopicName
global forwardVelocity
 
velmsg.Angular.Z = 0;
velmsg.Linear.X = forwardVelocity;
send(robot,velmsg);
latchpub = rospublisher(teleopTopicName, 'IsLatching', true);
 
 
%向左
function LeftButton_Callback(hObject, eventdata, handles)
 
global velmsg
global robot
global teleopTopicName
global leftVelocity
 
velmsg.Angular.Z = leftVelocity;
velmsg.Linear.X = 0;
send(robot,velmsg);
latchpub = rospublisher(teleopTopicName, 'IsLatching', true);
 
 
% 向右
function RightButton_Callback(hObject, eventdata, handles)
 
global velmsg
global robot
global teleopTopicName
global rightVelocity
 
velmsg.Angular.Z = rightVelocity;
velmsg.Linear.X = 0;
send(robot,velmsg);
latchpub = rospublisher(teleopTopicName, 'IsLatching', true);
 
 
% 向后
function BackwardButton_Callback(hObject, eventdata, handles)
 
global velmsg
global robot
global teleopTopicName
global backwardVelocity
 
velmsg.Angular.Z = 0;
velmsg.Linear.X = backwardVelocity;
send(robot,velmsg);
latchpub = rospublisher(teleopTopicName, 'IsLatching', true);

四、运行效果

  • OK,到此为止,我们已经在Matlab中实现了速度控制插件的界面和代码,接下来就可以运行看效果了。

  • 这里以小海龟的仿真作为控制对象,在ubuntu中运行ROS,并且查看ROS_MASTER_URI,然后运行小海龟仿真器。

请输入图片描述

  • 然后在matlab中运行我们刚才实现的速度控制工具,并且在输入框中输入对应的信息。

请输入图片描述

  • 接着点击“建立连接”,如果一切正常的话,可以在Matlab的命令窗口中看到如下信息:

请输入图片描述

  • 这样就可以开始控制了,我们点击前、后、左、右的按键(点击之后要放开鼠标),可以看到小海龟确实可以按照我们的指令运动。

请输入图片描述

  • 这样,我们就使用Matlab的可视化编程界面实现了一个ROS速度控制的小工具,更多功能和应用还等待我们继续探索。

纠错,疑问,交流: 请进入讨论区点击加入Q群

获取最新文章: 扫一扫右上角的二维码加入“创客智造”公众号


标签: ros探索总结