UUV_Simulator
1. 快速开始(可不看)
打开一个空的水下环境
roslaunch uuv_gazebo_worlds empty_underwater_world.launch
或者
roslaunch uuv_gazebo_worlds ocean_waves.launch
加载一个RexROV模型
roslaunch uuv_descriptions upload_rexrov.launch mode:=default x:=0 y:=0 z:=-20 namespace:=rexrov


2. RexROV 2模型

一. 控制器
1. 配置启动奇点树跟踪控制器节点。
roslaunch uuv_gazebo_worlds ocean_waves.launch
roslaunch rexrov2_description upload_rexrov2.launch
roslaunch rexrov2_control start_sf_controller.launch


2. 带恢复力补偿的PD控制器
START_PD_GRAV_COMPENSATION_CONTROLLER.LAUNCH
roslaunch uuv_gazebo_worlds ocean_waves.launch
roslaunch rexrov2_description upload_rexrov2.launch
roslaunch rexrov2_control start_pd_grav_compensation_controller.launch
3. 基于模型的反馈线性化控制器
控制器的默认参数Kp、Kd和Ki使用SMAC优化。
roslaunch uuv_gazebo_worlds ocean_waves.launch
roslaunch rexrov2_description upload_rexrov2.launch
roslaunch rexrov2_control start_mb_fl_controller.launch
4. 无模型滑模控制器
START_NMB_SM_CONTROLLER.LAUNCH
利用SMAC对控制器的默认参数K、Kd、Ki和斜率进行了优化。
roslaunch uuv_gazebo_worlds ocean_waves.launch
roslaunch rexrov2_description upload_rexrov2.launch
roslaunch rexrov2_control start_nmb_sm_controller.launch
5. 创建或重置推进器分配矩阵
如果必须创建或重新计算推进器分配矩阵,则按以下步骤开始模拟
roslaunch uuv_gazebo_worlds ocean_waves.launch
roslaunch rexrov2_description upload_rexrov2.launch
然后启动推进器管理器,并将reset_tam设置为true。该文件将存储在输入tam_file下随路径提供的文件名下,如下所示
roslaunch rexrov2_control start_thruster_manager.launch reset_tam:=true
Example
启动模拟,生成RexROV 2车辆,然后启动推进器分配节点,如下所示
roslaunch uuv_gazebo_worlds ocean_waves.launchroslaunch rexrov2_description upload_rexrov2.launchroslaunch rexrov2_control start_thruster_manager.launch
6. 六自由度PID控制器
利用SMAC对控制器的默认参数Kp、Kd和Ki进行了优化。
roslaunch uuv_gazebo_worlds ocean_waves.launchroslaunch rexrov2_description upload_rexrov2.launchroslaunch rexrov2_control start_pid_controller.launch
二. 模型文件
UPLOAD_REXROV2_OBERON_ARMS.LAUNCH
在模拟中生成RexROV 2车辆,一般用这个
三. 仿真文件
START_DEMO_PD_GRAV_COMPENSATION_CONTROLLER.LAUNCH
START_DEMO_NMB_SM_CONTROLLER.LAUNCH
START_DEMO_PID_CONTROLLER.LAUNCH
START_DEMO_SF_CONTROLLER.LAUNCH
START_DEMO_MB_FL_CONTROLLER.LAUNCH
四. 食用方法
- 第一步加载世界环境
roslaunch uuv_gazebo_worlds ocean_waves.launch
- 第二步加载描述文件和控制文件(二选一)
roslaunch rexrov2_description upload_rexrov2.launchroslaunch rexrov2_control start_demo_pid_controller.launch
- 第二步也可直接加载仿真文件(二选一)
roslaunch rexrov2_gazebo start_pid_controller.launch
3. ECA A9模型

一. 控制器
START_CONTROL_ALLOCATOR.LAUNCH
START_GEOMETRIC_TRACKING_CONTROL.LAUNCH
二. 模型文件
三. 仿真文件


四、食用方法
- 一般首先运行海底世界环境(必须)
roslaunch uuv_gazebo_worlds ocean_waves.launch
- 再运行模型文件和控制文件(二选一)
roslaunch eca_a9_description upload_eca_a9.launchroslaunch eca_a9_control start_geometric_tracking_control.launch
- 或者直接运行仿真文件(二选一)
roslaunch eca_a9_gazebo start_demo_teleop.launch
4. LAUV 模型

一. 控制器
START_CONTROL_ALLOCATOR.LAUNCH
START_AUV_TRAJECTORY_CONTROL.LAUNCH
二. 模型文件
三. 仿真文件

四. 食用方法
- 一般首先运行海底世界环境(必须)
roslaunch uuv_gazebo_worlds ocean_waves.launch
- 再运行模型文件和控制文件(二选一)
roslaunch lauv_description upload.launchroslaunch lauv_control start_auv_trajectory_control.launch
- 或者直接运行仿真文件(二选一)
roslaunch lauv_gazebo start_demo_auv_control.launch

5. Desistek SAGA ROV模型

一. 控制器
START_CASCADED_PID_WITH_TELEOP.LAUNCH
START_GEOMETRIC_TRACKING_CONTROL.LAUNCH
二. 模型文件
三.仿真文件
START_DEMO_NMB_SM_CONTROLLER.LAUNCH
四. 食用方法
- 第一步打开仿真环境
roslaunch uuv_gazebo_worlds ocean_waves.launch
- 第二步加载描述文件和控制文件,或者直接运行仿真文件如下:(二选一)
roslaunch desistek_saga_gazebo start_demo_teleop.launch


6. UUV_Simulator
一. 世界模型
-
AUV underwater world
roslaunch uuv_gazebo_worlds auv_underwater_world.launch
-
Empty underwater world
roslaunch uuv_gazebo_worlds empty_underwater_world.launch
-
Herkules ship wreck

roslaunch uuv_gazebo_worlds herkules_ship_wreck.launch
-
Lake

roslaunch uuv_gazebo_worlds lake.launch
-
Coast of Mangalia, Romania

roslaunch uuv_gazebo_worlds mangalia.launch
-
Munkholmen, Norway


roslaunch uuv_gazebo_worlds munkholmen.launch
-
Ocean waves world
此场景包括运行“海洋模型波浪”明暗器的海面,以在模拟期间设置波浪动画。

roslaunch uuv_gazebo_worlds ocean_waves.launch
-
Subsea BOP panel
在挪威特隆赫姆的欧盟项目群模拟操作演示中使用的场景。
它包含用于辅助定位操纵器末端效应器的移动阀和标记。

roslaunch uuv_gazebo_worlds subsea_bop_panel.launch
二. 轨迹发生器
该包中的路径和轨迹的产生大多是基于WayPoints的。 通过使用路径插值器来计算对控制器的参考,然后计算速度和加速设定点的有限区分,以防他们是期望的。
1. 螺旋形路径
要查看车辆所遵循的螺旋路径的示例,可以使用轨迹跟踪控制器启动ROV模型,如以下rexrov2软件包中所示。
roslaunch rexrov2_gazebo start_demo_pid_controller.launch
要生成带两圈的螺旋路径,请运行以下命令:
roslaunch uuv_control_utils start_helical_trajectory.launch uuv_name:=rexrov2 n_turns:=2
本例在生成的航路点上使用三次插值器。生成的路径可以被视为下图中的绿线。

