mirror of https://github.com/ArduPilot/ardupilot
Plane: move AP_Stats to AP_vehicle
This commit is contained in:
parent
eab70e3a1e
commit
0bc2c15485
|
@ -132,9 +132,6 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
|
|||
#if HAL_BUTTON_ENABLED
|
||||
SCHED_TASK_CLASS(AP_Button, &plane.button, update, 5, 100, 150),
|
||||
#endif
|
||||
#if STATS_ENABLED == ENABLED
|
||||
SCHED_TASK_CLASS(AP_Stats, &plane.g2.stats, update, 1, 100, 153),
|
||||
#endif
|
||||
#if AP_GRIPPER_ENABLED
|
||||
SCHED_TASK_CLASS(AP_Gripper, &plane.g2.gripper, update, 10, 75, 156),
|
||||
#endif
|
||||
|
|
|
@ -1032,11 +1032,6 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
|||
// @Values: 0:NotEnforced,1:Enforced
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("SYSID_ENFORCE", 4, ParametersG2, sysid_enforce, 0),
|
||||
#if STATS_ENABLED == ENABLED
|
||||
// @Group: STAT
|
||||
// @Path: ../libraries/AP_Stats/AP_Stats.cpp
|
||||
AP_SUBGROUPINFO(stats, "STAT", 5, ParametersG2, AP_Stats),
|
||||
#endif
|
||||
|
||||
// @Group: SERVO
|
||||
// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp
|
||||
|
@ -1557,5 +1552,20 @@ void Plane::load_parameters(void)
|
|||
|
||||
landing.convert_parameters();
|
||||
|
||||
// PARAMETER_CONVERSION - Added: Jan-2024 for Plane-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 = 5; // Old parameter index in g2
|
||||
const uint16_t old_top_element = 4037; // 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));
|
||||
}
|
||||
|
|
|
@ -484,11 +484,6 @@ public:
|
|||
AP_Button *button_ptr;
|
||||
#endif
|
||||
|
||||
#if STATS_ENABLED == ENABLED
|
||||
// vehicle statistics
|
||||
AP_Stats stats;
|
||||
#endif
|
||||
|
||||
#if AP_ICENGINE_ENABLED
|
||||
// internal combustion engine control
|
||||
AP_ICEngine ice_control;
|
||||
|
|
|
@ -44,7 +44,6 @@
|
|||
#include <AP_Camera/AP_Camera.h> // Photo or video camera
|
||||
#include <AP_Terrain/AP_Terrain.h>
|
||||
#include <AP_RPM/AP_RPM.h>
|
||||
#include <AP_Stats/AP_Stats.h> // statistics library
|
||||
#include <AP_Beacon/AP_Beacon.h>
|
||||
|
||||
#include <AP_AdvancedFailsafe/AP_AdvancedFailsafe.h>
|
||||
|
|
|
@ -219,10 +219,6 @@
|
|||
#define PARACHUTE HAL_PARACHUTE_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef STATS_ENABLED
|
||||
# define STATS_ENABLED ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef OSD_ENABLED
|
||||
#define OSD_ENABLED DISABLED
|
||||
#endif
|
||||
|
|
|
@ -1,5 +1,7 @@
|
|||
#include "Plane.h"
|
||||
|
||||
#include <AP_Stats/AP_Stats.h> // statistics library
|
||||
|
||||
/*
|
||||
is_flying and crash detection logic
|
||||
*/
|
||||
|
@ -163,8 +165,8 @@ void Plane::update_is_flying_5Hz(void)
|
|||
#if PARACHUTE == ENABLED
|
||||
parachute.set_is_flying(new_is_flying);
|
||||
#endif
|
||||
#if STATS_ENABLED == ENABLED
|
||||
g2.stats.set_flying(new_is_flying);
|
||||
#if AP_STATS_ENABLED
|
||||
AP::stats()->set_flying(new_is_flying);
|
||||
#endif
|
||||
AP_Notify::flags.flying = new_is_flying;
|
||||
|
||||
|
|
|
@ -17,11 +17,6 @@ static void failsafe_check_static()
|
|||
void Plane::init_ardupilot()
|
||||
{
|
||||
|
||||
#if STATS_ENABLED == ENABLED
|
||||
// initialise stats module
|
||||
g2.stats.init();
|
||||
#endif
|
||||
|
||||
ins.set_log_raw_bit(MASK_LOG_IMU_RAW);
|
||||
|
||||
// setup any board specific drivers
|
||||
|
|
Loading…
Reference in New Issue