mirror of https://github.com/ArduPilot/ardupilot
Tracker: move AP_Stats to AP_vehicle
This commit is contained in:
parent
2761a528f3
commit
3b1ec57f54
|
@ -560,10 +560,6 @@ const AP_Param::Info Tracker::var_info[] = {
|
|||
// @User: Standard
|
||||
GSCALAR(disarm_pwm, "SAFE_DISARM_PWM", 0),
|
||||
|
||||
// @Group: STAT
|
||||
// @Path: ../libraries/AP_Stats/AP_Stats.cpp
|
||||
GOBJECT(stats, "STAT", AP_Stats),
|
||||
|
||||
// @Param: AUTO_OPTIONS
|
||||
// @DisplayName: Auto mode options
|
||||
// @Description: 1: Scan for unknown target
|
||||
|
@ -617,6 +613,12 @@ void Tracker::load_parameters(void)
|
|||
uint32_t before = AP_HAL::micros();
|
||||
// Load all auto-loaded EEPROM variables
|
||||
AP_Param::load_all();
|
||||
|
||||
#if AP_STATS_ENABLED
|
||||
// PARAMETER_CONVERSION - Added: Jan-2024
|
||||
AP_Param::convert_class(g.k_param_stats_old, &stats, stats.var_info, 0, 0, true);
|
||||
#endif
|
||||
|
||||
hal.console->printf("load_all took %luus\n", (unsigned long)(AP_HAL::micros() - before));
|
||||
|
||||
#if HAL_HAVE_SAFETY_SWITCH
|
||||
|
|
|
@ -114,7 +114,7 @@ public:
|
|||
k_param_rc_channels,
|
||||
k_param_servo_channels,
|
||||
|
||||
k_param_stats = 218,
|
||||
k_param_stats_old = 218,
|
||||
k_param_scripting = 219,
|
||||
|
||||
//
|
||||
|
|
|
@ -159,8 +159,7 @@ Mode *Tracker::mode_from_mode_num(const Mode::Number num)
|
|||
*/
|
||||
void Tracker::stats_update(void)
|
||||
{
|
||||
stats.set_flying(hal.util->get_soft_armed());
|
||||
stats.update();
|
||||
AP::stats()->set_flying(hal.util->get_soft_armed());
|
||||
}
|
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
|
|
@ -40,7 +40,6 @@
|
|||
#include <SRV_Channel/SRV_Channel.h>
|
||||
#include <AP_Vehicle/AP_Vehicle.h>
|
||||
#include <AP_Mission/AP_Mission.h>
|
||||
#include <AP_Stats/AP_Stats.h> // statistics library
|
||||
#include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library
|
||||
|
||||
// Configuration
|
||||
|
@ -98,8 +97,6 @@ private:
|
|||
GCS_Tracker _gcs; // avoid using this; use gcs()
|
||||
GCS_Tracker &gcs() { return _gcs; }
|
||||
|
||||
AP_Stats stats;
|
||||
|
||||
// Battery Sensors
|
||||
AP_BattMonitor battery{MASK_LOG_CURRENT,
|
||||
FUNCTOR_BIND_MEMBER(&Tracker::handle_battery_failsafe, void, const char*, const int8_t),
|
||||
|
|
|
@ -5,9 +5,6 @@ static const StorageAccess wp_storage(StorageManager::StorageMission);
|
|||
|
||||
void Tracker::init_ardupilot()
|
||||
{
|
||||
// initialise stats module
|
||||
stats.init();
|
||||
|
||||
BoardConfig.init();
|
||||
#if HAL_MAX_CAN_PROTOCOL_DRIVERS
|
||||
can_mgr.init();
|
||||
|
|
Loading…
Reference in New Issue