mirror of https://github.com/ArduPilot/ardupilot
Rover: allow AP_Stats to be optional
This commit is contained in:
parent
98b8a61ca8
commit
bab54ea647
|
@ -87,7 +87,9 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
|
||||||
SCHED_TASK_CLASS(AP_InertialSensor, &rover.ins, periodic, 50, 50),
|
SCHED_TASK_CLASS(AP_InertialSensor, &rover.ins, periodic, 50, 50),
|
||||||
SCHED_TASK_CLASS(AP_Scheduler, &rover.scheduler, update_logging, 0.1, 75),
|
SCHED_TASK_CLASS(AP_Scheduler, &rover.scheduler, update_logging, 0.1, 75),
|
||||||
SCHED_TASK_CLASS(AP_Button, &rover.button, update, 5, 100),
|
SCHED_TASK_CLASS(AP_Button, &rover.button, update, 5, 100),
|
||||||
|
#if STATS_ENABLED == ENABLED
|
||||||
SCHED_TASK(stats_update, 1, 100),
|
SCHED_TASK(stats_update, 1, 100),
|
||||||
|
#endif
|
||||||
SCHED_TASK(crash_check, 10, 1000),
|
SCHED_TASK(crash_check, 10, 1000),
|
||||||
SCHED_TASK(cruise_learn_update, 50, 50),
|
SCHED_TASK(cruise_learn_update, 50, 50),
|
||||||
#if ADVANCED_FAILSAFE == ENABLED
|
#if ADVANCED_FAILSAFE == ENABLED
|
||||||
|
@ -95,6 +97,7 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
|
||||||
#endif
|
#endif
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#if STATS_ENABLED == ENABLED
|
||||||
/*
|
/*
|
||||||
update AP_Stats
|
update AP_Stats
|
||||||
*/
|
*/
|
||||||
|
@ -103,6 +106,7 @@ void Rover::stats_update(void)
|
||||||
g2.stats.set_flying(motor_active());
|
g2.stats.set_flying(motor_active());
|
||||||
g2.stats.update();
|
g2.stats.update();
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
/*
|
/*
|
||||||
setup is called when the sketch starts
|
setup is called when the sketch starts
|
||||||
|
|
|
@ -450,10 +450,11 @@ const AP_Param::Info Rover::var_info[] = {
|
||||||
2nd group of parameters
|
2nd group of parameters
|
||||||
*/
|
*/
|
||||||
const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
||||||
|
#if STATS_ENABLED == ENABLED
|
||||||
// @Group: STAT
|
// @Group: STAT
|
||||||
// @Path: ../libraries/AP_Stats/AP_Stats.cpp
|
// @Path: ../libraries/AP_Stats/AP_Stats.cpp
|
||||||
AP_SUBGROUPINFO(stats, "STAT", 1, ParametersG2, AP_Stats),
|
AP_SUBGROUPINFO(stats, "STAT", 1, ParametersG2, AP_Stats),
|
||||||
|
#endif
|
||||||
// @Param: SYSID_ENFORCE
|
// @Param: SYSID_ENFORCE
|
||||||
// @DisplayName: GCS sysid enforcement
|
// @DisplayName: GCS sysid enforcement
|
||||||
// @Description: This controls whether packets from other than the expected GCS system ID will be accepted
|
// @Description: This controls whether packets from other than the expected GCS system ID will be accepted
|
||||||
|
|
|
@ -284,8 +284,10 @@ public:
|
||||||
// var_info for holding Parameter information
|
// var_info for holding Parameter information
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
|
#if STATS_ENABLED == ENABLED
|
||||||
// vehicle statistics
|
// vehicle statistics
|
||||||
AP_Stats stats;
|
AP_Stats stats;
|
||||||
|
#endif
|
||||||
|
|
||||||
// whether to enforce acceptance of packets only from sysid_my_gcs
|
// whether to enforce acceptance of packets only from sysid_my_gcs
|
||||||
AP_Int8 sysid_enforce;
|
AP_Int8 sysid_enforce;
|
||||||
|
|
|
@ -166,3 +166,7 @@
|
||||||
#ifndef ADVANCED_FAILSAFE
|
#ifndef ADVANCED_FAILSAFE
|
||||||
#define ADVANCED_FAILSAFE DISABLED
|
#define ADVANCED_FAILSAFE DISABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifndef STATS_ENABLED
|
||||||
|
# define STATS_ENABLED ENABLED
|
||||||
|
#endif
|
||||||
|
|
|
@ -32,9 +32,10 @@ void Rover::init_ardupilot()
|
||||||
//
|
//
|
||||||
|
|
||||||
load_parameters();
|
load_parameters();
|
||||||
|
#if STATS_ENABLED == ENABLED
|
||||||
// initialise stats module
|
// initialise stats module
|
||||||
g2.stats.init();
|
g2.stats.init();
|
||||||
|
#endif
|
||||||
|
|
||||||
gcs().set_dataflash(&DataFlash);
|
gcs().set_dataflash(&DataFlash);
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue