跳到主要内容

指令飞行与云台控制

Event

flyto 执行结果事件通知

Topic: thing/product/{gateway_sn}/events

Direction: up

Method: fly_to_point_progress

Data:

ColumnNameTypeconstraintDescription
fly_to_id飞向目标点 IDtext本次 flyto 任务的唯一标识
status状态enum_string{"wayline_cancel":"取消飞向目标点","wayline_failed":"执行失败","wayline_ok":"执行成功,已飞向目标点","wayline_progress":"执行中"}flyto 任务当前执行状态
result返回码int非 0 代表错误
way_point_index当前执行到第几个航点int当前正在飞往的航点序号
remaining_distance剩余任务距离float{"step":0.1,"unit_name":"米 / m"}距离目标点的剩余飞行距离
remaining_time剩余任务时间float{"step":0.1,"unit_name":"秒 / s"}预计到达目标点的剩余时间
planned_path_points规划的轨迹点列表array{"size": -, "item_type": struct}飞行器规划的航线轨迹点序列
»latitude轨迹点纬度(角度值)double{"max":90,"min":-90}轨迹点纬度,角度值,南纬是负,北纬是正,精度到小数点后6位
»longitude轨迹点经度(角度值)double{"max":180,"min":-180}轨迹点经度,角度值,东经是正,西经是负,精度到小数点后6位
»height轨迹点高度float{"step":0.1,"unit_name":"米 / m"}轨迹点高度,椭球高

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"fly_to_id": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"planned_path_points": [
{
"height": 123.234,
"latitude": 13.23,
"longitude": 123.234
}
],
"remaining_distance": 0,
"remaining_time": 0,
"result": 0,
"status": "wayline_progress",
"way_point_index": 0
},
"need_reply": 1,
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 16540709686556,
"method": "fly_to_point_progress"
}

一键起飞结果事件通知

Topic: thing/product/{gateway_sn}/events

Direction: up

Method: takeoff_to_point_progress

Data:

ColumnNameTypeconstraintDescription
status任务状态enum_string{"task_finish":"一键起飞任务完成","task_ready":"准备起飞","wayline_cancel":"取消飞向目标点","wayline_failed":"执行失败","wayline_ok":"执行成功,已飞向目标点","wayline_progress":"执行中"}一键起飞任务当前执行状态
result返回码int非 0 代表错误
flight_id一键起飞任务 UUIDtext一键起飞任务的唯一标识
track_id航迹 IDtext飞行航迹的唯一标识
way_point_index当前执行到第几个航点int当前正在飞往的航点序号
remaining_distance剩余任务距离float{"step":0.1,"unit_name":"米 / m"}距离目标点的剩余飞行距离
remaining_time剩余任务时间float{"step":0.1,"unit_name":"秒 / s"}预计到达目标点的剩余时间
planned_path_points规划的轨迹点列表array{"size": -, "item_type": struct}飞行器规划的航线轨迹点序列
»latitude轨迹点纬度(角度值)double{"max":90,"min":-90}轨迹点纬度,角度值,南纬是负,北纬是正,精度到小数点后6位
»longitude轨迹点经度(角度值)double{"max":180,"min":-180}轨迹点经度,角度值,东经是正,西经是负,精度到小数点后6位
»height轨迹点高度float{"step":0.1,"unit_name":"米 / m"}轨迹点高度,椭球高

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"flight_id": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"planned_path_points": [
{
"height": 123.234,
"latitude": 13.23,
"longitude": 123.234
}
],
"remaining_distance": 0,
"remaining_time": 0,
"result": 0,
"status": "wayline_ok",
"track_id": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"way_point_index": 1
},
"need_reply": 1,
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 16540709686556,
"method": "takeoff_to_point_progress"
}

飞行控制权抢夺

Topic: thing/product/{gateway_sn}/services

Direction: down

Method: flight_authority_grab

Data: null

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {},
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "flight_authority_grab"
}

Topic: thing/product/{gateway_sn}/services_reply

Direction: up

Method: flight_authority_grab

Data:

ColumnNameTypeconstraintDescription
result返回码int非 0 代表错误

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"result": 0
},
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "flight_authority_grab"
}

负载控制权抢夺

Topic: thing/product/{gateway_sn}/services

Direction: down

Method: payload_authority_grab

Data:

ColumnNameTypeconstraintDescription
payload_index负载枚举值text镜头负载与挂载位置枚举值。非标准的 device_mode_key,格式为 {type-subtype-gimbalindex},可以参考产品支持页面

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"payload_index": "68-0-0"
},
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "payload_authority_grab"
}

