mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
ArduCopter: move AP_Stats to AP_Vehicle
This commit is contained in:
parent
652d2ec198
commit
eab70e3a1e
@ -9,7 +9,6 @@
|
||||
//#define AC_OAPATHPLANNER_ENABLED DISABLED // disable path planning around obstacles
|
||||
//#define PARACHUTE DISABLED // disable parachute release to save 1k of flash
|
||||
//#define NAV_GUIDED DISABLED // disable external navigation computer ability to control vehicle through MAV_CMD_NAV_GUIDED mission commands
|
||||
//#define STATS_ENABLED DISABLED // disable statistics support
|
||||
//#define MODE_ACRO_ENABLED DISABLED // disable acrobatic mode support
|
||||
//#define MODE_AUTO_ENABLED DISABLED // disable auto mode support
|
||||
//#define MODE_BRAKE_ENABLED DISABLED // disable brake mode support
|
||||
|
@ -260,9 +260,6 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
|
||||
#if HAL_BUTTON_ENABLED
|
||||
SCHED_TASK_CLASS(AP_Button, &copter.button, update, 5, 100, 168),
|
||||
#endif
|
||||
#if STATS_ENABLED == ENABLED
|
||||
SCHED_TASK_CLASS(AP_Stats, &copter.g2.stats, update, 1, 100, 171),
|
||||
#endif
|
||||
};
|
||||
|
||||
void Copter::get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
|
||||
|
@ -47,7 +47,6 @@
|
||||
#include <AC_AttitudeControl/AC_PosControl.h> // Position control library
|
||||
#include <AC_AttitudeControl/AC_CommandModel.h> // Command model library
|
||||
#include <AP_Motors/AP_Motors.h> // AP Motors library
|
||||
#include <AP_Stats/AP_Stats.h> // statistics library
|
||||
#include <Filter/Filter.h> // Filter library
|
||||
#include <AP_Vehicle/AP_Vehicle.h> // needed for AHRS build
|
||||
#include <AP_InertialNav/AP_InertialNav.h> // inertial navigation library
|
||||
|
@ -821,12 +821,6 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("SYSID_ENFORCE", 11, ParametersG2, sysid_enforce, 0),
|
||||
|
||||
#if STATS_ENABLED == ENABLED
|
||||
// @Group: STAT
|
||||
// @Path: ../libraries/AP_Stats/AP_Stats.cpp
|
||||
AP_SUBGROUPINFO(stats, "STAT", 12, ParametersG2, AP_Stats),
|
||||
#endif
|
||||
|
||||
#if AP_GRIPPER_ENABLED
|
||||
// @Group: GRIP_
|
||||
// @Path: ../libraries/AP_Gripper/AP_Gripper.cpp
|
||||
@ -1382,6 +1376,21 @@ void Copter::load_parameters(void)
|
||||
AP_Param::convert_class(g.k_param_fence_old, &fence, fence.var_info, 0, 0, true);
|
||||
#endif
|
||||
|
||||
// PARAMETER_CONVERSION - Added: Jan-2024 for Copter-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 = 12; // Old parameter index in g2
|
||||
const uint16_t old_top_element = 4044; // 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));
|
||||
|
||||
// setup AP_Param frame type flags
|
||||
|
@ -508,11 +508,6 @@ public:
|
||||
AP_Button *button_ptr;
|
||||
#endif
|
||||
|
||||
#if STATS_ENABLED == ENABLED
|
||||
// vehicle statistics
|
||||
AP_Stats stats;
|
||||
#endif
|
||||
|
||||
#if AP_GRIPPER_ENABLED
|
||||
AP_Gripper gripper;
|
||||
#endif
|
||||
|
@ -617,10 +617,6 @@
|
||||
#error Toy mode is not available on Helicopters
|
||||
#endif
|
||||
|
||||
#ifndef STATS_ENABLED
|
||||
# define STATS_ENABLED ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef OSD_ENABLED
|
||||
#define OSD_ENABLED DISABLED
|
||||
#endif
|
||||
|
@ -1,5 +1,7 @@
|
||||
#include "Copter.h"
|
||||
|
||||
#include <AP_Stats/AP_Stats.h> // statistics library
|
||||
|
||||
// Code to detect a crash main ArduCopter code
|
||||
#define LAND_CHECK_ANGLE_ERROR_DEG 30.0f // maximum angle error to be considered landing
|
||||
#define LAND_CHECK_LARGE_ANGLE_CD 1500.0f // maximum angle target to be considered landing
|
||||
@ -148,8 +150,8 @@ void Copter::set_land_complete(bool b)
|
||||
#endif
|
||||
ap.land_complete = b;
|
||||
|
||||
#if STATS_ENABLED == ENABLED
|
||||
g2.stats.set_flying(!b);
|
||||
#if AP_STATS_ENABLED
|
||||
AP::stats()->set_flying(!b);
|
||||
#endif
|
||||
|
||||
// tell AHRS flying state
|
||||
|
@ -16,11 +16,6 @@ static void failsafe_check_static()
|
||||
void Copter::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
Block a user