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设计