ArduPilot中beacon
ctime:2019-03-13 14:45:31 +0800|1552459531
标签(空格分隔): 技术 飞控
初始化过程:
在主文件中的init_ardupilot
函数中进行各种传感器、串口、外设的初始化。
init_beacon
初始化beacon设备,并在接下来
ahrs.set_beacon(&g2.beacon);
中将其绑定在ahrs对象中,因为ahrs解算姿态的时候,会用到beacon(如果有beacon设备的话)。
init_beacon
的实现如下:
void AP_Beacon::init(void)
{
if (_driver != nullptr) {
// init called a 2nd time?
return;
}
// create backend
if (_type == AP_BeaconType_Pozyx) {
_driver = new AP_Beacon_Pozyx(*this, serial_manager);
} else if (_type == AP_BeaconType_Marvelmind) {
_driver = new AP_Beacon_Marvelmind(*this, serial_manager);
}
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
if (_type == AP_BeaconType_SITL) {