本文檔講述在NIVIDIA開發板上使用大疆提供的Payload SDK獲取無人機實時GPS信息的方法,以及基于Payload SDK發布ROS GPS話題信息的方法。
文章目錄
- 0 實現目標
- 1 Payload SDK
- 1.1 PSDK 源碼的編譯
- 1.2 PSDK 的使用
- 2 遙測數據的讀取
- 2.1 示例代碼結構
- 2.2 讀取機載GPS信息的邏輯
- 2.3 運行效果
- 3 將 PSDK 源碼轉化為 ROS 形式
- 3.1 文件的布局
- 3.2 主函數的改寫
- 3.3 CMakeLists.txt的編寫
- 4 結尾
- 參考文檔
0 實現目標
在大疆Matrice 350 RTK無人機上安裝E-Port 開發者套件,再通過E-Port 開發者套件連接到英偉達開發板,便可以讀取當前無人機飛行時的RTK數據和GPS數據。RTK數據與GPS數據在組合導航算法中具有重要重要作用。
本文將要實現的,一是編譯大疆提供的Payload SDK,來獲取實時GPS數據;二是將獲取的GPS信息,以ROS話題的形式,發布出來,供組合導航中其他的ROS節點使用。
1 Payload SDK
Payload 是大疆提供的,用于在M350 RTK等機型上獲取無人機自帶傳感器設備信息的SDK,所獲取的信息包括無人機姿態、GPS信息、機載圖像等,其可獲取的所有信息見文末參考文檔中的遙測數據訂閱。
Payload SDK代碼可以從Github上的大疆官方頁下載:
git clone https://github.com/dji-sdk/Payload-SDK.git
1.1 PSDK 源碼的編譯
用戶使用SDK進行無人機二次開發前,需要編譯源碼,來產生后續開發用到的相關庫文件。
SDK源碼的結構如下:
CMakeLists.txt doc EULA.txt psdk_lib samples tools
psdk_lib中包括了SDK中所有庫的頭文件,以及不同平臺下的編譯器;samples是大疆官方給出的代碼示例,有C和C++兩種代碼,包含了GPS信息獲取和圖像傳輸等功能,后續的ROS代碼也是在samples的基礎上進行修改的;CMakeLists.txt則是使用CMake編譯源碼時的編譯配置文件。
下面講述本人在英偉達開發板上的PSDK的編譯歷程:
首先,在PSDK源碼所在的路徑下創建一個build文件夾,并切換到build目錄下:
XXX@YYY:~/Payload-SDK$ ls
CMakeLists.txt doc EULA.txt psdk_lib samples tools
XXX@YYY:~/Payload-SDK$ mkdir build
XXX@YYY:~/Payload-SDK$ cd build
隨后使用cmake命令生成Makefile文件:
XXX@YYY:~/Payload-SDK/build$ cmake ..
以下命令執行的結果和出現的問題:
什么,OPUS?想必是缺少一個庫,本人不知所云,然后發郵箱求助大疆客服:
照著客服的引導,我在英偉達開發板上源碼安裝了ffmpeg 4.1.3,結果還是報了那個錯誤。這真的讓人哭笑不得,其實這個問題只需要安裝opus的庫就行了:
XXX@YYY:~/Payload-SDK/build$ sudo apt-get install libopus-dev
然后就cmake成功了:
dji_sdk_demo_linux_cxx...
...
-- Configuring done
-- Generating done
-- Build files have been written to: XXX/Payload-SDK/build
XXX@YYY:~/Payload-SDK/build$ ls
bin CMakeCache.txt CMakeFiles cmake_install.cmake Makefile samples
可以看到,build路徑下生成了Makefile,那下一步當然就是使用make命令進行編譯啦:
make -j24
果然沒猜錯,又出現了問題,該問題的簡要描述為:
fatal error: opencv2/dnn.hpp: No such file or directory(opencv4)
這應該是OpenCV的版本不滿足要求。但是,版本為多少才是合適的呢,后來我新安裝了OpenCV 4.8,并在CMakelists.txt中添加了下面的語句:
find_package(OpenCV 4.8 REQUIRED)
安裝OpenCV 4.8時的cmake命令為:
sudo cmake -D CMAKE_BUILD_TYPE=Release -D CMAKE_INSTALL_PREFIX=/usr/local -DENABLE_PRECOMPILED_HEADERS=OFF ..
之后就會發現編譯成功了。
當然啦,上述本人遇到的OpenCV問題其他讀者不一定遇見,還是安裝并使用OpenCV 4.9為好,這是本人咨詢大疆客服獲知的:
好了,現在應該在自己的開發板上能看到對應的庫了:
XXX@YYY:~$ ls /usr/local/lib
cmake libopencv_features2d.so.4.8.0 libopencv_imgproc.so libopencv_stitching.so.408 libopencv_flann.so libopencv_imgproc.so.408 libopencv_stitching.so.4.8.0
libopencv_calib3d.so libopencv_flann.so.408 libopencv_imgproc.so.4.8.0 libopencv_videoio.so
libopencv_calib3d.so.408 libopencv_flann.so.4.8.0 libopencv_ml.so libopencv_videoio.so.408
libopencv_calib3d.so.4.8.0 libopencv_gapi.so libopencv_ml.so.408 libopencv_videoio.so.4.8.0 libopencv_core.so libopencv_gapi.so.408 libopencv_ml.so.4.8.0 libopencv_video.so
libopencv_core.so.408 libopencv_gapi.so.4.8.0 libopencv_objdetect.so libopencv_video.so.408
libopencv_core.so.4.8.0 libopencv_highgui.so libopencv_objdetect.so.408 libopencv_video.so.4.8.0 libopencv_dnn.so libopencv_highgui.so.408 libopencv_objdetect.so.4.8.0 libopus.a
libopencv_dnn.so.408 libopencv_highgui.so.4.8.0 libopencv_photo.so
libopencv_dnn.so.4.8.0 libopencv_imgcodecs.so libopencv_photo.so.408
libopencv_features2d.so libopencv_imgcodecs.so.408 libopencv_photo.so.4.8.0 python2.7
libopencv_features2d.so.408 libopencv_imgcodecs.so.4.8.0 libopencv_stitching.so python3.8
好了,總算把編譯的問題徹底解決了。
1.2 PSDK 的使用
開始運行程序前,需要解決E-Port 開發者套件與英偉達開發板之間的連接問題,在大疆開發者社區里,本人發現了以下信息:
建議把”推薦“去掉,本人一開始使用的普通的TTL串口線,沒使用FT232串口,以為能直接獲取到GPS信息,結果屢次插拔串口線都未能如愿,這才著重注意到了這一句話。害,官方未能著重突出這條信息,就真只能多走彎路。
在運行程序之前,還需使用大疆官方的上位機來設置信息傳輸的相關參數(包括傳輸的波特率),詳細的方法見參考文檔【1】。
這下可以開始運行程序看看效果了,先找出編譯成功的可執行文件dji_sdk_demo_linux
,這個文件在編譯好的文件目錄bin
中:
shallwing@9d57f9229b66:~/Payload-SDK/build$ ls
bin CMakeCache.txt CMakeFiles cmake_install.cmake Makefile samples
shallwing@9d57f9229b66:~/Payload-SDK/build$ cd bin
shallwing@9d57f9229b66:~/Payload-SDK/build/bin$ ls
dji_sdk_demo_linux dji_sdk_demo_linux_cxx
shallwing@9d57f9229b66:~/Payload-SDK/build/bin$ sudo ./dji_sdk_demo_linux
兩個可執行文件里面,dji_sdk_demo_linux
是C程序編譯生成的,dji_sdk_demo_linux_cxx
則是C++程序編譯生成的。本人先運行了dji_sdk_demo_linux
,然后報了下面的錯誤:
XXX@YYY:$ sudo ./dji_sdk_demo_linux
'Logs/latest.log' -> 'DJI_0001_20241220_00-22-55.log'
[0.004][user]-[Error]-[DjiUser_FillInUserInfo:578) Please fill in correct user information to 'samples/sample_c/platform/linux/manifold2/application/dji_sdk_app_info.h' file.
破案了,大疆這是需要每個使用其SDK的開發者要填寫自己的相關信息啊。好吧,那就在大疆官網上注冊信息,網上搜了一下注冊的方法,注冊成功之后,便填寫文件samples/sample_c/platform/linux/manifold2/application/dji_sdk_app_info.h
中的信息:
/* Exported constants --------------------------------------------------------*/
// ATTENTION: User must goto https://developer.dji.com/user/apps/#all to create your own dji sdk application, get dji sdk application
// information then fill in the application information here.
#define USER_APP_NAME "your_app_name"
#define USER_APP_ID "your_app_id"
#define USER_APP_KEY "your_app_key"
#define USER_APP_LICENSE "your_app_license"
#define USER_DEVELOPER_ACCOUNT "your_developer_account"
#define USER_BAUD_RATE "460800"
請注意,這里的USER_BAUD_RATE
一定需要與上位機中設置的波特率保持一直。
填寫完了,再次運行,終端打印的信息如下圖:
“Waiting payload negotiate finish”?,這是什么問題,去網上找了很多帖子,包括大疆開發社區,都沒有與此問題詳細的解決方案。算了,還是問客服來得快一點:
果然解鈴還需系鈴人啊,問題交到PSDK的作者們手中一下就解決了,那就找到這個dji_sdk_config.h
文件,然后修改CONFIG_HARDWARE_CONNECTION
宏的內容吧。
dji_sdk_config.h
在PSDK中的位置為:
Payload-SDK/samples/sample_c/platform/linux/manifold2/application
找到的這個宏定義:
/* Exported constants --------------------------------------------------------*/
#define DJI_USE_ONLY_UART (0)
#define DJI_USE_UART_AND_USB_BULK_DEVICE (1)
#define DJI_USE_UART_AND_NETWORK_DEVICE (2)/*!< Attention: Select your hardware connection mode here.
* */
#define CONFIG_HARDWARE_CONNECTION DJI_USE_UART_AND_NETWORK_DEVICE
將其中的DJI_USE_UART_AND_NETWORK_DEVICE
修改為DJI_USE_ONLY_UART
,隨后運行就正常了。好了,demo程序的運行沒有問題了,下面就可以開始深入了解demo源碼的含義,來自己編寫代碼獲取想要的信息了。
2 遙測數據的讀取
本章節以C++程序為例,講述如何在main函數中訂閱讀取GPS信息和RTK信息。
2.1 示例代碼結構
PSDK源碼中給出的C++代碼結構如下:
├── module_sample
│ ├── camera_manager
│ ├── flight_controller
│ ├── gimbal
│ ├── hms_manager
│ ├── liveview
│ └── perception
└── platform└── linux├── common├── manifold2│ ├── application│ │ ├── application.cpp│ │ ├── application.hpp│ │ ├── dji_sdk_app_info.h│ │ ├── dji_sdk_config.h│ │ ├── dji_sdk_config.json│ │ └── main.cpp│ ├── CMakeLists.txt│ └── hal└── nvidia_jetson
可以看到,代碼分為機載傳感器模塊代碼,和主函數實現的代碼,其中傳感器模塊代碼實現了每個傳感器數據接收的功能,這包括機載相機管理、飛行控制、云臺控制(gimal),健康管理系統(HMS)、實時視頻流(liveview)、**視覺圖像(perception)**等。
通過多次閱讀PSDK的C++源碼,可以得知,C++源碼調用了C代碼中的部分代碼,這個發現影響了下一章節將PSDK源碼改寫為ROS代碼的工作。
2.2 讀取機載GPS信息的邏輯
先給出本人改寫后的GPS信息和RTK信息的訂閱代碼:
int main(int argc, char **argv)
{Application application(argc, argv);T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();T_DjiReturnCode returnCode;T_DjiDataTimestamp timestamp = {0};T_DjiFcSubscriptionRtkPosition data = {0};T_DjiFcSubscriptionGpsPosition postion = {0};returnCode = DjiFcSubscription_SubscribeTopic(DJI_FC_SUBSCRIPTION_TOPIC_RTK_POSITION, \DJI_DATA_SUBSCRIPTION_TOPIC_1_HZ, NULL);if(returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)USER_LOG_ERROR("Subscribe RTK topic error.\n");elseprintf("Subscribe RTK topic success.\n");returnCode = DjiFcSubscription_SubscribeTopic(DJI_FC_SUBSCRIPTION_TOPIC_GPS_POSITION, \DJI_DATA_SUBSCRIPTION_TOPIC_1_HZ, NULL);if(returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)USER_LOG_ERROR("Subscribe GPS topic error.\n");elseprintf("Subscribe GPS topic success.\n");while (true) {returnCode = DjiFcSubscription_GetLatestValueOfTopic(DJI_FC_SUBSCRIPTION_TOPIC_RTK_POSITION, (uint8_t *)&data, sizeof(T_DjiFcSubscriptionRtkPosition), ×tamp);printf("microstamp == %u\n", timestamp.microsecond);printf("millistamp == %u\n", timestamp.millisecond);printf("longitude == %lf\n", data.longitude);printf("latitude == %lf\n", data.latitude);printf("hfsl == %lf\n", data.hfsl);returnCode = DjiFcSubscription_GetLatestValueOfTopic(DJI_FC_SUBSCRIPTION_TOPIC_GPS_POSITION, (uint8_t *)&postion, sizeof(T_DjiFcSubscriptionGpsPosition), ×tamp);printf("GPS X == %d\n", postion.x);printf("GPS Y == %d\n", postion.y);printf("GPS Z == %d\n\n", postion.z);osalHandler->TaskSleepMs(2000);}return 0;
}
首先,程序需要創建一個Application,這個Application是一個類,當Application類創建時會調用相應的構造函數來創建一個Dji應用程序核心,這個核心與ROS核心類似。可以推測出,大疆對機載傳感器的管理借鑒了ROS中傳感器節點的管理方法,即將每一個傳感器節點看作一個應用線程。若要了解更多與Application有關的信息,請直接閱讀源碼。
之后,程序開始定義各種后續需要使用的變量,其中T_DjiOsalHandler
是一個**操作系統抽象層(Opertating System Level)**類,這個類用于實現與不同操作系統之間的兼容,本人在代碼中使用了其延時的函數。
T_DjiDataTimestamp, T_DjiFcSubscriptionRtkPosition, T_DjiFcSubscriptionGpsPosition分別記錄了時間戳、RTK和GPS信息,而此處的時間戳是指的程序啟動到當前的運行時間間隔,并非是UNIX時間戳。很遺憾,大疆官方并沒有在源碼的頭文件里面告訴大家后兩個結構體中的詳細成員,但是我們可以從源碼文件sample_c/module_sample/fc_subscription/test_fc_subscription.c
中窺視出其中些許的信息。
test_fc_subscription.c
中的第152至第175行中,給出了FC話題訂閱的方法,我們可以運用該示例代碼,來實現GPS信息的訂閱:
djiStat = DjiFcSubscription_SubscribeTopic(DJI_FC_SUBSCRIPTION_TOPIC_GPS_POSITION,DJI_DATA_SUBSCRIPTION_TOPIC_1_HZ,NULL);if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {USER_LOG_ERROR("Subscribe topic gps position error.");return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;}
djiStat = DjiFcSubscription_GetLatestValueOfTopic(DJI_FC_SUBSCRIPTION_TOPIC_GPS_POSITION,(uint8_t *) &gpsPosition,sizeof(T_DjiFcSubscriptionGpsPosition),×tamp);if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {USER_LOG_ERROR("get value of topic gps position error.");} else {USER_LOG_INFO("gps position: x = %d y = %d z = %d.", gpsPosition.x, gpsPosition.y, gpsPosition.z);}
可以看到,GPS具有X,Y,Z三個信息,其中X表示經度(Longitude),Y表示緯度(Latitude),Z代表海拔高度。RTK與GPS的信息類似。PSDK中任何機載傳感器的遙測數據都通過FC話題進行發布與訂閱,訂閱FC話題的函數為**DjiFcSubscription_SubscribeTopic
,函數的第一個參數決定了遙測數據的類型,是一個宏,所有遙測數據及其對應的宏見參考文檔中的遙測數據訂閱
;第二個參數則用于指定消息獲取的頻率,也是一個宏,本人在代碼中設為了1HZ。通過訂閱函數指定訂閱話題之后,便可以使用DjiFcSubscription_GetLatestValueOfTopic
函數來獲取話題消息中的信息值,該函數的第一個參數和訂閱函數一樣,都是遙測數據對應的宏,第二個參數則是GPS結構體T_DjiFcSubscriptionGpsPosition對應的對象的地址;當使用DjiFcSubscription_GetLatestValueOfTopic
**函數獲取到GPS信息之后,便可以在GPS結構體對象gpsPosition中讀取其GPS信息,
2.3 運行效果
以下是在英偉達開發板上的運行效果,供讀者參考:
至此,讀取機載GPS信息的邏輯介紹完畢。
3 將 PSDK 源碼轉化為 ROS 形式
在一般的項目中,通常是使用ROS來實現傳感器數據的收集與管理,大疆無人機在使用時也是這樣,本章節講述如何將原始PSDK改寫為ROS包。
3.1 文件的布局
一個PSDK中各個模塊功能的實現需要多個頭文件,以及頭文件中定義的函數的C文件組成,因此,在ROS包下的應該具有這些頭文件和C文件,把所有頭文件放在ROS中的include文件夾中,并將所有.c文件放在src文件夾中。本人整理好的文件結構如下:
XXX@YYY:~/dji_ros/src/include$ ls
application.hpp dji_sdk_config.h gimbal interest_point utils
camera_emu dji_sdk_config.json gimbal_emu liveview waypoint_v2
camera_manager fc_subscription gimbal_manager osal waypoint_v3
data_transmission flight_control hms perception widget
dji_sdk_app_info.h flight_controller hms_manager power_management widget_interaction_test
以下是src的結構:
XXX@YYY:~/dji_ros/src/src$ ls
application.cpp fc_subscription gimbal_manager liveview positioning widget
camera_emu flight_control hal main.cpp power_management widget_interaction_test
camera_manager flight_controller hms osal utils
data_transmission gimbal hms_manager payload_collaboration waypoint_v2
dji_sdk_config.json gimbal_emu interest_point perception waypoint_v3
好了,絕對會有人告訴我這是如何整理的。沒有什么技巧,全靠蠻干,哈哈哈哈,就是把PSDK下sample_c和sample_c++的所有.c文件和.cpp文件全部整理好放在include和src文件里面就好了,慢慢來吧,不要心急,慢工出細活,哈哈哈哈。
3.2 主函數的改寫
因為是ROS是基于C++或Python語言進行開發的,所以主函數應該選擇PSDK中的main.cpp。修改main.cpp的方法也很簡單,只需要把GPS的信息對應發布到消息類型為sensor_msgs/NatSatFix
的話題中。
本人修改的地方主要集中在While死循環里:
#include <ros/ros.h>
#include <sensor_msgs/NavSatFix.h>//......ros::init(argc, argv, "dji_ros_gps");ros::NodeHandle nh;sensor_msgs::NavSatFix msg_gps, msg_rtk;ros::Publisher pub_rtk = nh.advertise<sensor_msgs::NavSatFix>("/dji_ros/rtk_info",10);ros::Publisher pub_gps = nh.advertise<sensor_msgs::NavSatFix>("/dji_ros/gps_info",10);while(1){//......msg_gps.header.stamp = ros::Time::now();msg_gps.header.frame_id = "DJI-GPS";msg_gps.status.status = sensor_msgs::NavSatStatus::STATUS_FIX;msg_gps.status.service = sensor_msgs::NavSatStatus::SERVICE_GPS;msg_gps.latitude = postion.x;msg_gps.longitude = postion.y;msg_gps.altitude = postion.z;msg_rtk.header.stamp = ros::Time::now();msg_rtk.header.frame_id = "DJI-RTK";msg_rtk.status.status = sensor_msgs::NavSatStatus::STATUS_FIX;msg_rtk.status.service = sensor_msgs::NavSatStatus::SERVICE_GPS;msg_rtk.latitude = data.latitude;msg_rtk.longitude = data.longitude;msg_rtk.altitude = data.hfsl;pub_rtk.publish(msg_rtk); pub_gps.publish(msg_gps);ROS_INFO("longitude == %lf, latitude == %lf, hfsl == %lf, GPS X == %d, GPS Y == %d, GPS Z == %d", \data.longitude, data.latitude, data.hfsl, postion.x, postion.y, postion.z);r.sleep();ros::spinOnce();}
NatSatFix是一個與地理坐標有關的消息類型,ROS官方給出的NatSatFix信息很齊全:
sensor_msgs是ROS中一個最重要的消息大類,除了NatSatFix之外,還有IMU、CameraInfo、Image等,它包含了當前常用傳感器的數據類型定義。
3.3 CMakeLists.txt的編寫
到了全文檔中最難解決的部分了,CMakeLists.txt是全ROS包中最關鍵的文檔,在這個文檔里,我們需要添加源碼的包含目錄,使之能正常編譯不報出undefined reference XXX的錯誤。最終形成的CMakeLists.txt如下:
cmake_minimum_required(VERSION 3.0.2)
project(dji_ros)find_package(catkin REQUIRED COMPONENTSnav_msgsroscppsensor_msgsstd_msgs
)aux_source_directory(./src SRC_LIST)
aux_source_directory(./src/fc_subscription SRC_LIST)
aux_source_directory(./src/hal SRC_LIST)
aux_source_directory(./src/data_transmission SRC_LIST)
aux_source_directory(./src/camera_manager SRC_LIST)
#aux_source_directory(./src/flight_controller SRC_LIST)
aux_source_directory(./src/gimbal SRC_LIST)
aux_source_directory(./src/hms_manager SRC_LIST)
aux_source_directory(./src/liveview SRC_LIST)
aux_source_directory(./src/perception SRC_LIST)
aux_source_directory(./src/osal SRC_LIST)
aux_source_directory(./src/utils SRC_LIST)
aux_source_directory(./src/flight_control SRC_LIST)
aux_source_directory(./src/gimbal_manager SRC_LIST)
aux_source_directory(./src/gimbal SRC_LIST)
aux_source_directory(./src/hms SRC_LIST)
aux_source_directory(./src/hms_manager SRC_LIST)
aux_source_directory(./src/waypoint_v2 SRC_LIST)
aux_source_directory(./src/waypoint_v3 SRC_LIST)
aux_source_directory(./src/widget SRC_LIST)
aux_source_directory(./src/widget_interaction_test SRC_LIST)
aux_source_directory(./src/interest_point SRC_LIST)
aux_source_directory(./src/power_management SRC_LIST)include_directories(${catkin_INCLUDE_DIRS}${CMAKE_CURRENT_SOURCE_DIR}/src
)add_executable(dji_nav ${SRC_LIST})target_link_libraries(dji_nav${catkin_LIBRARIES}mpayloadsdkpthread
)catkin_package(INCLUDE_DIRS includeLIBRARIES dji_rosCATKIN_DEPENDS roscpp sensor_msgs std_msgs
)
aux_source_directory
是Cmake中用來遞歸添加文件的命令,通過這個命令,我們可以省去一些繁瑣的步驟,只需要把先前展示的include中所有文件夾的內容添加上去即可。
4 結尾
大疆不是沒有給出過類似的ROS包,在OSDK中就有官方自己編寫的ROS代碼——Onboard-SDK-ROS,本人在PSDK中的工作,只能算對OSDK-ROS的拙劣模仿吧,哈哈哈哈。
好了,本文到這里也就講完了所有文件的編輯方法,后續經過catkin_make
編譯之后,只需要運行rosrun dji_ros dji_nav
命令就可以啟動GPS信息的話題發布節點,發布的話題消息在dji_ros/rtk_info
和dji_ros/gps_info
中。本文在實現ROS包的過程中還是留有遺憾,因為時間較為緊張,項目急需要交付,所以flight_controller部分的代碼沒有編譯(catkin_make編譯是屢次報出"undefined reference XXX"的錯誤),這也是后續需要改進的地方吧,本文只是簡簡單單實現一個GPS ROS話題消息發布的功能,并記錄一下自己的心路歷程。
最后還是插一句話:果然,大疆客服在我屢次發郵件問問題之后,解答問題的速度加快了,哈哈哈哈
參考文檔
【0】Payload SDK
PSDK詳細介紹
【1】E-Port 開發者套件
飛行器硬件連接
PSDK各機型連接
【2】PSDK數據的訂閱
遙測數據訂閱
PSDK中如何訂閱數據?
【3】拓展閱讀
時間同步
PSDK各機型連接
飛行器硬件連接
PSDK各機型連接
【2】PSDK數據的訂閱
遙測數據訂閱
PSDK中如何訂閱數據?
【3】拓展閱讀
時間同步
NatSatFix數據類型