2014-04-06 21:35:40 -03:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
|
|
|
|
/// @file AP_Rally.h
|
|
|
|
/// @brief Handles rally point storage, retrieval and lookup
|
|
|
|
|
|
|
|
/*
|
|
|
|
* The AP_Rally library:
|
|
|
|
*
|
|
|
|
* Initial implementation: Michael Day, September 2013
|
|
|
|
* Moved to AP_Rally lib: Andrew Chapman April 2014
|
|
|
|
*
|
|
|
|
* - responsible for managing a list of rally points
|
|
|
|
* - reads and writes the rally points to storage
|
|
|
|
* - provides access to the rally points, including logic to find the nearest one
|
|
|
|
*
|
|
|
|
*/
|
|
|
|
#ifndef AP_Rally_h
|
|
|
|
#define AP_Rally_h
|
|
|
|
|
|
|
|
#include <AP_Common.h>
|
|
|
|
#include <AP_Param.h>
|
|
|
|
#include <AP_AHRS.h>
|
|
|
|
|
2014-04-19 02:44:25 -03:00
|
|
|
#define AC_RALLY_WP_SIZE 15 // eeprom size of rally points
|
|
|
|
|
|
|
|
struct PACKED RallyLocation {
|
|
|
|
int32_t lat; //Latitude * 10^7
|
|
|
|
int32_t lng; //Longitude * 10^7
|
|
|
|
int16_t alt; //transit altitude (and loiter altitude) in meters;
|
|
|
|
int16_t break_alt; //when autolanding, break out of loiter at this alt (meters)
|
|
|
|
uint16_t land_dir; //when the time comes to auto-land, try to land in this direction (centidegrees)
|
|
|
|
uint8_t flags; //bit 0 = seek favorable winds when choosing a landing poi
|
|
|
|
//bit 1 = do auto land after arriving
|
|
|
|
//all other bits are for future use.
|
|
|
|
};
|
|
|
|
|
2014-04-06 21:35:40 -03:00
|
|
|
/// @class AP_Rally
|
|
|
|
/// @brief Object managing Rally Points
|
|
|
|
class AP_Rally {
|
|
|
|
|
|
|
|
public:
|
2014-04-18 16:22:16 -03:00
|
|
|
AP_Rally(AP_AHRS &ahrs, uint16_t max_rally_points, uint16_t rally_start_byte);
|
2014-04-06 21:35:40 -03:00
|
|
|
|
|
|
|
// 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; }
|
|
|
|
|
2014-04-21 18:30:06 -03:00
|
|
|
float get_rally_limit_km() const { return _rally_limit_km; }
|
|
|
|
|
|
|
|
Location rally_location_to_location(const RallyLocation &ret) const;
|
|
|
|
|
2014-04-06 21:35:40 -03:00
|
|
|
// logic handling
|
|
|
|
Location calc_best_rally_or_home_location(const Location ¤t_loc, float rtl_home_alt) const;
|
|
|
|
bool find_nearest_rally_point(const Location &myloc, RallyLocation &ret) const;
|
|
|
|
|
|
|
|
// parameter block
|
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
|
|
|
|
private:
|
|
|
|
// 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;
|
|
|
|
AP_Float _rally_limit_km;
|
|
|
|
};
|
|
|
|
|
|
|
|
|
|
|
|
#endif // AP_Rally_h
|