有時候,我們的飛控需要引入一些外部IO信號,比如:
01相機拍照反饋
單反相機熱靴接口的反饋信號,用于將照片拍攝的位置和時間保存到飛控的日志中;
02液位儀IO信號
植保無人機檢測剩余藥量是否低于警戒值;
03彈射檢測信號
通過一個金屬觸點彈片來檢測無人機是否從發射架上彈射出去,對于一些需要延遲開啟推進電機的應用比較有用。
硬件基礎
對于大部分運行APM固件的飛控來講,其第9通道以后(含)的PWM輸出通道同時也支持作為GPIO輸入,當然,部分飛控硬件的前8個通道也支持作為GPIO輸入,這與飛控的硬件架構相關。
如下圖所示,此飛控的PWM1~PWM8使用了SN74LVC8T245這款芯片作為接口保護芯片,并且將此芯片的方向控制引腳固定拉低,從而這8個通道只支持作為PWM輸出或者GPIO輸出。
如下圖所示,其PWM9~PWM16通道使用了TXS0108ERGYR這款芯片作為接口保護芯片,這款芯片支持自動切換各個通道的方向的功能,因此這8個通道既可以作為PWM輸出,也可以作為GPIO輸入。
軟件編程
APM固件的GPIO輸入功能的使用是非常簡單的,如下面的例子所示:
// 第一步,將GPIO50設置為輸入模式
hal.gpio- >pinMode(50, HAL_GPIO_INPUT);
// 第二步,將GPIO50設置為內部上拉(可選,可以不上拉;如果要下拉,則第二個參數設置為0)
hal.gpio- >write(50, 1);
// 第三步,讀取GPIO50的狀態,返回值為0表示低電平,為1表示高電平
uint8_t gpio_state = hal.gpio- >read(50);
注意,例程中的“50”是“軟件層面”的GPIO號,不是STM32單片機“硬件層面”的GPIO號, 并且各個飛控的定義不同。此值的定義在APM源代碼“Libraries/AP_HAL_ChibiOS/hwdef/飛控硬件名/hwdef.dat”中,下圖為原版Pixhawk對于GPIO號的定義:
參數設置
對于最新的APM固件,“BRD_PWM_COUNT”這個參數已經被刪掉了,因此不需要設置這個參數。
SERVOx_FUNCTION:設置為-1。注意,AUX OUT引腳的標號在參數表中是從9開始依次遞增的,如AUX OUT 1引腳對應SERVO9,AUX OUT 2引腳對應SERVO10,依次類推。
你看的沒錯,只需要設置這一個參數即可,非常簡單。
結語
以上就是APM固件GPIO輸入功能的使用方法,希望對對大家有所幫助,
-
單片機
+關注
關注
6039文章
44583瀏覽量
636629 -
PWM
+關注
關注
114文章
5193瀏覽量
214301 -
STM32
+關注
關注
2270文章
10910瀏覽量
356658 -
GPIO
+關注
關注
16文章
1213瀏覽量
52193 -
IO信號
+關注
關注
0文章
6瀏覽量
2086
發布評論請先 登錄
相關推薦
評論