AP_Vehicle: move Airspeed to AP_Vehicle

This commit is contained in:
Joshua Henderson 2022-01-03 16:17:01 -05:00 committed by Andrew Tridgell
parent 3cfbad0f4d
commit ee273da50d
2 changed files with 25 additions and 1 deletions

View File

@ -67,6 +67,12 @@ const AP_Param::GroupInfo AP_Vehicle::var_info[] = {
AP_SUBGROUPINFO(efi, "EFI", 9, AP_Vehicle, AP_EFI),
#endif
#if AP_AIRSPEED_ENABLED
// @Group: ARSPD
// @Path: ../AP_Airspeed/AP_Airspeed.cpp
AP_SUBGROUPINFO(airspeed, "ARSPD", 10, AP_Vehicle, AP_Airspeed),
#endif
AP_GROUPEND
};
@ -146,6 +152,18 @@ void AP_Vehicle::setup()
// init_ardupilot is where the vehicle does most of its initialisation.
init_ardupilot();
#if AP_AIRSPEED_ENABLED
airspeed.init();
if (airspeed.enabled()) {
airspeed.calibrate(true);
}
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
else {
GCS_SEND_TEXT(MAV_SEVERITY_WARNING,"No airspeed sensor present or enabled");
}
#endif
#endif // AP_AIRSPEED_ENABLED
#if !APM_BUILD_TYPE(APM_BUILD_Replay)
SRV_Channels::init();
#endif
@ -256,6 +274,9 @@ SCHED_TASK_CLASS arguments:
*/
const AP_Scheduler::Task AP_Vehicle::scheduler_tasks[] = {
#if AP_AIRSPEED_ENABLED
SCHED_TASK_CLASS(AP_Airspeed, &vehicle.airspeed, update, 10, 100, 41), // NOTE: the priority number here should be right before Plane's calc_airspeed_errors
#endif
#if HAL_RUNCAM_ENABLED
SCHED_TASK_CLASS(AP_RunCam, &vehicle.runcam, update, 50, 50, 200),
#endif
@ -486,7 +507,6 @@ void AP_Vehicle::accel_cal_update()
#endif // HAL_INS_ENABLED
}
AP_Vehicle *AP_Vehicle::_singleton = nullptr;
AP_Vehicle *AP_Vehicle::get_singleton()

View File

@ -367,6 +367,10 @@ protected:
AP_EFI efi;
#endif
#if AP_AIRSPEED_ENABLED
AP_Airspeed airspeed;
#endif
static const struct AP_Param::GroupInfo var_info[];
static const struct AP_Scheduler::Task scheduler_tasks[];