2. 线性内插器
线性内插器简单地使用线段连接所有航路点。
此路径生成器可能会导致拐角处出现意外的急动。
要查看车辆所遵循的线性插值器路径的示例,可以使用轨迹跟踪控制器启动ROV模型,如rexrov2软件包中的以下内容:
roslaunch rexrov2_gazebo start_demo_pid_controller.launch
然后使用将其控制器发送一组样本航点,使用内插器的线性输入如下
roslaunch uuv_control_utils send_waypoints_file.launch uuv_name:=rexrov2 interpolator:=linear

3. 立方插值器
三次插值器计算一条三次贝塞尔曲线,该曲线在输入集中的所有航路点之间进行分段。
要查看车辆所遵循的立方插值器路径的示例,可以使用轨迹跟踪控制器启动ROV模型,如以下rexrov2软件包中的内容。
roslaunch rexrov2_gazebo start_demo_pid_controller.launch
然后使用将其控制器发送一组样本航点,使用内插器的立方输入如下
roslaunch uuv_control_utils send_waypoints_file.launch uuv_name:=rexrov2 interpolator:=cubic

4. 多项式混合线性插值器
它基本上由路径上的每对点和拐角处的五阶贝塞尔曲线之间生成的线段组成。
要查看车辆跟随此内插器路径的示例,可以使用轨迹跟踪控制器启动ROV模型,如以下rexrov2软件包中的内容。
roslaunch rexrov2_gazebo start_demo_pid_controller.launch
然后使用将其控制器发送一组示例航点,使用内插器的LIPB输入如下
roslaunch uuv_control_utils send_waypoints_file.launch uuv_name:=rexrov2 interpolator:=lipb


5. Dubins插值器
Dubins路径生成器是2D Dubins路径算法的扩展,该算法计算两点之间的最短曲线。这条路径非常适合只能向前行驶的车辆,如水下机器人。
作为一项安全措施,特别是对于使用鳍操纵的AUV等车辆,设置了一个可配置的最大俯仰角(默认设置为5度),以控制车辆爬升的行为。如果两个航路点之间的必要俯仰角超过该角,则引入螺旋路径以避免产生可能使车辆失速的俯仰设定点。这将在下面的rexrov2车辆示例中看到。
要查看车辆跟随此内插器路径的示例,可以使用轨迹跟踪控制器启动ROV模型,如以下rexrov2软件包中的内容。
roslaunch rexrov2_gazebo start_demo_pid_controller.launch
然后使用dubins输入向控制器发送一组采样航路点,如下所示
roslaunch uuv_control_utils send_waypoints_file.launch uuv_name:=rexrov2 interpolator:=dubins

由于俯仰角超过限制,螺旋路径在前两个航路点之间生成。

三. 键盘运动控制
启动环境和水下机器人pid控制
执行命令:
roslaunch uuv_gazebo start_pid_demo_with_teleop.launch
这里机器人的速度控制还是经典的cmd_vel话题,我们可以自己创建速度控制脚本teletop.py:
#!/usr/bin/env python
import rospy
from geometry_msgs.msg import Twist
import sys, select, os
if os.name == 'nt':
import msvcrt
else:
import tty, termios
FETCH_MAX_LIN_VEL = 5
FETCH_MAX_ANG_VEL = 2.84
LIN_VEL_STEP_SIZE = 0.01
ANG_VEL_STEP_SIZE = 0.1
msg = """
Control Your Robot!
---------------------------
Moving around:
w
a s d
x
"""
e = """
Communications Failed
"""
def getKey():
if os.name == 'nt':
return msvcrt.getch()
tty.setraw(sys.stdin.fileno())
rlist, _, _ = select.select([sys.stdin], [], [], 0.1)
if rlist:
key = sys.stdin.read(1)
else:
key = ''
termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)
return key
def vels(target_linear_vel, target_angular_vel):
return "currently:\tlinear vel %s\t angular vel %s " % (target_linear_vel,target_angular_vel)
def makeSimpleProfile(output, input, slop):
if input > output:
output = min( input, output + slop )
elif input < output:
output = max( input, output - slop )
else:
output = input
return output
def constrain(input, low, high):
if input < low:
input = low
elif input > high:
input = high
else:
input = input
return input
def checkLinearLimitVelocity(vel):
vel = constrain(vel, -FETCH_MAX_LIN_VEL, FETCH_MAX_LIN_VEL)
return vel
def checkAngularLimitVelocity(vel):
vel = constrain(vel, -FETCH_MAX_ANG_VEL, FETCH_MAX_ANG_VEL)
return vel
if __name__=="__main__":
if os.name != 'nt':
settings = termios.tcgetattr(sys.stdin)
rospy.init_node('fetch_teleop')
pub = rospy.Publisher('/rexrov/cmd_vel', Twist, queue_size=10)
status = 0
target_linear_vel = 0.0
target_angular_vel = 0.0
control_linear_vel = 0.0
control_angular_vel = 0.0
try:
print(msg)
while(1):
key = getKey()
if key == 'w' :
target_linear_vel = checkLinearLimitVelocity(target_linear_vel + LIN_VEL_STEP_SIZE)
status = status + 1
print(vels(target_linear_vel,target_angular_vel))
elif key == 'x' :
target_linear_vel = checkLinearLimitVelocity(target_linear_vel - LIN_VEL_STEP_SIZE)
status = status + 1
print(vels(target_linear_vel,target_angular_vel))
elif key == 'a' :
target_angular_vel = checkAngularLimitVelocity(target_angular_vel + ANG_VEL_STEP_SIZE)
status = status + 1
print(vels(target_linear_vel,target_angular_vel))
elif key == 'd' :
target_angular_vel = checkAngularLimitVelocity(target_angular_vel - ANG_VEL_STEP_SIZE)
status = status + 1
print(vels(target_linear_vel,target_angular_vel))
elif key == ' ' or key == 's' :
target_linear_vel = 0.0
control_linear_vel = 0.0
target_angular_vel = 0.0
control_angular_vel = 0.0
print(vels(target_linear_vel, target_angular_vel))
else:
if (key == '\x03'):
break
if status == 20 :
print(msg)
status = 0
twist = Twist()
control_linear_vel = makeSimpleProfile(control_linear_vel, target_linear_vel, (LIN_VEL_STEP_SIZE/2.0))
twist.linear.x = control_linear_vel; twist.linear.y = 0.0; twist.linear.z = 0.0
control_angular_vel = makeSimpleProfile(control_angular_vel, target_angular_vel, (ANG_VEL_STEP_SIZE/2.0))
twist.angular.x = 0.0; twist.angular.y = 0.0; twist.angular.z = control_angular_vel
pub.publish(twist)
except:
print(e)
finally:
twist = Twist()
twist.linear.x = 0.0; twist.linear.y = 0.0; twist.linear.z = 0.0
twist.angular.x = 0.0; twist.angular.y = 0.0; twist.angular.z = 0.0
pub.publish(twist)
if os.name != 'nt':
termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)
运行脚本就可以控制船运动了:
python teletop.py
四. 配置推进器管理器
为了产生推力器驱动车辆的控制力,需要计算推力器分配矩阵,该矩阵将转换控制器的输出。
要使用新车辆的控制配置创建初始包,请在catkin工作区中运行以下命令:
rosrun uuv_assistants create_thruster_manager_configuration --robot_name <ROBOT_NAME>
此脚本将创建一个新的
如果您已经有了要存储这些文件的catkin包,请运行:
rosrun uuv_assistants create_thruster_manager_configuration --robot_name <ROBOT_NAME> --output_dir <CATKIN_PKG>
文件夹结构如下所示
<ROBOT_NAME>_control
|-- config
|-- thruster_manager.yaml
|-- launch
|-- start_thruster_manager.launch
`-- CMakeLists.txt
`-- package.xml
您应该编辑推力器thruster_manager.yaml文件,以包含正确的推力器模型参数和主题。
有关如何操作的说明可以在同一文件的注释中找到。以下是RexROV车辆推进器管理器配置的示例:
thruster_manager:
tf_prefix: rexrov
base_link: base_link
thruster_topic_prefix: thrusters/
thruster_topic_suffix: /input
thruster_frame_base: thruster_
max_thrust: 2000.0
timeout: -1
update_rate: 50
conversion_fcn: proportional
conversion_fcn_params:
gain: 0.00031
你必须编译你的catkin工作区
cd ~/catkin_auv_ws
catkin_make
你可以开始一个空的水下世界:
roslaunch uuv_gazebo_worlds empty_underwater_world.launch
然后加载车辆:
roslaunch <ROBOT_NAME>_description upload.launch
最后执行:
roslaunch <ROBOT_NAME>_control start_thruster_manager.launch reset_tam:=true
要指挥车辆,必须启动推进器管理器并向输入主题发布一条消息:
/<ROBOT_NAME or ROBOT_NAMESPACE>/thruster_manager/input
五. 创建新车辆
要创建新的水下航行器所需的catkin包和文件结构,可以在catkin工作区中运行以下脚本:
rosrun uuv_assistants create_new_robot_model --robot_name <ROBOT_NAME>
这将创建一个名为
包含了使用UUV模拟器插件的代码片段,应该进行修改才能使用。模板文件没有特别描述任何车辆。
用户还应将网格包含在“网格”文件夹中。完整的文件夹结构如下所示。
<ROBOT_NAME>_description
|-- launch
|-- upload.launch
|-- meshes
|-- README.md
|-- robots
|-- default.xacro
|-- urdf
|-- actuators.xacro
|-- base.xacro
|-- gazebo.xacro
|-- sensors.xacro
|-- snippets.xacro
`-- CMakeLists.txt
`-- package.xml
在机器人描述中,执行器和车辆分别建模,还应具有单独的网格文件。推进器插件宏将推进器的旋转轴设置为X轴,因此最好相应地设置网格,如下面显示RexROV推进器网格的示例所示。

