mirror of https://github.com/ArduPilot/ardupilot
Rover: move AP_Stats to AP_vehicle
This commit is contained in:
parent
81231997ff
commit
e4cf674891
|
@ -404,11 +404,6 @@ const AP_Param::Info Rover::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
|
||||
// @Param: SYSID_ENFORCE
|
||||
// @DisplayName: GCS sysid enforcement
|
||||
// @Description: This controls whether packets from other than the expected GCS system ID will be accepted
|
||||
|
@ -921,4 +916,20 @@ void Rover::load_parameters(void)
|
|||
#if AP_FENCE_ENABLED
|
||||
AP_Param::convert_class(info.old_key, &fence, fence.var_info, 17, 4049, false);
|
||||
#endif
|
||||
|
||||
// PARAMETER_CONVERSION - Added: Jan-2024 for Rover-4.6
|
||||
#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
|
||||
|
||||
}
|
||||
|
|
|
@ -293,11 +293,6 @@ public:
|
|||
// var_info for holding Parameter information
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
#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,9 +134,6 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
|
|||
#endif
|
||||
#if HAL_BUTTON_ENABLED
|
||||
SCHED_TASK_CLASS(AP_Button, &rover.button, update, 5, 200, 117),
|
||||
#endif
|
||||
#if STATS_ENABLED == ENABLED
|
||||
SCHED_TASK(stats_update, 1, 200, 120),
|
||||
#endif
|
||||
SCHED_TASK(crash_check, 10, 200, 123),
|
||||
SCHED_TASK(cruise_learn_update, 50, 200, 126),
|
||||
|
@ -302,14 +299,13 @@ void Rover::nav_script_time_done(uint16_t id)
|
|||
}
|
||||
#endif // AP_SCRIPTING_ENABLED
|
||||
|
||||
#if STATS_ENABLED == ENABLED
|
||||
#if AP_STATS_ENABLED
|
||||
/*
|
||||
update AP_Stats
|
||||
*/
|
||||
void Rover::stats_update(void)
|
||||
{
|
||||
g2.stats.set_flying(g2.motors.active());
|
||||
g2.stats.update();
|
||||
AP::stats()->set_flying(g2.motors.active());
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
|
@ -76,10 +76,6 @@
|
|||
#define ADVANCED_FAILSAFE DISABLED
|
||||
#endif
|
||||
|
||||
#ifndef STATS_ENABLED
|
||||
# define STATS_ENABLED ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef OSD_ENABLED
|
||||
#define OSD_ENABLED DISABLED
|
||||
#endif
|
||||
|
|
|
@ -14,11 +14,6 @@ static void failsafe_check_static()
|
|||
|
||||
void Rover::init_ardupilot()
|
||||
{
|
||||
#if STATS_ENABLED == ENABLED
|
||||
// initialise stats module
|
||||
g2.stats.init();
|
||||
#endif
|
||||
|
||||
BoardConfig.init();
|
||||
#if HAL_MAX_CAN_PROTOCOL_DRIVERS
|
||||
can_mgr.init();
|
||||
|
|
Loading…
Reference in New Issue