前言
这一篇文章主要是和大家分享一下关于ROS2 高级组件中的webots,会介绍关于webots的知识点,以及如何安装和测试环节,最后就是利用 webots 实现一个差速轮式机器人的运动仿真。
正文内容
webots 引入和学习资料
webots 是来自瑞士的 Cyberbotics 公司(Cyberbotics 官网)推出的机器人仿真软件,旨在降低机器人技术开发的门槛,并加速从理论到实践的转化过程。该平台用户群体非常广泛,涵盖了教育、科研和工业界。2018年以前,webots 是一款商业软件,2018年12月以后,Webots作为开放源码软件在Apache 2.0许可下发布(webots github)。
webots 和 ros:webots 本身是一款独立的仿真软件,跟 ros 没有关系。后来,ros1 有了 webots_ros 软件包,ros2 有了 webots_ros2 软件包,从而打通了 ros 与 webots 之间的接口,使得两者之间可以顺利通信。
webots 安装以及样例测试
(1)webots 安装:由于 webots 是从商业转向的开源,因此安装非常简单,如下。本系列 ros2 文章的基础环境是 Ubuntu22.04 + ros2 humble,安装的 webots 版本是 webotsR2023b。
cd ~
# webots_ros2
sudo apt-get install ros-humble-webots-ros2
# ~/.ros/webotsR2023b/webots
ros2 launch webots_ros2_universal_robot multirobot_launch.py
# WEBOTS_HOME
export WEBOTS_HOME=/home/ycao/.ros/webotsR2023b/webots

(2)在 webots_ros2 中,利用 webots 实现了多种机器人仿真,包括 TurtleBot3 ,Tesla Model3,测试 TurtleBot3 :
# TurtleBot3
ros2 launch webots_ros2_turtlebot robot_launch.py
ros2 run teleop_twist_keyboard teleop_twist_keyboard

