PhotoSkill CaptureJpeg 功能实现
1. 概述
1.1 实现的功能
为灵犀机器人交互系统增加了 通过 HAL 相机抓取单帧 JPEG 图片 的完整功能链路,具体包含:
- RPC 远程触发拍照 :外部可通过
ControlTask服务,指定task_type=7(PICTURE)来远程触发拍照 - 自动抓取 HAL 相机画面 :调用
/aima/hal/camera/CaptureJpegImage服务,从指定相机(如head_stereo_left)抓取 JPEG 帧 - 图片本地持久化 :将 JPEG 数据保存到
/home/run/images/<时间戳>.jpg - 资源更新通知 :通过 ROS2 Topic
/aima/resource/update广播ResourceUpdate消息,通知PictureService刷新缓存 - 图片查询服务 (PictureService 端):提供
GetPictureList(列图片)+GetPicture(取图片内容)两个 RPC 服务,采用缓存模式加速查询
1.2 架构概览
外部调用 (ros2 service call ControlTask {task_type: 7, control_type: 1})
│
▼
┌─────────────────────────────────┐
│ interaction 项目 │
│ │
│ Scheduler (RPC 服务端) │
│ ├─ ControlTaskService() │ ← aimrte 高层 API,ServeOn 注册
│ └─ 分发到 Dispatcher │
│ │ │
│ Dispatcher │
│ ├─ DispatchControlTask() │
│ ├─ DispatchPicture(trigger) │ ← 根据 task_type 路由
│ └─ DispatchPhoto(type) │
│ │ │
│ TaskFactory │
│ └─ CreateTaskPhoto("CaptureJpeg") │
│ │ │
│ T1PhotoTaskDescription │
│ └─ CaptureJpeg() │ ← 组装 SkillParamList
│ │ │
│ Worker → PhotoSkill::Exec() │
│ ├─ CaptureJpegImage (RPC 调用) │ → HAL 相机服务
│ ├─ 写文件 /home/run/images/ │
│ └─ Publish ResourceUpdate │ → /aima/resource/update
└─────────────────────────────────┘
│ Topic: /aima/resource/update
▼
┌─────────────────────────────────┐
│ picture_service / resource_manager 项目 │
│ │
│ PictureChannel │
│ ├─ Subscribe /aima/resource/update │
│ └─ filter: RESOURCE_TYPE_PICTURE │
│ │ │
│ PictureModule (callback) │
│ └─ RefreshCache() │ ← 收到通知,重建缓存
│ │ │
│ GetPictureListServiceImpl │
│ └─ 返回 cached_list_ (内存) │ ← 不读磁盘
│ │
│ GetPictureServiceImpl │
│ └─ 读文件系统,返回二进制 │
└─────────────────────────────────┘
1.3 依赖的协议接口
| 接口文件 | 用途 | 所属仓库 |
|---|---|---|
interaction/srv/ControlTask.srv |
外部控制任务(拍照、移动、动画等) | interface |
resource_manager/msg/ResourceUpdate.msg |
资源更新通知消息 | interface |
resource_manager/msg/ResourceUpdateItem.msg |
资源更新项(key + path) | interface |
resource_manager/msg/PictureInfo.msg |
图片信息(picture_id) | interface |
resource_manager/srv/GetPictureList.srv |
图片列表查询 RPC | interface |
resource_manager/srv/GetPicture.srv |
单张图片获取 RPC | interface |
hal/camera/srv/CaptureJpegImage.srv |
HAL 相机 JPEG 抓帧 RPC | interface |
2. interaction 项目 --- 详细实现
2.1 新增文件
2.1.1 photo_params.h --- 拍照参数结构
cpp
enum class PhotoType {
kUnknown = 0,
StartPhoto = 1, // Insta360 开始录像
StopPhoto = 2, // Insta360 停止录像
StartPicture = 3, // Insta360 拍一张照片
CaptureJpeg = 4, // 从 HAL 相机抓取单帧 JPEG(**新增**)
};
class PhotoParams : public SkillParam {
void SetPhotoType(PhotoType type);
PhotoType GetPhotoType() const;
void SetCameraId(const std::string& id); // **新增**:指定相机 ID
std::string GetCameraId() const;
void SetTimeoutMs(uint32_t ms); // **新增**:等待新帧超时
uint32_t GetTimeoutMs() const;
};
设计要点:
- 继承
SkillParam,由 Worker 框架统一管理生命周期 - 构造函数自动设置
SkillType::PhotoSkill,确保路由到PhotoSkill CaptureJpeg模式下需要 camera_id 和 timeout_ms;Insta360 模式不需要
2.2 修改文件
2.2.1 photo_skill.h --- PhotoSkill 类声明
新增 include:
cpp
#include "aimdk_msgs/msg/resource_update.hpp" // ResourceUpdate 消息
#include "aimdk_msgs/srv/CaptureJpegImage.h" // CaptureJpegImage 服务
Option 结构(核心变化):
cpp
struct Option {
// 原有:Insta360 控制服务
aimdk_msgs::srv::res::ControlInsta360Proxy control_insta360_proxy;
// **新增**:HAL 相机 JPEG 抓帧服务代理
aimdk_msgs::srv::res::CaptureJpegImageProxy capture_jpeg_image_proxy{"aima/hal/camera"};
// **新增**:资源更新话题发布者
aimrte::Pub<aimdk_msgs::msg::ResourceUpdate> resource_update_pub_;
};
关键技术点 --- service_name 为什么是 "aima/hal/camera":
CaptureJpegImageProxy 是 aimdk_msgs::srv::res:: 命名空间下的自动生成类。它的构造函数接收 service_name 参数:
cpp
CaptureJpegImageProxy(const std::string& service_name = {})
GetMethodNames(service_name) 会生成最终的 ROS2 服务路径:
"ros2:/" + service_name + "/CaptureJpegImage"
若 service_name = "aima/hal/camera",则路径为:
ros2:/aima/hal/camera/CaptureJpegImage
不要带前导
/!若写成"/aima/hal/camera",会变成ros2://aima/hal/camera/CaptureJpegImage/CaptureJpegImage(双斜杠 + 方法名重复)。
aimrte 会将 ros2:/aima/hal/camera/CaptureJpegImage 映射为 ROS2 原生服务路径 /aima/hal/camera/CaptureJpegImage。
2.2.2 photo_skill.cpp --- PhotoSkill 实现
Init() 方法 --- 注册通信资源:
cpp
void PhotoSkill::Init(aimrte::ctx::ModuleCfg& cfg) {
using namespace aimrte::cfg;
// RPC 后端:注册两个服务代理
cfg[Module::Basic][Rpc::ros2]
.Def(option_.control_insta360_proxy) // Insta360 控制
.Def(option_.capture_jpeg_image_proxy); // HAL 相机抓帧(**新增**)
// Channel 后端:注册资源更新发布者
cfg[Module::Basic][Ch::ros2]
.Def(option_.resource_update_pub_, "/aima/resource/update"); // **新增**
}
Exec() 方法 --- CaptureJpeg 分支(核心流程):
步骤 1: 参数校验
├─ dynamic_cast<PhotoParams*>(param) 获取拍照参数
├─ 检查 getPhotoType() == CaptureJpeg
└─ 检查 camera_id 非空
步骤 2: 构建 CaptureJpegImage 请求
├─ 填充时间戳 (CommonRequest → RequestHeader → Time)
├─ 设置 camera_id
└─ 设置 timeout_ms
步骤 3: RPC 调用 HAL 相机服务
├─ 创建 rpc_ctx,设置超时 5 秒
├─ option_.capture_jpeg_image_proxy.Func.Call(rpc_ctx, jpeg_req, jpeg_resp).Sync()
└─ 检查调用结果 (res.OK())
步骤 4: 校验响应
├─ jpeg_resp.response.header.code == 0
├─ jpeg_resp.response.status.value == CommonState::SUCCESS
└─ jpeg.image.data 非空
步骤 5: 保存 JPEG 到磁盘
├─ 文件名: /home/run/images/<timestamp_ms>.jpg
├─ std::filesystem::create_directories 确保目录存在
└─ std::ofstream 二进制写入
步骤 6: 发布 ResourceUpdate 通知
├─ update_type = UPDATE_TYPE_CREATE (1)
├─ resource_type = RESOURCE_TYPE_PICTURE (1)
├─ resource_key = timestamp 字符串
├─ resource_path = 文件路径
└─ option_.resource_update_pub_.Publish(update_msg)
完整代码(CaptureJpeg 分支):
cpp
if (photo_type == PhotoType::CaptureJpeg) {
// 校验 camera_id
std::string camera_id = photo_param->GetCameraId();
if (camera_id.empty()) {
AIMRTE_ERROR("PhotoSkill: CaptureJpeg需要camera_id");
return false;
}
// 构建请求
aimdk_msgs::srv::CaptureJpegImage::Request jpeg_req;
aimdk_msgs::srv::CaptureJpegImage::Response jpeg_resp;
{
auto now = std::chrono::system_clock::now();
auto now_sec = std::chrono::duration_cast<std::chrono::seconds>(now.time_since_epoch()).count();
auto now_nsec = std::chrono::duration_cast<std::chrono::nanoseconds>(now.time_since_epoch()).count() % 1000000000;
jpeg_req.request.header.stamp.sec = static_cast<int32_t>(now_sec);
jpeg_req.request.header.stamp.nanosec = static_cast<uint32_t>(now_nsec);
}
jpeg_req.camera_id = camera_id;
jpeg_req.timeout_ms = photo_param->GetTimeoutMs();
// RPC 调用
aimrt::rpc::Context rpc_ctx;
rpc_ctx.SetTimeout(std::chrono::seconds(5));
if (auto res = option_.capture_jpeg_image_proxy.Func.Call(rpc_ctx, jpeg_req, jpeg_resp).Sync(); not res.OK()) {
AIMRTE_ERROR("PhotoSkill: 调用CaptureJpegImage失败, camera={}, error: {}", camera_id, res.ToString());
return false;
}
// 校验响应
if (jpeg_resp.response.header.code != 0 ||
jpeg_resp.response.status.value != aimdk_msgs::msg::CommonState::SUCCESS) {
AIMRTE_ERROR("PhotoSkill: CaptureJpegImage失败, code={}, status={}, msg={}",
jpeg_resp.response.header.code,
jpeg_resp.response.status.value,
jpeg_resp.response.message);
return false;
}
// 保存文件
auto now_ms = std::chrono::duration_cast<std::chrono::milliseconds>(
std::chrono::system_clock::now().time_since_epoch()).count();
std::string output_file = "/home/run/images/" + std::to_string(now_ms) + ".jpg";
std::filesystem::create_directories("/home/run/images");
std::ofstream ofs(output_file, std::ios::binary | std::ios::trunc);
ofs.write(reinterpret_cast<const char*>(jpeg.image.data.data()),
static_cast<std::streamsize>(jpeg.image.data.size()));
ofs.close();
// 发布资源更新通知
aimdk_msgs::msg::ResourceUpdate update_msg;
update_msg.update_type = aimdk_msgs::msg::ResourceUpdate::UPDATE_TYPE_CREATE;
update_msg.resource_type = aimdk_msgs::msg::ResourceUpdate::RESOURCE_TYPE_PICTURE;
update_msg.update_item.resource_key = std::to_string(now_ms);
update_msg.update_item.resource_path = output_file;
option_.resource_update_pub_.Publish(update_msg);
return true;
}
2.2.3 t1_photo.h/cpp --- 任务描述
新增 CaptureJpeg 工厂方法:
cpp
std::shared_ptr<SkillParamList> T1PhotoTaskDescription::CaptureJpeg() {
auto skill_param_list = std::make_shared<SkillParamList>();
auto photo_params = std::make_shared<interaction::PhotoParams>();
photo_params->SetPhotoType(PhotoType::CaptureJpeg);
photo_params->SetCameraId("head_stereo_left"); // 左侧立体相机
photo_params->SetTimeoutMs(2000); // 等待新帧最多 2 秒
skill_param_list->PushSkillParam(photo_params);
return skill_param_list;
}
GetSkillParamList 路由:
cpp
// 新增 CaptureJpeg 路由分支
if (task_id == "CaptureJpeg") {
return CaptureJpeg();
}
2.2.4 dispatcher.h/cpp --- 事件分发
DispatchControlTask --- 新增 task_type 路由:
cpp
case aimdk_msgs::srv::ControlTask::Request::TASK_TYPE_PICTURE: // task_type=7
DispatchPicture(req.control_type == aimdk_msgs::srv::ControlTask::Request::CONTROL_TYPE_START);
break;
DispatchPicture --- 新增方法:
cpp
void Dispatcher::DispatchPicture(bool trigger) {
if (!trigger) return; // 非 START 直接忽略
auto task = TaskFactory::GetInstance()->CreateTaskPhoto("CaptureJpeg");
if (task == nullptr) {
AIMRTE_ERROR("Failed to create task for photo type: CaptureJpeg");
return;
}
AIMRTE_INFO("创建Photo task成功, photo_type: CaptureJpeg");
worker_manager_->ExecTask(task); // 投递给 WorkerManager 执行
}
Dispatcher::DispatchPhoto --- 修改(已有,处理 task_type=6 即 Insta360 控制):
cpp
// 在 switch 中新增 TASK_TYPE_PICTURE case
case aimdk_msgs::srv::ControlTask::Request::TASK_TYPE_PICTURE:
DispatchPicture(req.control_type == ...START);
break;
2.2.5 scheduler.h/cpp --- 中央调度器
Scheduler 中 ControlTask 服务的声明和注册 原本已存在 ------我们在 dispatcher 层新增了 TASK_TYPE_PICTURE 的路由分支。
注册链:
scheduler.h:79
aimdk_msgs::srv::res::ControlTask control_task_;
scheduler.cpp:41 (OnConfigure)
.Def(option_.control_task_) // 绑定到 ros2 RPC backend
scheduler.cpp:72 (OnInitialize)
option_.control_task_.Func.WhenInit()
.ServeOn(option_.exe_,
std::bind(&Scheduler::ControlTaskService, ...));
scheduler.cpp:273 (ControlTaskService)
dispatcher_->DispatchControlTask(req);
2.2.6 skill_manager.cpp --- Skill 注册
新增 PhotoSkill 注册:
cpp
#include "./atomic/photo_skill.h"
skill_map_[SkillType::PhotoSkill] = std::make_shared<PhotoSkill>();
注意:这是框架要求------每个 AtomicSkill 必须在 SkillManager::Init() 中注册到 skill_map_,运行时 Worker 通过 SkillType 查找对应的 Skill 实例。
2.2.7 cmake/GetAimRTe.cmake --- 协议依赖
新增 resource_manager 协议:
cmake
set(AIMRTE_BUILD_SOME_OF_ROBOT_PROTOCOLS
"hal;interaction;mc;hds;event;face_ui;algo;sm;app_proxy;housekeeper;insta360;resource_manager")
最后新增了 resource_manager,使 interaction 可以引用 ResourceUpdate 消息类型。
3. picture_service / resource_manager 项目 --- 详细实现
3.1 整体架构
src/
├── app/main.cpp # 入口:解析参数、注册模块、启动 AimRT
├── module/
│ ├── module.h/cpp # PictureModule:串联 RPC + Channel
│ ├── picture_rpc.h/cpp # GetPictureList + GetPicture 服务实现
│ └── picture_ch.h/cpp # Channel 订阅:监听 /aima/resource/update
└── install/
└── linux/bin/
├── cfg/picture_service.yaml # 运行时配置
└── em_run.sh # 启动脚本
3.2 逐文件说明
3.2.1 picture_ch.h/cpp --- Channel 订阅层
职责 :订阅 /aima/resource/update 话题,过滤 PICTURE 类型的资源更新,通过回调通知上层。
cpp
class PictureChannel {
public:
explicit PictureChannel(aimrt::CoreRef core) : core_(core) {}
void RegisterSubscribers(); // AimRT 底层 API 方式订阅话题
std::function<void(const std::shared_ptr<const aimdk_msgs::msg::ResourceUpdate>&)>
on_resource_update; // 上层回调
};
订阅实现 (使用 aimrt::channel::Subscribe<T> 底层 API):
cpp
void PictureChannel::RegisterSubscribers() {
auto channel = core_.GetChannelHandle();
auto sub = channel.GetSubscriber("/aima/resource/update");
bool ret = aimrt::channel::Subscribe<aimdk_msgs::msg::ResourceUpdate>(
sub,
[this](const std::shared_ptr<const aimdk_msgs::msg::ResourceUpdate>& msg) {
// 只处理图片类型的更新通知
if (msg->resource_type !=
aimdk_msgs::msg::ResourceUpdate::RESOURCE_TYPE_PICTURE) {
return;
}
AIMRT_INFO("收到资源更新通知: update_type={}, resource_key={}",
msg->update_type, msg->update_item.resource_key);
if (on_resource_update) on_resource_update(msg);
});
}
设计要点:
on_resource_update是回调函数指针,由PictureModule在外部绑定,实现 Channel 层和 RPC 层的解耦- 订阅回调中过滤
resource_type != RESOURCE_TYPE_PICTURE,避免非图片更新触发不必要的缓存刷新 - 使用
std::shared_ptr<const T>回调签名(AimRT Channel API 规范)
3.2.2 picture_rpc.h/cpp --- RPC 服务实现
GetPictureListServiceImpl --- 图片列表(缓存模式):
cpp
class GetPictureListServiceImpl : public aimdk_msgs::srv::GetPictureListSyncService {
// 继承自动生成的 SyncService 基类
aimrt::rpc::Status GetPictureList(...) override {
std::lock_guard<std::mutex> lock(cache_mutex_);
rsp.picture_list = cached_list_; // 直接返回缓存,不读磁盘
rsp.header.status.value = 1;
return {};
}
void RefreshCache() {
// 扫描 image_dir_,重建新缓存
std::vector<aimdk_msgs::msg::PictureInfo> new_list;
for (const auto& entry : fs::directory_iterator(image_dir_)) {
if (!entry.is_regular_file()) continue;
std::string ext = tolower(entry.path().extension());
if (ext in [.jpg, .jpeg, .png, .gif, .bmp]) {
PictureInfo info;
info.picture_id = std::stoll(entry.path().stem().string());
new_list.push_back(info);
}
}
// 用 swap 交换,最小化持锁时间
std::lock_guard<std::mutex> lock(cache_mutex_);
cached_list_.swap(new_list);
}
private:
std::mutex cache_mutex_; // 保护缓存
std::vector<aimdk_msgs::msg::PictureInfo> cached_list_; // 内存缓存
};
GetPictureServiceImpl --- 单张图片获取:
cpp
class GetPictureServiceImpl : public aimdk_msgs::srv::GetPictureSyncService {
aimrt::rpc::Status GetPicture(...) override {
// 按 picture_id 尝试各扩展名
for (const auto& ext : {".jpg", ".jpeg", ".png", ".gif", ".bmp"}) {
std::string test_path = image_dir_ + "/" + std::to_string(req.picture_id) + ext;
if (fs::exists(test_path)) {
image_path = test_path;
break;
}
}
// 读取整个文件为二进制
std::ifstream file(image_path, std::ios::binary | std::ios::ate);
std::streamsize size = file.tellg();
file.seekg(0);
std::vector<uint8_t> buffer(size);
file.read(reinterpret_cast<char*>(buffer.data()), size);
rsp.picture_data = buffer;
}
};
缓存策略:
- 启动时调用一次
RefreshCache()预建缓存 - 收到
/aima/resource/update通知时再调一次RefreshCache()刷新 - GetPictureList 始终返回缓存,不访问磁盘 → O(1) 响应
- GetPicture 每次都读磁盘(因为图片数据大,不适合全部缓存到内存)
3.2.3 module.h/cpp --- 模块入口
cpp
class PictureModule : public aimrt::ModuleBase {
bool Initialize(aimrt::CoreRef core) override {
// 1. 创建 RPC 服务实例
rpc_get_picture_list_ = std::make_shared<GetPictureListServiceImpl>(core_.GetLogger());
rpc_get_picture_ = std::make_shared<GetPictureServiceImpl>(core_.GetLogger());
// 2. 注册 RPC 服务到框架
core_.GetRpcHandle().RegisterService(rpc_get_picture_list_.get());
core_.GetRpcHandle().RegisterService(rpc_get_picture_.get());
// 3. 注册 Channel 订阅
ch_ = std::make_shared<PictureChannel>(core_);
ch_->RegisterSubscribers();
// 4. 设置回调:收到资源更新 → 刷新缓存(Channel → RPC 桥接)
ch_->on_resource_update = [this](const std::shared_ptr<const ResourceUpdate>&) {
rpc_get_picture_list_->RefreshCache();
};
// 5. 启动时预建缓存
rpc_get_picture_list_->RefreshCache();
}
};
设计要点:
- Channel 层和 RPC 层完全解耦:
PictureChannel不知道 RPC 服务的存在,只负责订阅和回调 - PictureModule 通过 lambda 将两者桥接,符合单一职责原则
3.2.4 picture_service.yaml --- 配置文件
yaml
aimrt:
log:
core_lvl: Info
backends:
- type: console
executor:
executors:
- name: picture_executor
type: asio_thread
options:
thread_num: 1
plugin:
plugins:
- name: ros2_plugin
path: libaimrt_ros2_plugin.so
options:
node_name: picture_service
rpc:
backends:
- type: ros2
servers_options:
- func_name: "(.*)"
enable_backends: [ros2]
channel:
backends:
- type: ros2
options:
sub_topics_options: # ← 内层配置(实际不生效,但保留)
- topic_name: "/aima/resource/update"
enable_backends: [ros2]
sub_topics_options: # ← 外层配置(实际生效)
- topic_name: "/aima/resource/update"
enable_backends: [ros2]
PictureModule:
executor_name: "picture_executor"
关键技术点 --- Channel 双层配置:
- AimRT Channel 的 topic 订阅需要同时在
channel.sub_topics_options(外层)和channel.backends[0].options.sub_topics_options(内层)都声明 topic - 实际生效的是外层
channel.sub_topics_options;内层配置虽然报告 "unused" warning 但无害 - 这是参考
coreon-fusion项目已验证的配置模式
3.2.5 em_run.sh --- 启动脚本
bash
#!/bin/bash
source /opt/ros/humble/setup.bash
cd $(dirname $0)
export LD_LIBRARY_PATH=../lib:./:$LD_LIBRARY_PATH
./picture_service --cfg_file_path=cfg/picture_service.yaml
3.2.6 cmake/GetAimRT.cmake --- 关键配置
cmake
set(AIMRT_USE_LOCAL_PROTOC_COMPILER ON) # **关键**:交叉编译时使用宿主 protoc
设为
OFF时,AimRT 框架会构建protobuf::protoc目标(ARM 二进制),交叉编译时无法在 x86 宿主机上执行,导致protobuf::protoc: not found错误。
3.2.7 cmake/GetAimRTe.cmake --- 协议导入
cmake
set(AIMRTE_IMPORT_PROTOCOL_ONLY ON) # 只导入协议,不导入 aimrte 运行时
set(AIMRTE_BUILD_SOME_OF_ROBOT_PROTOCOLS "resource_manager") # 只编译 resource_manager 协议
if(CMAKE_CROSSCOMPILING)
# 补丁:修复交叉编译时 protoc 调用问题
# 将 add_custom_command 中的 COMMAND ${original_protoc}
# 替换为 generator expression,优先使用宿主 protoc
...
endif()
4. 完整执行流程(端到端)
4.1 触发拍照
Step 1. 外部调用
ros2 service call /aimdk_5Fmsgs/srv/ControlTask \
aimdk_msgs/srv/ControlTask \
'{header: {header: {stamp: {sec: 0, nanosec: 0}}},
control_type: 1, task_type: 7}'
control_type=1 → CONTROL_TYPE_START(开始)
task_type=7 → TASK_TYPE_PICTURE(图片任务)
4.2 interaction 端处理链
Step 2. aimrte RPC Backend 接收请求
ROS2 服务 /aimdk_5Fmsgs/srv/ControlTask
→ aimrte ros2 backend 反序列化
→ 路由到 Scheduler::ControlTaskService()
Step 3. Scheduler → Dispatcher
Scheduler::ControlTaskService()
→ dispatcher_->DispatchControlTask(req)
Step 4. Dispatcher 路由
switch (req.task_type):
case TASK_TYPE_PICTURE (7):
trigger = (req.control_type == START) // true
DispatchPicture(true)
Step 5. 创建 Task
TaskFactory::CreateTaskPhoto("CaptureJpeg")
→ T1PhotoTaskDescription::GetSkillParamList("CaptureJpeg")
→ CaptureJpeg()
返回 SkillParamList:
[PhotoParams { type=CaptureJpeg, camera="head_stereo_left", timeout=2000ms }]
Step 6. WorkerManager 执行
worker_manager_->ExecTask(task)
→ Worker 取出 SkillParamList 中的 PhotoParams
→ 通过 skill_map_[PhotoSkill] 找到 PhotoSkill 实例
→ PhotoSkill::Exec(photo_params)
4.3 PhotoSkill 执行
Step 7. PhotoSkill::Exec() --- CaptureJpeg 分支
7a. 参数校验
├─ dynamic_cast<PhotoParams*>(param) ✓
├─ GetPhotoType() == CaptureJpeg ✓
└─ GetCameraId() = "head_stereo_left" ✓
7b. 构建请求
├─ RequestHeader.stamp = 当前时间戳 (sec + nanosec)
├─ camera_id = "head_stereo_left"
└─ timeout_ms = 2000
7c. RPC 调用 HAL 相机服务
CaptureJpegImageProxy.Func.Call(rpc_ctx, req, resp).Sync()
→ aimrte ros2 rpc backend
→ ROS2 服务 /aima/hal/camera/CaptureJpegImage
→ HAL 相机模块响应(返回 JPEG 数据)
7d. 校验响应
├─ code == 0 ✓
├─ status == SUCCESS ✓
└─ jpeg.image.data 非空 ✓
7e. 保存文件
/home/run/images/1778993069389.jpg
大小: ~xxx bytes, 分辨率: WxH
7f. 发布 ResourceUpdate
→ Topic: /aima/resource/update
→ 消息内容:
{
update_type: CREATE (1),
resource_type: PICTURE (1),
resource_key: "1778993069389",
resource_path: "/home/run/images/1778993069389.jpg"
}
4.4 picture_service 端处理
Step 8. PictureChannel 收到 ResourceUpdate
Channel 回调 → filter: resource_type == PICTURE ✓
→ on_resource_update(msg)
Step 9. PictureModule 回调
[lambda]: rpc_get_picture_list_->RefreshCache()
Step 10. RefreshCache 刷新缓存
├─ 扫描 /home/run/images/
├─ 找到 3 张 .jpg(包括刚存的那张)
├─ lock_guard 持锁
├─ cached_list_.swap(new_list) // 原子替换
└─ 日志: "缓存已刷新, 3 张图片"
4.5 外部查询
Step 11. 获取图片列表
ros2 service call /aimdk_5Fmsgs/srv/GetPictureList \
aimdk_msgs/srv/GetPictureList \
'{header: {header: {stamp: {sec: 0, nanosec: 0}}}}'
→ GetPictureListServiceImpl::GetPictureList()
→ lock_guard 持锁,返回 cached_list_(内存)
→ 响应: [picture_id=1778992494706, picture_id=1778993069389, picture_id=1778990734849]
Step 12. 获取具体图片
ros2 service call /aimdk_5Fmsgs/srv/GetPicture \
aimdk_msgs/srv/GetPicture \
'{header: {header: {stamp: {sec: 0, nanosec: 0}}}, picture_id: 1778993069389}'
→ GetPictureServiceImpl::GetPicture()
→ 读文件 /home/run/images/1778993069389.jpg
→ 响应: picture_data = [JPEG 二进制数据]
5. 关键技术决策
5.1 aimrte Proxy 的 service_name 约定
规则 :service_name 参数 不带前导 / 且 不带方法名。
正确: "aima/hal/camera" → ros2:/aima/hal/camera/CaptureJpegImage
错误: "/aima/hal/camera" → ros2://aima/hal/camera/CaptureJpegImage/CaptureJpegImage
错误: "/aima/hal/camera/CaptureJpegImage" → 会重复 append 方法名
原因:GetMethodNames(service_name) 自动在 service_name 后追加 "/" + MethodName。
5.2 Channel 配置的双层结构
AimRT 的 Channel topic 订阅要求 YAML 中在两处声明:
yaml
channel:
backends[0].options.sub_topics_options: [...] # 内层(框架需要,但标记 unused)
sub_topics_options: [...] # 外层(实际生效)
这是框架行为,不这样写 topic 不会出现在 ros2 topic list 中。
5.3 缓存策略
- GetPictureList:缓存模式。启动时预建 + 收到通知时刷新。磁盘扫描只在更新时发生,查询是 O(1)
- GetPicture:直接读磁盘。图片数据可能很大,不适合全部缓存
5.4 交叉编译 protoc 问题
AIMRT_USE_LOCAL_PROTOC_COMPILER OFF 时,AimRT 框架使用 protobuf::protoc CMake target(交叉编译的 ARM 二进制),无法在 x86 宿主机运行。设为 ON 后使用宿主系统安装的 protoc。
6. 文件清单
interaction 项目
| 文件 | 操作 | 说明 |
|---|---|---|
src/skill/atomic/photo_skill.h |
修改 | 新增 CaptureJpegImageProxy + ResourceUpdate Pub |
src/skill/atomic/photo_skill.cpp |
修改 | 新增 CaptureJpeg 分支 + 文件保存 + 通知发布 |
src/skill/params/photo_params.h |
修改 | 新增 CaptureJpeg 枚举 + camera_id + timeout_ms |
src/task_description/t1_photo.h |
修改 | 新增 CaptureJpeg() 声明 |
src/task_description/t1_photo.cpp |
修改 | 新增 CaptureJpeg() 实现 |
src/scheduler/dispatcher.h |
修改 | 新增 DispatchPicture() 声明 |
src/scheduler/dispatcher.cpp |
修改 | 新增 DispatchPicture() 实现 + TASK_TYPE_PICTURE 路由 |
src/skill/skill_manager.cpp |
修改 | 新增 PhotoSkill 注册 |
cmake/GetAimRTe.cmake |
修改 | 新增 resource_manager 协议依赖 |
picture_service / resource_manager 项目
| 文件 | 操作 | 说明 |
|---|---|---|
src/module/picture_ch.h |
新增 | Channel 订阅层声明 |
src/module/picture_ch.cpp |
新增 | Channel 订阅层实现(ResourceUpdate 监听) |
src/module/picture_rpc.h |
修改 | 新增 RefreshCache() + cache 成员 |
src/module/picture_rpc.cpp |
修改 | 新增 RefreshCache() 实现,GetPictureList 改为缓存模式 |
src/module/module.h |
修改 | 新增 PictureChannel 成员 |
src/module/module.cpp |
修改 | 串联 Channel → RPC 缓存刷新 |
src/install/linux/bin/cfg/picture_service.yaml |
修改 | 新增 Channel 配置(双层结构) |
cmake/GetAimRT.cmake |
修改 | AIMRT_USE_LOCAL_PROTOC_COMPILER 改为 ON |
cmake/GetAimRTe.cmake |
修改 | 新增 resource_manager 协议 + 交叉编译补丁 |
CMakeLists.txt |
修改 | project 名改为 resource_manager |
interface 项目(由组长定义
| 文件 | 说明 |
|---|---|
ros2/robot/resource_manager/msg/ResourceUpdate.msg |
资源更新消息 |
ros2/robot/resource_manager/msg/ResourceUpdateItem.msg |
资源更新项 |
ros2/robot/resource_manager/msg/PictureInfo.msg |
图片信息 |
ros2/robot/resource_manager/srv/GetPictureList.srv |
图片列表 RPC |
ros2/robot/resource_manager/srv/GetPicture.srv |
单张图片 RPC |
ros2/robot/hal/camera/srv/CaptureJpegImage.srv |
HAL 相机 JPEG 抓帧 RPC |
7. 测试命令
bash
# 加载环境
source /opt/ros/humble/setup.bash
source <install_dir>/setup.bash
# 触发拍照(task_type=7 为 PICTURE,control_type=1 为 START)
ros2 service call /aimdk_5Fmsgs/srv/ControlTask \
aimdk_msgs/srv/ControlTask \
'{header: {header: {stamp: {sec: 0, nanosec: 0}}}, control_type: 1, task_type: 7}'
# 查图片列表(缓存模式,不读磁盘)
ros2 service call /aimdk_5Fmsgs/srv/GetPictureList \
aimdk_msgs/srv/GetPictureList \
'{header: {header: {stamp: {sec: 0, nanosec: 0}}}}'
# 取具体图片
ros2 service call /aimdk_5Fmsgs/srv/GetPicture \
aimdk_msgs/srv/GetPicture \
'{header: {header: {stamp: {sec: 0, nanosec: 0}}}, picture_id: 1778993069389}'
# 直接看文件
ls -la /home/run/images/