AWS IoT FleetWise で車載カメラ画像をクラウドに送ってみた

AWS IoT FleetWise で車載カメラ画像をクラウドに送ってみた

2025.12.15

はじめに

製造ビジネステクノロジー部コネクティッドカーチームの新澤です。

AWS IoT FleetWise の
ビジョンシステムデータ対応
が発表されて2年が経ちましたが、自動車業界特化なサービスのためなのか、実際に試した日本語の情報はまだ多くありません。

この記事では「実際の車両からカメラ画像を送って、AWS 側で
S3 に保存する」ところまでを、なるべく具体的に分かる形で紹介したいと思います。
AWS 側とエッジ側が両方必要なので記事が少し長めですが、どうぞお付き合いください。

AWS IoT FleetWise のビジョンシステムデータ対応について

AWS IoT FleetWise は「車両から信号(スピード、ステアリング角度など)を設定した条件に従って収集し、
クラウドへ送る」ためのマネージドサービスです。

昨今では自動運転の開発や、ドライブレコーダーのデータ収集などの用途で、数値データだけでなくカメラ画像などの非構造化データをクラウドへアップロードする機会が
増えてきていますので、この対応により、カメラ画像などの非構造化データをクラウドへアップロードする際の実装が簡素化されます。

システム概要

全体アーキテクチャ

図にするとこんな感じです。

Raspberry Pi 内蔵の WiFi をアクセスポイントに設定して、そこにカメラデバイスを接続し、画像データを送信します。送信の仕組みには ROS2 を利用します。
IoT FleetWise のビジョンシステムデータ対応は FleetWise Edge Agent(FWE) が ROS2 を利用してデータを受信することを前提としているからです。

カメラデバイスは ROS2 のデバイス向け実装である micro-ROS を使ってデータを送信します。
FWE は ROS2 トピックをサブスクライブおり、直接 micro-ROS のデータを受信することはできないので、 micro-ROS Agent が micro-ROS と ROS2 のゲートウェイ役を担い、データが ROS2 トピックへ渡されます。

FWE は、収集条件に従って ROS2 トピックをサブスクライブし、受信したデータを収集ルールで定義された周期でクラウドへ送信します。

データフロー

上記の説明を図にすると、だいたいこのような感じです。

実装

全コードはリポジトリにアップしておきますので、要所に絞って解説します。

前提条件

  • Raspberry Pi OS ( Bookworm )
  • Raspberry Pi の内蔵 WiFi をアクセスポイントに設定済
  • Raspberry Pi の有線 LAN ポート、もしくは USB WiFi ドングルでインターネットに接続できる経路が設定済
  • Raspberry Pi に Docker の実行環境を設定済

1. AWS IoT FleetWise / IoT Core の CDK 実装

CDK 側では以下のようなリソースを実装します。
IoT Coreのリソースの役割は、通常の IoT Core を利用したシステムと同じです。

  • S3: Vision System Data の保存先バケット
  • IoT Core:
    • Thing(車両と関連付けられる)
    • 証明書(FleetWise Edge Agent からの相互 TLS に利用)
    • IoT Policy(IoT Core 接続や S3 バケットへのファイル送信に必要な権限)
    • Role Alias(Credentials Provider 用)
  • IoT FleetWise:
    • Signal Catalog: 車両から取りたい値(信号)と、その型や単位などのメタデータを定義してまとめたもの
    • Model Manifest: Signal Catalog から使う信号を選び、車両から取得できる信号のセットを定義するもの
    • Decoder Manifest: CAN/OBD/ROS 2 などの入力(バイナリやメッセージ)を、Model Manifest 上の信号にどう割り当てて解釈するかを定義するもの
    • Vehicle: Model Manifest と Decoder Manifest を紐づけた「車両インスタンス」。実体としては IoT Thing と対応し、必要に応じて属性(例: 車種や車両番号など)を付与できます
    • Campaign: いつ・どの信号を・どこへ送るかを定義する収集ルール。承認すると FleetWise からエッジへ配信され、S3/Timestream/MQTT などの宛先へデータが送られます

ROS 2 連携でのポイントは、「ROS 2 トピックを FleetWise の信号として解釈できるように Decoder を定義する」点です。
そのあたりに焦点を当てて解説していきます。

FleetWise リソースの実装

Signal Catalog

Signal Catalog は、FleetWise に定義する車両モデル全体から参照する「信号の辞書」です。

信号の定義は、以下のような内容でJSONで定義しています。(画像ファイル部分を抜粋)

まず、メッセージの構造体を定義していきます。基本的には、 ROS2 のメッセージ定義の構造体を "Types.<ROS2 メッセージ名 >" のように再定義していくようなイメージです。ちょっと面倒くさいですが、再定義していくだけなので、コーディングエージェントにまかせてしまえばあっという間に書けるでしょう。たぶん。。。

