继续将ROS2功能包和webots仿真利器深度融合,如何做呢?导航走一个?_?
稳不稳?六不六?
在最初以epuck为例,介绍了一些基本知识点,本节将以turtlebot3为主!
- 从epuck到turtlebot3!
turtlebot系列是ROS最强的教学机器人。
那熟悉的感觉又回来啦!!!
注意事项,环境一定要正确配置,官网介绍非常详细,linux和windows通用,这里以windows演示为主。
如果配置不正确会出现如下报错!
第一种功能包不全!
请补齐确少功能包再次编译!
参考如下:
第二种节点不正常工作!
一定不能有ERROR!!!WARNING不用担心,但也要知道原因!
如果出错,topic不全,无法后续仿真!
如果,正确配置,一切正常启动如下:
这时候topic列表如下:
可以发现有/scan,/odom,/cmd_vel等SLAM和导航必备的主题哦!
两步:
ros2 launch webots_ros2_turtlebot robot_launch.py
set TURTLEBOT3_MODEL='burger'
ros2 launch turtlebot3_navigation2 navigation2.launch.py use_sim_time:=true map:=C:\ros_ws\webots2\src\webots_ros2\webots_ros2_turtlebot\resource\turtlebot3_burger_example_map.yaml 或者 ros2 launch turtlebot3_navigation2 navigation2.launch.py use_sim_time:=true map:=C:\ros_ws\webots2\install\webots_ros2_turtlebot\share\webots_ros2_turtlebot\resource\turtlebot3_burger_example_map.yaml
开启导航前,请先定位机器人,一起正常如下:
这时候在仿真环境中的机器人如下:
来尝试一下导航吧???
如果ok?
细节后续讲解。
终端一:
终端二:
终端三:
这里比较重要的是launch和driver:
启动:
"""Launch Webots TurtleBot3 Burger driver."""
import os
from launch.substitutions import LaunchConfiguration
from launch.actions import DeclareLaunchArgument
from launch.substitutions.path_join_substitution import PathJoinSubstitution
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch import LaunchDescription
from ament_index_python.packages import get_package_share_directory
def generate_launch_description():
package_dir = get_package_share_directory('webots_ros2_turtlebot')
world = LaunchConfiguration('world')
webots = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
os.path.join(get_package_share_directory('webots_ros2_core'), 'launch', 'robot_launch.py')
),
launch_arguments=[
('package', 'webots_ros2_turtlebot'),
('executable', 'turtlebot_driver'),
('world', PathJoinSubstitution([package_dir, 'worlds', world])),
]
)
return LaunchDescription([
DeclareLaunchArgument(
'world',
default_value='turtlebot3_burger_example.wbt',
description='Choose one of the world files from `/webots_ros2_turtlebot/world` directory'
),
webots
])
驱动:
"""ROS2 TurtleBot3 Burger driver."""
import rclpy
from webots_ros2_core.webots_differential_drive_node import WebotsDifferentialDriveNode
class TurtlebotDriver(WebotsDifferentialDriveNode):
def __init__(self, args):
super().__init__(
'turtlebot_driver',
args,
left_encoder='left wheel sensor',
left_joint='left wheel motor',
right_encoder='right wheel sensor',
right_joint='right wheel motor',
robot_base_frame='base_link',
wheel_distance=0.160,
wheel_radius=0.033
)
self.start_device_manager({
'robot': {'publish_base_footprint': True},
'LDS-01': {'topic_name': '/scan'},
'accelerometer+gyro': {'frame_id': 'imu_link', 'topic_name': '/imu'}
})
def main(args=None):
rclpy.init(args=args)
driver = TurtlebotDriver(args=args)
rclpy.spin(driver)
rclpy.shutdown()
if __name__ == '__main__':
main()
比epuck-webotsros2驱动简洁一些。