Blimp: move AP_Stats to AP_vehicle
This commit is contained in:
parent
e4cf674891
commit
0a5b6c7797
@ -95,9 +95,6 @@ const AP_Scheduler::Task Blimp::scheduler_tasks[] = {
|
||||
#if HAL_LOGGING_ENABLED
|
||||
SCHED_TASK_CLASS(AP_Scheduler, &blimp.scheduler, update_logging, 0.1, 75, 69),
|
||||
#endif
|
||||
#if STATS_ENABLED == ENABLED
|
||||
SCHED_TASK_CLASS(AP_Stats, &blimp.g2.stats, update, 1, 100, 75),
|
||||
#endif
|
||||
};
|
||||
|
||||
void Blimp::get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
|
||||
|
@ -39,7 +39,6 @@
|
||||
// #include <AP_AccelCal/AP_AccelCal.h> // interface and maths for accelerometer calibration
|
||||
// #include <AP_InertialSensor/AP_InertialSensor.h> // ArduPilot Mega Inertial Sensor (accel & gyro) Library
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <AP_Stats/AP_Stats.h> // statistics library
|
||||
#include <Filter/Filter.h> // Filter library
|
||||
#include <AP_Vehicle/AP_Vehicle.h> // needed for AHRS build
|
||||
#include <AP_InertialNav/AP_InertialNav.h> // inertial navigation library
|
||||
|
@ -780,12 +780,6 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("SYSID_ENFORCE", 11, ParametersG2, sysid_enforce, 0),
|
||||
|
||||
#if STATS_ENABLED == ENABLED
|
||||
// @Group: STAT
|
||||
// @Path: ../libraries/AP_Stats/AP_Stats.cpp
|
||||
AP_SUBGROUPINFO(stats, "STAT", 12, ParametersG2, AP_Stats),
|
||||
#endif
|
||||
|
||||
// @Param: FRAME_CLASS
|
||||
// @DisplayName: Frame Class
|
||||
// @Description: Controls major frame class for blimp.
|
||||
@ -874,6 +868,21 @@ void Blimp::load_parameters(void)
|
||||
// Load all auto-loaded EEPROM variables
|
||||
AP_Param::load_all();
|
||||
|
||||
// PARAMETER_CONVERSION - Added: Jan-2024 for Copter-4.6
|
||||
#if AP_STATS_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 = 12; // Old parameter index in g2
|
||||
const uint16_t old_top_element = 4044; // Old group element in the tree for the first subgroup element (see AP_PARAM_KEY_DUMP)
|
||||
AP_Param::convert_class(info.old_key, &stats, stats.var_info, old_index, old_top_element, false);
|
||||
}
|
||||
#endif
|
||||
|
||||
hal.console->printf("load_all took %uus\n", (unsigned)(micros() - before));
|
||||
|
||||
// setup AP_Param frame type flags
|
||||
|
@ -281,11 +281,6 @@ public:
|
||||
// altitude at which nav control can start in takeoff
|
||||
AP_Float wp_navalt_min;
|
||||
|
||||
#if STATS_ENABLED == ENABLED
|
||||
// vehicle statistics
|
||||
AP_Stats stats;
|
||||
#endif
|
||||
|
||||
// whether to enforce acceptance of packets only from sysid_my_gcs
|
||||
AP_Int8 sysid_enforce;
|
||||
|
||||
|
@ -134,10 +134,6 @@
|
||||
# define CH_MODE_DEFAULT 5
|
||||
#endif
|
||||
|
||||
#ifndef STATS_ENABLED
|
||||
# define STATS_ENABLED ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef HAL_FRAME_TYPE_DEFAULT
|
||||
#define HAL_FRAME_TYPE_DEFAULT Fins::MOTOR_FRAME_TYPE_AIRFISH
|
||||
#endif
|
||||
|
@ -15,11 +15,6 @@ static void failsafe_check_static()
|
||||
void Blimp::init_ardupilot()
|
||||
{
|
||||
|
||||
#if STATS_ENABLED == ENABLED
|
||||
// initialise stats module
|
||||
g2.stats.init();
|
||||
#endif
|
||||
|
||||
BoardConfig.init();
|
||||
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user