可用于将FIN插孔的FIN插件宏设置为围绕Z轴旋转,因此Fin网格可以定位为下面的图像中,以避免在URDF文件中配置其起源和方向。
.. image:: ../images/tutorial_new_vehicle/fin_mesh.png
模板文件应具有ROV、AUV和简单水面舰艇所需的宏。如果您想为UUV模拟器插件检查更多的URDF代码段宏,您应该检查
uuv_gazebo_ros_plugins XACRO macros https://github.com/uuvsimulator/uuv_simulator/tree/master/uuv_gazebo_plugins/uuv_gazebo_ros_plugins/urdf
uuv_sensor_plugins_ros XACRO macros https://github.com/uuvsimulator/uuv_simulator/tree/master/uuv_sensor_plugins/uuv_sensor_plugins_ros/urdf.
传感器、致动器和浮力中心的位置和方向必须相对于车辆基础连杆的重心进行设置。ROS和Gazebo也默认使用ENU(East-North-Up)
reference frame http://www.ros.org/reps/rep-0103.html
六. 创建新的动态定位控制器
为了便于为本软件包中建模的车辆实施新的控制算法,创建了一些Python模块,作为车辆推进器管理器、本地规划器的接口,并设置接收轨迹消息和发送推进器命令所需的发布者和订阅者。该模块还包括Fossen运动方程的实现,可供基于模型的控制器使用。要基于此Python模块创建控制器,请参见以下步骤。
下面讨论的所有文件都可以在 uuv_tutorials文件夹的 uuv_tutorial_dp_controller 包中找到。
请记住在开发自己的模块时更改包的名称,以避免编译catkin工作区时发生冲突。
1. 创建自定义控制器包
首先,将创建一个新的catkin包,其中包含实现所需的脚本和启动文件。如果您的名称不同,请替换下面的catkin工作区catkin_ws的名称。
cd ~/catkin_ws/src
catkin_create_pkg uuv_tutorial_dp_controller
此命令将为新包创建必要的文件,此文件将在本教程中进一步编辑。接下来,需要两个文件夹,一个用于启动文件的启动文件夹和一个用于存储自定义控制器实现的脚本文件夹。
cd ~/catkin_ws/src/uuv_tutorial_dp_controller
mkdir launch scripts
2. 创建控制器节点
在scripts文件夹中,必须创建一个Python文件,在这里我们将命名它 : tutorial_dp_controller.py
touch scripts/tutorial_dp_controller.py
这个文件将实现名为 TutorialDPController 的控制器,一个非常简单的PID控制器,如下所示。
#!/usr/bin/env python
import rospy
import numpy as np
from uuv_control_interfaces import DPControllerBase
class TutorialDPController(DPControllerBase):
def __init__(self):
super(TutorialDPController, self).__init__(self)
self._Kp = np.zeros(shape=(6, 6))
self._Kd = np.zeros(shape=(6, 6))
self._Ki = np.zeros(shape=(6, 6))
self._int = np.zeros(shape=(6,))
self._error_pose = np.zeros(shape=(6,))
# Do the same for the other two matrices
if rospy.get_param('~Kp'):
diag = rospy.get_param('~Kp')
if len(diag) == 6:
self._Kp = np.diag(diag)
print 'Kp=\n', self._Kp
else:
# If the vector provided has the wrong dimension, raise an exception
raise rospy.ROSException('For the Kp diagonal matrix, 6 coefficients are needed')
if rospy.get_param('~Kd'):
diag = rospy.get_param('~Kd')
if len(diag) == 6:
self._Kd = np.diag(diag)
print 'Kd=\n', self._Kd
else:
# If the vector provided has the wrong dimension, raise an exception
raise rospy.ROSException('For the Kd diagonal matrix, 6 coefficients are needed')
if rospy.get_param('~Ki'):
diag = rospy.get_param('~Ki')
if len(diag) == 6:
self._Ki = np.diag(diag)
print 'Ki=\n', self._Ki
else:
# If the vector provided has the wrong dimension, raise an exception
raise rospy.ROSException('For the Ki diagonal matrix, 6 coefficients are needed')
self._is_init = True
def _reset_controller(self):
super(TutorialDPController, self)._reset_controller()
self._error_pose = np.zeros(shape=(6,))
self._int = np.zeros(shape=(6,))
def update_controller(self):
if not self._is_init:
return False
if not self.odom_is_init:
return
self._int = self._int + 0.5 * (self.error_pose_euler + self._error_pose) * self._dt
self._error_pose = self.error_pose_euler
tau = np.dot(self._Kp, self.error_pose_euler) + np.dot(self._Kd, self._errors['vel']) + np.dot(self._Ki, self._int)
self.publish_control_wrench(tau)
if __name__ == '__main__':
print('Tutorial - DP Controller')
rospy.init_node('tutorial_dp_controller')
try:
node = TutorialDPController()
rospy.spin()
except rospy.ROSInterruptException:
print('caught exception')
print('exiting')
详细分析该文件,控制器要使用 uuv_control_interfaces 接口的控制器模块,必须继承 DPControllerBase 类并对其进行初始化
class TutorialDPController(DPControllerBase):
def __init__(self):
super(TutorialDPController, self).__init__(self)
这将设置超类来初始化,例如,里程计消息订阅者和推进器管理器主题发布者。对于基于模型的控制器,必须将超类构造函数称为
super(TutorialDPController, self).__init__(self, is_model_based=True)
控制器参数 Kp, Kd and Ki 应从参数服务器检索,以允许在不同配置中使用控制器。另一种方法是从节点的私有参数名称空间中读取此信息,如下所示。这是通过在参数的标记前面添加~来完成的。必须在控制器的启动文件中相应地提供参数,这将在后面讨论。
if rospy.get_param('~Kd'):
diag = rospy.get_param('~Kd')
if len(diag) == 6:
self._Kd = np.diag(diag)
print 'Kd=\n', self._Kd
else:
# If the vector provided has the wrong dimension, raise an exception
raise rospy.ROSException('For the Kd diagonal matrix, 6 coefficients are needed')
如果在接收到重置服务调用时必须重置内部变量,则可以重写_reset_controller方法。还必须调用下面所示的超类的reset方法,以确保错误和参考向量也将被清除。
super(TutorialDPController, self)._reset_controller()
当使用超类 DPControllerBase 时,不需要添加控制器更新序列或计时器。一旦方法update_controller在controller类中实现,它将作为一个回调函数提供给里程计更新方法。此更新方法应包括控制器的算法并生成控制扭力向量(在这种情况下τ) 并使用超类函数publish_control_wrench将其发布到推进器管理器输入。
文件的最后一部分是执行ROS节点所必需的。
if __name__ == '__main__':
print('Tutorial - DP Controller')
rospy.init_node('tutorial_dp_controller')
try:
node = TutorialDPController()
rospy.spin()
except rospy.ROSInterruptException:
print('caught exception')
print('exiting')
3. 配置启动文件
定制控制器完成后,您必须将Python脚本转换为可执行文件,并且可以按以下步骤进行,否则您将无法启动ROS节点。
chmod u+x tutorial_dp_controller.py
下一步是为新控制器设置启动文件。创建一个新的启动文件,如下所示
cd ~/catkin_ws/src/uuv_tutorial_dp_controller/launch
touch start_tutorial_dp_controller.launch
编辑文件以包含以下内容
<launch>
<arg name="uuv_name"/>
<arg name="model_name" default="$(arg uuv_name)"/>
<arg name="saturation" default="5000"/>
<arg name="Kp" default="11993.888,11993.888,11993.888,19460.069,19460.069,19460.069"/>
<arg name="Kd" default="9077.459,9077.459,9077.459,18880.925,18880.925,18880.925"/>
<arg name="Ki" default="321.417,321.417,321.417,2096.951,2096.951,2096.951"/>
<arg name="output_dir" default="$(find uuv_thruster_manager)/config/$(arg model_name)"/>
<arg name="config_file" default="$(find uuv_thruster_manager)/config/$(arg model_name)/thruster_manager.yaml"/>
<arg name="tam_file" default="$(find uuv_thruster_manager)/config/$(arg model_name)/TAM.yaml"/>
<include file="$(find uuv_thruster_manager)/launch/thruster_manager.launch">
<arg name="uuv_name" value="$(arg uuv_name)"/>
<arg name="model_name" value="$(arg model_name)"/>
<arg name="output_dir" value="$(arg output_dir)"/>
<arg name="config_file" value="$(arg config_file)"/>
<arg name="tam_file" value="$(arg tam_file)"/>
</include>
<group ns="$(arg uuv_name)">
<node pkg="uuv_control_utils"
type="trajectory_marker_publisher.py"
name="trajectory_marker_publisher"
output="screen">
<remap from="trajectory" to="dp_controller/trajectory"/>
<remap from="waypoints" to="dp_controller/waypoints"/>
</node>
<node pkg="uuv_tutorial_dp_controller"
type="tutorial_dp_controller.py"
name="tutorial_dp_controller"
output="screen">
<remap from="odom" to="pose_gt"/>
<remap from="trajectory" to="dp_controller/trajectory"/>
<remap from="input_trajectory" to="dp_controller/input_trajectory"/>
<remap from="waypoints" to="dp_controller/waypoints"/>
<remap from="error" to="dp_controller/error"/>
<remap from="reference" to="dp_controller/reference"/>
<remap from="thruster_output" to="thruster_manager/input_stamped"/>
<rosparam subst_value="true">
saturation: $(arg saturation)
Kp: [$(arg Kp)]
Kd: [$(arg Kd)]
Ki: [$(arg Ki)]
</rosparam>
</node>
</group>
</launch>
要注意的启动文件最重要的部分是,必须始终提供车辆名称空间uuv_name名称,因为每个默认值的模拟将具有特定于在其名称空间中创建的每个车辆的操作的节点。推进器管理器也必须初始化。
最后,必须调用控制器节点以及参数设置的正确参数 Kp, Kd and Ki.在这个例子中。您可以通过命令行传递此参数,也可以如上所示设置默认向量,但是逗号和值之间不应该有空格。他们必须被安置rosparam块。trajectory_marker_publisher是一个可选节点,仅用于发布可视标记。
要使用RexROV车辆开始一个小演示,您可以创建另一个启动文件,如下所示:
cd ~/catkin_ws/src/uuv_tutorial_dp_controller/launch
touch start_tutorial_dp_controller_demo.launch
初始化一个世界,车辆和RViz可视化工具如下:
<launch>
<!-- This launch file will start the controller nodes with the necessary parameters -->
<!--
Vehicle namespace: since the simulation can run with multiple vehicle, each vehicle
is created under a namespace, which is per default equal to the name of vehicle model, but
can be assigned differently at startup
-->
<arg name="uuv_name"/>
<!-- Name of the vehicle model: the name of the robot model -->
<arg name="model_name" default="$(arg uuv_name)"/>
<!-- Control effort saturation -->
<arg name="saturation" default="5000"/>
<!--
The controller parameters are given below and will be given to the controller node in its
private namespace. These are vectors and for roslaunch to see this as one argument, there
can be no spaces between the commas and the floating point values. The default values
are usually the ones that are going to be used.
-->
<arg name="Kp" default="11993.888,11993.888,11993.888,19460.069,19460.069,19460.069"/>
<arg name="Kd" default="9077.459,9077.459,9077.459,18880.925,18880.925,18880.925"/>
<arg name="Ki" default="321.417,321.417,321.417,2096.951,2096.951,2096.951"/>
<arg name="output_dir" default="$(find uuv_thruster_manager)/config/$(arg model_name)"/>
<arg name="config_file" default="$(find uuv_thruster_manager)/config/$(arg model_name)/thruster_manager.yaml"/>
<arg name="tam_file" default="$(find uuv_thruster_manager)/config/$(arg model_name)/TAM.yaml"/>
<!--
For the control vector to be distributed amongst the thrusters, a thruster manager node
has to be initialized for this specific vehicle. The thruster manager will calculate the
thruster allocation matrix if none is provided, but it is better if the TAM is stored
in a YAML file beforehand. Check the tutorial on how to initialize the thruster allocation
matrix.
-->
<include file="$(find uuv_thruster_manager)/launch/thruster_manager.launch">
<!--
The thruster manager will use the namespace uuv_name to initialize the node and
will use the robot's model_name to search for the YAML file containing the thruster
allocation matrix.
-->
<arg name="uuv_name" value="$(arg uuv_name)"/>
<arg name="model_name" value="$(arg model_name)"/>
<arg name="output_dir" value="$(arg output_dir)"/>
<arg name="config_file" value="$(arg config_file)"/>
<arg name="tam_file" value="$(arg tam_file)"/>
</include>
<!--
It is important to start all nodes relative to this vehicle under the vehicle's
namespace in order to avoid errors and parameter being initialized in wrong place.
Most of the nodes per default are going to look for configuration parameters and
topics under the vehicle's namespace per default.
-->
<group ns="$(arg uuv_name)">
<!--
This node just reads the trajectory and waypoint topics and publishes visualization
markers to RViz, but is not essential to the controller's operation
-->
<node pkg="uuv_control_utils"
type="trajectory_marker_publisher.py"
name="trajectory_marker_publisher"
output="screen">
<remap from="trajectory" to="dp_controller/trajectory"/>
<remap from="waypoints" to="dp_controller/waypoints"/>
</node>
<!--
Start the vehicle controller node. Remember to include this controller's script
correctly in the CMakeLists.txt file of your catkin package. This can be done by
adding the following line in the CMakeLists.txt after the line where catkin_package()
is given:
catkin_install_python(PROGRAMS scripts/tutorial_dp_controller.py DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})
The scripts/tutorial_dp_controller.py file must also be set as an executable as follows
>> cd <path_to_ros_package>/scripts
>> chmod 777 tutorial_dp_controller.py
-->
<node pkg="uuv_tutorial_dp_controller"
type="tutorial_dp_controller.py"
name="tutorial_dp_controller"
output="screen">
<!-- Remap necessary topics -->
<remap from="odom" to="pose_gt"/>
<remap from="trajectory" to="dp_controller/trajectory"/>
<remap from="input_trajectory" to="dp_controller/input_trajectory"/>
<remap from="waypoints" to="dp_controller/waypoints"/>
<remap from="error" to="dp_controller/error"/>
<remap from="reference" to="dp_controller/reference"/>
<remap from="thruster_output" to="thruster_manager/input_stamped"/>
<!-- Set the controller parameters in the node's private namespace-->
<rosparam subst_value="true">
saturation: $(arg saturation)
Kp: [$(arg Kp)]
Kd: [$(arg Kd)]
Ki: [$(arg Ki)]
</rosparam>
</node>
</group>
<!--
Now run the demo file to start a new simulation with this controller
>> roslaunch uuv_tutorial_dp_controller start_tutorial_dp_controller_demo.launch
-->
</launch>
在运行此演示程序之前,必须先配置包。
4. 配置包
要允许catkin安装所有模块,可以从catkin包中打开CMakeLists.txt文件,并将其编辑为如下示例所示。
cmake_minimum_required(VERSION 2.8.3)
project(uuv_tutorial_dp_controller)
find_package(catkin REQUIRED)
catkin_package()
catkin_install_python(PROGRAMS scripts/tutorial_dp_controller.py DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})
install(DIRECTORY launch
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
PATTERN "*~" EXCLUDE)
5. 运行模拟
使用catkin_make或catkin build再次编译工作区后,可以运行之前创建的演示启动文件。
roslaunch uuv_tutorial_dp_controller start_tutorial_dp_controller_demo.launch
这将启动Gazebo模拟器,使用RexROV车辆实例,使用此自定义控制器进行定位。

