AP_Mission: 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:12 +11:00
parent 1dac512567
commit a3e07f66a1
2 changed files with 35 additions and 44 deletions

View File

@ -280,6 +280,34 @@ public:
FUNCTOR_TYPEDEF(mission_cmd_fn_t, bool, const Mission_Command&);
FUNCTOR_TYPEDEF(mission_complete_fn_t, void);
// constructor
AP_Mission(AP_AHRS &ahrs, mission_cmd_fn_t cmd_start_fn, mission_cmd_fn_t cmd_verify_fn, mission_complete_fn_t mission_complete_fn) :
_ahrs(ahrs),
_cmd_start_fn(cmd_start_fn),
_cmd_verify_fn(cmd_verify_fn),
_mission_complete_fn(mission_complete_fn),
_prev_nav_cmd_id(AP_MISSION_CMD_ID_NONE),
_prev_nav_cmd_index(AP_MISSION_CMD_INDEX_NONE),
_prev_nav_cmd_wp_index(AP_MISSION_CMD_INDEX_NONE),
_last_change_time_ms(0)
{
// load parameter defaults
AP_Param::setup_object_defaults(this, var_info);
// clear commands
_nav_cmd.index = AP_MISSION_CMD_INDEX_NONE;
_do_cmd.index = AP_MISSION_CMD_INDEX_NONE;
// initialise other internal variables
_flags.state = MISSION_STOPPED;
_flags.nav_cmd_loaded = false;
_flags.do_cmd_loaded = false;
}
/* Do not allow copies */
AP_Mission(const AP_Mission &other) = delete;
AP_Mission &operator=(const AP_Mission&) = delete;
// mission state enumeration
enum mission_state {
MISSION_STOPPED=0,
@ -287,19 +315,6 @@ public:
MISSION_COMPLETE=2
};
static AP_Mission create(AP_AHRS &ahrs,
mission_cmd_fn_t cmd_start_fn,
mission_cmd_fn_t cmd_verify_fn,
mission_complete_fn_t mission_complete_fn) {
return AP_Mission(ahrs, cmd_start_fn, cmd_verify_fn, mission_complete_fn);
}
constexpr AP_Mission(AP_Mission &&other) = default;
/* Do not allow copies */
AP_Mission(const AP_Mission &other) = delete;
AP_Mission &operator=(const AP_Mission&) = delete;
///
/// public mission methods
///
@ -458,30 +473,6 @@ private:
uint8_t do_cmd_all_done : 1; // true if all "do"/"conditional" commands have been completed (stops unnecessary searching through eeprom for do commands)
} _flags;
AP_Mission(AP_AHRS &ahrs, mission_cmd_fn_t cmd_start_fn, mission_cmd_fn_t cmd_verify_fn, mission_complete_fn_t mission_complete_fn) :
_ahrs(ahrs),
_cmd_start_fn(cmd_start_fn),
_cmd_verify_fn(cmd_verify_fn),
_mission_complete_fn(mission_complete_fn),
_prev_nav_cmd_id(AP_MISSION_CMD_ID_NONE),
_prev_nav_cmd_index(AP_MISSION_CMD_INDEX_NONE),
_prev_nav_cmd_wp_index(AP_MISSION_CMD_INDEX_NONE),
_last_change_time_ms(0)
{
// load parameter defaults
AP_Param::setup_object_defaults(this, var_info);
// clear commands
_nav_cmd.index = AP_MISSION_CMD_INDEX_NONE;
_do_cmd.index = AP_MISSION_CMD_INDEX_NONE;
// initialise other internal variables
_flags.state = MISSION_STOPPED;
_flags.nav_cmd_loaded = false;
_flags.do_cmd_loaded = false;
}
///
/// private methods
///

View File

@ -14,11 +14,11 @@ public:
void loop();
private:
AP_InertialSensor ins = AP_InertialSensor::create();
AP_Baro baro = AP_Baro::create();
AP_GPS gps = AP_GPS::create();
Compass compass = Compass::create();
AP_AHRS_DCM ahrs = AP_AHRS_DCM::create(ins, baro, gps);
AP_InertialSensor ins;
AP_Baro baro;
AP_GPS gps;
Compass compass;
AP_AHRS_DCM ahrs{ins, baro, gps};
// global constants that control how many verify calls must be made for a command before it completes
uint8_t verify_nav_cmd_iterations_to_complete = 3;
@ -44,10 +44,10 @@ private:
void run_replace_cmd_test();
void run_max_cmd_test();
AP_Mission mission = AP_Mission::create(ahrs,
AP_Mission mission{ahrs,
FUNCTOR_BIND_MEMBER(&MissionTest::start_cmd, bool, const AP_Mission::Mission_Command &),
FUNCTOR_BIND_MEMBER(&MissionTest::verify_cmd, bool, const AP_Mission::Mission_Command &),
FUNCTOR_BIND_MEMBER(&MissionTest::mission_complete, void));
FUNCTOR_BIND_MEMBER(&MissionTest::mission_complete, void)};
};
static MissionTest missiontest;