创建车辆接口#
如何实现车辆接口#
以下说明介绍如何创建车辆接口.
1. 为车辆接口创建目录#
建议在 <your-autoware-dir>/src/vehicle/external
cd <your-autoware-dir>/src/vehicle/external
2. 安装或实现您自己的车辆接口#
如果已经有一个完整的车辆接口包(如 pacmod_interface),您可以将其安装到您的环境中.
如果没有,您必须自己实现自己的车辆接口.让我们通过 ros2 pkg create 创建一个新包.以下示例将向您展示如何创建名为 my_vehicle_interface 的车辆接口包.
ros2 pkg create --build-type ament_cmake my_vehicle_interface
然后,你应该在 my_vehicle_interface/src 中编写你的车辆接口的实现.
同样,由于此实现非常特定于车辆的控制设备,因此详细描述如何实现车辆接口超出了本文档的范围.
以下是一些可能考虑的因素:
- Autoware 控制命令主题的一些必要主题订阅以控制您的车辆:
| Topic 名称 | Topic 类型 | 描述 |
|---|---|---|
| /control/command/control_cmd | autoware_auto_control_msgs/msg/AckermannControlCommand | 本主题包括控制我们车辆的主要主题,如转向轮胎角度、速度、加速度等. |
| /control/command/gear_cmd | autoware_auto_vehicle_msgs/msg/GearCommand | 本主题包括自动驾驶的 gear 命令,请检查 message values 以理解 gears 值.请检查此类型的 消息定义. |
| /control/current_gate_mode | tier4_control_msgs/msg/GateMode | 本主题介绍是否控制 autoware.请查看 GateMode 消息类型了解详细信息. |
| /control/command/emergency_cmd | tier4_vehicle_msgs/msg/VehicleEmergencyStamped | 当 autoware 处于紧急状态时,本主题发送紧急.请查看 VehicleEmergencyStamped 消息类型了解详细信息. |
| /control/command/turn_indicators_cmd | autoware_auto_vehicle_msgs/msg/TurnIndicatorsCommand | 本主题表示您自己车辆的转向信号灯.请查看 TurnIndicatorsCommand 消息类型以获取详细信息. |
| /control/command/hazard_lights_cmd | autoware_auto_vehicle_msgs/msg/HazardLightsCommand | 本主题发送危险信号灯的命令.请检查 HazardLightsCommand |
| /control/command/actuation_cmd | tier4_vehicle_msgs/msg/ActuationCommandStamped | 当您使用 raw_vehicle_command_converter 控制具有 B 型的车辆时,将启用此主题,我们在 车辆接口 部分中提到过.总之,如果您在车辆上使用 B 型,则会出现此主题,并包含在油门、制动、方向盘驱动命令中.请查看 ActuationCommandStamped 消息类型以获取详细信息. |
| etc. | etc. | etc. |
- 从车辆接口到 Autoware 的车辆状态主题的一些必要主题发布:
| Topic Name | Topic Type | Description |
|---|---|---|
| /vehicle/status/battery_charge | tier4_vehicle_msgs/msg/BatteryStatus | 本主题包括电池信息.请查看 BatteryStatus 信息类型了解详细信息.您可以使用此值来描述燃油油位等. |
| /vehicle/status/control_mode | autoware_auto_vehicle_msgs/msg/ControlModeReport | 本文介绍当前车辆的控制模式.请查看 ControlModeReport 消息类型了解详细信息. |
| /vehicle/status/gear_status | autoware_auto_vehicle_msgs/msg/GearReport | 本主题包括车辆的当前档位状态.请查看 GearReport 消息类型以获取详细信息. |
| /vehicle/status/hazard_lights_status | autoware_auto_vehicle_msgs/msg/HazardLightsReport | 本主题介绍车辆的危险信号灯状态.请查看 HazardLightsReport 消息类型以获取详细信息. |
| /vehicle/status/turn_indicators_status | autoware_auto_vehicle_msgs/msg/TurnIndicatorsReport | 本主题报告车辆的转向指示灯状态.请查看 TurnIndicatorsReport 消息类型了解详细信息. |
| /vehicle/status/steering_status | autoware_auto_vehicle_msgs/msg/SteeringReport | 本文介绍车辆的转向状态.请查看 SteeringReport 消息类型了解详细信息. |
| /vehicle/status/velocity_status | autoware_auto_vehicle_msgs/msg/VelocityReport | 本主题为我们提供了无人机的速度状态.请查看 VelocityReport 消息类型了解详细信息. |
| etc. | etc. | etc. |
此图作为车辆接口和汽车软件通信的示例,描述示例主题和消息类型.
您必须在 Vehicle Interface 上创建具有这些主题的订阅者和发布者.
让我们通过订阅 /control/command/control_cmd 和发布 /vehicle/status/gear_status 主题的简单演示进行解释.
因此,您的 YOUR-OWN-VEHICLE-INTERFACE.hpp 头文件应如下所示:
...
#include <autoware_auto_control_msgs/msg/ackermann_control_command.hpp>
#include <autoware_auto_vehicle_msgs/msg/gear_report.hpp>
...
class <YOUR-OWN-INTERFACE> : public rclcpp::Node
{
public:
...
private:
...
// 来自autoware
rclcpp::Subscription<autoware_auto_control_msgs::msg::AckermannControlCommand>::SharedPtr
control_cmd_sub_;
...
// 来自车辆
rclcpp::Publisher<autoware_auto_vehicle_msgs::msg::GearReport>::SharedPtr gear_status_pub_;
...
// Autoware 命令消息
...
autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr control_cmd_ptr_;
...
// 回调
...
void callback_control_cmd(
const autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr msg);
...
void to_vehicle();
void from_vehicle();
}
你的 YOUR-OWN-VEHICLE-INTERFACE.cpp .cpp 文件应该是这样的:
#include <YOUR-OWN-VEHICLE-INTERFACE>/<YOUR-OWN-VEHICLE-INTERFACE>.hpp>
...
<YOUR-OWN-VEHICLE-INTERFACE>::<YOUR-OWN-VEHICLE-INTERFACE>()
: Node("<YOUR-OWN-VEHICLE-INTERFACE>")
{
...
/* 用户 */
using std::placeholders::_1;
// 来自 autoware
control_cmd_sub_ = create_subscription<autoware_auto_control_msgs::msg::AckermannControlCommand>(
"/control/command/control_cmd", 1, std::bind(&<YOUR-OWN-VEHICLE-INTERFACE>::callback_control_cmd, this, _1));
...
// 发往 autoware
gear_status_pub_ = create_publisher<autoware_auto_vehicle_msgs::msg::GearReport>(
"/vehicle/status/gear_status", rclcpp::QoS{1});
...
}
void <YOUR-OWN-VEHICLE-INTERFACE>::callback_control_cmd(
const autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr msg)
{
control_cmd_ptr_ = msg;
}
void <YOUR-OWN-VEHICLE-INTERFACE>::to_vehicle()
{
...
// 您应该根据自己的车辆设计实现此结构
control_command_to_vehicle(control_cmd_ptr_);
...
}
void <YOUR-OWN-VEHICLE-INTERFACE>::to_autoware()
{
...
// 您应该根据自己的车辆设计实现此结构
autoware_auto_vehicle_msgs::msg::GearReport gear_report_msg;
convert_gear_status_to_autoware_msg(gear_report_msg);
gear_status_pub_->publish(gear_report_msg);
...
}
- 根据需要修改控制值
- 在某些情况下,您可能需要修改控制命令.例如,Autoware 需要以 米/秒 为单位的车辆速度信息,但如果您的车辆以其他格式(即 公里/小时)发布该信息,则必须先将其转换为该信息,然后再将其发送到 Autoware.
3. 准备启动文件#
在实现车辆接口后,或者您希望通过启动它来调试它,
创建车辆接口的启动文件,并将其包含在 <VEHICLE_ID>_vehicle_launch 包中的 vehicle_interface.launch.xml
我们分叉并创建了,在 [创建车辆和传感器模型页面](../creating-vehicle-and-sensor-model/index.md
不要混淆.首先,您需要为自己的车辆接口模块(如 my_vehicle_interface.launch.xml )创建一个启动文件,然后将其包含在另一个目录中的 vehicle_interface.launch.xml 中.
-
在 my_vehicle_interface 目录下添加一个 launch 目录,并在其中创建您自己的车辆接口的 launch 文件.请查看 ROS 2 文档中的 创建启动文件.
-
打开启动文件,将其车辆接口
_launch/ _launch/launch/vehicle_interface.launch.xml 中包含,并添加如下所示的包含的配置.
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<arg name="vehicle_id" default="$(env VEHICLE_ID default)"/>
<!-- 请添加您创建的 Vehicle Interface 启动文件 -->
<include file="$(find-pkg-share my_vehicle_interface)/launch/my_vehicle_interface.launch.xml">
</include>
</launch>
最后,您的目录结构可能如下所示.为清楚起见,省略了大多数文件,但此处显示的文件需要修改,如上一个和当前过程中所述.
<your-autoware-dir>/
└─ src/
└─ vehicle/
├─ external/
+ │ └─ <YOUR-VEHICLE-NAME>_interface/
+ │ ├─ src/
+ │ └─ launch/
+ │ └─ my_vehicle_interface.launch.xml
+ └─ <YOUR-VEHICLE-NAME>_launch/ (COPIED FROM sample_vehicle_launch)
+ ├─ <YOUR-VEHICLE-NAME>_launch/
+ │ ├─ launch/
+ │ │ └─ vehicle_interface.launch.xml
+ │ ├─ CMakeLists.txt
+ │ └─ package.xml
+ ├─ <YOUR-VEHICLE-NAME>_description/
+ │ ├─ config/
+ │ ├─ mesh/
+ │ ├─ urdf/
+ │ │ └─ vehicle.xacro
+ │ ├─ CMakeLists.txt
+ │ └─ package.xml
+ └─ README.md
4. 构建车辆接口包和启动包#
构建三个软件包 my_vehicle_interface, <YOUR-VEHICLE-NAME>_launch
以及 colcon build 的 _description ,
或者如果你做了其他事情,你可以只构建整个 Autoware.
colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release --packages-select my_vehicle_interface <YOUR-VEHICLE-NAME>_launch <YOUR-VEHICLE-NAME>_description
5. 启动Autoware#
最后,您已完成车辆接口模块的实现!请注意,您需要使用适当的 vehicle_model 选项启动 Autoware,如下例所示.此示例是启动规划模拟器.
ros2 launch autoware_launch planning.launch.xml map_path:=$HOME/autoware_map/sample-map-planning vehicle_model:=<YOUR-VEHICLE-NAME> sensor_model:=<YOUR-VEHICLE-NAME>_sensor_kit
技巧#
有一些提示可能会对您有所帮助.
-
如果需要,您可以将车辆接口细分为更小的包.然后你的目录结构可能如下所示(虽然不是唯一的方法).不要忘记在
my_vehicle_interface.launch.xml中启动所有软件包.<your-autoware-dir>/ └─ src/ └─ vehicle/ ├─ external/ │ └─ my_vehicle_interface/ │ ├─ src/ │ │ ├─ package1/ │ │ ├─ package2/ │ │ └─ package3/ │ └─ launch/ │ └─ my_vehicle_interface.launch.xml ├─ sample_vehicle_launch/ └─ my_vehicle_name_launch/
-
如果您使用的是车辆接口并从打开的 git 存储库启动包,或者创建自己的 git 存储库,强烈建议将这些存储库添加到位于 autoware 文件夹正下方的
autoware.repos文件中,如下例所示.您可以通过 version 标签指定分支或提交哈希.autoware.repos# 车辆(此部分应位于 autoware.repos 中的某个位置,并添加以下内容) vehicle/external/my_vehicle_interface: type: git url: https://github.com/<repository-name-B>/my_vehicle_interface.git version: main
然后,您可以使用 vcs import 命令轻松地将整个环境导入到另一个本地设备.(参见 源代码安装指南)