AP_Scheduler: removed create() method for objects

See discussion here:

  https://github.com/ArduPilot/ardupilot/issues/7331

we were getting some uninitialised variables. While it only showed up in
AP_SbusOut, it means we can't be sure it won't happen on other objects,
so safest to remove the approach

Thanks to assistance from Lucas, Peter and Francisco
This commit is contained in:
Andrew Tridgell 2017-12-13 12:06:14 +11:00
parent dec3a27d91
commit 580af4a69a
3 changed files with 5 additions and 15 deletions

View File

@ -51,9 +51,7 @@
class AP_Scheduler
{
public:
static AP_Scheduler create() { return AP_Scheduler{}; }
constexpr AP_Scheduler(AP_Scheduler &&other) = default;
AP_Scheduler();
/* Do not allow copies */
AP_Scheduler(const AP_Scheduler &other) = delete;
@ -105,8 +103,6 @@ public:
static int8_t current_task;
private:
AP_Scheduler();
// used to enable scheduler debugging
AP_Int8 _debug;

View File

@ -4,10 +4,7 @@ namespace AP {
class PerfInfo {
public:
static PerfInfo create() { return PerfInfo{}; }
constexpr PerfInfo(PerfInfo &&other) = default;
PerfInfo() {}
/* Do not allow copies */
PerfInfo(const PerfInfo &other) = delete;
@ -25,9 +22,6 @@ public:
uint32_t get_stddev_time() const;
private:
PerfInfo() {}
uint16_t loop_count;
uint32_t max_time; // in microseconds
uint32_t min_time; // in microseconds

View File

@ -16,8 +16,8 @@ public:
private:
AP_InertialSensor ins = AP_InertialSensor::create();
AP_Scheduler scheduler = AP_Scheduler::create();
AP_InertialSensor ins;
AP_Scheduler scheduler;
uint32_t ins_counter;
static const AP_Scheduler::Task scheduler_tasks[];
@ -27,7 +27,7 @@ private:
void five_second_call(void);
};
static AP_BoardConfig board_config = AP_BoardConfig::create();
static AP_BoardConfig board_config;
static SchedTest schedtest;
#define SCHED_TASK(func, _interval_ticks, _max_time_micros) SCHED_TASK_CLASS(SchedTest, &schedtest, func, _interval_ticks, _max_time_micros)