cloud/lib/ros2-nodes.json
[
  {
    "struct": {
      "fullyQualifiedName": "Types.sensor_msgs_msg_CompressedImage"
    }
  },
  {
    "struct": {
      "fullyQualifiedName": "Types.std_msgs_Header"
    }
  },
  {
    "struct": {
      "fullyQualifiedName": "Types.builtin_interfaces_Time"
    }
  },
  {
    "property": {
      "fullyQualifiedName": "Types.builtin_interfaces_Time.sec",
      "dataType": "INT32",
      "dataEncoding": "TYPED"
    }
  },
  {
    "property": {
      "fullyQualifiedName": "Types.builtin_interfaces_Time.nanosec",
      "dataType": "UINT32",
      "dataEncoding": "TYPED"
    }
  },
  {
    "property": {
      "fullyQualifiedName": "Types.std_msgs_Header.stamp",
      "dataType": "STRUCT",
      "structFullyQualifiedName": "Types.builtin_interfaces_Time"
    }
  },
  {
    "property": {
      "fullyQualifiedName": "Types.std_msgs_Header.frame_id",
      "dataType": "STRING",
      "dataEncoding": "TYPED"
    }
  },
  {
    "property": {
      "fullyQualifiedName": "Types.sensor_msgs_msg_CompressedImage.header",
      "dataType": "STRUCT",
      "structFullyQualifiedName": "Types.std_msgs_Header"
    }
  },
  {
    "property": {
      "fullyQualifiedName": "Types.sensor_msgs_msg_CompressedImage.format",
      "dataType": "STRING",
      "dataEncoding": "TYPED"
    }
  },
  {
    "property": {
      "fullyQualifiedName": "Types.sensor_msgs_msg_CompressedImage.data",
      "dataType": "UINT8_ARRAY",
      "dataEncoding": "BINARY"
    }
  },
  {
    "branch": {
      "fullyQualifiedName": "Vehicle.Cameras.Front",
      "description": "Vehicle.Cameras.Front"
    }
  },
  {
    "sensor": {
      "fullyQualifiedName": "Vehicle.Cameras.Front.Image",
      "dataType": "STRUCT",
      "structFullyQualifiedName": "Types.sensor_msgs_msg_CompressedImage"
    }
  }
]

その後にセンサーノードとして Vehicle.Cameras.Front.Image を定義しました。

車両の前方カメラで撮影した画像、という感じですね。

cloud/lib/ros2-nodes.json
  {
    "branch": {
      "fullyQualifiedName": "Vehicle",
      "description": "Vehicle"
    }
  },
  {
    "branch": {
      "fullyQualifiedName": "Vehicle.Cameras",
      "description": "Vehicle.Cameras"
    }
  },
  {
    "branch": {
      "fullyQualifiedName": "Vehicle.Cameras.Front",
      "description": "Vehicle.Cameras.Front"
    }
  },
  {
    "sensor": {
      "fullyQualifiedName": "Vehicle.Cameras.Front.Image",
      "dataType": "STRUCT",
      "structFullyQualifiedName": "Types.sensor_msgs_msg_CompressedImage"
    }
  }

CDK の実装は、現時点では実装はちょっと面倒です。というのも、2025 年 12 月時点では CloudFormation の FleetWise のリソースが ROS2 未対応なため、AWS Custom Resource で API を呼び出して定義していく形になります。

cloud/lib/cloud-stack.ts
const nodes = JSON.parse(fs.readFileSync('lib/ros2-nodes.json', 'utf8'));

const signalCatalogCr = new cr.AwsCustomResource(this, 'SignalCatalogCr', {
  onCreate: {
    service: 'iotfleetwise',
    action: 'CreateSignalCatalog',
    parameters: { name: 'DefaultSignalCatalog', nodes },
    physicalResourceId: cr.PhysicalResourceId.of('ros2-signal-catalog'),
  },
  onDelete: {
    service: 'iotfleetwise',
    action: 'DeleteSignalCatalog',
    parameters: { name: 'DefaultSignalCatalog' },
    physicalResourceId: cr.PhysicalResourceId.of('ros2-signal-catalog'),
  },
  policy: cr.AwsCustomResourcePolicy.fromSdkCalls({
    resources: cr.AwsCustomResourcePolicy.ANY_RESOURCE,
  }),
  installLatestAwsSdk: true,
});
Model Manifest

Model Manifest は「車両で収集可能な信号のセット」を定義するリソースです。
今回は、画像・速度・温度・加速度の 4 つの信号を車両モデルの信号として定義してみました。

cloud/lib/cloud-stack.ts
const modelManifest = new iotfleetwise.CfnModelManifest(this, 'ModelManifest', {
  name: 'Ros2ModelManifest',
  description: 'Model Manifest for ROS2',
  signalCatalogArn: signalCatalogArn,
  status: 'ACTIVE',
  nodes: [
    'Vehicle.Cameras.Front.Image',
    'Vehicle.Speed',
    "Vehicle.Temperature",
    'Vehicle.Acceleration',
  ],
});
ネットワークインターフェース

車両が利用可能なネットワークインターフェースを定義します。

通常は CAN インターフェースを定義することが多いですが、今回は以下のようにして ROS2 インターフェースを定義します。

cloud/lib/cloud-stack.ts
[
  {
    "interfaceId": "10",
    "type": "VEHICLE_MIDDLEWARE",
    "vehicleMiddleware": {
      "name": "ros2",
      "protocolName": "ROS_2"
    }
  }
]
デコーダー

Vehicle.Cameras.Front.Image という信号に対して、ROS 2 のトピック
/ego_vehicle/rgb_front/image_compressed を紐づけています。