您可以使用 uuv_control_utils 包中的一个模块向车辆发送一些航路点,并查看控制器的工作情况。例如,使用默认的航路点列表,并使用
roslaunch uuv_control_utils send_waypoints_file.launch uuv_name:=rexrov
注意:默认航路点在 uuv_simulator/uuv_control/uuv_control_utils/config/example_waypoints.yaml 文件下。
官方地址: default list of waypoints
inertial_frame_id: world
waypoints:
-
point: [0, 2, -22]
max_forward_speed: 0.4
heading: 0
use_fixed_heading: False
-
point: [16, 12, -24]
max_forward_speed: 0.4
heading: 0
use_fixed_heading: False
-
point: [20, 12, -27]
max_forward_speed: 0.4
heading: 0
use_fixed_heading: False
-
point: [25, 16, -25]
max_forward_speed: 0.4
heading: 0
use_fixed_heading: False
-
point: [25, 20, -25]
max_forward_speed: 0.4
heading: 0
use_fixed_heading: False
-
point: [30, 40, -25]
max_forward_speed: 0.4
heading: 0
use_fixed_heading: False
-
point: [36, 45, -25]
max_forward_speed: 0.4
heading: 0
use_fixed_heading: False
-
point: [60, 70, -45]
max_forward_speed: 0.4
heading: 0
use_fixed_heading: False
-
point: [105, 56, -60]
max_forward_speed: 0.4
heading: 0
use_fixed_heading: False
-
point: [100, -20, -60]
max_forward_speed: 0.4
heading: 0
use_fixed_heading: False
-
point: [100, -20, -59]
max_forward_speed: 0.4
heading: 0
use_fixed_heading: False
注意:DPControllerBase类默认使用的uuv_control_interfaces接口中的本地规划器将接收航路点,并应用多项式混合的线性插值来生成车辆要遵循的路径。

