11 #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) 12 #define RALLY_LIMIT_KM_DEFAULT 0.3f 13 #define RALLY_INCLUDE_HOME_DEFAULT 1 14 #elif APM_BUILD_TYPE(APM_BUILD_ArduPlane) 15 #define RALLY_LIMIT_KM_DEFAULT 5.0f 16 #define RALLY_INCLUDE_HOME_DEFAULT 0 17 #elif APM_BUILD_TYPE(APM_BUILD_APMrover2) 18 #define RALLY_LIMIT_KM_DEFAULT 0.5f 19 #define RALLY_INCLUDE_HOME_DEFAULT 0 21 #define RALLY_LIMIT_KM_DEFAULT 1.0f 22 #define RALLY_INCLUDE_HOME_DEFAULT 0 53 , _last_change_time_ms(0xFFFFFFFF)
67 if (ret.
lat == 0 && ret.
lng == 0) {
125 if (
is_valid(rally_loc) && (dis < min_dis || min_dis < 0)) {
127 return_loc = next_rally;
157 return_loc = home_loc;
158 return_loc.
alt = rtl_home_alt;
static const struct AP_Param::GroupInfo var_info[]
Object managing Rally Points.
const struct Location & get_home(void) const
#define AP_GROUPINFO(name, idx, clazz, element, def)
float get_distance(const struct Location &loc1, const struct Location &loc2)
uint8_t get_rally_max(void) const
Location calc_best_rally_or_home_location(const Location ¤t_loc, float rtl_home_alt) const
uint32_t _last_change_time_ms
#define RALLY_LIMIT_KM_DEFAULT
bool set_rally_point_with_index(uint8_t i, const RallyLocation &rallyLoc)
int32_t lat
param 3 - Latitude * 10**7
bool find_nearest_rally_point(const Location &myloc, RallyLocation &ret) const
Location rally_location_to_location(const RallyLocation &ret) const
Handles rally point storage and retrieval.
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
virtual bool is_valid(const Location &rally_point) const
bool read_block(void *dst, uint16_t src, size_t n) const
Location_Option_Flags flags
options bitmask (1<<0 = relative altitude)
static StorageAccess _storage
bool get_rally_point_with_index(uint8_t i, RallyLocation &ret) const
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
int32_t lng
param 4 - Longitude * 10**7
bool write_block(uint16_t dst, const void *src, size_t n) const
AP_Int8 _rally_point_total_count
#define RALLY_INCLUDE_HOME_DEFAULT
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)