トピック名は任意です。

sensor_msgs/msg/CompressedImage は、 ROS2 で標準で定義されている圧縮画像のメッセージタイプです。

messageSignal.topicName<TopicName>:<MessageType> 形式で定義します。

cloud/lib/ros2-decoders.json
{
  "fullyQualifiedName": "Vehicle.Cameras.Front.Image",
  "type": "MESSAGE_SIGNAL",
  "interfaceId": "10",
  "messageSignal": {
    "topicName": "/ego_vehicle/rgb_front/image_compressed:sensor_msgs/msg/CompressedImage",
    "structuredMessage": {
      "structuredMessageDefinition": [
        {
          "fieldName": "header",
          "dataType": {
            "structuredMessageDefinition": [
              {
                "fieldName": "stamp",
                "dataType": {
                  "structuredMessageDefinition": [
                    {
                      "fieldName": "sec",
                      "dataType": {
                        "primitiveMessageDefinition": {
                          "ros2PrimitiveMessageDefinition": { "primitiveType": "INT32" }
                        }
                      }
                    },
                    {
                      "fieldName": "nanosec",
                      "dataType": {
                        "primitiveMessageDefinition": {
                          "ros2PrimitiveMessageDefinition": { "primitiveType": "UINT32" }
                        }
                      }
                    }
                  ]
                }
              },
              {
                "fieldName": "frame_id",
                "dataType": {
                  "primitiveMessageDefinition": {
                    "ros2PrimitiveMessageDefinition": { "primitiveType": "STRING" }
                  }
                }
              }
            ]
          }
        },
        {
          "fieldName": "format",
          "dataType": {
            "primitiveMessageDefinition": {
              "ros2PrimitiveMessageDefinition": { "primitiveType": "STRING" }
            }
          }
        },
        {
          "fieldName": "data",
          "dataType": {
            "structuredMessageListDefinition": {
              "name": "listType",
              "memberType": {
                "primitiveMessageDefinition": {
                  "ros2PrimitiveMessageDefinition": { "primitiveType": "UINT8" }
                }
              },
              "capacity": 0,
              "listType": "DYNAMIC_UNBOUNDED_CAPACITY"
            }
          }
        }
      ]
    }
  }
}

Decoder Manifest も Signal Catalog 同様に AWS Custom Resource で定義します。

cloud/lib/cloud-stack.ts
const networkInterfaces = JSON.parse(
  fs.readFileSync('lib/network-interfaces.json', 'utf8'),
);
const decoders = JSON.parse(fs.readFileSync('lib/ros2-decoders.json', 'utf8'));

const decoderManifestParams = {
  modelManifestArn: modelManifest.attrArn,
  name: 'Ros2DecoderManifest',
  description: 'Decoder Manifest for ROS2',
  networkInterfaces,
  signalDecoders: decoders,
  status: 'ACTIVE',
};

const decoderManifestCr = new cr.AwsCustomResource(this, 'DecoderManifestCr', {
  onCreate: {
    service: 'iotfleetwise',
    action: 'CreateDecoderManifest',
    parameters: decoderManifestParams,
    physicalResourceId: cr.PhysicalResourceId.of('ros2-decoder-manifest'),
  },
  // ... onDelete は省略 ...
  policy: cr.AwsCustomResourcePolicy.fromStatements([
    new iam.PolicyStatement({
      actions: ['iotfleetwise:CreateDecoderManifest', 'iotfleetwise:DeleteDecoderManifest'],
      resources: ['*'],
    }),
  ]),
  installLatestAwsSdk: true,
});
decoderManifestCr.node.addDependency(modelManifest);

const decoderManifestArn = decoderManifestCr.getResponseField('arn');
Vehicle

Vehicle は、IoT Thing 名(thingName)と紐づく「車両インスタンス」です。
ここで上記で定義した Model Manifest / Decoder Manifest を Vehicle に紐づけます。

associationBehavior は IoT Thing を新規作成するか、既存 Thing と紐づけるかの選択を指定します。

Vehicle を定義する場合は、別途 Thing を定義して、それらと紐づけるように実装しましょう。

自動で新規作成してしまうと、あとで証明書を取り出せなくなってしまい、詰んでしまうので気をつけてください。

( Thing の実装については、リポジトリを参考にしてください。)

cloud/lib/cloud-stack.ts
const vehicle = new iotfleetwise.CfnVehicle(this, 'Vehicle', {
  name: thingName,
  modelManifestArn: modelManifest.attrArn,
  decoderManifestArn: decoderManifestArn,
  associationBehavior: 'ValidateIotThingExists',
});
vehicle.node.addDependency(modelManifest);
Campaign

Campaign は車両データの収集ルール(「いつ」「何を」「どこへ」)を定義します。
この例では 10 秒周期で 3 信号を集め、S3 を宛先にしています。

ちなみに、 Campaign に1つでも ROS2 のデータが含まれていると、送信先は S3 しか選べないので注意してください。