Topic: thing/product/{gateway_sn}/services_reply

Direction: up

Method: payload_authority_grab

Data:

ColumnNameTypeconstraintDescription
result返回码int非 0 代表错误

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"result": 0
},
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "payload_authority_grab"
}

进入指令飞行控制模式

Topic: thing/product/{gateway_sn}/services

Direction: down

Method: drc_mode_enter

Data:

ColumnNameTypeconstraintDescription
mqtt_brokerBroker 连接信息struct获取 MQTT 中继服务的地址与认证信息
»address服务器连接地址text服务器连接地址,例如:192.0.2.1:8883, mqtt.autel.com:8883
»client_id客户端 IDtext可自定义的 MQTT 客户端 ID。建议使用设备的SN码的前缀组合,例如,drc-TH12345678,不建议直接使用设备SN码,避免同一个MQTT互相挤下线
»username用户名text建立连接时使用的用户名
»password密码text建立连接时认证所需要的密码
»expire_time认证信息过期时间int{"unit_name":"秒 / s"}在有效期内认证信息可以重复使用,另外认证信息过期后,并不会影响已建立连接的设备
»enable_tls是否启用 TLSbool启用 TLS 即对 MQTT 链路开启加密
osd_frequencyOSD 频率int{"max":30,"min":1,"unit_name":"赫兹 / Hz"}设置 OSD 上报频率
hsi_frequencyHSI 频率int{"max":30,"min":1,"unit_name":"赫兹 / Hz"}设置 HSI 上报频率

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"hsi_frequency": 1,
"mqtt_broker": {
"address": "mqtt.autel.com:8883",
"client_id": "sn_a",
"enable_tls": true,
"expire_time": 1672744922,
"password": "jwt_token",
"username": "sn_a_username"
},
"osd_frequency": 10
},
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "drc_mode_enter"
}

Topic: thing/product/{gateway_sn}/services_reply

Direction: up

Method: drc_mode_enter

Data:

ColumnNameTypeconstraintDescription
result返回码int非 0 代表错误

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"result": 0
},
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "drc_mode_enter"
}

退出指令飞行控制模式

Topic: thing/product/{gateway_sn}/services

Direction: down

Method: drc_mode_exit

Data: null

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {},
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "drc_mode_exit"
}

Topic: thing/product/{gateway_sn}/services_reply

Direction: up

Method: drc_mode_exit

Data:

ColumnNameTypeconstraintDescription
result返回码int非 0 代表错误

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"result": 0
},
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "drc_mode_exit"
}

一键起飞

Topic: thing/product/{gateway_sn}/services

Direction: down

Method: takeoff_to_point

Data:

ColumnNameTypeconstraintDescription
target_latitude目标点纬度(角度值)double{"max":90,"min":-90}目标点纬度,角度值,南纬是负,北纬是正,精度到小数点后6位
target_longitude目标点经度(角度值)double{"max":180,"min":-180}目标点经度,角度值,东经是正,西经是负,精度到小数点后6位
target_height目标点高度float{"max":1500,"min":2,"step":0.1,"unit_name":"米 / m"}目标点高度(相对高)
flight_id一键起飞任务 UUIDtext任务 UUID,全局唯一,用于染色,云端区分该值是普通计划任务还是一键起飞任务
max_speed一键起飞的飞行过程中能达到的最大速度int{"max":15,"min":1,"unit_name":"米每秒 / m/s"}限制飞行器的最大飞行速度

device_list:

ColumnNameTypeconstraintDescription
sn飞机序列号text要执行任务的飞机序列号

Example: 注意一键起飞只能在室外,并且目标经纬度不能离当前经纬度太远

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"flight_id": "ABDEAC21DCADDA",
"max_speed": 12,
"target_height": 100,
"target_latitude": 12.23,
"target_longitude": 12.32
},
"device_list": [{
"sn": "1748xx"
}, {
"sn": "174822xx"
}],
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "takeoff_to_point"
}

Topic: thing/product/{gateway_sn}/services_reply

Direction: up

Method: takeoff_to_point

Data:

ColumnNameTypeconstraintDescription
result返回码int非 0 代表错误

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"result": 0
},
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "takeoff_to_point"
}

flyto 飞向目标点

Topic: thing/product/{gateway_sn}/services

Direction: down

Method: fly_to_point

Data:

