惯导移动机器人控制说明

更新时间:2026-04-29 07:16:48LLM 副本以 Markdown 格式查看下载 PDF

文档目录

  1. 概述与功能介绍
  2. 初始化与媒体适配
  3. 语音下载注册
  4. 复杂业务协议
  5. 算法 SDK 接口

为降低设备侧集成成本,方便设备与 App / 云端交互,本文将 IoT 与媒体初始化、语音资源下载、算法 SDK 以及惯导移动机器人协议等复杂控制封装为对外 API。应用开发者按头文件声明注册回调并调用上报接口,即可完成协议侧数据收发与状态同步。

功能介绍

当前 API 主要提供以下方面的能力:

  • 完成机器人侧 IoT / 媒体适配 初始化,包括音视频事件、环形缓冲、实时数据传输状态回调等。
  • 完成 机器人语音 / 宠物语音 下载目录与结果回调注册。
  • 完成 惯导移动机器人复杂协议 的 SET / QUERY 命令分发:通过回调将解码后的命令与参数交付业务;设备侧数据同步时调用相应 response / push / report 接口完成上报。
  • 完成 算法 SDK 的模型配置、任务管理、传感器接入、地图管理与感知服务集成。

API 总体关系图

App 面板
云端
SDK
初始化与媒体适配
语音下载注册
复杂业务协议
算法 SDK 接口
设备业务逻辑
response / push / report

当前 API 支持的能力与命令概览

分类 标识/接口 方向/用途
IoT 初始化 ty_movbot_iot_init 设备侧初始化
流事件注册 ty_movbot_media_av_event_init 设备侧初始化
媒体适配 ty_movbot_media_adapter_init 设备侧初始化
环形缓冲 ty_movbot_media_ring_buffer_init 设备侧初始化
服务状态回调 ty_movbot_server_init 设备侧初始化
语音下载 ty_movbot_voice_download_init 设备侧注册
宠物语音下载 ty_movbot_pet_voice_download_init 设备侧注册
跟随控制 MOVBOT_FOLLOW_CONTROL_REQ_SET / QUERY 面板/云端 -> 设备
遥控控制 MOVBOT_REMOTE_CONTROL_SET 面板/云端 -> 设备
路径编辑 MOVBOT_PATH_EDIT_REQ_SET 面板/云端 -> 设备
区域设置 MOVBOT_ZONE_SET / QUERY 面板/云端 -> 设备
AI 检测 MOVBOT_AI_DETECT_SET / QUERY 面板/云端 -> 设备
宠物语音 MOVBOT_VOICE_PLAY_* 面板/云端 -> 设备
录像定时 MOVBOT_RECORD_SCHEDULE_SET / QUERY 面板/云端 -> 设备
巡查定时 MOVBOT_PATROL_SCHEDULE_SET / QUERY 面板/云端 -> 设备
休眠定时 MOVBOT_DORMANCY_SCHEDULE_SET / QUERY 面板/云端 -> 设备
声音勿扰 MOVBOT_SOUND_SCHEDULE_SET / QUERY 面板/云端 -> 设备
灯光勿扰 MOVBOT_LIGHT_SCHEDULE_SET / QUERY 面板/云端 -> 设备
录像策略 MOVBOT_VIDEO_RECORD_SET / QUERY 面板/云端 -> 设备
存储信息 MOVBOT_STORAGE_INFO_QUERY 面板/云端 -> 设备
存储格式化 MOVBOT_STORAGE_FORMAT_SET / QUERY 面板/云端 -> 设备
设备信息 MOVBOT_DEVICE_INFO_QUERY 面板/云端 -> 设备
提示音 MOVBOT_PROMPT_SOUND_SET / QUERY 面板/云端 -> 设备
算法初始化 tuya_robot_nav_sdk_init_ex 设备侧初始化
任务管理 tuya_robot_add_task / pause / resume / cancel 设备侧控制
传感器接入 tuya_robot_register_new_sensor / add_sensor_data 设备侧数据接入
地图管理 tuya_robot_switch_map / get_all_map_id / get_current_trajectory 设备侧能力
感知服务 tuya_robot_perception_init 设备侧初始化

对外头文件一览

头文件 作用
ty_movbot_sdk_init.h 机器人侧 IoT/媒体适配初始化、音视频事件、环形缓冲、服务端状态回调
ty_movbot_api.h 语音/宠物语音下载目录与结果回调注册
ty_movbot_func.h MovBot 复杂协议命令枚举、请求/应答结构体、MQTT 侧 SET/QUERY 回调注册及主动上报接口
tuya_robot_nav_sdk.h 算法 SDK 对外接口,包含模型配置、任务管理、传感器接入、地图管理与感知服务

通用约定

返回值: 接口返回 OPERATE_RET,成功一般为 OPRT_OK,其余见 tuya_error_code.h

初始化与媒体适配(ty_movbot_sdk_init.h)

功能说明: 本节描述媒体适配、环形缓冲与传输状态相关的类型与初始化接口。参数中的通道号、事件枚举等与 流媒体模块 保持一致。

集成顺序建议

典型调用顺序如下(具体以产品启动流程为准):

  1. ty_movbot_iot_init — 注册 IoT 侧能力
  2. ty_movbot_media_av_event_init — 注册音视频流事件回调
  3. ty_movbot_media_adapter_init — 配置媒体适配与设备编解码信息
  4. ty_movbot_media_ring_buffer_init — 按通道初始化环形缓冲
  5. ty_movbot_server_init — 注册实时数据传输状态回调

流程图:

设备应用svc_movbot_api流媒体模块ty_movbot_iot_init()ty_movbot_media_av_event_init()注册流事件回调ty_movbot_media_adapter_init()配置媒体适配参数ty_movbot_media_ring_buffer_init()初始化环形缓冲ty_movbot_server_init()等待传输状态回调设备应用svc_movbot_api流媒体模块

回调类型

