Copter: instantiate AP_Mission object

This commit is contained in:
Randy Mackay 2014-02-28 10:16:54 +09:00
parent 1bad6a4b15
commit 5d568502a0

View File

@ -108,6 +108,7 @@
#include <AP_InertialSensor.h> // ArduPilot Mega Inertial Sensor (accel & gyro) Library
#include <AP_AHRS.h>
#include <AP_NavEKF.h>
#include <AP_Mission.h> // Mission command library
#include <AC_PID.h> // PID library
#include <AC_P.h> // P library
#include <AC_AttitudeControl.h> // Attitude control library
@ -347,6 +348,13 @@ AP_AHRS_NavEKF ahrs(ins, barometer, g_gps);
AP_AHRS_DCM ahrs(ins, barometer, g_gps);
#endif
// Mission library
// forward declaration to keep compiler happy
static bool start_command(const AP_Mission::Mission_Command& cmd);
static bool verify_command(const AP_Mission::Mission_Command& cmd);
static void exit_mission();
AP_Mission mission(&start_command, &verify_command, &exit_mission);
////////////////////////////////////////////////////////////////////////////////
// Optical flow sensor
////////////////////////////////////////////////////////////////////////////////
@ -514,18 +522,6 @@ static int32_t home_bearing;
static int32_t home_distance;
// distance between plane and next waypoint in cm.
static uint32_t wp_distance;
// Register containing the index of the current navigation command in the mission script
static int16_t command_nav_index;
// Register containing the index of the previous navigation command in the mission script
// Used to manage the execution of conditional commands
static uint8_t prev_nav_index;
// Register containing the index of the current conditional command in the mission script
static uint8_t command_cond_index;
// Used to track the required WP navigation information
// options include
// NAV_ALTITUDE - have we reached the desired altitude?
// NAV_LOCATION - have we reached the desired location?
// NAV_DELAY - have we waited at the waypoint the desired time?
static float lon_error, lat_error; // Used to report how many cm we are from the next waypoint or loiter target position
static uint8_t land_state; // records state of land (flying to location, descending)
@ -580,14 +576,6 @@ static uint16_t loiter_time_max; // How long we should stay in Lo
static uint32_t loiter_time; // How long have we been loitering - The start time in millis
////////////////////////////////////////////////////////////////////////////////
// CH7 and CH8 save waypoint control
////////////////////////////////////////////////////////////////////////////////
// This register tracks the current Mission Command index when writing
// a mission using Ch7 or Ch8 aux switches in flight
static int8_t aux_switch_wp_index;
////////////////////////////////////////////////////////////////////////////////
// Battery Sensors
////////////////////////////////////////////////////////////////////////////////
@ -614,10 +602,6 @@ static const struct Location &home = ahrs.get_home();
// Current location of the copter
static struct Location current_loc;
// Holds the current loaded command from the EEPROM for navigation
static struct Location command_nav_queue;
// Holds the current loaded command from the EEPROM for conditional scripts
static struct Location command_cond_queue;
////////////////////////////////////////////////////////////////////////////////