ColumnNameTypeconstraintDescription
fly_to_id飞向目标点 IDtext本次 flyto 任务的唯一标识
max_speedflyto 的飞行过程中能达到的最大速度int{"max":15,"min":0,"unit_name":"米每秒 / m/s"}限制飞行器的最大飞行速度
pointsflyto 目标点列表array{"size": -, "item_type": struct}仅支持 1 个目标点
»latitude目标点纬度(角度值)double{"max":90,"min":-90}目标点纬度,角度值,南纬是负,北纬是正,精度到小数点后6位
»longitude目标点经度(角度值)double{"max":180,"min":-180}目标点经度,角度值,东经是正,西经是负,精度到小数点后6位
»height目标点高度float{"max":10000,"min":2,"step":0.1,"unit_name":"米 / m"}目标点高度(相对高)

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"fly_to_id": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"max_speed": 12,
"points": [
{
"height": 100,
"latitude": 12.23,
"longitude": 12.23
}
]
},
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "fly_to_point"
}

Topic: thing/product/{gateway_sn}/services_reply

Direction: up

Method: fly_to_point

Data:

ColumnNameTypeconstraintDescription
result返回码int非 0 代表错误

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"result": 0
},
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "fly_to_point"
}

结束 flyto 飞向目标点任务

Topic: thing/product/{gateway_sn}/services

Direction: down

Method: fly_to_point_stop

Data: null

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {},
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "fly_to_point_stop"
}

Topic: thing/product/{gateway_sn}/services_reply

Direction: up

Method: fly_to_point_stop

Data:

ColumnNameTypeconstraintDescription
result返回码int非 0 代表错误

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"result": 0
},
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "fly_to_point_stop"
}

Joystick 控制无效原因通知

Joystick 是一个无人机综合控制功能,若不可用,则无法使用 drone_control 能力,实现手动操控

Topic: thing/product/{gateway_sn}/events

Direction: up

Method: joystick_invalid_notify

Data:

ColumnNameTypeconstraintDescription
reason任务状态int{"0":"遥控器失联","1":"低电量返航","2":"低电量降落","3":"靠近限飞区","4":"遥控器夺权(例如:触发了返航,B控夺权)"}任务被中断或状态变化的原因

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"reason": 0
},
"need_reply": 1,
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "joystick_invalid_notify"
}

负载控制—单拍

Topic: thing/product/{gateway_sn}/services

Direction: down

Method: camera_photo_take

Data:

ColumnNameTypeconstraintDescription
payload_index相机枚举text相机枚举值。非标准的 device_mode_key,格式为 {type-subtype-gimbalindex},可以参考[产品支持]

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"payload_index": "68-0-0"
},
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "camera_photo_take"
}

Topic: thing/product/{gateway_sn}/services_reply

Direction: up

Method: camera_photo_take

Data:

ColumnNameTypeconstraintDescription
result返回码int非 0 代表错误

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"result": 0
},
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "camera_photo_take"
}

负载控制—开始录像

Topic: thing/product/{gateway_sn}/services

Direction: down

Method: camera_recording_start

Data:

ColumnNameTypeconstraintDescription
payload_index相机枚举text相机枚举值。非标准的 device_mode_key,格式为 {type-subtype-gimbalindex},可以参考[产品支持]

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"payload_index": "68-0-0"
},
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "camera_recording_start"
}

Topic: thing/product/{gateway_sn}/services_reply

Direction: up

Method: camera_recording_start

Data:

ColumnNameTypeconstraintDescription
result返回码int非 0 代表错误

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"result": 0
},
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "camera_recording_start"
}

负载控制—停止录像

Topic: thing/product/{gateway_sn}/services

Direction: down

Method: camera_recording_stop

Data:

ColumnNameTypeconstraintDescription
payload_index相机枚举text相机枚举值。非标准的 device_mode_key,格式为 {type-subtype-gimbalindex},可以参考[产品支持]

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"payload_index": "68-0-0"
},
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "camera_recording_stop"
}

Topic: thing/product/{gateway_sn}/services_reply

Direction: up

Method: camera_recording_stop

Data:

ColumnNameTypeconstraintDescription
result返回码int非 0 代表错误

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"result": 0
},
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "camera_recording_stop"
}

负载控制—画面拖动控制

Topic: thing/product/{gateway_sn}/services

Direction: down

Method: camera_screen_drag

Data:

ColumnNameTypeconstraintDescription
payload_index相机枚举text相机枚举值。非标准的 device_mode_key,格式为 {type-subtype-gimbalindex},可以参考[产品支持]
locked机头和云台的相对关系是否锁定bool{"false":"仅云台转,机身不转","true":"锁定机头,云台和机身一起转"}控制云台旋转时是否同步旋转机头
pitch_speed云台 pitch 速度double{"unit_name":"度每秒 / deg/s"}云台 pitch 速度,仅支持云台转
yaw_speed云台 yaw 速度double{"unit_name":"度每秒 / deg/s"}云台 yaw 速度,仅支持锁机头

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"locked": false,
"payload_index": "68-0-0",
"pitch_speed": 0.1,
"yaw_speed": 0.1
},
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "camera_screen_drag"
}

Topic: thing/product/{gateway_sn}/services_reply

Direction: up

Method: camera_screen_drag

Data:

ColumnNameTypeconstraintDescription
result返回码int非 0 代表错误

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"result": 0
},
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "camera_screen_drag"
}

负载控制—变焦

Topic: thing/product/{gateway_sn}/services

Direction: down

Method: camera_focal_length_set

Data:

ColumnNameTypeconstraintDescription
payload_index相机枚举text相机枚举值。非标准的 device_mode_key,格式为 {type-subtype-gimbalindex},可以参考[产品支持]
camera_type相机类型enum_string{"ir":"红外","wide":"广角","zoom":"变焦"}相机类型枚举
zoom_factor变焦倍数double{"max":200,"min":2}变焦倍数,可见光是2-200,红外是2-20

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"camera_type": "zoom",
"payload_index": "68-0-0",
"zoom_factor": 5
},
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "camera_focal_length_set"
}

Topic: thing/product/{gateway_sn}/services_reply

Direction: up

Method: camera_focal_length_set

Data:

ColumnNameTypeconstraintDescription
result返回码int非 0 代表错误

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"result": 0
},
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "camera_focal_length_set"
}

负载控制—重置云台

Topic: thing/product/{gateway_sn}/services

Direction: down

Method: gimbal_reset

Data:

ColumnNameTypeconstraintDescription
payload_index负载编号text负载编号,相机枚举值。非标准的 device_mode_key,格式为 {type-subtype-gimbalindex},可以参考[产品支持]
reset_mode重置模式类型enum_int{"0":"回中","1":"向下","2":"偏航回中","3":"向下45度"}指定云台重置后的目标姿态

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"payload_index": "68-0-0",
"reset_mode": 0
},
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "gimbal_reset"
}

Topic: thing/product/{gateway_sn}/services_reply

Direction: up

Method: gimbal_reset

Data:

ColumnNameTypeconstraintDescription
result返回码int非 0 代表错误

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"result": 0
},
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "gimbal_reset"
}

负载控制—照片存储设置

Topic: thing/product/{gateway_sn}/services

Direction: down

Method: photo_storage_set

Data:

ColumnNameTypeconstraintDescription
payload_index相机枚举text相机枚举值。非标准的 device_mode_key,格式为 {type-subtype-gimbalindex},可以参考[产品支持]
photo_storage_settings照片存储设置集合array{"size": -, "item_type": enum_string}拍照存储类型{current, wide, zoom, ir},可多选

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"payload_index": "68-0-0",
"photo_storage_settings": [
"current",
"wide",
"zoom",
"ir"
]
},
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "photo_storage_set"
}

Topic: thing/product/{gateway_sn}/services_reply

Direction: up

Method: photo_storage_set

Data:

ColumnNameTypeconstraintDescription
result返回码int非 0 代表错误

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"result": 0
},
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "photo_storage_set"
}

负载控制—视频存储设置

Topic: thing/product/{gateway_sn}/services

Direction: down

Method: video_storage_set

Data:

ColumnNameTypeconstraintDescription
payload_index相机枚举text相机枚举值。非标准的 device_mode_key,格式为 {type-subtype-gimbalindex},可以参考[产品支持]
video_storage_settings视频存储设置集合array{"size": -, "item_type": enum_string}视频存储类型{current, wide, zoom, ir},可多选

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"payload_index": "68-0-0",
"video_storage_settings": [
"current",
"wide",
"zoom",
"ir"
]
},
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "video_storage_set"
}

Topic: thing/product/{gateway_sn}/services_reply

Direction: up

Method: video_storage_set

Data:

ColumnNameTypeconstraintDescription
result返回码int非 0 代表错误

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"result": 0
},
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "video_storage_set"
}

负载控制—Look At

Topic: thing/product/{gateway_sn}/services

Direction: down

Method: camera_look_at

Data:

ColumnNameTypeconstraintDescription
latitude目标点纬度double{"max":90,"min":-90}角度值。南纬是负,北纬是正,精度到小数点后6位。
longitude目标点经度double{"max":180,"min":-180}角度值。东经是正,西经是负,精度到小数点后6位。
height目标点高度float{"max":10000,"min":2,"step":0.1,"unit_name":"米 / m"}目标点高度(椭球高)

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"height": 100,
"latitude": 12.23,
"longitude": 12.23
},
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "camera_look_at"
}

DRC

DRC-飞行控制

进入指令飞行模式后允许通过该指令控制无人机航行方向与速度,发送的频率需要保持在5-10hz以内让设备能够比较精准的控制速度变化与方向。同时,需要保证飞机已经处于打桨飞行的状态,要不会无效。

Topic: thing/product/{gateway_sn}/drc/down

Direction: down

Method: drone_control

Data:

ColumnNameTypeconstraintDescription
seq命令序号int递增的序号,保证指令顺序执行。若 x、y、h、w 参数发生变化,seq 需要从 0 开始增长。
x前进后退方向的速度double{"max":17,"min":-17,"unit_name":"米每秒 / m/s"}前进后退的最大速度,负值表示向后移动
y左右方向的速度double{"max":17,"min":-17,"unit_name":"米每秒 / m/s"}左右移动的最大速度,负值表示向左移动
h上下方向的速度double{"max":5,"min":-4,"unit_name":"米每秒 / m/s"}向上向下移动的最大速度,负值表示向下移动
w机身角速度double{"max":90,"min":-90,"unit_name":"弧度每秒 / rad/s"}顺时针与逆时针的最大角速度,负值表示逆时针转动

Example:

{
"data": {
"freq": 10,
"h": 2.76,
"seq": 1,
"w": 2.86,
"x": 2.34,
"y": -2.45
},
"method": "drone_control"
}

Topic: thing/product/{gateway_sn}/drc/up

Direction: up

Method: drone_control

Data:

ColumnNameTypeconstraintDescription
result返回码int非 0 代表错误,异常case:没有飞行控制权,没有虚拟摇杆权限,数据包序号不对
output输出struct服务响应输出内容
»seq命令序号int递增的序号,保证指令顺序执行

Example:

{
"data": {
"output": {
"seq": 1
},
"result": 0
},
"method": "drone_control"
}

DRC-无人机急停

Topic: thing/product/{gateway_sn}/drc/down

Direction: down

Method: drone_emergency_stop

Data: null

Example:

{
"data": {},
"method": "drone_emergency_stop"
}

Topic: thing/product/{gateway_sn}/drc/up

Direction: up

Method: drone_emergency_stop

Data:

ColumnNameTypeconstraintDescription
result返回码int非 0 代表错误

Example:

{
"data": {
"result": 0
},
"method": "drone_emergency_stop"
}

DRC-心跳

Topic: thing/product/{gateway_sn}/drc/down

Direction: down

Method: heart_beat

Data:

ColumnNameTypeconstraintDescription
seq命令序号int递增的序号,保证指令顺序执行
timestamp心跳发送时间戳int{"unit_name":"毫秒 / ms"}收到的心跳发送时的时间戳,非设备端的时间,便于云端根据收发的间隔做时延计算

Example:

{
"data": {
"seq": 10,
"timestamp": 1670415891013
},
"method": "heart_beat"
}

Topic: thing/product/{gateway_sn}/drc/up

Direction: up

Method: heart_beat

Data:

ColumnNameTypeconstraintDescription
seq命令序号int递增的序号,保证指令顺序执行
timestamp心跳发送时间戳int{"unit_name":"毫秒 / ms"}收到的心跳发送时的时间戳,非设备端的时间,便于云端根据收发的间隔做时延计算

Example:

{
"data": {
"seq": 10,
"timestamp": 1670415891013
},
"method": "heart_beat"
}

DRC-避障信息上报

Topic: thing/product/{gateway_sn}/drc/up

Direction: up

Method: hsi_info_push

Data:

