Sub: move Airspeed to AP_Vehicle

This commit is contained in:
Joshua Henderson 2022-01-09 20:36:53 -05:00 committed by Andrew Tridgell
parent ee273da50d
commit a765bb048d
6 changed files with 20 additions and 21 deletions

View File

@ -98,7 +98,6 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = {
#ifdef USERHOOK_SUPERSLOWLOOP
SCHED_TASK(userhook_SuperSlowLoop, 1, 75, 90),
#endif
SCHED_TASK(read_airspeed, 10, 100, 93),
};
void Sub::get_scheduler_tasks(const AP_Scheduler::Task *&tasks,

View File

@ -657,9 +657,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
AP_SUBGROUPINFO(scripting, "SCR_", 18, ParametersG2, AP_Scripting),
#endif
// @Group: ARSPD
// @Path: ../libraries/AP_Airspeed/AP_Airspeed.cpp
AP_SUBGROUPINFO(airspeed, "ARSPD", 19, ParametersG2, AP_Airspeed),
// 19 was airspeed
AP_GROUPEND
};
@ -667,8 +665,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
/*
constructor for g2 object
*/
ParametersG2::ParametersG2():
airspeed()
ParametersG2::ParametersG2()
{
AP_Param::setup_object_defaults(this, var_info);
}
@ -730,6 +727,20 @@ void Sub::load_parameters()
AP_Param::set_by_name("MNT_RC_IN_TILT", 8);
// We should ignore this parameter since ROVs are neutral buoyancy
AP_Param::set_by_name("MOT_THST_HOVER", 0.5);
// PARAMETER_CONVERSION - Added: JAN-2022
#if AP_AIRSPEED_ENABLED
// Find G2's Top Level Key
AP_Param::ConversionInfo info;
if (!AP_Param::find_top_level_key_by_pointer(&g2, info.old_key)) {
return;
}
const uint16_t old_index = 19; // Old parameter index in the tree
const uint16_t old_top_element = 4051; // Old group element in the tree for the first subgroup element
AP_Param::convert_class(info.old_key, &airspeed, airspeed.var_info, old_index, old_top_element, false);
#endif
}
void Sub::convert_old_parameters()

View File

@ -338,10 +338,6 @@ public:
#if AP_SCRIPTING_ENABLED
AP_Scripting scripting;
#endif // AP_SCRIPTING_ENABLED
// Airspeed
AP_Airspeed airspeed;
};
extern const AP_Param::Info var_info[];

View File

@ -577,7 +577,6 @@ private:
bool verify_nav_delay(const AP_Mission::Mission_Command& cmd);
void log_init(void);
void read_airspeed();
void failsafe_leak_check();
void failsafe_internal_pressure_check();

View File

@ -70,11 +70,3 @@ bool Sub::rangefinder_alt_ok() const
{
return (rangefinder_state.enabled && rangefinder_state.alt_healthy);
}
/*
ask airspeed sensor for a new value, duplicated from plane
*/
void Sub::read_airspeed()
{
g2.airspeed.update(should_log(MASK_LOG_IMU));
}

View File

@ -85,6 +85,10 @@ void Sub::init_ardupilot()
AP::compass().set_log_bit(MASK_LOG_COMPASS);
AP::compass().init();
#if AP_AIRSPEED_ENABLED
airspeed.set_log_bit(MASK_LOG_IMU);
#endif
#if AP_OPTICALFLOW_ENABLED
// initialise optical flow sensor
optflow.init(MASK_LOG_OPTFLOW);
@ -155,8 +159,6 @@ void Sub::init_ardupilot()
g2.scripting.init();
#endif // AP_SCRIPTING_ENABLED
g2.airspeed.init();
// we don't want writes to the serial port to cause us to pause
// mid-flight, so set the serial ports non-blocking once we are
// ready to fly