Sub: move AP_Stats to AP_vehicle

This commit is contained in:
Peter Barker 2024-01-26 14:05:58 +11:00 committed by Andrew Tridgell
parent 0bc2c15485
commit 81231997ff
5 changed files with 18 additions and 25 deletions

View File

@ -105,7 +105,7 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = {
#if AP_GRIPPER_ENABLED
SCHED_TASK_CLASS(AP_Gripper, &sub.g2.gripper, update, 10, 75, 75),
#endif
#if STATS_ENABLED == ENABLED
#if AP_STATS_ENABLED
SCHED_TASK(stats_update, 1, 200, 76),
#endif
#ifdef USERHOOK_FASTLOOP
@ -370,14 +370,13 @@ bool Sub::get_wp_crosstrack_error_m(float &xtrack_error) const
return true;
}
#if STATS_ENABLED == ENABLED
#if AP_STATS_ENABLED
/*
update AP_Stats
*/
void Sub::stats_update(void)
{
g2.stats.set_flying(motors.armed());
g2.stats.update();
AP::stats()->set_flying(motors.armed());
}
#endif

View File

@ -690,11 +690,6 @@ const AP_Param::Info Sub::var_info[] = {
2nd group of parameters
*/
const AP_Param::GroupInfo ParametersG2::var_info[] = {
#if STATS_ENABLED == ENABLED
// @Group: STAT
// @Path: ../libraries/AP_Stats/AP_Stats.cpp
AP_SUBGROUPINFO(stats, "STAT", 1, ParametersG2, AP_Stats),
#endif
#if HAL_PROXIMITY_ENABLED
// @Group: PRX
// @Path: ../libraries/AP_Proximity/AP_Proximity.cpp
@ -791,6 +786,21 @@ void Sub::load_parameters()
#if AP_FENCE_ENABLED
AP_Param::convert_class(g.k_param_fence_old, &fence, fence.var_info, 0, 0, true);
#endif
// PARAMETER_CONVERSION - Added: Jan-2024
#if AP_STATS_ENABLED
{
// Find G2's Top Level Key
AP_Param::ConversionInfo stats_info;
if (!AP_Param::find_top_level_key_by_pointer(&g2, stats_info.old_key)) {
return;
}
const uint16_t stats_old_index = 1; // Old parameter index in g2
const uint16_t stats_old_top_element = 4033; // Old group element in the tree for the first subgroup element (see AP_PARAM_KEY_DUMP)
AP_Param::convert_class(stats_info.old_key, &stats, stats.var_info, stats_old_index, stats_old_top_element, false);
}
#endif
}
void Sub::convert_old_parameters()

View File

@ -5,7 +5,6 @@
#include <AP_Common/AP_Common.h>
#include <AP_Gripper/AP_Gripper.h>
#include <AP_Stats/AP_Stats.h>
#include <AP_Arming/AP_Arming.h>
#if AP_SCRIPTING_ENABLED
@ -354,10 +353,6 @@ public:
class ParametersG2 {
public:
ParametersG2(void);
#if STATS_ENABLED == ENABLED
// vehicle statistics
AP_Stats stats;
#endif
// var_info for holding Parameter information
static const struct AP_Param::GroupInfo var_info[];

View File

@ -187,12 +187,6 @@
// Logging control
//
// Statistics
#ifndef STATS_ENABLED
# define STATS_ENABLED (AP_STATS_ENABLED ? ENABLED : DISABLED)
#endif
// Default logging bitmask
#ifndef DEFAULT_LOG_BITMASK
# define DEFAULT_LOG_BITMASK \

View File

@ -19,11 +19,6 @@ void Sub::init_ardupilot()
can_mgr.init();
#endif
#if STATS_ENABLED == ENABLED
// initialise stats module
g2.stats.init();
#endif
// init cargo gripper
#if AP_GRIPPER_ENABLED
g2.gripper.init();