diff --git a/APMrover2/Rover.cpp b/APMrover2/Rover.cpp index 91c6278139..fad1c3727b 100644 --- a/APMrover2/Rover.cpp +++ b/APMrover2/Rover.cpp @@ -31,10 +31,6 @@ Rover::Rover(void) : modes(&g.mode1), L1_controller(ahrs, nullptr), nav_controller(&L1_controller), - mission(ahrs, - FUNCTOR_BIND_MEMBER(&Rover::start_command, bool, const AP_Mission::Mission_Command&), - FUNCTOR_BIND_MEMBER(&Rover::verify_command_callback, bool, const AP_Mission::Mission_Command&), - FUNCTOR_BIND_MEMBER(&Rover::exit_mission, void)), ServoRelayEvents(relay), #if CAMERA == ENABLED camera(&relay, MASK_LOG_CAMERA, current_loc, gps, ahrs), diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index 9976199b88..4f56e6e2dd 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -179,7 +179,10 @@ private: AP_Navigation *nav_controller; // Mission library - AP_Mission mission; + AP_Mission mission = AP_Mission::create(ahrs, + FUNCTOR_BIND_MEMBER(&Rover::start_command, bool, const AP_Mission::Mission_Command&), + FUNCTOR_BIND_MEMBER(&Rover::verify_command_callback, bool, const AP_Mission::Mission_Command&), + FUNCTOR_BIND_MEMBER(&Rover::exit_mission, void)); #if AP_AHRS_NAVEKF_AVAILABLE OpticalFlow optflow{ahrs}; diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index bf2b6c39db..6b2708a123 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -26,10 +26,6 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); Copter::Copter(void) : DataFlash(DataFlash_Class::create(fwver.fw_string, g.log_bitmask)), flight_modes(&g.flight_mode1), - mission(ahrs, - FUNCTOR_BIND_MEMBER(&Copter::start_command, bool, const AP_Mission::Mission_Command &), - FUNCTOR_BIND_MEMBER(&Copter::verify_command_callback, bool, const AP_Mission::Mission_Command &), - FUNCTOR_BIND_MEMBER(&Copter::exit_mission, void)), control_mode(STABILIZE), scaleLongDown(1), wp_bearing(0), diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 6c5934bcd1..d62ca15218 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -223,7 +223,10 @@ private: #endif // Mission library - AP_Mission mission; + AP_Mission mission = AP_Mission::create(ahrs, + FUNCTOR_BIND_MEMBER(&Copter::start_command, bool, const AP_Mission::Mission_Command &), + FUNCTOR_BIND_MEMBER(&Copter::verify_command_callback, bool, const AP_Mission::Mission_Command &), + FUNCTOR_BIND_MEMBER(&Copter::exit_mission, void)); // Arming/Disarming mangement class AP_Arming_Copter arming {ahrs, barometer, compass, battery, inertial_nav, ins}; diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index cf895a72b8..92598cb48b 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -599,10 +599,10 @@ private: float smoothed_airspeed; // Mission library - AP_Mission mission {ahrs, + AP_Mission mission = AP_Mission::create(ahrs, FUNCTOR_BIND_MEMBER(&Plane::start_command_callback, bool, const AP_Mission::Mission_Command &), FUNCTOR_BIND_MEMBER(&Plane::verify_command_callback, bool, const AP_Mission::Mission_Command &), - FUNCTOR_BIND_MEMBER(&Plane::exit_mission_callback, void)}; + FUNCTOR_BIND_MEMBER(&Plane::exit_mission_callback, void)); #if PARACHUTE == ENABLED diff --git a/ArduSub/Sub.cpp b/ArduSub/Sub.cpp index e705575681..a0c1d16ff0 100644 --- a/ArduSub/Sub.cpp +++ b/ArduSub/Sub.cpp @@ -25,10 +25,6 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); */ Sub::Sub(void) : DataFlash(DataFlash_Class::create(fwver.fw_string, g.log_bitmask)), - mission(ahrs, - FUNCTOR_BIND_MEMBER(&Sub::start_command, bool, const AP_Mission::Mission_Command &), - FUNCTOR_BIND_MEMBER(&Sub::verify_command_callback, bool, const AP_Mission::Mission_Command &), - FUNCTOR_BIND_MEMBER(&Sub::exit_mission, void)), control_mode(MANUAL), motors(MAIN_LOOP_RATE), scaleLongDown(1), diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index 2521d13ed0..137df0f5c9 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -193,7 +193,10 @@ private: #endif // Mission library - AP_Mission mission; + AP_Mission mission = AP_Mission::create(ahrs, + FUNCTOR_BIND_MEMBER(&Sub::start_command, bool, const AP_Mission::Mission_Command &), + FUNCTOR_BIND_MEMBER(&Sub::verify_command_callback, bool, const AP_Mission::Mission_Command &), + FUNCTOR_BIND_MEMBER(&Sub::exit_mission, void)); // Optical flow sensor #if OPTFLOW == ENABLED diff --git a/libraries/AP_Mission/examples/AP_Mission_test/AP_Mission_test.cpp b/libraries/AP_Mission/examples/AP_Mission_test/AP_Mission_test.cpp index a5c1ed1e63..4544b128fc 100644 --- a/libraries/AP_Mission/examples/AP_Mission_test/AP_Mission_test.cpp +++ b/libraries/AP_Mission/examples/AP_Mission_test/AP_Mission_test.cpp @@ -44,10 +44,10 @@ private: void run_replace_cmd_test(); void run_max_cmd_test(); - AP_Mission mission{ahrs, + AP_Mission mission = AP_Mission::create(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;