Version:

ROS 2 概念和结构

本文介绍了 Open 3D Engine (O3DE) 中 ROS 2 Gem 的底层概念和结构。 您将了解 ROS 2 和 O3DE 如何通信,以及 ROS 2 组件如何相互连接以在机器人模拟中执行各种功能。

ROS 2 概念

有关 ROS 2 概念的快速介绍,请参阅 ROS 2 概念文档 .

结构和通信

ROS2 Gem 创建了一个 ROS 2 节点 ,它直接成为 ROS 2 生态系统的一部分。因此,您的模拟不会使用任何桥接进行通信,并且会通过 Environment Variables(环境变量)等设置进行配置。它确实是生态系统的一部分。

请注意,模拟节点是通过ROS2SystemComponent - 一个单例来处理的。但是,如果您需要多个节点,则可以自由创建和使用自己的节点。

通常,您将创建发布者和订阅,以便使用常见主题与 ROS 2 生态系统进行通信。 这是通过 rclcpp API 完成的。例:

auto ros2Node = ROS2Interface::Get()->GetNode();
AZStd::string fullTopic = ROS2Names::GetNamespacedName(GetNamespace(), m_MyTopic);
m_myPublisher = ros2Node->create_publisher<sensor_msgs::msg::PointCloud2>(fullTopic.data(), QoS());

请注意,QoS 类是一个简单的包装器 rclcpp::QoS .

ROS 2 相关 Gems

提供了四个与ROS 2相关的Gems,每个都有特定用途:

Gem 名称说明
ROS2Base Gem for any ROS 2 based Gem/project, including:
  • ROS 2 Node (singleton) allowing the communication with the ROS 2 ecosystem
  • automated handling of simulation time
  • handling of transformation frames
  • handling ROS 2 namespaces and ROS 2 topics
  • dynamic objects spawning via ROS 2 services
  • base components (e.g. for sensors that can be implemented in any Gem)
ROS2SensorsGem interfacing with ROS 2 ecosystem implementing the following simulation sensors: camera, contact, GNSS, imu, lidar, odometry
ROS2ControllersGem interfacing with ROS 2 ecosystem implementing robot control, manipulation, grippers, and vehicle dynamics; it will also include sensors related to controllers (e.g. wheel odometry)
ROS2RobotImporterGem implementing robot importer tool using ROS 2 components

组件概述

  • Central Singleton
    • ROS2SystemComponent
  • Core abstractions
    • ROS2FrameComponent
    • ROS2SensorComponent
  • Sensors
    • ROS2CameraSensorComponent (available in ROS2Sensors Gem)
    • ROS2GNSSSensorComponent (available in ROS2Sensors Gem)
    • ROS2IMUSensorComponent (available in ROS2Sensors Gem)
    • ROS2LidarSensorComponent (available in ROS2Sensors Gem)
    • ROS2Lidar2DSensorComponent (available in ROS2Sensors Gem)
    • ROS2OdometrySensorComponent (available in ROS2Sensors Gem)
    • ROS2ContactSensorComponent (available in ROS2Sensors Gem)
  • Robot control
    • AckermannControlComponent (available in ROS2Controllers Gem)
    • RigidBodyTwistControlComponent (available in ROS2Controllers Gem)
    • SkidSteeringControlComponent (available in ROS2Controllers Gem)
  • Spawner
    • ROS2SpawnerComponent
    • ROS2SpawnPointComponent
  • Vehicle dynamics
    • AckermannVehicleModelComponent (available in ROS2Controllers Gem)
    • SkidSteeringModelComponent (available in ROS2Controllers Gem)
    • WheelControllerComponent (available in ROS2Controllers Gem)
  • Robot Import (URDF) system component
    • ROS2RobotImporterSystemComponent (available in ROS2RobotImporter Gem)
  • Joints and Manipulation
    • JointsManipulationComponent (available in ROS2Controllers Gem)
    • JointsTrajectoryComponent (available in ROS2Controllers Gem)
    • JointsArticulationControllerComponent (available in ROS2Controllers Gem)
    • JointsPIDControllerComponent (available in ROS2Controllers Gem)

Frames

ROS2FrameComponent 表示机器人的一个有趣的物理部分。它处理此部分与其他参考系之间的时空关系。它还封装了命名空间,这有助于区分不同的机器人和机器人的不同部分,例如在一个机器人上有多个相同的传感器的情况下。

所有传感器和机器人控制组件都需要ROS2FrameComponent.

传感器

传感器从模拟环境中采集数据,并将其发布到ROS 2域中。传感器组件继承自ROS2SensorComponentBase,该基类为所有传感器提供了通用接口。

  • 每个传感器都有一个配置,包括一个或多个发布者。
  • 传感器使用以下两个事件源之一以给定的速率(频率)发布:帧更新或物理场景模拟事件。
  • 一些传感器可以可视化。

如果提供的传感器组件不支持您的传感器,您很可能需要创建一个派生自ROS2SensorComponentBase. 在开发新传感器时,查看 ROS2 Gem 中已经提供的传感器是如何实现的非常有用的。 考虑将新传感器添加为单独的 Gem。这种传感器 Gem 的一个很好的例子是 RGL Gem .

最常用的传感器已实现于ROS2Sensors Gem中。

机器人控制

该 Gem 带有 ROS2RobotControlComponent,您可以使用它来移动您的机器人:

