Browse Source

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.
mission-4.1.18
Lucas De Marchi 8 years ago committed by Francisco Ferreira
parent
commit
b36a5919f5
  1. 4
      APMrover2/Rover.cpp
  2. 5
      APMrover2/Rover.h
  3. 4
      ArduCopter/Copter.cpp
  4. 5
      ArduCopter/Copter.h
  5. 4
      ArduPlane/Plane.h
  6. 4
      ArduSub/Sub.cpp
  7. 5
      ArduSub/Sub.h
  8. 4
      libraries/AP_Mission/examples/AP_Mission_test/AP_Mission_test.cpp

4
APMrover2/Rover.cpp

@ -31,10 +31,6 @@ Rover::Rover(void) : @@ -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),

5
APMrover2/Rover.h

@ -179,7 +179,10 @@ private: @@ -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};

4
ArduCopter/Copter.cpp

@ -26,10 +26,6 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); @@ -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),

5
ArduCopter/Copter.h

@ -223,7 +223,10 @@ private: @@ -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};

4
ArduPlane/Plane.h

@ -599,10 +599,10 @@ private: @@ -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

4
ArduSub/Sub.cpp

@ -25,10 +25,6 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); @@ -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),

5
ArduSub/Sub.h

@ -193,7 +193,10 @@ private: @@ -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

4
libraries/AP_Mission/examples/AP_Mission_test/AP_Mission_test.cpp

@ -44,10 +44,10 @@ private: @@ -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;

Loading…
Cancel
Save