ColumnNameTypeconstraintDescription
down_distance下方障碍物距离int单位:毫米下视传感器检测到的最近障碍物距离
up_distance上方障碍物距离int单位:毫米上视传感器检测到的最近障碍物距离
front1_distance前方1号雷达障碍物距离int单位:毫米前方1号雷达检测到的最近障碍物距离
front2_distance前方2号雷达障碍物距离int单位:毫米前方2号雷达检测到的最近障碍物距离
front3_distance前方3号雷达障碍物距离int单位:毫米前方3号雷达检测到的最近障碍物距离
front4_distance前方4号雷达障碍物距离int单位:毫米前方4号雷达检测到的最近障碍物距离
left1_distance左侧1号雷达障碍物距离int单位:毫米左侧1号雷达检测到的最近障碍物距离
left2_distance左侧2号雷达障碍物距离int单位:毫米左侧2号雷达检测到的最近障碍物距离
left3_distance左侧3号雷达障碍物距离int单位:毫米左侧3号雷达检测到的最近障碍物距离
rear1_distance后方1号雷达障碍物距离int单位:毫米后方1号雷达检测到的最近障碍物距离
rear2_distance后方2号雷达障碍物距离int单位:毫米后方2号雷达检测到的最近障碍物距离
rear3_distance后方3号雷达障碍物距离int单位:毫米后方3号雷达检测到的最近障碍物距离
rear4_distance后方4号雷达障碍物距离int单位:毫米后方4号雷达检测到的最近障碍物距离
right1_distance右侧1号雷达障碍物距离int单位:毫米右侧1号雷达检测到的最近障碍物距离
right2_distance右侧2号雷达障碍物距离int单位:毫米右侧2号雷达检测到的最近障碍物距离
right3_distance右侧3号雷达障碍物距离int单位:毫米右侧3号雷达检测到的最近障碍物距离
radar_enable避障开关boolean飞行器避障功能是否开启

Example:

{
"bid":"xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data":{
"down_distance":0,
"front1_distance":0,
"front2_distance":0,
"front3_distance":0,
"front4_distance":0,
"left1_distance":0,
"left2_distance":0,
"left3_distance":0,
"radar_enable":true,
"rear1_distance":0,
"rear2_distance":0,
"rear3_distance":0,
"rear4_distance":0,
"right1_distance":0,
"right2_distance":0,
"right3_distance":0,
"up_distance":0
},
"tid":"xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp":1726131014572,
"method":"hsi_info_push"
}

负载控制—拍照/录像模式切换

Topic: thing/product/{gateway_sn}/services

Direction: down

Method: camera_mode_switch

Data:

ColumnNameTypeconstraintDescription
payload_index相机枚举text相机枚举值。非标准的 device_mode_key,格式为 {type-subtype-gimbalindex},可以参考[产品支持]
camera_mode拍照/录像模式enum_int{"0":"拍照","1":"录像"}设置相机的工作模式

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"camera_mode": 0,
"payload_index": "68-0-0"
},
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "camera_mode_switch"
}

Topic: thing/product/{gateway_sn}/services_reply

Direction: up

Method: camera_mode_switch

Data:

ColumnNameTypeconstraintDescription
result返回码int非 0 代表错误

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"result": 0
},
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "camera_mode_switch"
}

负载控制—连续变焦

Topic: thing/product/{gateway_sn}/services

Direction: down

Method: camera_focal_length_drag

Data:

ColumnNameTypeconstraintDescription
payload_index相机枚举text相机枚举值。非标准的 device_mode_key,格式为 {type-subtype-gimbalindex},可以参考[产品支持]
camera_type相机类型enum_string{"ir":"红外","wide":"广角","zoom":"变焦"}相机类型枚举
zoom_type变焦类型enum_int{"0":"缩小","1":"放大","2":"停止"}连续变焦操作类型

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"camera_type": "zoom",
"payload_index": "68-0-0",
"zoom_type": 1
},
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "camera_focal_length_drag"
}

Topic: thing/product/{gateway_sn}/services_reply

Direction: up

Method: camera_focal_length_drag

Data:

ColumnNameTypeconstraintDescription
result返回码int非 0 代表错误

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"result": 0
},
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "camera_focal_length_drag"
}

喊话器—设置音量

Topic: thing/product/{gateway_sn}/services

Direction: down

Method: speaker_play_volume_set

Data:

ColumnNameTypeconstraintDescription
play_volume喊话器音量int{"max":100,"min":0}喊话器音量百分比

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"play_volume": 50
},
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "speaker_play_volume_set"
}

Topic: thing/product/{gateway_sn}/services_reply

Direction: up

Method: speaker_play_volume_set

Data:

ColumnNameTypeconstraintDescription
result返回码int非 0 代表错误

Example:

{
"bid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"data": {
"result": 0
},
"tid": "xxxxxxxx-xxxx-xxxx-xxxx-xxxxxxxxxx",
"timestamp": 1654070968655,
"method": "speaker_play_volume_set"
}