组件在配置的主题上订阅这些命令消息。默认情况下,该主题是 cmd_vel 的,位于 ROS2Frame 指定的命名空间中。

要使用收到的命令消息,请使用AckermannControlComponent, RigidBodyTwistControlComponent, 或 SkidSteeringControlComponent,具体取决于转向类型。 您还可以实现自己的控制组件或使用 Lua 脚本来处理这些命令。 除非使用脚本,否则控制组件应将 ROS 2 命令转换为 VehicleInputControlBus. 如果存在 VehicleModelComponent,则这些事件将由 VehicleModelComponent处理。 您可以使用 rqt_robot_steering 等工具通过 Twist 消息移动您的机器人。 RobotControl 适合与 ROS 2 导航堆栈 . 可以使用此组件实现自己的控制机制。

该实现可在 ROS2Controllers Gem 中获取。

关节和操纵器

为了控制机械臂等机器人关节系统,与 MoveIt2 进行了一些集成。 支持两种模拟关节系统:

  • 接合链接,受益于物理引擎中简化的坐标接合的稳定性。
  • 铰链和棱柱关节组件。 当 导入机器人 带有关节时,您可以决定使用哪些系统。

有三个接口可用于控制关节系统: JointsPositionControllerRequests, JointsManipulationRequests and JointsTrajectoryRequest. 这些接口中的每一个在 ROS 2 Gem 中都有一个或多个实现,并且可以使用这些接口以模块化方式开发自定义行为。

JointManipulationComponent 允许您为所有关节设置目标位置。如果您希望使用 trajectory through 控制移动 FollowJointTrajectory 操作 , 使用 JointsTrajectoryComponent.

该实现可在 ROS2Controllers Gem 中获取。

Joint States

JointsManipulationComponent 默认也发布 关节状态

该实现可在 ROS2Controllers Gem 中获取。

Vehicle Model

VehicleModelComponent用于将目标速度、转向或加速度等输入转换为车辆部件(机器人)上的物理力。 VehicleModel 有一个 VehicleConfiguration,用于定义车轴、参数化和分配车轮。 该模型需要每个轮子实体中都存在一个 WheelControllerComponent 。它还使用了 DriveModel 的实现,将车辆输入转换为作用在转向元件和车轮上的力。

该实现可在 ROS2Controllers Gem 中获取。

Vehicle Dynamics

Vehicle Dynamics 章节。

Spawner

ROS2SpawnerComponent 处理在模拟期间生成实体。 在模拟之前,您必须设置为组件的可用可生成项,并通过 O3DE 编辑器 在组件的属性中定义命名的生成点。 这可以通过将 ROS2SpawnPointComponent 添加到具有 ROS2SpawnerComponent 的实体的子实体来完成。 在模拟期间,您可以使用 ROS 2 服务访问可用可生成对象的名称并请求生成。 服务的名称分布包括/get_available_spawnable_names/spawn_entityGetWorldProperties.srvSpawnEntity.srv 类型用于处理这些功能。 为了请求定义的生成点名称,您可以使用带有GetWorldProperties.srv 类型的/get_spawn_points_names服务。 有关特定生成点的详细信息,例如姿势,可以使用具有GetModelState.srv类型的/get_spawn_point_info服务进行访问。 所有使用的服务类型都在 gazebo_msgs 包中定义。

  • Spawning: 要生成,您必须将可生成名称传入request.name 中,将实体的位置传入 request.initial_pose 中。
    • 示例调用:
    ros2 service call /spawn_entity gazebo_msgs/srv/SpawnEntity "{name: 'robot', initial_pose: {position:{ x: 4.0, y: 4.0, z: 0.2 }, orientation: { x: 0.0, y: 0.0, z: 0.0, w: 0.0 } } }"
    
  • Spawning in defined spawn point: 将可生成对象传入 request.name 中,将生成点的名称传入 request.xml 中。
    • 示例调用:
      ros2 service call /spawn_entity gazebo_msgs/srv/SpawnEntity "{name: 'robot', xml: 'spawn_spot'}"
      
  • Spawning using WGS84 coordinates: 启用 Georeference 组件 时,您还可以使用地理位置生成对象。将 reference_frame 设置为 wgs84 并提供坐标。
    • 示例调用 生成在 52°14′22″N, 21°02′44″E:
      ros2 service call /spawn_entity gazebo_msgs/srv/SpawnEntity "{name: 'robot', initial_pose: { position: { x: 52.2406855386909, y: 21.04264386637526, z: 0.0 }, orientation: {  x: 0.0, y: 0.0, z: 0.0, w: 0.0 } }, reference_frame: 'wgs84'}"
      
  • Available spawnable names access: 将可用可生成对象的名称发送到 response.model_names 中。
    • 示例调用:
      ros2 service call /get_available_spawnable_names gazebo_msgs/srv/GetWorldProperties
      
  • Defined spawn points’ names access: 将已定义点的名称发送到 response.model_names
    • 示例调用:
      ros2 service call /get_spawn_points_names gazebo_msgs/srv/GetWorldProperties
      
  • Detailed spawn point info access: 将生成点名称传入 request.model_name 中,将定义的姿势传入 response.pose 中。
    • 示例调用:
      ros2 service call /get_spawn_point_info gazebo_msgs/srv/GetModelState "{model_name: 'spawn_spot'}"