七. 产生干扰
使用控制策略评估车辆性能的步骤之一是检查车辆在各种干扰下的性能。一个可以使用的工具是通过GUI在Gazebo中的一个选项,或者使用ROS服务对场景中的链接施加力和扭矩。此外,还可以使用此软件包的“水下世界”Gazebo插件提供的服务来设置车辆的恒定流速。
为了使这种类型的测试更容易,包装 uuv_control_utils 中有一些脚本可以在模拟期间调度触扰发生干扰,使得更容易再现一个场景,其中干扰仅在某个模拟时间或有限的持续时间 。 uuv_control_utils包提供脚本以在特定时间应用干扰,并且还可以启动可在用例方案中构建的文件。 下面提到的文件可在 uuv_tutorial_disturbances中获得。
1. 推进器故障
要测试的一个有趣的用例是,看看在一个或多个推进器停止工作的情况下,车辆将如何工作。推力器插件提供一个服务调用来将推力器状态设置为ON或OFF。每个推进器单元自动生成服务名称,如下所示
/<model_name>/thrusters/<thruster_id>/set_thruster_state
/<model_name>/thrusters/<thruster_id>/get_thruster_state
例如,RexROV车辆为推进器 #2 提供设置推进器状态服务
/rexrov/thrusters/2/set_thruster_state.
要使用服务呼叫,下面提供了一些选项。
SETTING THRUSTER STATE THROUGH ROS SERVICE CALL
当你用推进器驱动的水下航行器开始模拟时,推进器服务将由推进器单元插件提供。例如,如果您启动PID控制器演示启动文件
roslaunch uuv_gazebo start_pid_demo.launch
您可以使用以下命令将其中一个推进器的状态设置为关闭:
rosservice call /rexrov/thrusters/2/set_thruster_state "'on': false"
您可以通过检查推进器单元的状态:
rosservice call /rexrov/thrusters/2/get_thruster_state
这应该回来
is_on: False
即使服务调用可以在运行时使用,如果您希望计划在特定时间关闭一个或多个推进器,并且(可选)将它们设置为在一段时间后再次打开,您可以使用 uuv_control_utils 中的ROS节点, set_thruster_state.py 。
例如,再次启动以前的模拟:
roslaunch uuv_gazebo start_pid_demo.launch
然后以其启动文件启动节点
roslaunch uuv_control_utils set_thruster_state.launch uuv_name:=rexrov starting_time:=10 duration:=20 is_on:=false thruster_id:=2
参数uuv_name指的是机器人模型的名称空间,starting_time指的是推进器状态将以秒为单位改变时的模拟时间戳,duration指的是这个新推进器状态的持续时间(如果推进器应该无限期地保持在这个状态,则将其设置为-1),应将is_on设置为“否”以关闭推进器,thruster_id是装置的索引。
此启动文件也可以包含在其他启动文件中,以使用此推进器故障设置构建场景。可以调用下面的示例来演示这一点
roslaunch uuv_tutorial_disturbances tutorial_thruster_state.launch
在模拟过程中,您可以使用rqt_plot图或通过如下方式读取推力器单元输出主题来监视推力器输出
rostopic echo /rexrov/thrusters/2/thrust
2. 推进器和螺旋桨效率损失
另一种可能性是为推进器单元的推力输出和/或推进器的动态变量(通常是转子的角速度)设置一个效率系数。允许这些设置的服务分别是
/<model_name>/thrusters/<thruster_id>/set_thrust_force_efficiency
/<model_name>/thrusters/<thruster_id>/set_dynamic_state_efficiency
与上一个示例类似,您可以使用车辆启动模拟场景,例如演示
roslaunch uuv_gazebo start_pid_demo.launch
然后做一个服务呼叫,如
rosservice call /rexrov/thrusters/2/set_thrust_force_efficiency "efficiency: 0.1"
为了在模拟过程中设置推力器输出效率系数,可以使用启动文件
roslaunch uuv_control_utils set_thruster_output_efficiency.launch uuv_name:=rexrov starting_time:=10 thruster_id:=2 duration:=20 efficiency:=0.3
其中参数 efficiency 必须是0.0到1.0之间的浮点数。下面提供了一个示例,可以按如下方式启动
roslaunch uuv_tutorial_disturbances tutorial_thruster_efficiency.launch
3. 车身舵机故障
在使用Gazebo的apply body扳手服务进行模拟的过程中,还可以设置一个简单的步进扳手扰动,以应用于车辆的质心。要查看有关如何使用Gazebo的ROS服务的更多详细信息,请查看此链接 link 。
为了在启动文件中使用此干扰,还可以使用以下命令:
roslaunch uuv_control_utils apply_body_wrench.launch uuv_name:=rexrov starting_time:=0.0 duration:=10 force_x:=0 force_y:=0 force_z:=0 torque_x:=0 torque_y:=0 torque_z:=0
如果要将力和转矩分量设置为0.0,则无需显式设置它们,启动文件已经按照默认值执行了该操作。如果必须无限期地使用扳手,则持续时间可以设置为-1。
重要的是要记住,相对于惯性系,扳手将施加在车辆基本连杆的质心上。您可以运行以下启动文件来查看此干扰的示例
roslaunch uuv_tutorial_disturbances tutorial_body_wrench.launch
4. 流速
流速可能是这个列表中最重要的扰动类型。仿真中的每个模型运行 underwater object plugin 定义了线性和二次阻尼系数后,水下世界插件通过本主题 /hydrodynamics/current_velocity发布的流速将影响阻尼系数。水下对象插件也可以订阅自己的私有流速主题/<model_name/current_velocity,但这是另一个教程的主题。
underwater world plugin 可以使用Fossen,2011中描述的三个单独的Gauss-Markov过程(当前速度大小、水平角和垂直角)生成当前速度主题,也可以在世界SDF文件中设置。
通过服务调用设置当前速度有不同的可能性。最简单的选择是简单地设置恒流速度矢量,如示例所示
rosservice call /hydrodynamics/set_current_velocity "velocity: 1.0
horizontal_angle: -0.8
vertical_angle: 0.2"
这里的角度用弧度表示。也可以使用以下调用单独设置这些参数
rosservice call /hydrodynamics/set_current_horz_angle "angle: 0.0"
rosservice call /hydrodynamics/set_current_vert_angle "angle: 0.0"
您可以监视当前速度主题 /hydrodynamics/current_velocity 在终端上 rostopic echo or in rqt.
值得注意的是,流速是在Gazebo的ENU参考系中计算的,因为它不识别SNAME约定。如果在RViz中可视化模拟输出,则可以订阅主题/

如前所述,流速大小、水平角和垂直角被建模为高斯-马尔可夫过程,以允许在平均值附近有小的变化。可以使用下面的服务调用来设置这些模型
rosservice call /hydrodynamics/set_current_velocity_model "{mean: 0.0, min: 0.0, max: 0.0, noise: 0.0, mu: 0.0}"
rosservice call /hydrodynamics/set_current_horz_angle_model "{mean: 0.0, min: 0.0, max: 0.0, noise: 0.0, mu: 0.0}"
rosservice call /hydrodynamics/set_current_vert_angle_model "{mean: 0.0, min: 0.0, max: 0.0, noise: 0.0, mu: 0.0}"
为了在不需要手动服务调用或更改世界SDF文件的情况下为模拟设置流速, uuv_control_utils 包中提供了ROS节点,但目前仅适用于恒流速模型。您可以使用以下启动文件调用它
roslaunch uuv_control_utils set_timed_current_perturbation.launch starting_time:=0.0 end_time:=10.0 current_vel:=1.0 horizontal_angle:=10.0 vertical_angle:=30
这个ROS节点以度数表示水平角和垂直角,还可以使用参数end_time将电流设置为在固定时间内结束。您可以运行下面的教程示例来了解如何使用它
roslaunch uuv_tutorial_disturbances tutorial_timed_current.launch
5. 干扰管理器
所有这些过去的例子都非常有助于设置单个干扰,但是如果一个场景需要在同一个模拟场景中激活多个(有时是不同的)干扰模型,您可以使用 disturbance manager node 使用此工具,您可以创建一个YAML文件,其中包含将在模拟过程中激活的干扰的完整配置,如下面的示例所示.
disturbances:
-
type: current
starting_time: 0
velocity: 1.2
horizontal_angle: 0
vertical_angle: 0
duration: 10
-
type: thruster_state
starting_time: 10
duration: 10
thruster_id: 2
is_on: 0
-
type: propeller_efficiency
starting_time: 20
duration: 10
thruster_id: 4
efficiency: 0.2
-
type: thrust_efficiency
starting_time: 30
duration: 10
thruster_id: 4
efficiency: 0.1
-
type: wrench
starting_time: 40
duration: 10
force:
- 1500
- 0
- -1500
torque:
- 1000
- 0
- 0
并将文件的路径传递到扰动管理器节点,如下面的示例所示:
<include file="$(find uuv_control_utils)/launch/start_disturbance_manager.launch">
<arg name="uuv_name" value="rexrov"/>
<arg name="use_file" value="true"/>
<arg name="disturbance_file" value="$(find uuv_tutorial_disturbances)/config/disturbances.yaml"/>
</include>
前面提到的功能,例如干扰持续时间,保持不变。运行以下示例以了解其工作原理:
roslaunch uuv_tutorial_disturbances tutorial_disturbance_manager.launch
八. 定制海底创造新世界
对于以下教程,所有文件也可以在 uuv_tutorial_seabed_world 包中找到。在模拟场景中,海底可能非常关键,例如,目标是使用无人水下航行器进行水深测绘,或者只是使场景看起来更真实。Gazebo已经有了从灰度图像生成高度图的功能。这是设置高度图的一种非常快速的方法,但是在尝试与它交互时,它的复杂性可能会使模拟运行较慢。
另一种选择是获取海底的现有点云,并将其转换为可以像任何其他模型一样导入Gazebo的网格。
1. 创建网格文件
测量数据可以是稀疏的,并且在生成网格之前需要删除异常值。下面的脚本是一个示例,说明如何将测量数据插值到网格中,然后将其转换为STL文件。对于本例,我们将使用 matplotlib 包中提供的测试曲面,但您应该用自己的点云数据替换它。您还需要 numpy、scipy和numpy-stl 包。
要安装必要的软件包,可以使用pip
sudo apt install python-pip
pip install numpy scipy matplotlib numpy-stl --user
要生成网格,请根据需要更改下面的代码
import numpy as np
from scipy.interpolate import griddata
import scipy.ndimage as ndimage
from scipy.ndimage import gaussian_filter
from scipy.misc import imsave
from matplotlib import cm
import matplotlib.pyplot as plt
from mpl_toolkits.mplot3d import Axes3D
from stl import mesh, Mode
import matplotlib.tri as mtri
from mpl_toolkits.mplot3d.axes3d import get_test_data
# Generating the surface
x, y, z = get_test_data(delta=0.1)
# Scale the surface for this example
z *= 0.05
# Remember that Gazebo uses ENU (east-north-up) convention, so underwater
# the Z coordinate will be negative
z -= 3
# Note: Gazebo will import your mesh in meters.
# Point clouds usually don't come in nice grids, so let's make it a (N, 3)
# matrix just to show how it can be done. If you have outliers or noise, you should
# treat those values now.
xyz = np.zeros(shape=(x.size, 3))
xyz[:, 0] = x.flatten()
xyz[:, 1] = y.flatten()
xyz[:, 2] = z.flatten()
# Generate a grid for the X and Y coordinates, change the number of points
# to your needs. Large grids can generate files that are too big for Gazebo, so
# be careful when choosing the resolution of your grid.
x_grid, y_grid = np.meshgrid(np.linspace(xyz[:, 0].min(), xyz[:, 0].max(), 300),
np.linspace(xyz[:, 1].min(), xyz[:, 1].max(), 200))
# Interpolate over the point cloud for our grid
z_grid = griddata(xyz[:, 0:2], xyz[:, 2], (x_grid, y_grid),
method='linear')
# Option to treat noise
#z_grid = gaussian_filter(z_grid, sigma=1)
# Show the resulting heightmap as an image
fig = plt.figure(figsize=(8, 6))
ax = fig.add_subplot(111)
plt.imshow(z_grid)
# Flatten our interpolated data for triangulation
output = np.zeros(shape=(x_grid.size, 3))
output[:, 0] = x_grid.flatten()
output[:, 1] = y_grid.flatten()
output[:, 2] = z_grid.flatten()
# Triangulation of the interpolated data
tri = mtri.Triangulation(output[:, 0], output[:, 1])
# Show the resulting surface
fig = plt.figure(figsize=(8, 6))
ax = fig.add_subplot(111, projection='3d')
ax.plot_trisurf(tri, output[:, 2], cmap=plt.cm.CMRmap, shade=True, linewidth=0.1)
ax.axis('equal')
# Create the mesh object
seabed_mesh = mesh.Mesh(np.zeros(tri.triangles.shape[0], dtype=mesh.Mesh.dtype))
# Set the vectors
for i, f in enumerate(tri.triangles):
for j in range(3):
seabed_mesh.vectors[i][j] = output[f[j]]
# Store the seabed as a STL file
seabed_mesh.save('seabed.stl')
plt.show()
在下面,您可以看到作为图像的结果高度图

