2016-07-21 09:44:09 -03:00
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include <AP_Avoidance/AP_Avoidance.h>
|
|
|
|
|
|
|
|
// Provide Copter-specific implementation of avoidance. While most of
|
|
|
|
// the logic for doing the actual avoidance is present in
|
|
|
|
// AP_Avoidance, this class allows Copter to override base
|
|
|
|
// functionality - for example, not doing anything while landed.
|
|
|
|
class AP_Avoidance_Copter : public AP_Avoidance {
|
|
|
|
public:
|
2019-07-09 03:05:42 -03:00
|
|
|
|
|
|
|
using AP_Avoidance::AP_Avoidance;
|
2016-07-21 09:44:09 -03:00
|
|
|
|
2017-09-18 22:39:00 -03:00
|
|
|
/* Do not allow copies */
|
|
|
|
AP_Avoidance_Copter(const AP_Avoidance_Copter &other) = delete;
|
|
|
|
AP_Avoidance_Copter &operator=(const AP_Avoidance_Copter&) = delete;
|
2016-08-17 04:17:05 -03:00
|
|
|
|
2017-09-18 22:39:00 -03:00
|
|
|
private:
|
2016-08-17 04:17:05 -03:00
|
|
|
// helper function to set modes and always succeed
|
2019-09-07 20:33:56 -03:00
|
|
|
void set_mode_else_try_RTL_else_LAND(Mode::Number mode);
|
2016-08-17 04:17:05 -03:00
|
|
|
|
2021-01-08 23:17:08 -04:00
|
|
|
// get minimum limit altitude allowed on descend
|
2021-09-15 01:00:54 -03:00
|
|
|
int32_t get_altitude_minimum() const;
|
2021-01-08 23:17:08 -04:00
|
|
|
|
2016-07-21 09:44:09 -03:00
|
|
|
protected:
|
|
|
|
// override avoidance handler
|
|
|
|
MAV_COLLISION_ACTION handle_avoidance(const AP_Avoidance::Obstacle *obstacle, MAV_COLLISION_ACTION requested_action) override;
|
|
|
|
|
|
|
|
// override recovery handler
|
2020-08-15 23:12:52 -03:00
|
|
|
void handle_recovery(RecoveryAction recovery_action) override;
|
2016-07-21 09:44:09 -03:00
|
|
|
|
|
|
|
// check flight mode is avoid_adsb
|
|
|
|
bool check_flightmode(bool allow_mode_change);
|
|
|
|
|
|
|
|
// vertical avoidance handler
|
|
|
|
bool handle_avoidance_vertical(const AP_Avoidance::Obstacle *obstacle, bool allow_mode_change);
|
|
|
|
|
|
|
|
// horizontal avoidance handler
|
|
|
|
bool handle_avoidance_horizontal(const AP_Avoidance::Obstacle *obstacle, bool allow_mode_change);
|
|
|
|
|
|
|
|
// perpendicular (3 dimensional) avoidance handler
|
|
|
|
bool handle_avoidance_perpendicular(const AP_Avoidance::Obstacle *obstacle, bool allow_mode_change);
|
|
|
|
|
|
|
|
// control mode before avoidance began
|
2019-09-07 20:33:56 -03:00
|
|
|
Mode::Number prev_control_mode = Mode::Number::RTL;
|
2016-07-21 09:44:09 -03:00
|
|
|
};
|