mirror of https://github.com/ArduPilot/ardupilot
AP_Vehicle: Move AP_Generator to all vehicles
This commit is contained in:
parent
2dc684622e
commit
d25f9d5d3a
|
@ -44,6 +44,12 @@ const AP_Param::GroupInfo AP_Vehicle::var_info[] = {
|
|||
AP_SUBGROUPINFO(frsky_parameters, "FRSKY_", 6, AP_Vehicle, AP_Frsky_Parameters),
|
||||
#endif
|
||||
|
||||
#if GENERATOR_ENABLED
|
||||
// @Group: GEN_
|
||||
// @Path: ../AP_Generator/AP_Generator.cpp
|
||||
AP_SUBGROUPINFO(generator, "GEN_", 7, AP_Vehicle, AP_Generator),
|
||||
#endif
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -132,6 +138,10 @@ void AP_Vehicle::setup()
|
|||
#endif
|
||||
|
||||
send_watchdog_reset_statustext();
|
||||
|
||||
#if GENERATOR_ENABLED
|
||||
generator.init();
|
||||
#endif
|
||||
}
|
||||
|
||||
void AP_Vehicle::loop()
|
||||
|
@ -166,6 +176,9 @@ const AP_Scheduler::Task AP_Vehicle::scheduler_tasks[] = {
|
|||
SCHED_TASK(update_dynamic_notch, 200, 200),
|
||||
SCHED_TASK_CLASS(AP_VideoTX, &vehicle.vtx, update, 2, 100),
|
||||
SCHED_TASK(send_watchdog_reset_statustext, 0.1, 20),
|
||||
#if GENERATOR_ENABLED
|
||||
SCHED_TASK_CLASS(AP_Generator, &vehicle.generator, update, 10, 50),
|
||||
#endif
|
||||
};
|
||||
|
||||
void AP_Vehicle::get_common_scheduler_tasks(const AP_Scheduler::Task*& tasks, uint8_t& num_tasks)
|
||||
|
|
|
@ -26,7 +26,7 @@
|
|||
#include <AP_CANManager/AP_CANManager.h>
|
||||
#include <AP_Button/AP_Button.h>
|
||||
#include <AP_GPS/AP_GPS.h>
|
||||
#include <AP_Generator/AP_Generator_RichenPower.h>
|
||||
#include <AP_Generator/AP_Generator.h>
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
#include <AP_Notify/AP_Notify.h> // Notify library
|
||||
#include <AP_Param/AP_Param.h>
|
||||
|
@ -288,7 +288,7 @@ protected:
|
|||
#endif
|
||||
|
||||
#if GENERATOR_ENABLED
|
||||
AP_Generator_RichenPower generator;
|
||||
AP_Generator generator;
|
||||
#endif
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
|
Loading…
Reference in New Issue