はじめに
この記事では、公式から設定ファイルを提供されていないゲームコントローラーを使用して、Autowareの車両を手動運転する方法について解説します。
Autowareでは、以下の4種類のコントローラーに対して設定ファイルが提供されています。
- PlayStation 4 コントローラー
- Logitech G29 ハンドルコントローラ
- P65 ジョイスティック
- Xbox コントローラー
参考: Autoware Universe Documentation: autoware_joy_controller
しかし、独自のコントローラーを使用する方法については詳細な手順が記載されていなかったため、今回記事としてまとめました。
今回の環境
項目 | コマンド | 内容 |
---|---|---|
OS | lsb_release -a |
Ubuntu 22.04.5 LTS |
ROSのバージョン | echo $ROS_DISTRO |
ROS 2 Humble |
Autoware | Source installationでインストール | autowarefoundation/autowareリポジトリ |
ゲームコントローラー | - |
ロジクール USBランブルパッド2[G-UF13] (公式の画像が見つかりませんでした🙇♀️) |
構成
本記事では、以下の流れで説明します。
- ゲームコントローラーの接続と設定
-
/joy
トピックでキーマップを確認 - 独自コントローラー用のKey Mapを作成
- Autoware で手動運転を行うためのノード設定
- ビルド & 起動による動作確認
1. ゲームコントローラーの接続と設定
まず、ゲームコントローラーを PC に USB 接続し、正しく認識されているか確認します。
ls /dev/input/
上記コマンドを実行し、js0
などのデバイスが表示されていれば、認識されています。
2. /joy
トピックでキーマップを確認
USB 接続したコントローラーの入力内容は/joy
トピックに publish されます。これを確認するために、joy
パッケージを使用します。
ROSのディストリビューションに応じて、joy
パッケージをインストールします。
sudo apt update
sudo apt install ros-humble-joy
続いてjoy_node
を起動して、ゲームパッドの入力をROS 2トピック/joy
として publish します。
ros2 run joy joy_node
以下のような出力が得られれば、正常に認識されています。
[INFO 1738507095.763071507] [joy_node]: Opened joystick: Logitech RumblePad 2 USB. deadzone: 0.050000 (handleJoyDeviceAdded() at ./src/joy.cpp:400)
そして、/joy
トピックにPublishされているデータを確認します。CLIとGUIのどちらでも確認できますが、GUIの方が見やすいのでオススメです。
ros2 topic echo /joy # CLIで確認
rqt # GUIで確認
CLIでの結果例
header:
stamp:
sec: 1742366616
nanosec: 407861589
frame_id: joy
axes:
- -0.0
- -0.0010167482541874051
- -0.0
- -0.0
- 0.0
- 0.0
buttons:
- 0
- 0
- 0
- 0
- 0
- 0
- 0
- 0
- 0
- 0
- 0
- 0
コントローラーをカチャカチャ動かして、ボタンやスティックの入力に応じて値が変化することを確認してください。その後、以下のように各スティック・ボタンが配列の何番目の値に対応しているかメモしておきます。
3. 独自コントローラー用のKey Mapを作成
先ほど確認したキーマップをもとに、公式で用意されているコントローラーと同じように車両の操作に必要なスティック・ボタンを割り当てた Key Map を作成します。
(参考)既存のDS4コントローラー用のパラメータファイル
DS4 Joystick Key Map
Action | Button |
---|---|
Acceleration | R2, ×, or Right Stick Up |
Brake | L2, □, or Right Stick Down |
Steering | Left Stick Left/Right |
Shift up | Cursor Up |
Shift down | Cursor Down |
Shift Drive | Cursor Left |
Shift Reverse | Cursor Right |
Turn Signal Left | L1 |
Turn Signal Right | R1 |
Clear Turn Signal | SHARE |
Gate Mode | OPTIONS |
Emergency Stop | PS |
Clear Emergency Stop | PS |
Autoware Engage | ○ |
Autoware Disengage | ○ |
Vehicle Engage | △ |
Vehicle Disengage | △ |
今回作成したランブルパッド用のKey Map
4. Autowareで手動運転を実現するためのノード設定
公式ドキュメントでは、autoware_joy_controller
ノードの起動方法は以下のように書かれています。
# デフォルト設定(DS4コントローラー)
ros2 launch autoware_joy_controller joy_controller.launch.xml
# 既存のパラメータファイルから選択
ros2 launch autoware_joy_controller joy_controller_param_selection.launch.xml joy_type:=ds4 # または g29, p65, xbox
# パラメータファイルを指定して起動
ros2 launch autoware_joy_controller joy_controller.launch.xml config_file:=/path/to/your/param.yaml
今回は、ランブルパッド用のパラメータファイルを作成し、指定できるようにします。
(参考)既存のDS4コントローラー用のパラメータファイル
autoware/src/universe/autoware.universe/control/autoware_joy_controller/config/joy_controller_ds4.param.yaml
/**:
ros__parameters:
joy_type: DS4
update_rate: 10.0
accel_ratio: 3.0
brake_ratio: 5.0
steer_ratio: 0.5
steering_angle_velocity: 0.1
accel_sensitivity: 1.0
brake_sensitivity: 1.0
control_command:
raw_control: false
velocity_gain: 3.0
max_forward_velocity: 20.0
max_backward_velocity: 3.0
backward_accel_ratio: 1.0
今回作成したランブルパッド用のパラメータファイル
autoware/src/universe/autoware.universe/control/autoware_joy_controller/config/joy_controller_rumblepad.param.yaml
/**:
ros__parameters:
joy_type: RUMBLEPAD
update_rate: 10.0
accel_ratio: 3.0
brake_ratio: 5.0
steer_ratio: 0.5
steering_angle_velocity: 0.1
accel_sensitivity: 1.0
brake_sensitivity: 1.0
control_command:
raw_control: false
velocity_gain: 3.0
max_forward_velocity: 20.0
max_backward_velocity: 3.0
backward_accel_ratio: 1.0
(余談)このままROS 2ノードを起動してみるとエラーが出る
ros2 launch autoware_joy_controller joy_controller.launch.xml config_file:=autoware/src/universe/autoware.universe/control/autoware_joy_controller/config/joy_controller_rumblepad.param.yaml
[INFO] [launch]: All log files can be found below /home/sdoi/.ros/log/2025-03-19-19-09-51-697486-sdoi-FRONTIER-29934
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [autoware_joy_controller-1]: process started with pid [29935]
[INFO] [joy_node-2]: process started with pid [29937]
[autoware_joy_controller-1] [INFO 1742378991.826372611] [joy_controller]: Joy type: RUMBLEPAD (AutowareJoyControllerNode() at /home/sdoi/autoware/src/universe/autoware.universe/control/autoware_joy_controller/src/joy_controller_node.cpp:494)
[joy_node-2] [INFO 1742378992.158306823] [joy_node]: Opened joystick: Logitech RumblePad 2 USB. deadzone: 0.000000 (handleJoyDeviceAdded() at ./src/joy.cpp:400)
[autoware_joy_controller-1] [INFO 1742378992.830009327] [joy_controller]: Waiting for emergency_stop service connection... (AutowareJoyControllerNode() at /home/sdoi/autoware/src/universe/autoware.universe/control/autoware_joy_controller/src/joy_controller_node.cpp:530)
: # Autoware+AWSIMを起動する
[autoware_joy_controller-1] terminate called after throwing an instance of 'std::out_of_range'
[autoware_joy_controller-1] what(): vector::_M_range_check: __n (which is 7) >= this->size() (which is 6)
[ERROR] [autoware_joy_controller-1]: process has died [pid 35826, exit code -6, cmd '/home/sdoi/autoware/install/autoware_joy_controller/lib/autoware_joy_controller/autoware_joy_controller --ros-args -r __node:=joy_controller --params-file /tmp/launch_params_r4nx16ek -r input/joy:=/joy -r input/odometry:=/localization/kinematic_state -r output/control_command:=/external/remote/joy/control_cmd -r output/external_control_command:=/api/external/set/command/remote/control -r output/shift:=/api/external/set/command/remote/shift -r output/turn_signal:=/api/external/set/command/remote/turn_signal -r output/gate_mode:=/control/gate_mode_cmd -r output/heartbeat:=/api/external/set/command/remote/heartbeat -r output/vehicle_engage:=/vehicle/engage -r service/emergency_stop:=/api/autoware/set/emergency -r service/autoware_engage:=/api/autoware/set/engage'].
このようにエラーメッセージから、autoware_joy_controller
内でstd::out_of_range
例外が発生していることがわかります。
そのため単純にパラメータファイルを指定しただけでは範囲外エラーが出てしまうので、autoware_joy_controller
の中身を確認していきます。
続いて、autoware_joy_controller
の中身であるautoware/src/universe/autoware.universe/control/autoware_joy_controller/src/joy_controller_node.cpp
を見てみます。
ここで、AutowareJoyControllerNode::onJoy()
に注目します。
onJoy()
関数は/joy
トピックからジョイスティックの入力を取得し、適切なコントローラーの型に変換した後、それに応じたコマンドを発行する処理を行います。
void AutowareJoyControllerNode::onJoy()
{
const auto msg = sub_joy_.takeData();
if (!msg) {
return;
}
last_joy_received_time_ = msg->header.stamp;
if (joy_type_ == "G29") {
joy_ = std::make_shared<const G29JoyConverter>(*msg);
} else if (joy_type_ == "DS4") {
joy_ = std::make_shared<const DS4JoyConverter>(*msg);
} else if (joy_type_ == "XBOX") {
joy_ = std::make_shared<const XBOXJoyConverter>(*msg);
} else {
joy_ = std::make_shared<const P65JoyConverter>(*msg);
}
:
}
ここで、joy_type
とは既存のパラメータファイルから選択してautoware_joy_controller
ノードを起動する際のパラメータを示しています。
ros2 launch autoware_joy_controller joy_controller_param_selection.launch.xml joy_type:=ds4 # または g29, p65, xbox
既存のコードでは、G29
、DS4
、XBOX
、以外のパラメータは全てP65
として変換されてしまうので、独自コントローラー用のパラメータとコンバーターを追加する必要があります。(先ほどの余談で紹介した範囲外エラーはこれが原因です)
- 今回はランブルパッド用の分岐を追加
void AutowareJoyControllerNode::onJoy()
{
const auto msg = sub_joy_.takeData();
if (!msg) {
return;
}
last_joy_received_time_ = msg->header.stamp;
if (joy_type_ == "G29") {
joy_ = std::make_shared<const G29JoyConverter>(*msg);
} else if (joy_type_ == "DS4") {
joy_ = std::make_shared<const DS4JoyConverter>(*msg);
} else if (joy_type_ == "XBOX") {
joy_ = std::make_shared<const XBOXJoyConverter>(*msg);
+ }else if (joy_type_ == "RUMBLEPAD") {
+ joy_ = std::make_shared<const RumblepadJoyConverter>(*msg);
} else {
joy_ = std::make_shared<const P65JoyConverter>(*msg);
}
:
}
続いて、RumblepadJoyConverter
も追加します。車両操作とスティック・ボタンの対応付けは、3. 独自コントローラー用のKye Mapを作成で作成したKey Mapをもとに行ってください。
(参考)既存のDS4コントローラー用のコンバーターファイル
autoware/src/universe/autoware.universe/control/autoware_joy_controller/include/autoware/joy_controller/joy_converter/ds4_joy_converter.hpp
// Copyright 2020 Tier IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef AUTOWARE__JOY_CONTROLLER__JOY_CONVERTER__DS4_JOY_CONVERTER_HPP_
#define AUTOWARE__JOY_CONTROLLER__JOY_CONVERTER__DS4_JOY_CONVERTER_HPP_
#include "autoware/joy_controller/joy_converter/joy_converter_base.hpp"
#include <algorithm>
namespace autoware::joy_controller
{
class DS4JoyConverter : public JoyConverterBase
{
public:
explicit DS4JoyConverter(const sensor_msgs::msg::Joy & j) : j_(j) {}
float accel() const
{
const auto button = static_cast<float>(Cross());
const auto stick = std::max(0.0f, RStickUpDown());
const auto trigger = std::max(0.0f, -RTrigger());
return std::max({button, stick, trigger});
}
float brake() const
{
const auto button = static_cast<float>(Square());
const auto stick = std::max(0.0f, -RStickUpDown());
const auto trigger = std::max(0.0f, -LTrigger());
return std::max({button, stick, trigger});
}
float steer() const { return LStickLeftRight(); }
bool shift_up() const { return CursorUpDown() == 1.0f; }
bool shift_down() const { return CursorUpDown() == -1.0f; }
bool shift_drive() const { return CursorLeftRight() == 1.0f; }
bool shift_reverse() const { return CursorLeftRight() == -1.0f; }
bool turn_signal_left() const { return L1(); }
bool turn_signal_right() const { return R1(); }
bool clear_turn_signal() const { return Share(); }
bool gate_mode() const { return Options(); }
bool emergency_stop() const { return !reverse() && PS(); }
bool clear_emergency_stop() const { return reverse() && PS(); }
bool autoware_engage() const { return !reverse() && Circle(); }
bool autoware_disengage() const { return reverse() && Circle(); }
bool vehicle_engage() const { return !reverse() && Triangle(); }
bool vehicle_disengage() const { return reverse() && Triangle(); }
private:
float LStickLeftRight() const { return j_.axes.at(0); }
float LStickUpDown() const { return j_.axes.at(1); }
float LTrigger() const { return j_.axes.at(2); }
float RStickLeftRight() const { return j_.axes.at(3); }
float RStickUpDown() const { return j_.axes.at(4); }
float RTrigger() const { return j_.axes.at(5); }
float CursorLeftRight() const { return j_.axes.at(6); }
float CursorUpDown() const { return j_.axes.at(7); }
bool Cross() const { return j_.buttons.at(0); }
bool Circle() const { return j_.buttons.at(1); }
bool Triangle() const { return j_.buttons.at(2); }
bool Square() const { return j_.buttons.at(3); }
bool L1() const { return j_.buttons.at(4); }
bool R1() const { return j_.buttons.at(5); }
bool L2() const { return j_.buttons.at(6); }
bool R2() const { return j_.buttons.at(7); }
bool Share() const { return j_.buttons.at(8); }
bool Options() const { return j_.buttons.at(9); }
bool PS() const { return j_.buttons.at(10); }
const sensor_msgs::msg::Joy j_;
bool reverse() const { return Share(); }
};
} // namespace autoware::joy_controller
#endif // AUTOWARE__JOY_CONTROLLER__JOY_CONVERTER__DS4_JOY_CONVERTER_HPP_
今回作成したランブルパッド用のコンバーターファイル
autoware/src/universe/autoware.universe/control/autoware_joy_controller/include/autoware/joy_controller/joy_converter/rumblepad_joy_converter.hpp
#ifndef AUTOWARE__JOY_CONTROLLER__JOY_CONVERTER__RUMBLEPAD_JOY_CONVERTER_HPP_
#define AUTOWARE__JOY_CONTROLLER__JOY_CONVERTER__RUMBLEPAD_JOY_CONVERTER_HPP_
#include "autoware/joy_controller/joy_converter/joy_converter_base.hpp"
#include <algorithm>
namespace autoware::joy_controller
{
class RumblepadJoyConverter : public JoyConverterBase
{
public:
explicit RumblepadJoyConverter(const sensor_msgs::msg::Joy & j) : j_(j) {}
float accel() const { return std::max(0.0f, RStickUpDown()); }
float brake() const { return std::max(0.0f, LStickUpDown()); }
float steer() const { return CursorLeftRight(); }
bool shift_drive() const { return CursorUpDown() == 1.0f; }
bool shift_reverse() const { return CursorUpDown() == -1.0f; }
bool shift_up() const override { return L2(); }
bool shift_down() const override { return R2(); }
bool turn_signal_left() const { return L1(); }
bool turn_signal_right() const { return R1(); }
bool clear_turn_signal() const { return A(); }
bool gate_mode() const { return B(); }
bool emergency_stop() const { return Select(); }
bool clear_emergency_stop() const { return Start(); }
bool autoware_engage() const { return X(); }
bool autoware_disengage() const { return Y(); }
bool vehicle_engage() const { return LTrigger(); }
bool vehicle_disengage() const { return RTrigger(); }
private:
// 軸 (axes) は 0~5 の計6つ
float LStickLeftRight() const { return j_.axes.at(0); }
float LStickUpDown() const { return j_.axes.at(1); }
float RStickLeftRight() const { return j_.axes.at(2); }
float RStickUpDown() const { return j_.axes.at(3); }
float CursorLeftRight() const { return j_.axes.at(4); }
float CursorUpDown() const { return j_.axes.at(5); }
// ボタン (buttons) は 0~11 の計12個
bool A() const { return j_.buttons.at(2); }
bool B() const { return j_.buttons.at(1); }
bool X() const { return j_.buttons.at(3); }
bool Y() const { return j_.buttons.at(0); }
bool L1() const { return j_.buttons.at(4); }
bool R1() const { return j_.buttons.at(5); }
bool L2() const { return j_.buttons.at(6); }
bool R2() const { return j_.buttons.at(7); }
bool Select() const { return j_.buttons.at(8); }
bool Start() const { return j_.buttons.at(9); }
bool LTrigger() const { return j_.buttons.at(10); }
bool RTrigger() const { return j_.buttons.at(11); }
const sensor_msgs::msg::Joy j_;
};
} // namespace autoware::joy_controller
#endif // AUTOWARE__JOY_CONTROLLER__JOY_CONVERTER__RUMBLEPAD_JOY_CONVERTER_HPP_
再度joy_controller_node.cpp
に戻り、作成したhppファイルをincludeします。
autoware/src/universe/autoware.universe/control/autoware_joy_controller/src/joy_controller_node.cpp
#include "autoware/joy_controller/joy_controller.hpp"
#include "autoware/joy_controller/joy_converter/ds4_joy_converter.hpp"
#include "autoware/joy_controller/joy_converter/g29_joy_converter.hpp"
#include "autoware/joy_controller/joy_converter/p65_joy_converter.hpp"
#include "autoware/joy_controller/joy_converter/xbox_joy_converter.hpp"
+ #include "autoware/joy_controller/joy_converter/rumblepad_joy_converter.hpp"
最後に、autoware_joy_controller
ノードを起動する際に指定するパラメータファイルにランブルパッド用のものを指定できるようにするためにrumblepad
パラメータを追加します。
autoware/src/universe/autoware.universe/control/autoware_joy_controller/launch/joy_controller_param_selection.launch.xml
<launch>
- <arg name="joy_type" default="ds4" description="options: ds4, g29, p65, xbox"/>
+ <arg name="joy_type" default="ds4" description="options: ds4, g29, p65, xbox, rumblepad"/>
<include file="$(find-pkg-share autoware_joy_controller)/launch/joy_controller.launch.xml">
<arg name="config_file" value="$(find-pkg-share autoware_joy_controller)/config/joy_controller_$(var joy_type).param.yaml"/>
</include>
</launch>
5. ビルド & 起動による動作確認
ここまでの設定が完了したら、部分ビルドを実行し、autoware_joy_controller
ノードを起動します。
- 部分ビルド
colcon build --symlink-install --packages-up-to autoware_joy_controller
:
Finished <<< autoware_vehicle_msgs [1.11s]
Finished <<< tier4_planning_msgs [1.16s]
Starting >>> autoware_universe_utils
Finished <<< autoware_universe_utils [0.68s]
Starting >>> autoware_joy_controller
Finished <<< autoware_joy_controller [0.59s]
Summary: 15 packages finished [10.3s]
-
joy_type:=rumblepad
を指定してautoware_joy_controller
ノードを起動
ros2 launch autoware_joy_controller joy_controller_param_selection.launch.xml joy_type:=rumblepad
[INFO] [launch]: All log files can be found below /home/sdoi/.ros/log/2025-02-17-12-40-13-183652-sdoi-FRONTIER-22998
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [autoware_joy_controller-1]: process started with pid [22999]
[INFO] [joy_node-2]: process started with pid [23001]
[autoware_joy_controller-1] [INFO 1739763613.336659167] [joy_controller]: Joy type: RUMBLEPAD (AutowareJoyControllerNode() at /home/sdoi/autoware/src/universe/autoware.universe/control/autoware_joy_controller/src/joy_controller_node.cpp:494)
[joy_node-2] [INFO 1739763613.451018462] [joy_node]: Opened joystick: Logitech RumblePad 2 USB. deadzone: 0.000000 (handleJoyDeviceAdded() at ./src/joy.cpp:400)
[autoware_joy_controller-1] [INFO 1742381696.794340015] [joy_controller]: Waiting for emergency_stop service connection... (AutowareJoyControllerNode() at /home/sdoi/autoware/src/universe/autoware.universe/control/autoware_joy_controller/src/joy_controller_node.cpp:530)
: # Autoware+AWSIMを起動する
:
[autoware_joy_controller-1] [INFO 1742381775.101209426] [joy_controller]: Autoware Engage (publishAutowareEngage() at /home/sdoi/autoware/src/universe/autoware.universe/control/autoware_joy_controller/src/joy_controller_node.cpp:430)
[autoware_joy_controller-1] [INFO 1742381775.101770392] [joy_controller]: Accel Value: 0.000000 (publishControlCommand() at /home/sdoi/autoware/src/universe/autoware.universe/control/autoware_joy_controller/src/joy_controller_node.cpp:285)
[autoware_joy_controller-1] [INFO 1742381775.101880078] [joy_controller]: /api/autoware/set/engage: 1, (operator()() at /home/sdoi/autoware/src/universe/autoware.universe/control/autoware_joy_controller/src/joy_controller_node.cpp:445)
[autoware_joy_controller-1] [INFO 1742381775.201273646] [joy_controller]: Autoware Engage (publishAutowareEngage() at /home/sdoi/autoware/src/universe/autoware.universe/control/autoware_joy_controller/src/joy_controller_node.cpp:430)
[autoware_joy_controller-1] [INFO 1742381775.202261996] [joy_controller]: Accel Value: 0.003937 (publishControlCommand() at /home/sdoi/autoware/src/universe/autoware.universe/control/autoware_joy_controller/src/joy_controller_node.cpp:285)
[autoware_joy_controller-1] [INFO 1742381775.202484174] [joy_controller]: /api/autoware/set/engage: 1, (operator()() at /home/sdoi/autoware/src/universe/autoware.universe/control/autoware_joy_controller/src/joy_controller_node.cpp:445)
OperationMode
をRemote
に変更後、対応するボタンで【D】(ドライブ)に切り替え、アクセル用のスティックを傾けると車両が動きます!
※ランブルパッドでの操作は50秒~
以下のように"joy msg is timeout"
や"twist msg is timeout"
といった警告が出ており、車両も動かない場合
[autoware_joy_controller-1] [WARN 1742383772.186362482] [joy_controller]: twist msg is timeout (isDataReady() at /home/sdoi/autoware/src/universe/autoware.universe/control/autoware_joy_controller/src/joy_controller_node.cpp:251)
原因
メッセージの受信がタイムアウトしており、それ以降の処理(コントロールコマンドの送信など)がスキップされるため。
解決策
timeout
の値を大きくする。私の場合、Twistで警告が出たので0.5秒→5秒に変更すると警告が出なくなり車両が動くようになりました。
bool AutowareJoyControllerNode::isDataReady()
{
// Joy
{
if (!joy_) {
RCLCPP_WARN_THROTTLE(
get_logger(), *get_clock(), std::chrono::milliseconds(5000).count(),
"waiting for joy msg...");
return false;
}
constexpr auto timeout = 2.0;
const auto time_diff = this->now() - last_joy_received_time_;
if (time_diff.seconds() > timeout) {
RCLCPP_WARN_THROTTLE(
get_logger(), *get_clock(), std::chrono::milliseconds(5000).count(), "joy msg is timeout");
return false;
}
}
// Twist
if (!raw_control_) {
if (!twist_) {
RCLCPP_WARN_THROTTLE(
get_logger(), *get_clock(), std::chrono::milliseconds(5000).count(),
"waiting for twist msg...");
return false;
}
- constexpr auto timeout = 0.5;
+ constexpr auto timeout = 5.0;
const auto time_diff = this->now() - twist_->header.stamp;
if (time_diff.seconds() > timeout) {
RCLCPP_WARN_THROTTLE(
get_logger(), *get_clock(), std::chrono::milliseconds(5000).count(),
"twist msg is timeout");
return false;
}
}
return true;
}
ファイルの変更後は再度部分ビルドし直す必要があります。
colcon build --symlink-install --packages-up-to autoware_joy_controller
まとめ
今回は、Autowareで独自のゲームコントローラーを使用して手動運転を行う方法を紹介しました。
作成・編集したファイル一覧は以下の通りです。
joy_controller_rumblepad.param.yaml
rumblepad_joy_converter.hpp
joy_controller_param_selection.launch.xml
joy_controller_node.cpp