mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 09:43:57 -04:00
Copter: convert to using StorageManager
This commit is contained in:
parent
ce9b14f0c8
commit
e260f1c569
@ -87,6 +87,7 @@
|
|||||||
#include <AP_Progmem.h>
|
#include <AP_Progmem.h>
|
||||||
#include <AP_Menu.h>
|
#include <AP_Menu.h>
|
||||||
#include <AP_Param.h>
|
#include <AP_Param.h>
|
||||||
|
#include <StorageManager.h>
|
||||||
// AP_HAL
|
// AP_HAL
|
||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
#include <AP_HAL_AVR.h>
|
#include <AP_HAL_AVR.h>
|
||||||
@ -323,7 +324,7 @@ SITL sitl;
|
|||||||
static bool start_command(const AP_Mission::Mission_Command& cmd);
|
static bool start_command(const AP_Mission::Mission_Command& cmd);
|
||||||
static bool verify_command(const AP_Mission::Mission_Command& cmd);
|
static bool verify_command(const AP_Mission::Mission_Command& cmd);
|
||||||
static void exit_mission();
|
static void exit_mission();
|
||||||
AP_Mission mission(ahrs, &start_command, &verify_command, &exit_mission, MISSION_START_BYTE, MISSION_END_BYTE);
|
AP_Mission mission(ahrs, &start_command, &verify_command, &exit_mission);
|
||||||
|
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
// Optical flow sensor
|
// Optical flow sensor
|
||||||
@ -716,7 +717,7 @@ AC_Fence fence(&inertial_nav);
|
|||||||
// Rally library
|
// Rally library
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
#if AC_RALLY == ENABLED
|
#if AC_RALLY == ENABLED
|
||||||
AP_Rally rally(ahrs, MAX_RALLYPOINTS, RALLY_START_BYTE);
|
AP_Rally rally(ahrs);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
@ -766,7 +767,7 @@ static void pre_arm_checks(bool display_failure);
|
|||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
|
|
||||||
// setup the var_info table
|
// setup the var_info table
|
||||||
AP_Param param_loader(var_info, MISSION_START_BYTE);
|
AP_Param param_loader(var_info);
|
||||||
|
|
||||||
#if MAIN_LOOP_RATE == 400
|
#if MAIN_LOOP_RATE == 400
|
||||||
/*
|
/*
|
||||||
@ -912,6 +913,9 @@ void setup()
|
|||||||
// Load the default values of variables listed in var_info[]s
|
// Load the default values of variables listed in var_info[]s
|
||||||
AP_Param::setup_sketch_defaults();
|
AP_Param::setup_sketch_defaults();
|
||||||
|
|
||||||
|
// setup storage layout for copter
|
||||||
|
StorageManager::set_layout_copter();
|
||||||
|
|
||||||
init_ardupilot();
|
init_ardupilot();
|
||||||
|
|
||||||
// initialise the main loop scheduler
|
// initialise the main loop scheduler
|
||||||
|
@ -1329,7 +1329,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
break;
|
break;
|
||||||
|
|
||||||
if (packet.idx >= rally.get_rally_total() ||
|
if (packet.idx >= rally.get_rally_total() ||
|
||||||
packet.idx >= MAX_RALLYPOINTS) {
|
packet.idx >= rally.get_rally_max()) {
|
||||||
send_text_P(SEVERITY_LOW,PSTR("bad rally point message ID"));
|
send_text_P(SEVERITY_LOW,PSTR("bad rally point message ID"));
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
@ -310,25 +310,6 @@ enum FlipState {
|
|||||||
// Centi-degrees to radians
|
// Centi-degrees to radians
|
||||||
#define DEGX100 5729.57795f
|
#define DEGX100 5729.57795f
|
||||||
|
|
||||||
// fence points are stored at the end of the EEPROM
|
|
||||||
#define MAX_FENCEPOINTS 6
|
|
||||||
#define FENCE_WP_SIZE sizeof(Vector2l)
|
|
||||||
#define FENCE_START_BYTE (HAL_STORAGE_SIZE_AVAILABLE-(MAX_FENCEPOINTS*FENCE_WP_SIZE))
|
|
||||||
|
|
||||||
// rally points shoehorned between fence points and waypoints
|
|
||||||
#define MAX_RALLYPOINTS 6
|
|
||||||
#define RALLY_START_BYTE (FENCE_START_BYTE-(MAX_RALLYPOINTS*AC_RALLY_WP_SIZE))
|
|
||||||
#define RALLY_LIMIT_KM_DEFAULT 2.0 // we'll set a per-vehicle default for this
|
|
||||||
|
|
||||||
// parameters get the first 1536 bytes of EEPROM
|
|
||||||
// mission commands are stored between these params and the rally points, or fence points if rally disabled
|
|
||||||
#define MISSION_START_BYTE 0x600
|
|
||||||
#if AC_RALLY == ENABLED
|
|
||||||
#define MISSION_END_BYTE (RALLY_START_BYTE-1)
|
|
||||||
#else
|
|
||||||
#define MISSION_END_BYTE (FENCE_START_BYTE-1)
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// mark a function as not to be inlined
|
// mark a function as not to be inlined
|
||||||
#define NOINLINE __attribute__((noinline))
|
#define NOINLINE __attribute__((noinline))
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user