测试 Tesla Model3
ros2 launch webots_ros2_tesla robot_launch.py
自编写 webots_demo
(1)创建 webots_demo 软件包以及相关文件
cd ~/colcon_ws/src
ros2 pkg create --build-type ament_python --license Apache-2.0 webots_demo --dependencies rclpy geometry_msgs webots_ros2_driver
cd webots_demo
mkdir launch worlds
touch launch/mbot_launch.py
touch resource/mbot.urdf
touch webots_demo/mbot_driver.py webots_demo/obstacle_avoider.py
(2)在 worlds 目录中添加 my_world.wbt,这个文件是 webots 的建模文件,里面包含虚拟仿真环境和一个差速轮式机器人。
(3)编写 mbot_driver.py:这是差速轮式机器人车轮电机控制程序
import rclpy
from geometry_msgs.msg import Twist
HALF_DISTANCE_BETWEEN_WHEELS = 0.045
WHEEL_RADIUS = 0.025
class MbotDriver:
def init(self, webots_node, properties):
self._robot = webots_node.robot
self._left_motor = self._robot.getDevice('left wheel motor')
self._right_motor = self._robot.getDevice('right wheel motor')
self._left_motor.setPosition(float('inf'))
self._left_motor.setVelocity(0)
self._right_motor.setPosition(float('inf'))
self._right_motor.setVelocity(0)
self._target_twist = Twist()
rclpy.init(args=None)
self._node = rclpy.create_node('mbot_driver')
self._node.create_subscription(Twist, 'cmd_vel', self._cmd_vel_callback, 1)
def _cmd_vel_callback(self, twist):
self._target_twist = twist
def step(self):
rclpy.spin_once(self._node, timeout_sec=0)
forward_speed = self._target_twist.linear.x
angular_speed = self._target_twist.angular.z
command_motor_left = (forward_speed - angular_speed * HALF_DISTANCE_BETWEEN_WHEELS) / WHEEL_RADIUS
command_motor_right = (forward_speed + angular_speed * HALF_DISTANCE_BETWEEN_WHEELS) / WHEEL_RADIUS
self._left_motor.setVelocity(command_motor_left)
self._right_motor.setVelocity(command_motor_right)
(4)编写 mbot.urdf:这是差速轮式机器人的 URDF 描述文件(Unified Robot Description Format,统一的机器人描述文件格式,使用 xml 格式),为机器人添加了左右距离传感器,并指定了车轮电机控制器。
<?xml version="1.0" ?>
<robot name="My robot">
<webots>
<device reference="ds0" type="DistanceSensor">
<ros>
<topicName>/left_sensor</topicName>
<alwaysOn>true</alwaysOn>
</ros>
</device>
<device reference="ds1" type="DistanceSensor">
<ros>
<topicName>/right_sensor</topicName>
<alwaysOn>true</alwaysOn>
</ros>
</device>
<plugin type="webots_demo.mbot_driver.MbotDriver" />
</webots>
</robot>
(5)编写 obstacle_avoider.py:这个程序基于左右距离传感器的数据,通过 cmd_vel topic 控制机器人避障。
import rclpy
from rclpy.node import Node
from sensor_msgs.msg import Range
from geometry_msgs.msg import Twist
MAX_RANGE = 0.15
class ObstacleAvoider(Node):
def __init__(self):
super().__init__('obstacle_avoider')
self._publisher = self.create_publisher(Twist, 'cmd_vel', 1)
self.create_subscription(Range, 'left_sensor', self._left_sensor_callback, 1)
self.create_subscription(Range, 'right_sensor', self._right_sensor_callback, 1)
def _left_sensor_callback(self, message):
self._left_sensor_value = message.range
def _right_sensor_callback(self, message):
self._right_sensor_value = message.range
command_message = Twist()
command_message.linear.x = 0.1
if self._left_sensor_value < 0.9 * MAX_RANGE or self._right_sensor_value < 0.9 * MAX_RANGE:
command_message.angular.z = -2.0
self._publisher.publish(command_message)
def main(args=None):
rclpy.init(args=args)
avoider = ObstacleAvoider()
rclpy.spin(avoider)
avoider.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
(6)编写 mbot_launch.py :
import os
import launch
from launch_ros.actions import Node
from launch import LaunchDescription
from ament_index_python.packages import get_package_share_directory
from webots_ros2_driver.webots_launcher import WebotsLauncher
from webots_ros2_driver.webots_controller import WebotsController
def generate_launch_description():
package_dir = get_package_share_directory('webots_demo')
mbot_description_path = os.path.join(package_dir, 'resource', 'mbot.urdf')
# https://cyberbotics.com/doc/guide/tutorials
webots_world = WebotsLauncher(
world=os.path.join(package_dir, 'worlds', 'my_world.wbt')
)
mbot_controller = WebotsController(
robot_name='mbot_car',
parameters=[
{'robot_description': mbot_description_path},
],
)
obstacle_avoider = Node(
package='webots_demo',
executable='obstacle_avoider',
)
return LaunchDescription([
webots_world,
mbot_controller,
obstacle_avoider,
launch.actions.RegisterEventHandler(
event_handler=launch.event_handlers.OnProcessExit(
target_action=webots_world,
on_exit=[launch.actions.EmitEvent(event=launch.events.Shutdown())],
)
)
])
(7)修改 setup.py
import os
from glob import glob
from setuptools import find_packages, setup
package_name = 'webots_demo'
setup(
name=package_name,
version='0.0.0',
packages=find_packages(exclude=['test']),
data_files=[
('share/ament_index/resource_index/packages',
['resource/' + package_name]),
('share/' + package_name, ['package.xml']),
(os.path.join('share', package_name, 'launch'), glob(os.path.join('launch', '*_launch.py'))),
(os.path.join('share', package_name, 'worlds'), glob(os.path.join('worlds', '*.wbt'))),
(os.path.join('share', package_name, 'resource'), glob(os.path.join('resource', '*.urdf')))
],
install_requires=['setuptools'],
zip_safe=True,
maintainer='ycao',
maintainer_email='[email protected]',
description='TODO: Package description',
license='Apache-2.0',
tests_require=['pytest'],
entry_points={
'console_scripts': [
'mbot_driver = webots_demo.mbot_driver:main',
'obstacle_avoider = webots_demo.obstacle_avoider:main'
],
},
)
(8)编译并运行
cd ~/colcon_ws/src
colcon build --packages-select webots_demo
source install/local_setup.bash
ros2 launch webots_demo mbot_launch.py

总结
本文主要通过一个差速轮式机器人仿真样例,为大家引入 webots ,但没有深入探究 webots 的建模细节。 有兴趣的朋友可以自己深入研究一下内容哟。