mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Rally: correct math conversion problems
If the rally point storage size got *large* you'd end up with integer overflow problems here.
This commit is contained in:
parent
e3057b40f3
commit
ddfccf1e67
@ -9,6 +9,8 @@
|
||||
// storage object
|
||||
StorageAccess AP_Rally::_storage(StorageManager::StorageRally);
|
||||
|
||||
assert_storage_size<RallyLocation, 15> _assert_storage_size_RallyLocation;
|
||||
|
||||
#if APM_BUILD_TYPE(APM_BUILD_ArduCopter)
|
||||
#define RALLY_LIMIT_KM_DEFAULT 0.3f
|
||||
#define RALLY_INCLUDE_HOME_DEFAULT 1
|
||||
|
@ -18,8 +18,6 @@
|
||||
#include <AP_Common/Location.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
|
||||
#define AP_RALLY_WP_SIZE 15 // eeprom size of rally points
|
||||
|
||||
struct PACKED RallyLocation {
|
||||
int32_t lat; //Latitude * 10^7
|
||||
int32_t lng; //Longitude * 10^7
|
||||
@ -44,8 +42,16 @@ public:
|
||||
// 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; }
|
||||
uint8_t get_rally_total() const {
|
||||
return (uint8_t)_rally_point_total_count;
|
||||
}
|
||||
uint8_t get_rally_max(void) const {
|
||||
const uint16_t ret = _storage.size() / uint16_t(sizeof(RallyLocation));
|
||||
if (ret > 255) {
|
||||
return 255;
|
||||
}
|
||||
return (uint8_t)ret;
|
||||
}
|
||||
|
||||
float get_rally_limit_km() const { return _rally_limit_km; }
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user