自動運転ミニカーバトル2024のシミュレーション用Unityプロジェクト
ラジコンを走らせる周回コースを自動運転で3周走りきるタイムを競う競技 開催ごとに周回後に駐車したり、コース上の障害物を倒すことで加点される
- PC (Jetson Orin Nano)
- フロントカメラ (B0287)
- リアカメラ (B0287)
- 2Dライダ (YDLIDAR X4)
- ToFセンサ (AE-VL53L1X)
- IMU (BMX055)
3Dモデル (Googleドライブ)
-
/cmd_vel (geometry_msgs/Twist)
ロボット動作指示
-
/imu (sensor_msgs/Imu)
IMUセンサ値
-
/range_[right, center, left] (sensor_msgs/Range)
ToFセンサ値
-
/scan (sensor_msgs/LaserScan)
2D Lidarセンサ値
-
/front_camera/compressed (sensor_msgs/CompressedImage)
前面カメラ値
-
/rear_camera/compressed (sensor_msgs/CompressedImage)
後面カメラ値
Unity側のROS-TCP-Connector
と接続するためのROS-TCP-Endpoint
を起動する
# ワークスペースの作成
mkdir -p colcon_ws/src
cd colcon_ws
# リポジトリをクローンする
git clone https://github.com/Unity-Technologies/ROS-TCP-Endpoint src/ROS-TCP-Endpoint
# ビルドする
colcon build --symlink-install
# 起動する
source install/local_setup.bash
ros2 run ros_tcp_endpoint default_server_endpoint
Unity側から送信されるカメラ画像データは圧縮形式のため解凍して表示できるようにする
# Terminal 1
ros2 run image_transport republish compressed raw \
--ros-args -r /in/compressed:=/front_camera/compressed -r /out:=/front_camera/raw
# Terminal 2
ros2 run image_transport republish compressed raw \
--ros-args -r /in/compressed:=/rear_camera/compressed -r /out:=/rear_camera/raw
Library\PackageCache\com.frj.unity-sensors-ros@c33247ddf2\Runtime\Scripts\Serializers\TF\TFMsgSerializer.cs(37,50): error CS1061: 'HeaderMsg' does not contain a definition for 'seq' and no accessible extension method 'seq' accepting a first argument of type 'HeaderMsg' could be found (are you missing a using directive or an assembly reference?)
UnityプロジェクトをROS2に設定した際に、下記のようなエラーが発生した場合はLibrary\PackageCache\com.frj.unity-sensors-ros@c33247ddf2\Runtime\Scripts\Serializers\TF\TFMsgSerializer.cs
の37行目をコメントアウトする
変更前
TransformStampedMsg transform = new TransformStampedMsg();
transform.header.seq = headerMsg.seq;
transform.header.stamp = headerMsg.stamp;
変更後
TransformStampedMsg transform = new TransformStampedMsg();
// transform.header.seq = headerMsg.seq;
transform.header.stamp = headerMsg.stamp;