mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-28 19:48:31 -04:00
AP_Rally: convert to using StorageManager
This commit is contained in:
parent
f133f45c3c
commit
7cbb326405
@ -7,6 +7,9 @@
|
||||
#include <AP_HAL.h>
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
// storage object
|
||||
StorageAccess AP_Rally::_storage(StorageManager::StorageRally);
|
||||
|
||||
// ArduCopter/defines.h sets this, and this definition will be moved into ArduPlane/defines.h when that is patched to use the lib
|
||||
#ifdef APM_BUILD_DIRECTORY
|
||||
#if APM_BUILD_TYPE(APM_BUILD_ArduCopter)
|
||||
@ -41,10 +44,8 @@ const AP_Param::GroupInfo AP_Rally::var_info[] PROGMEM = {
|
||||
};
|
||||
|
||||
// constructor
|
||||
AP_Rally::AP_Rally(AP_AHRS &ahrs, uint16_t max_rally_points, uint16_t rally_start_byte)
|
||||
AP_Rally::AP_Rally(AP_AHRS &ahrs)
|
||||
: _ahrs(ahrs)
|
||||
, _max_rally_points(max_rally_points)
|
||||
, _rally_start_byte(rally_start_byte)
|
||||
, _last_change_time_ms(0xFFFFFFFF)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
@ -57,7 +58,7 @@ bool AP_Rally::get_rally_point_with_index(uint8_t i, RallyLocation &ret) const
|
||||
return false;
|
||||
}
|
||||
|
||||
hal.storage->read_block(&ret, _rally_start_byte + (i * sizeof(RallyLocation)), sizeof(RallyLocation));
|
||||
_storage.read_block(&ret, i * sizeof(RallyLocation), sizeof(RallyLocation));
|
||||
|
||||
if (ret.lat == 0 && ret.lng == 0) {
|
||||
return false; // sanity check
|
||||
@ -73,11 +74,11 @@ bool AP_Rally::set_rally_point_with_index(uint8_t i, const RallyLocation &rallyL
|
||||
return false;
|
||||
}
|
||||
|
||||
if (i >= (uint8_t) _max_rally_points) {
|
||||
if (i >= get_rally_max()) {
|
||||
return false;
|
||||
}
|
||||
|
||||
hal.storage->write_block(_rally_start_byte + (i * sizeof(RallyLocation)), &rallyLoc, sizeof(RallyLocation));
|
||||
_storage.write_block(i * sizeof(RallyLocation), &rallyLoc, sizeof(RallyLocation));
|
||||
|
||||
_last_change_time_ms = hal.scheduler->millis();
|
||||
|
||||
|
@ -20,8 +20,9 @@
|
||||
#include <AP_Common.h>
|
||||
#include <AP_Param.h>
|
||||
#include <AP_AHRS.h>
|
||||
#include <../StorageManager/StorageManager.h>
|
||||
|
||||
#define AC_RALLY_WP_SIZE 15 // eeprom size of rally points
|
||||
#define AP_RALLY_WP_SIZE 15 // eeprom size of rally points
|
||||
|
||||
struct PACKED RallyLocation {
|
||||
int32_t lat; //Latitude * 10^7
|
||||
@ -39,12 +40,13 @@ struct PACKED RallyLocation {
|
||||
class AP_Rally {
|
||||
|
||||
public:
|
||||
AP_Rally(AP_AHRS &ahrs, uint16_t max_rally_points, uint16_t rally_start_byte);
|
||||
AP_Rally(AP_AHRS &ahrs);
|
||||
|
||||
// data handling
|
||||
bool get_rally_point_with_index(uint8_t i, RallyLocation &ret) const;
|
||||
bool set_rally_point_with_index(uint8_t i, const RallyLocation &rallyLoc);
|
||||
uint8_t get_rally_total() const { return _rally_point_total_count; }
|
||||
uint8_t get_rally_max(void) const { return _storage.size() / AP_RALLY_WP_SIZE; }
|
||||
|
||||
float get_rally_limit_km() const { return _rally_limit_km; }
|
||||
|
||||
@ -61,10 +63,10 @@ public:
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
private:
|
||||
static StorageAccess _storage;
|
||||
|
||||
// internal variables
|
||||
const AP_AHRS& _ahrs; // used only for home position
|
||||
uint16_t _max_rally_points;
|
||||
const uint16_t _rally_start_byte;
|
||||
|
||||
// parameters
|
||||
AP_Int8 _rally_point_total_count;
|
||||
|
Loading…
Reference in New Issue
Block a user