mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Avoidance: add static create method for AP_Avoidance_*
This commit is contained in:
parent
6d009cdf6e
commit
46e8d9b6d1
@ -39,9 +39,7 @@
|
|||||||
#define AP_AVOIDANCE_ESCAPE_TIME_SEC 2 // vehicle runs from thread for 2 seconds
|
#define AP_AVOIDANCE_ESCAPE_TIME_SEC 2 // vehicle runs from thread for 2 seconds
|
||||||
|
|
||||||
class AP_Avoidance {
|
class AP_Avoidance {
|
||||||
|
|
||||||
public:
|
public:
|
||||||
|
|
||||||
// obstacle class to hold latest information for a known obstacles
|
// obstacle class to hold latest information for a known obstacles
|
||||||
class Obstacle {
|
class Obstacle {
|
||||||
public:
|
public:
|
||||||
@ -61,8 +59,6 @@ public:
|
|||||||
uint32_t last_gcs_report_time; // millis
|
uint32_t last_gcs_report_time; // millis
|
||||||
};
|
};
|
||||||
|
|
||||||
// constructor
|
|
||||||
AP_Avoidance(AP_AHRS &ahrs, class AP_ADSB &adsb);
|
|
||||||
|
|
||||||
// add obstacle to the list of known obstacles
|
// add obstacle to the list of known obstacles
|
||||||
void add_obstacle(uint32_t obstacle_timestamp_ms,
|
void add_obstacle(uint32_t obstacle_timestamp_ms,
|
||||||
@ -96,6 +92,8 @@ public:
|
|||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
// constructor
|
||||||
|
AP_Avoidance(AP_AHRS &ahrs, class AP_ADSB &adsb);
|
||||||
|
|
||||||
// top level avoidance handler. This calls the vehicle specific handle_avoidance with requested action
|
// top level avoidance handler. This calls the vehicle specific handle_avoidance with requested action
|
||||||
void handle_avoidance_local(AP_Avoidance::Obstacle *threat);
|
void handle_avoidance_local(AP_Avoidance::Obstacle *threat);
|
||||||
|
Loading…
Reference in New Issue
Block a user