以及用于创建海床的三角网格

现在已经创建了 sebed.stl 数据,也可以在此处 here 下载。您可以使用 MeshLab 或 Blender 打开它。在这里我们将使用搅拌机显示表面。如果需要,也可以使用Blender编辑网格。

即使表面已经准备好了,如果你把它导入原样的凉亭里,如果你用你的机器人撞到海床上,你可能就不会有接触力。解决这个问题的一种方法是使用STL导入工具在Blender中导入STL

上传曲面后,转到右面板的“修改器”部分,如下所示

并在“添加修改器”弹出菜单中选择“固化”选项。

输入曲面厚度的值,如下所示,然后单击“应用”按钮。

现在可以使用STL导出器工具再次导出曲面。现在,您需要创建一个SDF模型描述您的海底加载到Gazebo。
2. 创建Gazebo海底模型
为了能够在Gazebo中加载海底网格,您需要一个描述它的SDF模型。从文件夹结构开始,让我们为这个世界描述创建一个新的catkin包。下面的文件夹结构只是基于此包中使用的结构的建议。
cd ~/catkin_ws/src
catkin_create_pkg uuv_tutorial_seabed_world
cd uuv_tutorial_seabed_world
mkdir models worlds launch
mkdir -p models/tutorial_seabed/meshes
我们为海底模型创建文件。
cd ~/catkin_ws/src/uuv_tutorial_seabed_world/models/tutorial_seabed
touch model.config model.sdf
现在将 sebed.stl 文件复制到文件夹中
uuv_tutorial_seabed_world/models/tutorial_seabed/meshes.
对于Gazebo海底模型,您需要创建以下文件 uuv_tutorial_seabed_world/models/tutorial_seabed 文件夹. 下面使用的材料来自UUV模拟器的材料描述 materials description。可以将其替换为其他纹理。例如,可以将它们更改为Gazebo提供的默认材质 default materials provided by Gazebo。
- model.config
<?xml version="1.0"?>
<model>
<name>Tutorial - Seabed</name>
<version>1.0</version>
<sdf version="1.5">model.sdf</sdf>
<author>
<name>John Doe</name>
<email>john.doe@email.com</email>
</author>
<description>
A nice seabed.
</description>
</model>
- model.sdf
<?xml version="1.0" ?>
<sdf version="1.5">
<model name="seabed">
<static>true</static>
<link name="seabed_link">
<visual name="surface">
<cast_shadows>false</cast_shadows>
<pose>0 0 0 0 0 0</pose>
<geometry>
<box>
<size>60 60 .1</size>
</box>
</geometry>
<material>
<script>
<uri>file://Media/materials/scripts/water.material</uri>
<name>UUVSimulator/StaticWater</name>
</script>
</material>
</visual>
<visual name="seafloor">
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh><uri>model://tutorial_seabed/meshes/seabed.stl</uri><scale>1 1 1</scale></mesh>
</geometry>
<material>
<script>
<uri>file://Media/materials/scripts/sand.material</uri>
<name>UUVSimulator/SandAndStones</name>
</script>
</material>
</visual>
<collision name="seafloor">
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh><uri>model://tutorial_seabed/meshes/seabed.stl</uri><scale>1 1 1</scale></mesh>
</geometry>
</collision>
</link>
</model>
</sdf>
现在您可以配置您的catkin包,以便该模型可以作为模型在Gazebo中列出。为此,您必须配置 package.xml 和 CMakeLists.txt 文件,如下例所示。
- CMakeLists.txt
cmake_minimum_required(VERSION 2.8.3)
project(uuv_tutorial_seabed_world)
find_package(catkin REQUIRED)
catkin_package()
install(DIRECTORY launch worlds models
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
PATTERN "*~" EXCLUDE)
- package.xml
对于此文件,请确保具有以下行
<?xml version="1.0"?>
<package format="2">
<name>uuv_tutorial_seabed_world</name>
<version>0.6.11</version>
<description>A simple tutorial on how to create a new Gazebo model with a seabed and how to configure it as a simulation scenario</description>
<maintainer email="musa.marcusso@de.bosch.com">Musa Morena Marcusso Manhaes</maintainer>
<maintainer email="sebastian.scherer2@de.bosch.com">Sebastian Scherer</maintainer>
<maintainer email="luizricardo.douat@de.bosch.com">Luiz Ricardo Douat</maintainer>
<author email="musa.marcusso@de.bosch.com">Musa Morena Marcusso Manhaes</author>
<author email="sebastian.scherer2@de.bosch.com">Sebastian Scherer</author>
<author email="luizricardo.douat@de.bosch.com">Luiz Ricardo Douat</author>
<license>Apache-2.0</license>
<buildtool_depend>catkin</buildtool_depend>
<exec_depend>gazebo_ros</exec_depend>
<export>
<gazebo_ros gazebo_media_path="${prefix}"
gazebo_model_path="${prefix}/models"/>
</export>
</package>
现在您可以将工作区构建为
cd ~/catkin_ws
catkin_make
如果你使用的是 catkin_tools.
现在,如果你打开Gazebo使用
roslaunch gazebo_ros empty_world.launch
并删除“ground_plane”列表下的地平面模型,然后从“插入”选项卡的列表中选择“教程-海底模型”,您将能够看到以下屏幕

