mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 07:13:56 -04:00
global: use static method to construct AP_Mission
This also move the initialization to be in the header for those that weren't already to maintain consistency.
This commit is contained in:
parent
ef50783268
commit
b36a5919f5
@ -31,10 +31,6 @@ Rover::Rover(void) :
|
|||||||
modes(&g.mode1),
|
modes(&g.mode1),
|
||||||
L1_controller(ahrs, nullptr),
|
L1_controller(ahrs, nullptr),
|
||||||
nav_controller(&L1_controller),
|
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),
|
ServoRelayEvents(relay),
|
||||||
#if CAMERA == ENABLED
|
#if CAMERA == ENABLED
|
||||||
camera(&relay, MASK_LOG_CAMERA, current_loc, gps, ahrs),
|
camera(&relay, MASK_LOG_CAMERA, current_loc, gps, ahrs),
|
||||||
|
@ -179,7 +179,10 @@ private:
|
|||||||
AP_Navigation *nav_controller;
|
AP_Navigation *nav_controller;
|
||||||
|
|
||||||
// Mission library
|
// 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
|
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||||
OpticalFlow optflow{ahrs};
|
OpticalFlow optflow{ahrs};
|
||||||
|
@ -26,10 +26,6 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
|||||||
Copter::Copter(void)
|
Copter::Copter(void)
|
||||||
: DataFlash(DataFlash_Class::create(fwver.fw_string, g.log_bitmask)),
|
: DataFlash(DataFlash_Class::create(fwver.fw_string, g.log_bitmask)),
|
||||||
flight_modes(&g.flight_mode1),
|
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),
|
control_mode(STABILIZE),
|
||||||
scaleLongDown(1),
|
scaleLongDown(1),
|
||||||
wp_bearing(0),
|
wp_bearing(0),
|
||||||
|
@ -223,7 +223,10 @@ private:
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Mission library
|
// 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
|
// Arming/Disarming mangement class
|
||||||
AP_Arming_Copter arming {ahrs, barometer, compass, battery, inertial_nav, ins};
|
AP_Arming_Copter arming {ahrs, barometer, compass, battery, inertial_nav, ins};
|
||||||
|
@ -599,10 +599,10 @@ private:
|
|||||||
float smoothed_airspeed;
|
float smoothed_airspeed;
|
||||||
|
|
||||||
// Mission library
|
// 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::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::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
|
#if PARACHUTE == ENABLED
|
||||||
|
@ -25,10 +25,6 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
|||||||
*/
|
*/
|
||||||
Sub::Sub(void)
|
Sub::Sub(void)
|
||||||
: DataFlash(DataFlash_Class::create(fwver.fw_string, g.log_bitmask)),
|
: 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),
|
control_mode(MANUAL),
|
||||||
motors(MAIN_LOOP_RATE),
|
motors(MAIN_LOOP_RATE),
|
||||||
scaleLongDown(1),
|
scaleLongDown(1),
|
||||||
|
@ -193,7 +193,10 @@ private:
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Mission library
|
// 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
|
// Optical flow sensor
|
||||||
#if OPTFLOW == ENABLED
|
#if OPTFLOW == ENABLED
|
||||||
|
@ -44,10 +44,10 @@ private:
|
|||||||
void run_replace_cmd_test();
|
void run_replace_cmd_test();
|
||||||
void run_max_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::start_cmd, bool, const AP_Mission::Mission_Command &),
|
||||||
FUNCTOR_BIND_MEMBER(&MissionTest::verify_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;
|
static MissionTest missiontest;
|
||||||
|
Loading…
Reference in New Issue
Block a user