MOVBOT_AV_STREAM_EVENT_CB

参数说明:

参数 类型 说明
channel INT_T 媒体通道号,与流媒体通道定义一致
event MEDIA_STREAM_EVENT_E 媒体流事件类型(定义见 tuya_ipc_media_stream_event.h 等)
args PVOID_T 事件附带数据指针,具体类型依 event 而定;无附加数据时可能为 NULL

MOVBOT_TRANS_EVENT_CB

参数说明:

参数 类型 说明
onoff int 实时数据传输状态;头文件注释为 start/end 类开关语义,具体取值以业务约定为准

结构体 TY_SDK_MEDIA_ADAPTER_S

成员说明:

成员 类型 说明
enable BOOL_T FALSE 时其余字段无效,表示不启用该适配配置
live_mode TRANS_DEFAULT_QUALITY_E 多码流场景下直播预览默认画质
media_event_cb MEDIA_STREAM_EVENT_CB 媒体事件回调
rev_audio_cb MEDIA_RECV_AUDIO_CB App → 设备 音频 下行回调
rev_video_cb MEDIA_RECV_VIDEO_CB App → 设备 视频 下行回调
rev_file_cb MEDIA_RECV_FILE_CB App → 设备文件类数据回调
get_snapshot_cb MEDIA_GET_SNAPSHOT_CB 抓拍/截图获取回调

结构体 DEVICE_SDK_MEDIA_INFO_S

成员说明:

成员 类型 说明
av_encode_info IPC_MEDIA_INFO_T 音视频编码参数(见 tuya_ipc_media_stream.h 等)
audio_decode_info MEDIA_AUDIO_DECODE_INFO_T 音频解码参数
max_pic_len INT_T 单帧图像缓冲上限,默认100 单位:KB

初始化函数说明

ty_movbot_iot_init

参数说明:

参数 类型 说明
alarm_types CONST TUYA_ALARM_TYPE_E * 要向 IPC 告警/事件模块注册的告警类型数组首指针
alarm_type_cnt UINT_T alarm_types 元素个数,必须 ≥ 1

ty_movbot_media_av_event_init

参数说明:

参数 类型 说明
event_cb MOVBOT_AV_STREAM_EVENT_CB 音视频流事件回调

ty_movbot_media_adapter_init

参数说明:

参数 类型 说明
p_media_adatper_info TY_SDK_MEDIA_ADAPTER_S * 媒体适配参数
p_media_infos DEVICE_SDK_MEDIA_INFO_S * 设备侧编解码与最大图像尺寸信息

ty_movbot_media_ring_buffer_init

参数说明:

参数 类型 说明
pMediaInfo CONST DEVICE_SDK_MEDIA_INFO_S * 与媒体环形缓冲一致的媒体信息
max_buffer_seconds INT_T 环形缓冲时长(秒),建议 6~10 秒
channel INT_T 媒体通道号

ty_movbot_server_init

参数说明:

参数 类型 说明
event_handler MOVBOT_TRANS_EVENT_CB 实时数据传输状态回调(开始/结束等)

语音下载注册(ty_movbot_api.h)

功能说明: 配置 机器人语音宠物语音 的本地存储路径及下载结果通知。路径需可写。

下载流程图

云端语音资源
下载模块
保存到本地目录
结果回调
设备业务处理
应用语音或上报状态

回调类型

USER_VOICE_LOAD_CB

参数说明:

参数 类型 说明
result int 机器人语音文件下载结果
voice_id int 语音资源 ID(整型)

USER_PET_VOICE_LOAD_CB

参数说明:

参数 类型 说明
result int 宠物语音下载结果
voice_id const char * 宠物语音字符串 ID;指针生命周期以实现为准,回调内应尽快拷贝

初始化函数说明

ty_movbot_voice_download_init

参数说明:

参数 类型 说明
path CHAR_T * 语音文件存储目录路径,需可写
file_name CHAR_T * 存储用文件名
sets_handler USER_VOICE_LOAD_CB 下载完成后的结果回调

ty_movbot_pet_voice_download_init

参数说明:

参数 类型 说明
path CHAR_T * 宠物语音文件存储目录
sets_handler USER_PET_VOICE_LOAD_CB 下载结果回调

复杂业务协议(ty_movbot_func.h)

功能说明: 本节对应惯导移动机器人相关复杂命令。通过 ty_movbot_complex_func_register 注册 SET / QUERY 处理函数,在回调中根据 cmd 解析 param;查询类应答需通过各 ty_movbot_*_response 等接口上报。

SDK 通过注册的回调函数向应用传递命令,设备在完成处理后再调用对应的 response / push / report 接口完成结果同步。

协议处理总流程图

App 面板云端svc_movbot_api设备业务发起 SET / QUERY下发协议消息解码 cmd / paramMOVBOT_FUNC_SET_CB(cmd, param)ty_movbot_*_response()MOVBOT_FUNC_QUERY_CB(cmd, NULL)ty_movbot_*_response()alt[SET][QUERY]ty_movbot_status_push() / ty_movbot_report_*()上报结果 / 状态刷新面板状态App 面板云端svc_movbot_api设备业务

当前复杂协议支持的常见命令