3. 创造一个新的露台世界
现在模型已经完成,您可以创建一个Gazebo世界,用 sebed 模型加载场景。创建一个新的世界文件,如下所示
roscd uuv_tutorial_seabed_world/worlds
touch example_underwater.world
一个启动文件来启动它:
roscd uuv_tutorial_seabed_world/launch
touch tutorial_seabed_world.launch
两个文件的内容如下所示:
- example_underwater.world
<?xml version="1.0" ?>
<sdf version="1.5">
<world name="example_underwater">
<physics name="default_physics" default="true" type="ode">
<max_step_size>0.002</max_step_size>
<real_time_factor>1</real_time_factor>
<real_time_update_rate>500</real_time_update_rate>
<ode>
<solver>
<type>quick</type>
<iters>50</iters>
<sor>0.5</sor>
</solver>
</ode>
</physics>
<scene>
<ambient>0.01 0.01 0.01 1.0</ambient>
<sky>
<clouds>
<speed>12</speed>
</clouds>
</sky>
<shadows>1</shadows>
</scene>
<!-- Global light source -->
<include>
<uri>model://sun</uri>
</include>
<include>
<uri>model://tutorial_seabed</uri>
<pose>0 0 0 0 0 0</pose>
</include>
<plugin name="underwater_current_plugin" filename="libuuv_underwater_current_ros_plugin.so">
<namespace>hydrodynamics</namespace>
<constant_current>
<topic>current_velocity</topic>
<velocity>
<mean>0</mean>
<min>0</min>
<max>5</max>
<mu>0.0</mu>
<noiseAmp>0.0</noiseAmp>
</velocity>
<horizontal_angle>
<mean>0</mean>
<min>-3.141592653589793238</min>
<max>3.141592653589793238</max>
<mu>0.0</mu>
<noiseAmp>0.0</noiseAmp>
</horizontal_angle>
<vertical_angle>
<mean>0</mean>
<min>-3.141592653589793238</min>
<max>3.141592653589793238</max>
<mu>0.0</mu>
<noiseAmp>0.0</noiseAmp>
</vertical_angle>
</constant_current>
</plugin>
<plugin name="sc_interface" filename="libuuv_sc_ros_interface_plugin.so"/>
</world>
</sdf>
- tutorial_seabed_world.launch
<launch>
<arg name="gui" default="true"/>
<arg name="paused" default="false"/>
<!-- We resume the logic in empty_world.launch, changing only the name of the world to be launched -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<!-- Edit the name of the world file (example_underwater.world) when using this template -->
<arg name="world_name" value="worlds/example_underwater.world"/>
<arg name="paused" value="$(arg paused)"/>
<arg name="use_sim_time" value="true"/>
<arg name="gui" value="$(arg gui)"/>
<arg name="headless" value="false"/>
<arg name="debug" value="false"/>
<arg name="verbose" value="true"/>
</include>
</launch>
现在,您可以使用您的世界使用:
roslaunch uuv_tutorial_seabed_world tutorial_seabed_world.launch
屏幕上的结果应该是

完成!现在可以使用自定义seabed进行模拟。
九. 总结
详细说明请上官网
程序中的各种 Packages 和 C++API 和 Python API 请到官网了解使用。