ArduPilot開源代碼之OpticalFlow_backend
- 1. 源由
- 2. Library設計
- 3. 重要例程
- 3.1 OpticalFlow_backend::_update_frontend
- 3.2 OpticalFlow_backend::_applyYaw
- 4. 總結
- 5. 參考資料
1. 源由
光流計是一種低成本定位傳感器,所有的光流計設備傳感驅動代碼抽象公共部分統一由OpticalFlow_backend
實現。設計的核心思想是將光流傳感器的具體實現與其前端接口分離開來,通過純虛函數和友元類的機制,實現了靈活且可擴展的架構。
2. Library設計
OpticalFlow_backend類是一個抽象基類,用于表示光流傳感器的后端實現。它包含了一些基本的接口函數,如初始化、更新和消息處理函數。
- 公共部分使用虛函數,根據不同硬件傳感設備進行實現;
- init函數是一個虛函數,允許子類在必要時重寫初始化過程。
- update函數是一個純虛函數,強制所有子類必須實現自己的更新邏輯。
- handle_msg和handle_msp函數用于處理不同類型的消息,提供了默認的空實現,子類可以根據需要進行重寫。
- 保護部分直接抽象的公共部分的函數實現,如訪問前端對象、更新前端狀態、獲取縮放參數、計算偏航角等。
- AP_OpticalFlow類被聲明為友元類,允許它訪問OpticalFlow_backend的私有和保護成員。這表示AP_OpticalFlow可能是該后端類的管理類或控制類。
- **CLASS_NO_COPY(OpticalFlow_backend)**是一個宏,用于禁止該類的拷貝構造和賦值操作,確保每個對象都是唯一的。
class OpticalFlow_backend
{// 將AP_OpticalFlow類聲明為友元類,允許其訪問OpticalFlow_backend的私有成員friend class AP_OpticalFlow;public:// 構造函數,接受一個AP_OpticalFlow對象的引用OpticalFlow_backend(AP_OpticalFlow &_frontend);// 虛析構函數,允許子類重寫virtual ~OpticalFlow_backend(void);// 禁止拷貝構造和拷貝賦值操作CLASS_NO_COPY(OpticalFlow_backend);// 初始化傳感器的函數,默認實現為空virtual void init() {}// 從傳感器讀取最新的值并填充x, y和totals的純虛函數,必須在子類中實現virtual void update() = 0;// 處理光流的mavlink消息的虛函數,默認實現為空virtual void handle_msg(const mavlink_message_t &msg) {}#if HAL_MSP_OPTICALFLOW_ENABLED// 處理光流的msp消息的虛函數,默認實現為空virtual void handle_msp(const MSP::msp_opflow_data_message_t &pkt) {}
#endifprotected:// 前端對象的引用AP_OpticalFlow &frontend;// 更新前端狀態的函數void _update_frontend(const struct AP_OpticalFlow::OpticalFlow_state &state);// 獲取光流縮放參數的函數,返回一個包含X和Y軸縮放因子的向量Vector2f _flowScaler(void) const { return Vector2f(frontend._flowScalerX, frontend._flowScalerY); }// 獲取以弧度表示的偏航角的函數float _yawAngleRad(void) const { return radians(float(frontend._yawAngle_cd) * 0.01f); }// 應用偏航角到一個向量上的函數void _applyYaw(Vector2f &v);// 獲取ADDR參數值的函數uint8_t get_address(void) const { return frontend._address; }// 用于訪問共享前端數據的信號量HAL_Semaphore _sem;
};
3. 重要例程
3.1 OpticalFlow_backend::_update_frontend
// update the frontend
void OpticalFlow_backend::_update_frontend(const struct AP_OpticalFlow::OpticalFlow_state &state)
{frontend.update_state(state);
}
3.2 OpticalFlow_backend::_applyYaw
// apply yaw angle to a vector
void OpticalFlow_backend::_applyYaw(Vector2f &v)
{float yawAngleRad = _yawAngleRad();if (is_zero(yawAngleRad)) {return;}v.rotate(yawAngleRad);
}
4. 總結
OpticalFlow_backend
繼承出來的硬件傳感設備在Ardupilot上,目前有以下幾類設備:
- AP_OpticalFlow_CXOF
- AP_OpticalFlow_HereFlow
- AP_OpticalFlow_MAV
- AP_OpticalFlow_MSP
- AP_OpticalFlow_Onboard
- AP_OpticalFlow_Pixart
- AP_OpticalFlow_PX4Flow
- AP_OpticalFlow_SITL
- AP_OpticalFlow_UPFLOW
MATEKSYS Optical Flow & LIDAR 3901-L0X是其中的一種。
- 傳感模塊:MATEKSYS Optical Flow & LIDAR 3901-L0X
- [ArduPilot開源代碼之MatekSys Optical Flow 3901-L0X](ArduPilot開源代碼之MatekSys Optical Flow 3901-L0X)
- ArduPilot開源飛控之AP_OpticalFlow
5. 參考資料
【1】ArduPilot開源飛控系統之簡單介紹
【2】ArduPilot之開源代碼Task介紹
【3】ArduPilot飛控啟動&運行過程簡介
【4】ArduPilot之開源代碼Library&Sketches設計
【5】ArduPilot之開源代碼Sensor Drivers設計