技术-XTDrone项目学习-VRX无人艇项目例程-多无人艇生成-ROS-Matlab通信编程

前言:因为从事的研究是无人艇控制方面的,之前仅仅在Matlab上设计算法,验证控制算法的效果,一直想在一个仿真3D环境下验证算法有效性。在最近Follow的XTDrone项目中有一项无人机与无人船协同初步,项目在环境配置正确的条件下能够非常顺畅地跑通,如获至宝。
这里记录一下相关过程及一些注意事项,以及在进行多无人艇算法验证过程中的一些关键点,方便以后查询。

一. 项目下载

VRX项目介绍页面已经有很详细的下载流程了。需要注意一下这里是2022年的版本,支持的系统是ubuntu20.04+ROS1,其最新的2023年版本支持的系统是ubuntu22.04+ROS2。我下载的是2022年的ubuntu20.04版本。
step1. 更新库

sudo apt update
sudo apt full-upgrade

step2. 下载依赖-主要是Gazebo,我的版本是ROS Noetic自带的Gazebo11.14

sudo apt install -y build-essential cmake cppcheck curl git gnupg libeigen3-dev libgles2-mesa-dev lsb-release pkg-config protobuf-compiler qtbase5-dev python3-dbg python3-pip python3-venv ruby software-properties-common wget 
sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list'
sudo apt-key adv --keyserver 'hkp://keyserver.ubuntu.com:80' --recv-key C1CF6E31E6BADE8868B172B4F42ED6FBAB17C654
sudo sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-stable.list'
wget http://packages.osrfoundation.org/gazebo.key -O - | sudo apt-key add -
sudo apt update
DIST=noetic
GAZ=gazebo11
sudo apt install ${GAZ} lib${GAZ}-dev ros-${DIST}-gazebo-plugins ros-${DIST}-gazebo-ros ros-${DIST}-hector-gazebo-plugins ros-${DIST}-joy ros-${DIST}-joy-teleop ros-${DIST}-key-teleop ros-${DIST}-robot-localization ros-${DIST}-robot-state-publisher ros-${DIST}-joint-state-publisher ros-${DIST}-rviz ros-${DIST}-ros-base ros-${DIST}-teleop-tools ros-${DIST}-teleop-twist-keyboard ros-${DIST}-velodyne-simulator ros-${DIST}-xacro ros-${DIST}-rqt ros-${DIST}-rqt-common-plugins

