diff --git a/libraries/AP_Mission/AP_Mission.h b/libraries/AP_Mission/AP_Mission.h index 3bb063be0a..0df0710cc4 100644 --- a/libraries/AP_Mission/AP_Mission.h +++ b/libraries/AP_Mission/AP_Mission.h @@ -272,30 +272,19 @@ public: MISSION_COMPLETE=2 }; - /// 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; + 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 /// @@ -454,6 +443,30 @@ 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 ///