cloud/lib/cloud-stack.ts
const campaign = new iotfleetwise.CfnCampaign(this, 'Campaign', {
  name: 'Ros2Campaign',
  description: 'Campaign for ROS2',
  action: 'APPROVE',
  signalCatalogArn: signalCatalogArn,
  targetArn: vehicle.attrArn,
  collectionScheme: { timeBasedCollectionScheme: { periodMs: 10000 } },
  compression: 'SNAPPY',
  dataDestinationConfigs: [{ s3Config: { bucketArn: bucket.bucketArn } }],
  signalsToCollect: [
    { name: 'Vehicle.Cameras.Front.Image' },
    { name: 'Vehicle.Speed' },
    { name: 'Vehicle.Acceleration' },
  ],
});

CDK のデプロイ

リポジトリから clone した後、CDK のディレクトリ(iotfleetwise-ros2/cloud/)で
pnpm を使ってデプロイします。

デプロイ実行時に AWS 認証情報が必要なので、aws cliの設定は済ませておいてください。

pnpm install
pnpm run cdk deploy

AWS リソースをデプロイできたら、次はエッジ側の実装です。

AWS IoT FleetWise Edge Agent(FWE)の設定

FWE, micro-ROS Agent

以下の docker-compose ファイルで FWE と micro-ROS Agent のコンテナを起動できるようにします。

docker-compose.yaml
services:
  microros-agent:
    image: microros/micro-ros-agent:humble
    container_name: microros-agent
    network_mode: host
    ipc: host
    command: ["udp4", "--port", "8888"]
    volumes:
      - /dev:/dev
      - /dev/shm:/dev/shm
    environment:
      - ROS_DISTRO=humble
      - ROS_DOMAIN_ID=0
      - RMW_IMPLEMENTATION=rmw_fastrtps_cpp
      - FASTDDS_BUILTIN_TRANSPORTS=UDPv4
    healthcheck:
      test: ["CMD", "pgrep", "-f", "micro_ros_agent"]
      interval: 30s
      timeout: 10s
      retries: 3
      start_period: 10s
    restart: unless-stopped

  fwe-edge-agent:
    image: public.ecr.aws/aws-iot-fleetwise-edge/aws-iot-fleetwise-edge-ros2:latest
    container_name: fwe-edge-agent
    network_mode: host
    ipc: host
    volumes:
      - /dev:/dev
      - /dev/shm:/dev/shm
      - ./cert/certificate.pem:/etc/aws-iot-fleetwise/certificate.pem:ro
      - ./cert/private.key:/etc/aws-iot-fleetwise/private-key.key:ro
    environment:
      - VEHICLE_NAME=${VEHICLE_NAME}
      - ENDPOINT_URL=${ENDPOINT_URL}
      - CREDS_ENDPOINT_URL=${CREDS_ENDPOINT_URL}
      - CREDS_ROLE_ALIAS=${CREDS_ROLE_ALIAS}
      # ROS2 interface
      - ENABLE_ROS2_INTERFACE=true
      - ROS_VERSION=2
      - ROS_DISTRO=humble
      - ROS_DOMAIN_ID=0
      - ROS_PYTHON_VERSION=3
      - RMW_IMPLEMENTATION=rmw_fastrtps_cpp
      # - FASTDDS_BUILTIN_TRANSPORTS=SHM
      - COLCON_PREFIX_PATH=/opt/ros/humble
      - COLCON_PYTHON_EXECUTABLE=/usr/bin/python3
      # /usr/bin/start-fwe.sh が /opt/ros/humble/local_setup.bash を読む際に
      # set -u 相当で未定義変数があると落ちるので、空でも良いので定義しておく
      - AMENT_PREFIX_PATH=
      - CMAKE_PREFIX_PATH=
      - LD_LIBRARY_PATH=
      - PKG_CONFIG_PATH=
      - PYTHONPATH=
      - AMENT_TRACE_SETUP_FILES=
      - COLCON_TRACE=
    depends_on:
      - microros-agent
    restart: unless-stopped

必要な環境変数は以下の4つ。

  • VEHICLE_NAME: FleetWise Vehicle 名 ( IoT Thing 名と同一 )
  • ENDPOINT_URL: AWS IoT Core データプレーンエンドポイント
  • CREDS_ENDPOINT_URL: AWS IoT Core 認証情報プロバイダーエンドポイント
  • CREDS_ROLE_ALIAS: Role Alias 名

リポジトリのCDKでデプロイした場合は、以下で.envファイルを生成できます。
docker-compose.yaml と同じディレクトリに作成します。