step3. 下载编译源码(这里默认已经下载好了ROS
以下编译过程要求安装Eigen3库,这是一个大坑,我遇到的问题是卸载重装Eigen3之后一直报.cmake找不到,用locate eigne3查看,发现确实在/usr/lib/share路径下不存在Eigen3的cmake文件,查了各种方法都没用,一气之下开了个新虚拟机搭了个新的环境。

mkdir -p ~/vrx_ws/src
cd ~/vrx_ws/src
git clone https://github.com/osrf/vrx -b gazebo_classic

# 编译
cd ~/vrx_ws
catkin_make

step4. 跑例程

source  ~/vrx_ws/devel/setup.bash
# 或者
echo "source  ~/vrx_ws/devel/setup.bash" >> ~/.bashrc
source ~/.bashrc

# 跑例程
roslaunch vrx_gazebo vrx.launch

效果:
在这里插入图片描述

二. 生成多个无人艇

由于要做多无人艇协同嘛,所以需要在仿真器中生成多个艇,因此需要修改.launch文件,以文件~/vrx_ws/src/vrx/vrx_gazebo/launch/vrx.launch为例,注意几个点。完整的修改文件在博客最后

step1. 修改namespace,ROS发布的消息将以此为前缀

 <arg name="namespace" default="wamv1"/>
 <arg name="namespace2" default="wamv2"/>

step2. 增加生成艇的初始状态,六个自由度,包括三维坐标和三方向姿态,注意不要和其他艇重叠,也不要设在陆地上了。

<!-- Initial USV location and attitude-->
  <arg name="x" default="-532" />
  <arg name="y" default="162" />
  <arg name="z" default="0.1" />
  <arg name="P" default="0" />
  <arg name="R" default="0" />
  <arg name="Y" default="1" />
  
 <!-- USV02 -->
  <arg name="x2" default="-432" />
  <arg name="y2" default="262" />
  <arg name="z2" default="0.1" />
  <arg name="P2" default="0" />
  <arg name="R2" default="0" />
  <arg name="Y2" default="1" />

step3. 设置生成参数,并调用生成服务spawn_model,注意节点名不要重复

<!-- USV01 -->
  <param name="$(arg namespace)/robot_description"
         command="$(find xacro)/xacro &#x002D;&#x002D;inorder '$(arg urdf)'
         locked:=$(arg wamv_locked)		   
         thruster_config:=$(arg thrust_config)
         vrx_sensors_enabled:=$(arg vrx_sensors_enabled)
         namespace:=$(arg namespace) "/>

  <!-- Spawn model in Gazebo -->
  <node name="spawn_model" pkg="gazebo_ros" type="spawn_model"
        args="-x $(arg x) -y $(arg y) -z $(arg z)
              -R $(arg R) -P $(arg P) -Y $(arg Y)
              -urdf -param $(arg namespace)/robot_description -model wamv"/>
              
  <!-- USV02 -->
  <param name="$(arg namespace2)/robot_description"
         command="$(find xacro)/xacro &#x002D;&#x002D;inorder '$(arg urdf)'
         locked:=$(arg wamv_locked)		   
         thruster_config:=$(arg thrust_config)
         vrx_sensors_enabled:=$(arg vrx_sensors_enabled)
         namespace:=$(arg namespace2) "/>

  <!-- Spawn model in Gazebo -->
  <node name="spawn_model2" pkg="gazebo_ros" type="spawn_model"
        args="-x $(arg x2) -y $(arg y2) -z $(arg z2)
              -R $(arg R2) -P $(arg P2) -Y $(arg Y2)
              -urdf -param $(arg namespace2)/robot_description -model wamv2"/>

step4. 保存退出,运行

roslaunch vrx_gazebo vrx.launch

效果如下:
在这里插入图片描述

三. 通过Matlab发布ROS话题操作无人艇

虽然当年也是系统地学过C++、ROS的人,但过了这么长时间也忘得差不多了。作为一个学术狗和代码渣渣,最熟悉的工具还是Matlab,而且C++各种依赖包,复杂的代码编写和要命的编译过程,还是Matlab更合适。就个人而言,就好比即使会开手动挡的车,终究还是自动挡开着省心。
这里就记录一下如何使用物理机(PC)上的Matlab,和虚拟机上的ROS相互通信。
说一下配置:

物理机: Windows10 + Matlab2022
虚拟机: Ubuntu20.04 + ROS Noetic
虚拟机软件: VMWare WorkStation Pro

我们希望将虚拟机设置为ROS Master,物理机网络和其通信。

step1. 虚拟机使用网络桥接模式
在这里插入图片描述
step2. 查询虚拟机ip,填入ROS_Master

ifconfig

# 在 ~/.bashrc中填入 (上面查询出来的IP)
export ROS_IP=192.168.190.128

step3. 查询物理机IP
win+r-cmd-ipconfig
在matlab中创建脚本test01.m

clear;
clc;

%% setup
setenv('ROS_MASTER_URI','http://192.168.190.128:11311/'); % 虚拟机ROS Master ip
setenv('ROS_IP','192.168.3.162'); % 物理机的IP
rosshutdown;
rosinit;

%% 发布命令

usv_thrust_pub = rospublisher('/wamv1/thrusters/right_thrust_angle',...
                 'std_msgs/Float32');
count = 0;
while (1)
    msg = rosmessage(usv_thrust_pub);
    msg.Data = 1.57;
    % 发布消息
    send(usv_thrust_pub, msg);
    count = count + 1;
    pause(0.1);
end

step4. 执行
以上在/wamv1/thrusters/right_thrust_angle话题中发布了数据1.57,其效果是让无人艇的螺旋桨转90°,可以同时在matlab终端和Ubuntu终端查看话题数据,

rostopic echo /wamv1/thrusters/right_thrust_angle

显示:
在这里插入图片描述
并且对应无人艇的右边桨叶角度旋转。
在这里插入图片描述

附件:完整的修改后.launch文件

<?xml version="1.0"?>
<launch>
  <env name="ROSCONSOLE_CONFIG_FILE" value="$(find vrx_gazebo)/config/custom_rosconsole.conf"/>
  <!-- Gazebo world to load -->
  <arg name="world" default="$(find vrx_gazebo)/worlds/example_course.world" />
  <!-- If true, run gazebo GUI -->
  <arg name="gui" default="true" />
  <!-- If true, run gazebo in verbose mode -->
  <arg name="verbose" default="false"/>
  <!-- Set various other gazebo arguments-->
  <arg name="extra_gazebo_args" default=""/>
  <!-- Start in a default namespace -->
  <arg name="namespace" default="wamv1"/>
  <arg name="namespace2" default="wamv2"/>
  <!-- Do we lock the vessel to the world? -->
  <arg name="wamv_locked" default="false" />
  <!-- Start paused? -->
  <arg name="paused" default="false"/>
  <!-- Acoustic pinger position(s) -->
  <!--arg name="pinger_params" default="$(find vrx_gazebo)/config/pinger.yaml"/-->

  <!-- Initial USV location and attitude-->
  <arg name="x" default="-532" />
  <arg name="y" default="162" />
  <arg name="z" default="0.1" />
  <arg name="P" default="0" />
  <arg name="R" default="0" />
  <arg name="Y" default="1" />

  <!-- Allow user specified thruster configurations
       H = stern trusters on each hull
       T = H with a lateral thruster
       X = "holonomic" configuration -->
  <arg name="thrust_config" default="T" />

  <!-- Do we load the VRX sensor suite? -->
  <arg name="vrx_sensors_enabled" default="true" />

  <!-- Start Gazebo with the world file -->
  <include file="$(find gazebo_ros)/launch/empty_world.launch">
    <arg name="world_name"   value="$(arg world)"/>
    <arg name="verbose"      value="$(arg verbose)"/>
    <arg name="paused"       value="$(arg paused)"/>
    <arg name="use_sim_time" value="true"/>
    <arg name="gui"          value="$(arg gui)" />
    <arg name="extra_gazebo_args" value="$(arg extra_gazebo_args)"/>
  </include>

  <!-- Load robot model -->
  <!-- Determine which model -->
  <arg name="h_config" value="$(eval int((thrust_config)=='H'))"/>
  <arg name="t_config" value="$(eval int((thrust_config)=='T'))"/>
  <arg name="x_config" value="$(eval int((thrust_config)=='X'))"/>

  <!-- For now - can only use the T configuration! -->
  <arg if="$(arg t_config)" name="urdf" default="$(find wamv_gazebo)/urdf/wamv_gazebo.urdf.xacro"/>

	<!-- USV01 -->
  <param name="$(arg namespace)/robot_description"
         command="$(find xacro)/xacro &#x002D;&#x002D;inorder '$(arg urdf)'
         locked:=$(arg wamv_locked)		   
         thruster_config:=$(arg thrust_config)
         vrx_sensors_enabled:=$(arg vrx_sensors_enabled)
         namespace:=$(arg namespace) "/>

  <!-- Spawn model in Gazebo -->
  <node name="spawn_model" pkg="gazebo_ros" type="spawn_model"
        args="-x $(arg x) -y $(arg y) -z $(arg z)
              -R $(arg R) -P $(arg P) -Y $(arg Y)
              -urdf -param $(arg namespace)/robot_description -model wamv"/>

  <!-- Pinger visualization -->
  <!--node name="pinger_visualization" pkg="vrx_gazebo" type="pinger_visualization.py" /-->
  <!-- USV02 -->
  <arg name="x2" default="-432" />
  <arg name="y2" default="262" />
  <arg name="z2" default="0.1" />
  <arg name="P2" default="0" />
  <arg name="R2" default="0" />
  <arg name="Y2" default="1" />
  
  <param name="$(arg namespace2)/robot_description"
         command="$(find xacro)/xacro &#x002D;&#x002D;inorder '$(arg urdf)'
         locked:=$(arg wamv_locked)		   
         thruster_config:=$(arg thrust_config)
         vrx_sensors_enabled:=$(arg vrx_sensors_enabled)
         namespace:=$(arg namespace2) "/>

  <!-- Spawn model in Gazebo -->
  <node name="spawn_model2" pkg="gazebo_ros" type="spawn_model"
        args="-x $(arg x2) -y $(arg y2) -z $(arg z2)
              -R $(arg R2) -P $(arg P2) -Y $(arg Y2)
              -urdf -param $(arg namespace2)/robot_description -model wamv2"/>

</launch>
  • 4
    点赞
  • 36
    收藏
    觉得还不错? 一键收藏
  • 6
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论 6
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值