功能 命令类型标识 发起方向
跟随控制设置 MOVBOT_FOLLOW_CONTROL_REQ_SET 面板/云端 -> 设备
跟随控制查询 MOVBOT_FOLLOW_CONTROL_QUERY 面板/云端 -> 设备
遥控控制设置 MOVBOT_REMOTE_CONTROL_SET 面板/云端 -> 设备
路径编辑设置 MOVBOT_PATH_EDIT_REQ_SET 面板/云端 -> 设备
区域设置 MOVBOT_ZONE_SET 面板/云端 -> 设备
区域查询 MOVBOT_ZONE_QUERY 面板/云端 -> 设备
AI 检测设置 MOVBOT_AI_DETECT_SET 面板/云端 -> 设备
AI 检测查询 MOVBOT_AI_DETECT_QUERY 面板/云端 -> 设备
宠物语音播放/删除 MOVBOT_VOICE_PLAY_IN_USE / MOVBOT_VOICE_PLAY_DELETE 面板/云端 -> 设备
宠物语音查询 MOVBOT_VOICE_PLAY_QUERY 面板/云端 -> 设备
机器人语音查询 MOVBOT_ROBOT_VOICE_QUERY 面板/云端 -> 设备
录像定时设置/查询 MOVBOT_RECORD_SCHEDULE_SET / QUERY 面板/云端 -> 设备
巡查定时设置/查询 MOVBOT_PATROL_SCHEDULE_SET / QUERY 面板/云端 -> 设备
休眠定时设置/查询 MOVBOT_DORMANCY_SCHEDULE_SET / QUERY 面板/云端 -> 设备
声音勿扰设置/查询 MOVBOT_SOUND_SCHEDULE_SET / QUERY 面板/云端 -> 设备
灯光勿扰设置/查询 MOVBOT_LIGHT_SCHEDULE_SET / QUERY 面板/云端 -> 设备
录像策略设置/查询 MOVBOT_VIDEO_RECORD_SET / QUERY 面板/云端 -> 设备
存储信息查询 MOVBOT_STORAGE_INFO_QUERY 面板/云端 -> 设备
存储格式化设置/查询 MOVBOT_STORAGE_FORMAT_SET / QUERY 面板/云端 -> 设备
设备信息查询 MOVBOT_DEVICE_INFO_QUERY 面板/云端 -> 设备
提示音设置/查询 MOVBOT_PROMPT_SOUND_SET / QUERY 面板/云端 -> 设备

触发时机说明

1. SET 命令(写类)

触发场景: 用户在 App 面板修改配置、下发控制或云端主动下发写类指令时,SDK 解析后经 MOVBOT_FUNC_SET_CB 回调到应用。

处理流程:

用户/云端操作 → App/云端 → SDK 解码 → MOVBOT_FUNC_SET_CB(cmd, param) → 应用处理 → ty_movbot_*_response 等上报结果
用户修改配置 / 云端写入
SDK 收到 SET 指令
解析 cmd 和 param
MOVBOT_FUNC_SET_CB
设备执行业务逻辑
调用 ty_movbot_*_response
结果同步到云端和面板

说明: set_handler 不可为 NULL,否则 ty_movbot_complex_func_register 返回 OPRT_INVALID_PARM

2. QUERY 命令(读类)

触发场景: 面板进入某页面或下拉刷新等需要拉取设备侧状态时,SDK 解析后经 MOVBOT_FUNC_QUERY_CB 回调到应用。

处理流程:

面板刷新/查询 → 云端 → SDK 解码 → MOVBOT_FUNC_QUERY_CB(cmd, param) → 应用组装数据 → ty_movbot_*_response 上报
面板打开页面 / 下拉刷新
云端发起 QUERY
SDK 解码查询命令
MOVBOT_FUNC_QUERY_CB
设备查询当前状态
调用 ty_movbot_*_response
查询结果返回云端
面板展示最新数据

说明: 多数查询场景下 param 恒为 NULL;收到对应 cmd 后应组装应答并调用下文 主动上报接口列表 中的 response 函数。

3. 主动上报与状态推送

触发场景: SET/QUERY 处理完成后,或设备侧状态变化需同步云端时,调用各上报接口。

处理流程:

设备业务逻辑 → 填充应答/推送结构体 → ty_movbot_*_response / ty_movbot_status_push / ty_movbot_report_* 等

ty_movbot_complex_func_register

参数说明:

参数 类型 说明
set_handler MOVBOT_FUNC_SET_CB 云端 SET/写类请求经解码后的回调;不可为 NULL(否则返回 OPRT_INVALID_PARM
query_handler MOVBOT_FUNC_QUERY_CB 云端 QUERY/读类请求回调

回调函数指针类型

类型定义:

  • MOVBOT_FUNC_SET_CBOPERATE_RET (*MOVBOT_FUNC_SET_CB)(IN COMPLEX_MOVBOT_CMD_E cmd, IN void *param);
  • MOVBOT_FUNC_QUERY_CBOPERATE_RET (*MOVBOT_FUNC_QUERY_CB)(IN COMPLEX_MOVBOT_CMD_E cmd, IN void *param);

SET:cmdparam 对应关系

说明: 下表为常见 SET 命令与 param 实际类型的对应关系。

COMPLEX_MOVBOT_CMD_E param 实际类型 说明
MOVBOT_FOLLOW_CONTROL_REQ_SET MOVBOT_FOLLOW_CONTROL_REQ_S * 跟随控制目标框与 ID
MOVBOT_REMOTE_CONTROL_SET 若定义 MOVBOT_INTERNAL_TASK_CTRLMOVBOT_REMOTE_CONTROL_S *;否则:MOVBOT_REMOTE_CONTROL_REQ_S * 内部任务控制:遥控模式与结果;否则:线速度、角速度
MOVBOT_PATH_EDIT_REQ_SET MOVBOT_PATH_EDIT_REQ_S * 路径编辑操作类型及关联 ID
MOVBOT_ZONE_SET MOVBOT_ZONE_SET_REQ_S * 检测区域设置
MOVBOT_AI_DETECT_SET MOVBOT_AI_DETECT_REQ_S * 声音/人形/宠物检测
MOVBOT_VOICE_PLAY_DELETE MOVBOT_PET_VOICE_DELETE_REQ_S * 宠物语音删除
MOVBOT_VOICE_PLAY_IN_USE MOVBOT_PET_VOICE_REQ_S * 宠物语音播放(已存在文件,通常无 URL)
MOVBOT_RECORD_SCHEDULE_SET MOVBOT_RECORD_SCHEDULE_REQ_S * 录像定时
MOVBOT_PATROL_SCHEDULE_SET MOVBOT_PATROL_SCHEDULE_REQ_S * 巡查定时
MOVBOT_DORMANCY_SCHEDULE_SET MOVBOT_DORMANCY_SCHEDULE_REQ_S * 休眠定时
MOVBOT_SOUND_SCHEDULE_SET MOVBOT_SOUND_SCHEDULE_REQ_S * 声音勿扰时段
MOVBOT_LIGHT_SCHEDULE_SET MOVBOT_LIGHT_SCHEDULE_REQ_S * 灯光勿扰时段
MOVBOT_VIDEO_RECORD_SET MOVBOT_VIDEO_RECORD_REQ_S * 录像模式/循环/SD 等
MOVBOT_STORAGE_FORMAT_SET MOVBOT_STORAGE_FORMAT_REQ_S * 存储格式化请求
MOVBOT_PROMPT_SOUND_SET MOVBOT_PROMPT_SOUND_REQ_S * 提示音开关与类型

常见 QUERY 命令

说明: cmd 示例(非穷举)包括:MOVBOT_FOLLOW_CONTROL_QUERYMOVBOT_ZONE_QUERYMOVBOT_AI_DETECT_QUERYMOVBOT_VOICE_PLAY_QUERYMOVBOT_ROBOT_VOICE_QUERY、各类 *_SCHEDULE_QUERYMOVBOT_VIDEO_RECORD_QUERYMOVBOT_STORAGE_INFO_QUERYMOVBOT_STORAGE_FORMAT_QUERYMOVBOT_DEVICE_INFO_QUERYMOVBOT_PROMPT_SOUND_QUERY 等。

查询命令 典型用途
MOVBOT_FOLLOW_CONTROL_QUERY 查询当前跟随控制状态或参数
MOVBOT_ZONE_QUERY 查询当前检测区域配置
MOVBOT_AI_DETECT_QUERY 查询声音/人形/宠物检测配置
MOVBOT_VOICE_PLAY_QUERY 查询宠物语音列表、状态或当前使用项
MOVBOT_ROBOT_VOICE_QUERY 查询机器人语音资源或当前应用语音
MOVBOT_RECORD_SCHEDULE_QUERY 查询录像定时配置
MOVBOT_PATROL_SCHEDULE_QUERY 查询巡查定时配置
MOVBOT_DORMANCY_SCHEDULE_QUERY 查询休眠定时配置
MOVBOT_SOUND_SCHEDULE_QUERY 查询声音勿扰配置
MOVBOT_LIGHT_SCHEDULE_QUERY 查询灯光勿扰配置
MOVBOT_VIDEO_RECORD_QUERY 查询录像策略
MOVBOT_STORAGE_INFO_QUERY 查询存储空间使用情况
MOVBOT_STORAGE_FORMAT_QUERY 查询格式化状态或结果
MOVBOT_DEVICE_INFO_QUERY 查询设备基础信息
MOVBOT_PROMPT_SOUND_QUERY 查询提示音配置

主动上报接口列表

说明: 以下函数入参均为已填充的结构体指针。若结构体中含 MOVBOT_BASE_RESPONSE_S,需正确填写 successerror_code(类型为 MOVBOT_ERRORCODE_E)。

函数 入参 说明
ty_movbot_zone_set_response MOVBOT_ZONE_SET_RES_S *res 区域设置结果
ty_movbot_ai_detect_response MOVBOT_AI_DETECT_RES_S *res AI 检测配置
ty_movbot_record_schedule_response MOVBOT_RECORD_SCHEDULE_RES_S *res 录像定时
ty_movbot_patrol_schedule_response MOVBOT_PATROL_SCHEDULE_RES_S *res 巡查定时
ty_movbot_dormancy_schedule_response MOVBOT_DORMANCY_SCHEDULE_RES_S *res 休眠定时
ty_movbot_sound_schedule_response MOVBOT_SOUND_SCHEDULE_RES_S *res 声音勿扰
ty_movbot_light_schedule_response MOVBOT_LIGHT_SCHEDULE_RES_S *res 灯光勿扰
ty_movbot_video_record_response MOVBOT_VIDEO_RECORD_RES_S *res 录像策略
ty_movbot_storage_info_response MOVBOT_STORAGE_INFO_RES_S *res 总/已用/剩余 MB
ty_movbot_storage_format_response MOVBOT_STORAGE_FORMAT_RES_S *res 格式化结果
ty_movbot_device_info_response MOVBOT_DEVICE_INFO_RES_S *res SN、UUID、MAC、SSID、IP、信号等
ty_movbot_prompt_sound_set_response MOVBOT_PROMPT_SOUND_RES_S *res 提示音设置应答
ty_movbot_prompt_sound_query_response MOVBOT_PROMPT_SOUND_RES_S *res 提示音查询应答
ty_movbot_status_push MOVBOT_STATUS_PUSH_S *push 状态推送:event_type 决定 union 有效成员
ty_movbot_follow_control_response MOVBOT_FOLLOW_CONTROL_RES_S *res 跟随控制应答
ty_movbot_pet_voice_response MOVBOT_PET_VOICE_RES_S *res 宠物语音列表/状态
ty_movbot_robot_voice_response MOVBOT_ROBOT_VOICE_RES_S *res 机器人语音列表/状态
ty_movbot_path_edit_response MOVBOT_PATH_EDIT_RES_S *res 路径编辑结果

ty_movbot_report_pet_voice_status

参数说明:

参数 类型 说明
voice_id CONST CHAR_T * 宠物语音字符串 ID
status MOVBOT_PET_VOICE_STATUS_E 下载中/失败/成功/播放中等

ty_movbot_report_voice_applied

参数说明:

参数 类型 说明
voice_id INT_T 机器人语音整型 ID,表示已应用

主要请求/应答结构体(节选字段说明)

说明: 以下为常用字段速查,完整定义见头文件与 proto。

结构体 要点
MOVBOT_FOLLOW_CONTROL_REQ_S target_id;矩形 target_leftup_x/ytarget_rightbottom_x/y(坐标系与地图一致)
MOVBOT_PATH_EDIT_REQ_S typeMOVBOT_PATH_OP_TYPE_E);path_id / point_id / start_point_id / end_point_id 按操作类型选填
MOVBOT_DETECTION_ZONE_S zone_id;矩形坐标;alarm_enabledalarm_level
MOVBOT_ZONE_SET_REQ_S total_numzone_cntzones[](≤ MOVBOT_ZONE_MAX_NUM
MOVBOT_AI_DETECT_REQ_S sound_detect(含 sound_level,协议侧常校验 0~2)、human_detectpet_detect
MOVBOT_PET_VOICE_REQ_S voice_idvoice_id_lenrepeat_num;可选 urlurl_len
MOVBOT_ROBOT_VOICE_SET_PARAMS_S 整型 voice_idurlmd5sum 及长度字段
MOVBOT_SCHEDULE_PERIOD_S start_minend_min(日内分钟)
MOVBOT_VIDEO_RECORD_REQ_S enableloopmode(事件/连续)、sd_store
MOVBOT_STORAGE_FORMAT_REQ_S format_typeforce
MOVBOT_STATUS_PUSH_S MOVBOT_STATUS_EVENT_E 使用 union 中对应字段

算法SDK 接口

功能说明: 本节整理 svc_nav_sdk_interface 文件中 tuya_robot_nav_sdk.h 提供的算法相关接口,覆盖机器人模型配置、底盘控制回调、任务管理、传感器接入、地图管理、算法状态与感知服务,便于在 MovBot 集成场景中统一查阅。

功能概览

tuya_robot_nav_sdk.h 主要提供以下能力:

  • 机器人模型配置与算法 SDK 初始化
  • 差速底盘角速度控制回调注册
  • 回充 IR 控制命令发送回调注册
  • 当前机器人位姿与 IMU 朝向查询
  • 录制、回放、遥控、回充、自定义动作等任务管理
  • 编码器、IMU、IR 等传感器注册与数据上报
  • 地图删除、切换、查询轨迹、获取地图列表等地图接口
  • 算法状态查询与全景航点插入
  • 感知服务初始化与目标检测结果回调

算法 SDK 能力总览

分类 主要接口 说明
初始化 tuya_robot_nav_sdk_init_ex 初始化算法 SDK,并传入机器人模型
底盘控制 tuya_robot_attach_diff_wheel_angular_vel_cmd 注册差速底盘左右轮角速度控制回调
回充控制 tuya_robot_attach_dock_ir_cmd_sender 注册回充 IR 命令发送回调
位姿查询 tuya_robot_get_robot_pose / tuya_robot_get_imu_orientation 获取机器人位姿与 IMU 朝向
任务管理 tuya_robot_add_task / pause / resume / cancel 管理录制、回放、遥控、回充等任务
传感器接入 tuya_robot_register_new_sensor / tuya_robot_add_sensor_data 注册传感器并持续上报数据
地图管理 tuya_robot_switch_map / get_all_map_id / get_current_trajectory 切换地图并查询地图轨迹
状态查询 tuya_robot_get_nav_status / tuya_robot_add_panorama_waypoint 查询算法状态与插入全景航点
感知服务 tuya_robot_perception_init 初始化视频感知与目标输出能力

算法 SDK 接入总流程

准备机器人模型参数
tuya_robot_nav_sdk_init_ex
注册底盘角速度控制回调
注册回充 IR 发送回调
注册传感器
持续上报传感器数据
创建/执行算法相关任务
查询状态/地图/位姿

基本约定

返回值: 所有接口返回 OPERATE_RET,成功一般为 OPRT_OK,失败原因见 tuya_error_code.h

地图 ID:

  • MAP_ID_T 定义为 uint32_t
  • map_id = path_id
  • 获取地图列表时最多返回 TUYA_ROBOT_MAX_MAP_IDS,即 8

单位约定:

类型 单位
距离 米(m)
角度/角速度 弧度(rad)/ 弧度每秒(rad/s)
时间戳 毫秒(ms)
超时 毫秒(ms)

配置类型与机器人模型

配置类型 ROBOT_NAV_CONFIG_TYPE

对应配置结构
ROBOT_CONFIG_ROBOT_MODEL_E 1000 msg_robot_model_config_s
ROBOT_CONFIG_ROBOT_MAX_SPEED_E 1001 msg_robot_max_speed_config_s
ROBOT_CONFIG_ROBOT_CHARGE_STATION_E 1002 msg_robot_charge_station_s
ROBOT_CONFIG_ROBOT_AVOID_CARPET_E 1003 msg_robot_avoid_carpet_config_s
ROBOT_CONFIG_ROBOT_DOCK_MODEL_E 1004 msg_robot_dock_model_config_s
ROBOT_CONFIG_ROBOT_Y_MOP_E 1005 msg_robot_y_mop_config_s
ROBOT_CONFIG_CLEAN_FAR_TO_NEAR_E 1006 msg_robot_clean_far_to_near_config_s
ROBOT_CONFIG_CLEAN_MODE_E 1007 msg_robot_clean_mode_config_s
ROBOT_CONFIG_ROBOT_MAPPING_E 1008 msg_robot_mapping_config_s

说明: 上述部分配置结构未在 tuya_robot_nav_sdk.h 中完整展开,集成时需结合相关依赖头文件进一步确认。

机器人类型 ROBOT_TYPE

说明
ROBOT_TYPE_DIFFERENTIAL_WHEEL_ROBOT 0 轮式双轮差分机器人
ROBOT_TYPE_MECANUM_WHEEL_ROBOT 1 麦克纳姆轮机器人
ROBOT_TYPE_AKMAN_WHEEL_ROBOT 2 阿克曼底盘
ROBOT_TYPE_DEFAULT_ARM_ROBOT 10 默认机械臂
ROBOT_TYPE_DEFAULT_HUMANOID_ROBOT 30 默认人形机器人

差分机器人参数

struct msg_robot_diff_param_s {
    float left_wheel_radius;
    float right_wheel_radius;
    float wheel_separation;
};

字段说明:

  • left_wheel_radius:左轮半径,单位米
  • right_wheel_radius:右轮半径,单位米
  • wheel_separation:轮距,单位米

机器人模型配置

struct msg_robot_model_config_s {
    ROBOT_TYPE type;
    struct msg_robot_diff_param_s diff_robot_param;
    float robot_radius;
};

字段说明:

  • type:机器人类型
  • diff_robot_param:差分底盘参数
  • robot_radius:机器人结构半径,圆形结构下有效

初始化与回调注册

tuya_robot_nav_sdk_init_ex

OPERATE_RET tuya_robot_nav_sdk_init_ex(struct msg_robot_model_config_s *robot_model);

说明:

  • 用于初始化算法 SDK
  • robot_model 不可为 NULL
  • 建议在任何任务、地图、传感器接口调用前执行

tuya_robot_attach_diff_wheel_angular_vel_cmd / tuya_robot_detach_diff_wheel_angular_vel_cmd

typedef void (*robot_robot_diff_run_angluar_cmd_fun)(struct msg_robot_diff_wheel_run_angular_cmd_s *);
OPERATE_RET tuya_robot_attach_diff_wheel_angular_vel_cmd(robot_robot_diff_run_angluar_cmd_fun callback_fun);
OPERATE_RET tuya_robot_detach_diff_wheel_angular_vel_cmd(robot_robot_diff_run_angluar_cmd_fun callback_fun);

说明:

  • 通过该回调向业务侧下发左右轮角速度控制命令
  • 适用于差速底盘
  • 注销时通常传入与注册时相同的函数指针

控制命令结构:

struct msg_robot_diff_wheel_run_angular_cmd_s {
    float left_angular_vel;
    float right_angular_vel;
};

tuya_robot_attach_dock_ir_cmd_sender / tuya_robot_detach_dock_ir_cmd_sender

typedef OPERATE_RET (*tuya_robot_dock_ir_cmd_sender_t)(unsigned char action, const char *cmd_desc);
OPERATE_RET tuya_robot_attach_dock_ir_cmd_sender(tuya_robot_dock_ir_cmd_sender_t callback_fun);
OPERATE_RET tuya_robot_detach_dock_ir_cmd_sender(tuya_robot_dock_ir_cmd_sender_t callback_fun);

action 取值语义:

说明
0 开始对接
1 停止对接
2 开始下桩

说明:

  • 业务侧可在该回调中对接串口、底盘控制器或红外发射模块
  • 注销接口说明中提到实现可忽略该参数,传 NULL 也可

位姿与朝向接口

tuya_robot_get_robot_pose

OPERATE_RET tuya_robot_get_robot_pose(struct msg_robot_pos_s *pos);

位姿结构:

struct msg_robot_pos_s {
    float x;
    float y;
    float z;
    float yaw;
    float pitch;
    float roll;
};

说明:

  • 表示机器人在地图世界坐标系下的位姿
  • 平移单位为米,姿态单位为弧度

tuya_robot_get_imu_orientation

OPERATE_RET tuya_robot_get_imu_orientation(struct msg_robot_orientation_s *orientation);

说明:

  • 仅返回 yaw / pitch / roll
  • 适合轻量查询当前朝向,不替代完整 IMU 数据流

任务模型与任务接口

任务类型

说明 参数字段
ROBOT_NAV_TASK_RECORDING_E 0 录制任务 recording
ROBOT_NAV_TASK_PLAYBACK_E 1 回放任务 playback
ROBOT_NAV_TASK_REMOTE_CONTROL_E 2 遥控任务 remote_control
ROBOT_NAV_TASK_DOCKING_CHARGE_E 3 回充对接任务 docking_charge
ROBOT_NAV_TASK_CUSTOM_ACTION_E 4 自定义动作任务 custom_action

任务参数结构

录制任务

struct robot_nav_task_recording_param_s {
    char path_name[32];
    double waypoint_spacing;
};
  • path_name:录制路径名称
  • waypoint_spacing:路径点间距,单位米

回放任务

struct robot_nav_task_playback_param_s {
    uint32_t path_id;
    int reverse;
    double waypoint_tolerance;
};
  • path_id:回放的路径 ID
  • reverse:是否反向回放
  • waypoint_tolerance:路径点到达容差

遥控任务

struct robot_nav_task_remote_control_param_s {
    float v_x;
    float v_y;
    float w;
};

说明:

  • 初始值可填 0
  • 实际速度建议通过 tuya_robot_set_remote_velocity() 周期下发

回充任务

struct robot_nav_task_docking_charge_param_s {
    uint32_t docking_timeout_ms;
};
  • 0 表示使用默认超时

自定义动作任务

struct robot_nav_task_custom_action_param_s {
    int reserved;
};

当前为预留结构。

任务描述结构

struct msg_robot_task_s {
    char task_id[64];
    ROBOT_NAV_TASK_TYPE task_type;
    robot_nav_task_param_u param;
};

说明:

  • task_id 由业务侧维护,建议全局唯一
  • task_type 决定 param 联合体中哪个字段有效

任务接口

OPERATE_RET tuya_robot_add_task(struct msg_robot_task_s *task);
OPERATE_RET tuya_robot_cancel_task(char *task_id);
OPERATE_RET tuya_robot_pause_task(char *task_id);
OPERATE_RET tuya_robot_resume_task(char *task_id);

接口语义:

  • add_task:添加任务
  • cancel_task:取消任务
  • pause_task:暂停任务
    • 录制任务:停止录制
    • 回放任务:停止回放并保留恢复所需路径信息
  • resume_task:恢复任务
    • 当前仅支持由 pause_task 暂停的回放任务
接口 作用 备注
tuya_robot_add_task 添加任务 task_id 需由业务侧保证唯一
tuya_robot_cancel_task 取消任务 按任务 ID 操作
tuya_robot_pause_task 暂停任务 对回放任务会保留恢复所需状态
tuya_robot_resume_task 恢复任务 当前仅支持恢复已暂停的回放任务

遥控速度与自定义动作

OPERATE_RET tuya_robot_set_remote_velocity(const struct msg_robot_wheel_run_cmd_s *cmd);
OPERATE_RET tuya_robot_execute_custom_action(int action_id);

说明:

  • tuya_robot_set_remote_velocity() 仅当有任务运行时有效
  • 头文件建议以 20Hz 左右周期调用
  • 无任务时通常返回 OPRT_RESOURCE_NOT_READY
  • tuya_robot_execute_custom_action() 也要求当前存在运行中的任务
接口 作用 调用条件
tuya_robot_set_remote_velocity 持续下发遥控车体速度 有任务运行时有效
tuya_robot_execute_custom_action 执行自定义动作 有任务运行时有效

任务处理流程

录制
回放
遥控
回充
自定义动作
构造 msg_robot_task_s
tuya_robot_add_task
任务类型
生成路径
跟随既有路径
周期调用 tuya_robot_set_remote_velocity
执行回桩流程
调用 tuya_robot_execute_custom_action
暂停/取消/恢复

传感器接入

支持的传感器类型

说明
ROBOT_SENSOR_ENCODER 50003 编码器
ROBOT_SENSOR_IMU 50004 IMU
ROBOT_SENSOR_IR 50016 IR 状态传感器

编码器默认 sensor_id

ROBOT_SENSOR_ENCODER_LEFT_ID 0
ROBOT_SENSOR_ENCODER_RIGHT_ID 1

传感器安装位姿

struct msg_robot_nav_sensor_pose_s {
    float offset_x;
    float offset_y;
    float offset_z;
    float roll;
    float pitch;
    float yaw;
};

说明:

  • 表示传感器相对机器人中心坐标系的安装位姿
  • 可在注册传感器时传入

传感器注册

OPERATE_RET tuya_robot_register_new_sensor(ROBOT_SENSOR_TYPE sensor_type, int sensor_id,
                                           struct msg_robot_nav_sensor_pose_s *sensor_pose);

说明:

  • sensor_type + sensor_id 唯一标识一个传感器
  • 同类型同 ID 重复注册时会覆盖
  • sensor_poseNULL 表示不更新位姿信息
  • 表满时返回 OPRT_RESOURCE_NOT_READY

传感器数据上报

OPERATE_RET tuya_robot_add_sensor_data(ROBOT_SENSOR_TYPE sensor_type, int sensor_id, void *data, int data_len);

说明:

  • 编码器和 IMU 数据会继续转发到里程计处理链路
  • 其它类型当前可能被忽略
  • data 类型需与 sensor_type 对应
接口 作用 备注
tuya_robot_register_new_sensor 注册一个传感器实例 sensor_type + sensor_id 唯一
tuya_robot_add_sensor_data 上报传感器数据 编码器/IMU 会进入里程计处理链

主要传感器数据结构

编码器

struct msg_robot_nav_encoder_sensor_s {
    float resolution;
    int count_up_limit;
    int count_down_limit;
    int counts;
    uint64_t time_stamp;
    uint64_t time_stamp_up_limit;
    uint64_t time_stamp_down_limit;
    float angular_speed;
};

IMU

struct msg_robot_nav_imu_sensor_s {
    uint64_t time_stamp;
    float roll;
    float pitch;
    float yaw;
    float orientation_covariance[9];
    float w_roll;
    float w_pitch;
    float w_yaw;
    float angular_velocity_covariance[9];
    float x_acceleration;
    float y_acceleration;
    float z_acceleration;
    float linear_acceleration_covariance[9];
};

IR 状态传感器

struct msg_robot_nav_ir_status_sensor_s {
    uint8_t status;
};

传感器接入流程

设备应用算法 SDK里程计链路tuya_robot_register_new_sensor(type, id, pose)tuya_robot_add_sensor_data(type, id, data, len)转发到里程计当前可能忽略alt[编码器或 IMU][其它传感器]loop[周期上报]设备应用算法 SDK里程计链路

地图接口(惯导系列不使用)

地图与路径关系

  • 地图本质上复用路径管理的能力
  • map_id = path_id

地图相关接口

OPERATE_RET tuya_robot_delete_map(MAP_ID_T map_id);
OPERATE_RET tuya_robot_delete_all_maps(void);
OPERATE_RET tuya_robot_get_current_trajectory(uint8_t **data, int *length);
OPERATE_RET tuya_robot_get_all_map_id(int *map_count, MAP_ID_T map_ids[TUYA_ROBOT_MAX_MAP_IDS]);
OPERATE_RET tuya_robot_switch_map(MAP_ID_T map_id);
OPERATE_RET tuya_robot_set_map_name(struct msg_user_room_name_s *user_rooms_name);
接口 作用 备注
tuya_robot_delete_map 删除指定地图 map_id = path_id
tuya_robot_delete_all_maps 删除所有地图 清空本地地图/路径
tuya_robot_get_current_trajectory 获取当前地图轨迹 返回 SDK 内部缓冲区
tuya_robot_get_all_map_id 获取地图 ID 列表 最多 TUYA_ROBOT_MAX_MAP_IDS
tuya_robot_switch_map 切换当前地图上下文 按地图 ID 操作
tuya_robot_set_map_name 设置地图名 当前返回 OPRT_NOT_SUPPORTED

获取当前轨迹

tuya_robot_get_current_trajectory() 返回当前地图对应路径的轨迹数据。

返回格式:

[uint32_t count][(x,y,theta,timestamp)*count]

说明:

  • 缓冲区由 SDK 提供
  • 返回数据只在下次调用前有效
  • 无地图或无路径时:
    • data = NULL
    • length = 0
    • 返回值仍可能为 OPRT_OK

获取地图列表

说明:

  • map_count 返回地图数量
  • map_ids 需要至少容纳 TUYA_ROBOT_MAX_MAP_IDS 个元素

设置地图名称

struct msg_user_room_name_s {
    MAP_ID_T map_id;
    char name[32];
};

说明:

  • 该接口当前为预留能力
  • tuya_robot_set_map_name() 目前返回 OPRT_NOT_SUPPORTED

状态与辅助接口

算法 SDK 状态

typedef enum {
    ROBOT_NAV_STATUS_UNINITIALIZED = 0,
    ROBOT_NAV_STATUS_IDLE,
    ROBOT_NAV_STATUS_RECORDING,
    ROBOT_NAV_STATUS_PLAYING,
    ROBOT_NAV_STATUS_ERROR
} ROBOT_NAV_STATUS_E;

查询接口:

OPERATE_RET tuya_robot_get_nav_status(ROBOT_NAV_STATUS_E *status);

说明:

  • 未初始化时返回 OPRT_RESOURCE_NOT_READY

tuya_robot_add_panorama_waypoint

OPERATE_RET tuya_robot_add_panorama_waypoint(void);

说明:

  • 仅当主任务为录制任务时有效
  • 调用后会将当前位置作为路径点写入
  • 回放到该路径点时执行一次 360° 全景旋转

感知服务

功能说明

对外提供感知服务初始化接口,可接入视频帧输入与目标结果输出,形成“取帧 -> 感知推理 -> 结果回调”的处理链。

目标结构

typedef struct {
    int32_t   id;
    int32_t   class_id;
    char     *class_name;
    float     confidence;
    float     x;
    float     y;
    float     width;
    float     height;
    uint64_t  last_update_time;
    uint8_t   is_valid;
    uint8_t   frames_since_update;
} tuya_robot_percep_target_t;

一帧结果结构

typedef struct {
    tuya_robot_percep_target_t *targets;
    int32_t                     count;
    uint64_t                    timestamp_ms;
} tuya_robot_percep_frame_result_t;

BEV 参数

typedef struct {
    double perspective_matrix[9];
} tuya_robot_percep_bev_param_t;

感知回调类型

typedef int (*tuya_robot_percep_get_frame_cb_t)(TKL_VENC_FRAME_T *frame);
typedef int (*tuya_robot_percep_target_output_cb_t)(const tuya_robot_percep_frame_result_t *frame_result);

说明:

  • get_frame_cb:感知模块主动拉取一帧视频数据
  • target_output_cb:感知模块输出一帧目标检测/跟踪结果

感知配置

typedef struct {
    tuya_robot_percep_bev_param_t        bev_param;
    tuya_robot_percep_get_frame_cb_t     get_frame_cb;
    tuya_robot_percep_target_output_cb_t target_output_cb;
    float                                confidence_threshold;
} tuya_robot_percep_config_t;

说明:

  • bev_param:3x3 透视矩阵参数
  • get_frame_cb:不可缺失
  • target_output_cb:不可缺失
  • confidence_threshold = 0 时使用默认值

感知初始化

OPERATE_RET tuya_robot_perception_init(const tuya_robot_percep_config_t *config);
接口 作用 关键入参
tuya_robot_perception_init 初始化感知服务 bev_paramget_frame_cbtarget_output_cb

感知流程

业务侧提供取帧回调
tuya_robot_perception_init
感知模块拉取视频帧
模型推理与目标跟踪
target_output_cb 输出结果
业务侧消费目标数据

最小接入建议

差速底盘算法

推荐顺序:

  1. 构造 msg_robot_model_config_s
  2. 调用 tuya_robot_nav_sdk_init_ex()
  3. 注册差速底盘角速度控制回调
  4. 注册左右编码器和 IMU
  5. 周期调用 tuya_robot_add_sensor_data() 上报编码器/IMU 数据
  6. 按业务创建录制、回放、遥控或回充任务
  7. 需要时查询位姿、状态、地图、轨迹

接入注意事项

  • tuya_robot_set_remote_velocity() 仅在任务运行期间有效
  • tuya_robot_execute_custom_action() 也要求当前存在活动任务
  • tuya_robot_resume_task() 当前仅支持恢复已暂停的回放任务
  • tuya_robot_add_panorama_waypoint() 仅在录制任务中有效
  • tuya_robot_set_map_name() 当前不支持
  • tuya_robot_get_current_trajectory() 返回的缓冲区不是业务侧持有,若需长期保存应自行拷贝

接口速查

初始化与回调

  • tuya_robot_nav_sdk_init_ex()
  • tuya_robot_attach_diff_wheel_angular_vel_cmd()
  • tuya_robot_detach_diff_wheel_angular_vel_cmd()
  • tuya_robot_attach_dock_ir_cmd_sender()
  • tuya_robot_detach_dock_ir_cmd_sender()

位姿与状态

  • tuya_robot_get_robot_pose()
  • tuya_robot_get_imu_orientation()
  • tuya_robot_get_nav_status()
  • tuya_robot_add_panorama_waypoint()

任务

  • tuya_robot_add_task()
  • tuya_robot_cancel_task()
  • tuya_robot_pause_task()
  • tuya_robot_resume_task()
  • tuya_robot_set_remote_velocity()
  • tuya_robot_execute_custom_action()

传感器

  • tuya_robot_register_new_sensor()
  • tuya_robot_add_sensor_data()

地图(预留功能)

  • tuya_robot_delete_map()
  • tuya_robot_delete_all_maps()
  • tuya_robot_get_current_trajectory()
  • tuya_robot_get_all_map_id()
  • tuya_robot_switch_map()
  • tuya_robot_set_map_name()

感知

  • tuya_robot_perception_init()