REGION=us-east-1 bash -lc 'set -euo pipefail
VEHICLE_NAME="$(aws cloudformation list-exports --region "$REGION" --query "Exports[?Name==\`FleetWiseVehicleName\`].Value|[0]" --output text)"
CREDS_ROLE_ALIAS="$(aws cloudformation list-exports --region "$REGION" --query "Exports[?Name==\`CredentialsProviderRoleAlias\`].Value|[0]" --output text)"
ENDPOINT_URL="$(aws iot describe-endpoint --region "$REGION" --endpoint-type iot:Data-ATS --query endpointAddress --output text)"
CREDS_ENDPOINT_URL="$(aws iot describe-endpoint --region "$REGION" --endpoint-type iot:CredentialProvider --query endpointAddress --output text)"
cat > .env <<EOF
# FleetWise Edge Agent
VEHICLE_NAME=${VEHICLE_NAME}
ENDPOINT_URL=${ENDPOINT_URL}
CREDS_ENDPOINT_URL=${CREDS_ENDPOINT_URL}
CREDS_ROLE_ALIAS=${CREDS_ROLE_ALIAS}
EOF
echo "wrote .env"'

証明書・秘密鍵ファイル

FWE が使用するデバイス証明書と秘密鍵のファイルを作成します。
CDK で作成した証明書 / 秘密鍵は AWS Secrets Manager に格納しているので、取得して docker-compose.yaml ファイルからみて ./cert/ ディレクトリにファイルを配置しておきましょう。

証明書。秘密鍵ファイルは以下のようにして取得できます。

REGION=us-east-1
SECRET_ID="$(aws cloudformation list-exports --region "${REGION}" --query "Exports[?Name==\`IotCoreCertificateSecret\`].Value|[0]" --output text)"

mkdir -p cert

aws secretsmanager get-secret-value \
  --region "${REGION}" \
  --secret-id "${SECRET_ID}" \
  --query SecretString \
  --output text > cert/secret.json

perl -0777 -ne '
  if (/"privateKey":"(.*?)"/s) {
    $key = $1;
    $key =~ s/\\n/\n/g;
    open(my $fh, ">", "cert/private.key");
    print $fh $key;
    close($fh);
  }
  if (/"certificate":"(.*?)"/s) {
    $cert = $1;
    $cert =~ s/\\n/\n/g;
    open(my $fh, ">", "cert/certificate.pem");
    print $fh $cert;
    close($fh);
  }
' cert/secret.json

chmod 600 cert/certificate.pem cert/private.key
rm -f cert/secret.json

ファイルの転送

scp コマンドで Raspberry Pi に作成したファイルを転送します。

ssh pi@<RPI_IP_ADDRESS> "mkdir -p ~/fwe"
scp -r docker-compose.yaml .env cert/* pi@<RPI_IP_ADDRESS>:~/fwe/

FWE + micro-ROS Agent を起動する

RPi で以下を実行して、 FWE と micro-ROS を起動します。

docker compose up -d

車載カメラ(UnitCamS3)の実装

Unit CamS3 は M5 Stack 社から発売された ESP32S3 モジュールをベースとしたコンパクトなカメラユニットです。 2MP カメラ (OV2640) を搭載していて、最大 1600x1200 で撮影可能です。 (この製品は EOL になっており、後継として 5MP カメラ (PY260) を搭載した Unit CamS3-5MP が販売されています)
Unit CamS3-5MP

カメラ側は UnitCamS3(ESP32-S3)で JPEG を取得し、
micro-ROS で 画像データのメッセージを publish します。

main.cpp
main.cpp
#include <Arduino.h>
#include <micro_ros_platformio.h>
#include "secret.h"
#include <rcl/rcl.h>
#include <rclc/rclc.h>
#include <rclc/executor.h>
#include <esp_log.h>
#include <rosidl_runtime_c/string_functions.h>

#include <std_msgs/msg/int32.h>
#include <std_msgs/msg/float32.h>
#include <sensor_msgs/msg/compressed_image.h>

#include "esp_camera.h"
#define CAMERA_MODEL_M5STACK_CAMS3_UNIT
#include "camera_pins.h"

#if !defined(MICRO_ROS_TRANSPORT_ARDUINO_WIFI)
#error This example is only avaliable for Arduino framework with wifi transport.
#endif

// 定数定義
static const char* TAG = "FWE_NODE";
const char* NODE_NAME = "fwe_node";
const char* INT32_TOPIC = "/fwe_topic";
const char* SPEED_TOPIC = "/ego_vehicle/speedometer";
const char* IMAGE_TOPIC = "/ego_vehicle/rgb_front/image_compressed";
const unsigned int TIMER_TIMEOUT_MS = 1000;

// グローバル変数
rcl_publisher_t publisher;
std_msgs__msg__Int32 msg;
rcl_publisher_t speed_publisher;
std_msgs__msg__Float32 speed_msg;
rcl_publisher_t image_publisher;
sensor_msgs__msg__CompressedImage image_msg;
rclc_executor_t executor;
rclc_support_t support;
rcl_allocator_t allocator;
rcl_node_t node;
rcl_timer_t timer;

// エラーハンドルループ
void error_loop(rcl_ret_t error_code, const char* function_name) {
  while(1) {
    ESP_LOGE(TAG, "エラーが発生しました。関数: %s, エラーコード: %d, リカバリーのためループしています。", function_name, error_code);
    delay(100);
  }
}

#define RCCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){error_loop(temp_rc, #fn);}}
#define RCSOFTCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){} }

// Int32タイマーコールバック
void timer_callback(rcl_timer_t * timer, int64_t last_call_time) {
  RCLC_UNUSED(last_call_time);
  if (timer != NULL) {
    // Int32メッセージをパブリッシュ
    RCSOFTCHECK(rcl_publish(&publisher, &msg, NULL));
    ESP_LOGD(TAG, "Int32メッセージをパブリッシュしました: %d", msg.data);
    msg.data++;

    // 速度データをパブリッシュ(テストデータ:0-120km/hの範囲で変動)
    static float speed_counter = 0.0;
    speed_msg.data = 30.0 + 20.0 * sin(speed_counter * 0.1); // 10-50km/hの範囲で変動
    speed_counter += 1.0;
    if (speed_counter > 62.8) speed_counter = 0.0; // 2π*10でリセット

    RCSOFTCHECK(rcl_publish(&speed_publisher, &speed_msg, NULL));
    ESP_LOGD(TAG, "速度メッセージをパブリッシュしました: %.2f km/h", speed_msg.data);
  }
}

// LEDフラッシュ初期化(必要な場合のみ)
void setupLedFlash(int pin) {
  pinMode(pin, OUTPUT);
  digitalWrite(pin, LOW);
}

// カメラ初期化処理
bool init_camera() {
  camera_config_t config;
  config.ledc_channel = LEDC_CHANNEL_0;
  config.ledc_timer = LEDC_TIMER_0;
  config.pin_d0 = Y2_GPIO_NUM;
  config.pin_d1 = Y3_GPIO_NUM;
  config.pin_d2 = Y4_GPIO_NUM;
  config.pin_d3 = Y5_GPIO_NUM;
  config.pin_d4 = Y6_GPIO_NUM;
  config.pin_d5 = Y7_GPIO_NUM;
  config.pin_d6 = Y8_GPIO_NUM;
  config.pin_d7 = Y9_GPIO_NUM;
  config.pin_xclk = XCLK_GPIO_NUM;
  config.pin_pclk = PCLK_GPIO_NUM;
  config.pin_vsync = VSYNC_GPIO_NUM;
  config.pin_href = HREF_GPIO_NUM;
  config.pin_sccb_sda = SIOD_GPIO_NUM;
  config.pin_sccb_scl = SIOC_GPIO_NUM;
  config.pin_pwdn = PWDN_GPIO_NUM;
  config.pin_reset = RESET_GPIO_NUM;
  config.xclk_freq_hz = 20000000;
#ifdef CAMERA_MODEL_M5STACK_CAMS3_UNIT
  config.frame_size = FRAMESIZE_HD;  // HD画質 (1280x720) に変更
#else
  config.frame_size = FRAMESIZE_HD;  // HD画質 (1280x720) に変更
#endif
  config.pixel_format = PIXFORMAT_JPEG;
  config.grab_mode = CAMERA_GRAB_WHEN_EMPTY;
  config.fb_location = CAMERA_FB_IN_PSRAM;
  config.jpeg_quality = 15;  // HD画質に合わせて品質を調整
  config.fb_count = 1;

  if (config.pixel_format == PIXFORMAT_JPEG) {
    if (psramFound()) {
      config.jpeg_quality = 12;  // HD画質用に品質を調整
#ifdef CAMERA_MODEL_M5STACK_CAMS3_UNIT
      config.fb_count = 2;
      config.frame_size = FRAMESIZE_HD;  // HD画質に設定
#else
      config.fb_count = 2;
      config.frame_size = FRAMESIZE_HD;  // HD画質に設定
#endif
      config.grab_mode = CAMERA_GRAB_LATEST;
      ESP_LOGI(TAG, "PSRAMあり: JPEG品質12, HD画質 (1280x720)");
    } else {
      config.frame_size = FRAMESIZE_VGA;  // PSRAMなしの場合はVGA画質
      config.fb_location = CAMERA_FB_IN_DRAM;
      ESP_LOGI(TAG, "PSRAMなし: VGA画質 (640x480) - メモリ制限のため");
    }
  } else {
    config.frame_size = FRAMESIZE_240X240;
#if CONFIG_IDF_TARGET_ESP32S3
    config.fb_count = 2;
#endif
    ESP_LOGI(TAG, "RGB/顔認識用設定");
  }

  esp_err_t err = esp_camera_init(&config);
  if (err != ESP_OK) {
    ESP_LOGE(TAG, "カメラの初期化に失敗しました。エラーコード: 0x%x", err);
    return false;
  }
  ESP_LOGI(TAG, "カメラの初期化が完了しました");

  sensor_t *s = esp_camera_sensor_get();
  if (s->id.PID == OV3660_PID) {
    s->set_vflip(s, 1);
    s->set_brightness(s, 1);
    s->set_saturation(s, -2);
    ESP_LOGI(TAG, "OV3660センサーの設定を調整しました: vflip=1, brightness=1, saturation=-2");
  }
  if (config.pixel_format == PIXFORMAT_JPEG) {
#ifdef CAMERA_MODEL_M5STACK_CAMS3_UNIT
    s->set_framesize(s, FRAMESIZE_HD);  // 1280x720
    ESP_LOGI(TAG, "JPEGフォーマット: フレームサイズをHDに設定しました (1280x720)");
#else
    s->set_framesize(s, FRAMESIZE_HD);   // 1280x720
    ESP_LOGI(TAG, "JPEGフォーマット: フレームサイズをHDに設定しました (1280x720)");
#endif
  }
  return true;
}

// 画像publish処理
void publish_camera_image() {
  static uint32_t image_counter = 0;

  // 画像送信頻度を下げる(5秒に1回)
  if (image_counter % 5 != 0) {
    image_counter++;
    return;
  }
  image_counter++;

  camera_fb_t *fb = esp_camera_fb_get();
  if (fb && fb->format == PIXFORMAT_JPEG) {
    ESP_LOGI(TAG, "画像を取得しました: %dバイト", fb->len);

    // サイズチェック(HD画質用に100KB以下に制限)
    if (fb->len > 102400) {
      ESP_LOGW(TAG, "画像サイズが大きすぎます: %dバイト > 100KB、スキップします", fb->len);
      esp_camera_fb_return(fb);
      return;
    }

    image_msg.header.stamp.sec = (int32_t)(millis() / 1000);
    image_msg.header.stamp.nanosec = (int32_t)((millis() % 1000) * 1000000);
    image_msg.header.frame_id.data = (char*)"camera";
    image_msg.header.frame_id.size = strlen("camera");
    image_msg.header.frame_id.capacity = strlen("camera") + 1;
    image_msg.format.data = (char*)"jpeg";
    image_msg.format.size = strlen("jpeg");
    image_msg.format.capacity = strlen("jpeg") + 1;
    if (image_msg.data.capacity < fb->len) {
      if (image_msg.data.data) free(image_msg.data.data);
      image_msg.data.data = (uint8_t*)malloc(fb->len);
      image_msg.data.capacity = fb->len;
      ESP_LOGD(TAG, "画像バッファを再確保しました: %dバイト", fb->len);
    }
    memcpy(image_msg.data.data, fb->buf, fb->len);
    image_msg.data.size = fb->len;
    rcl_ret_t pub_ret = rcl_publish(&image_publisher, &image_msg, NULL);
    if (pub_ret == RCL_RET_OK) {
      ESP_LOGI(TAG, "画像をパブリッシュしました: %dバイト", fb->len);
    } else {
      ESP_LOGW(TAG, "画像のパブリッシュに失敗しました: %d", pub_ret);
    }
    esp_camera_fb_return(fb);
  } else {
    ESP_LOGW(TAG, "画像の取得に失敗したか、JPEGフォーマットではありません");
  }
}

void setup() {
  delay(2000);
  Serial.begin(115200);
  esp_log_level_set(TAG, ESP_LOG_DEBUG);
  ESP_LOGI(TAG, "セットアップを開始します");

  // micro-ROS WiFi設定
  IPAddress agent_ip;
  agent_ip.fromString(MICRO_ROS_AGENT_IP);
  uint16_t agent_port = MICRO_ROS_AGENT_PORT;
  char ssid[] = WIFI_SSID;
  char password[] = WIFI_PASSWORD;
  set_microros_wifi_transports(ssid, password, agent_ip, agent_port);
  ESP_LOGI(TAG, "micro-ROS WiFiトランスポートを設定しました (SSID: %s, Agent IP: %s:%d)", ssid, MICRO_ROS_AGENT_IP, agent_port);

  // WiFi接続とmicro-ROSエージェント接続の確立を待つ
  ESP_LOGI(TAG, "micro-ROSエージェントとの接続を確立中...");
  delay(5000);  // WiFi接続の安定化を待つ

  allocator = rcl_get_default_allocator();

  // rclcサポート初期化(リトライ機能付き)
  int retry_count = 0;
  const int max_retries = 10;
  rcl_ret_t ret;

  while (retry_count < max_retries) {
    ret = rclc_support_init(&support, 0, NULL, &allocator);
    if (ret == RCL_RET_OK) {
      ESP_LOGI(TAG, "rclc_support_initが完了しました(試行回数: %d)", retry_count + 1);
      break;
    } else {
      retry_count++;
      ESP_LOGW(TAG, "rclc_support_init失敗(試行 %d/%d)、エラーコード: %d", retry_count, max_retries, ret);
      if (retry_count < max_retries) {
        delay(2000);  // 2秒待ってリトライ
      }
    }
  }

  if (ret != RCL_RET_OK) {
    ESP_LOGE(TAG, "rclc_support_initが最大試行回数後も失敗しました");
    error_loop(ret, "rclc_support_init");
  }

  // ノード作成
  RCCHECK(rclc_node_init_default(&node, NODE_NAME, "", &support));
  ESP_LOGI(TAG, "ノードを作成しました: %s", NODE_NAME);

  // Int32パブリッシャ作成
  RCCHECK(rclc_publisher_init_default(&publisher, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32), INT32_TOPIC));
  ESP_LOGI(TAG, "Int32パブリッシャを作成しました: %s", INT32_TOPIC);

  // 速度パブリッシャ作成
  RCCHECK(rclc_publisher_init_default(&speed_publisher, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Float32), SPEED_TOPIC));
  ESP_LOGI(TAG, "速度パブリッシャを作成しました: %s", SPEED_TOPIC);

  // タイマー作成
  RCCHECK(rclc_timer_init_default(&timer, &support, RCL_MS_TO_NS(TIMER_TIMEOUT_MS), timer_callback));
  ESP_LOGI(TAG, "タイマーを作成しました: %dms", TIMER_TIMEOUT_MS);

  // エグゼキュータ作成
  RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator));
  RCCHECK(rclc_executor_add_timer(&executor, &timer));
  ESP_LOGI(TAG, "エグゼキュータを作成しました");

  msg.data = 0;
  speed_msg.data = 0.0;

  // 画像パブリッシャ作成
  RCCHECK(rclc_publisher_init_default(&image_publisher, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(sensor_msgs, msg, CompressedImage), IMAGE_TOPIC));
  ESP_LOGI(TAG, "CompressedImageパブリッシャを作成しました: %s", IMAGE_TOPIC);

  // カメラ初期化
  if (!init_camera()) {
    ESP_LOGE(TAG, "カメラ初期化に失敗しました");
    error_loop(-1, "init_camera");
  }

#if defined(LED_GPIO_NUM)
  setupLedFlash(LED_GPIO_NUM);
  ESP_LOGI(TAG, "LEDフラッシュ初期化");
#endif
}

void loop() {
  delay(1000);
  RCSOFTCHECK(rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100)));
  publish_camera_image();
}

UnitCamS3 に上記コードを PlatformIO で書き込みます。

pio run -e esp32s3box -t upload

シリアルログをモニターして、 Raspberry Pi の WiFi AP に接続し、 micro-ROS Agent に接続できていることを確認します。

全て問題なければ、画像とダミーの速度データを micro-ROS Agent に送信し始めます。

pio device monitor-b 115200

ROS 2 トピックを確認する

UnitCam からデータが publish され、 micro-ROS Agent によって ROS2 トピックにデータが正常に転送されていれば、RPi 上で次を実行するとトピックが確認できます。

docker run --rm --net=host --ipc=host \
  -v /dev:/dev \
  -v /dev/shm:/dev/shm \
  -e ROS_DOMAIN_ID=0 \
  -e RMW_IMPLEMENTATION=rmw_fastrtps_cpp \
  ros:humble-ros-base \
  bash -lc 'source /opt/ros/humble/setup.bash; ros2 topic list -t'

今回の場合だと、以下の2つが表示されます:

  • /ego_vehicle/rgb_front/image_compressed [sensor_msgs/msg/CompressedImage]
  • /ego_vehicle/speedometer [std_msgs/msg/Float32]

Campaign をデプロイする

FleetWise は Campaign が有効化(承認)されてはじめてエッジに収集設定を配信します。
Campaign が WAITING_FOR_APPROVALSUSPENDED の状態だと、FWE 側ログで
Updating raw buffer configuration for 0 signals のように「収集対象 0」となり、S3 に送信されません。

マネージメントコンソールでキャンペーンを開き、「キャンペーンの概要」ページで「デプロイ」を選択します。
デプロイされると、 FWE のログに収集条件とデコーダーマニフェストを受信したログが確認できます。

車両に載せてみる

レゴで組んだ台にカメラを取り付けて、ダッシュボードに載せてみました。
M5 Stack 製品はレゴ穴が開いているものが多いので、プロトタイピング時の機械的な取り付けが容易です。

alt text

実走して、 S3 にアップされた内容を確認してみる

走行後、S3 バケットを確認すると次の 3 つのフォルダができていました。

  • raw-data/: FWE がアップロードしたファイル (Amazon Ion形式)
  • processed-data/: FleetWise によってIonファイルからデコードされたデータ (Parquet 形式 )
  • unstructured-data/: FleetWise によってIonファイルからデコードされたビジョンシステムデータ (画像など)

今回の場合は、 processd-data フォルダに速度データが Parquet 形式で格納されていました。
内容を確認してみると、以下のように画像データへのポインタ情報や、速度などの実データが格納されていました。

{
  "campaignName": "Ros2Campaign",
  "eventId": "1406428931",
  "vehicleName": "vehicle-ros2-test",
  "measure_name": "Vehicle.Cameras.Front.Image",
  "time": 1765690035337,
  "measure_value_STRUCT": {
    "Types.sensor_msgs_msg_CompressedImage": {
      "data": "s3://vision-system-data-123456789012-us-east-1/unstructured-data/c1387eca-6969-3366-9a42-c276f5fabf94-2025-12-14-05-27-15-337-vehicle-ros2-test-Vehicle.Cameras.Front.Image-data",
      "format": "jpeg",
      "header": {
        "stamp": {
          "sec": 17,
          "nanosec": 667000000
        },
        "frame_id": "camera"
      }
    },
    "Types.std_msgs_msg_Float32": null
  }
},
{
  "campaignName": "Ros2Campaign",
  "eventId": "1406428931",
  "vehicleName": "vehicle-ros2-test",
  "measure_name": "Vehicle.Speed",
  "time": 1765690036353,
  "measure_value_STRUCT": {
    "Types.sensor_msgs_msg_CompressedImage": null,
    "Types.std_msgs_msg_Float32": {
      "data": 41.29285
    }
  }
}

そして、 unstructured-data のほうの上記の S3 バケットの URI を確認してみると、画像ファイルとして保存されているのが確認できました。

alt text

まとめ

AWS IoT FleetWise の Vision System Data の仕組みを使うと、
車載カメラ画像のようなデータも最小限の設定で収集可能になります。

今回はカメラ画像を題材にしましたが、
Vision System Data は LiDAR のようなセンサーデータも収集可能です。

車両データ収集の基盤として IoT FleetWise は、最小限の設定で複数のデータ型(構造化・非構造化)を一元管理できるマネージドサービスですので、機会があればぜひ試してみて欲しいです。

参考

この記事をシェアする

FacebookHatena blogX

関連記事