2022-09-29 20:10:41 -03:00
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include <AP_Param/AP_Param.h>
|
|
|
|
|
|
|
|
/*
|
|
|
|
common parameters for fixed wing aircraft
|
|
|
|
*/
|
|
|
|
struct AP_FixedWing {
|
|
|
|
AP_Int8 throttle_min;
|
|
|
|
AP_Int8 throttle_max;
|
|
|
|
AP_Int8 throttle_slewrate;
|
|
|
|
AP_Int8 throttle_cruise;
|
|
|
|
AP_Int8 takeoff_throttle_max;
|
2024-05-24 06:38:42 -03:00
|
|
|
AP_Int8 takeoff_throttle_min;
|
2024-10-08 15:38:28 -03:00
|
|
|
AP_Int8 takeoff_throttle_idle;
|
2024-07-25 16:29:22 -03:00
|
|
|
AP_Int32 takeoff_options;
|
2022-09-29 20:10:41 -03:00
|
|
|
AP_Int16 airspeed_min;
|
|
|
|
AP_Int16 airspeed_max;
|
2024-01-17 22:34:22 -04:00
|
|
|
AP_Float airspeed_cruise;
|
2024-07-09 13:45:15 -03:00
|
|
|
AP_Float airspeed_stall;
|
2024-01-18 01:53:11 -04:00
|
|
|
AP_Float min_groundspeed;
|
2022-09-29 20:10:41 -03:00
|
|
|
AP_Int8 crash_detection_enable;
|
2024-01-18 21:58:28 -04:00
|
|
|
AP_Float roll_limit;
|
2024-01-18 21:50:35 -04:00
|
|
|
AP_Float pitch_limit_max;
|
|
|
|
AP_Float pitch_limit_min;
|
2022-09-29 20:10:41 -03:00
|
|
|
AP_Int8 autotune_level;
|
2023-07-19 09:41:12 -03:00
|
|
|
AP_Int32 autotune_options;
|
2022-09-29 20:10:41 -03:00
|
|
|
AP_Int8 stall_prevention;
|
|
|
|
AP_Int16 loiter_radius;
|
2023-01-09 23:53:41 -04:00
|
|
|
AP_Float takeoff_throttle_max_t;
|
2022-09-29 20:10:41 -03:00
|
|
|
|
|
|
|
struct Rangefinder_State {
|
|
|
|
bool in_range:1;
|
|
|
|
bool have_initial_reading:1;
|
|
|
|
bool in_use:1;
|
|
|
|
float initial_range;
|
|
|
|
float correction;
|
|
|
|
float initial_correction;
|
|
|
|
float last_stable_correction;
|
|
|
|
uint32_t last_correction_time_ms;
|
|
|
|
uint8_t in_range_count;
|
|
|
|
float height_estimate;
|
|
|
|
float last_distance;
|
|
|
|
};
|
|
|
|
|
|
|
|
|
|
|
|
// stages of flight
|
|
|
|
enum class FlightStage {
|
|
|
|
TAKEOFF = 1,
|
|
|
|
VTOL = 2,
|
|
|
|
NORMAL = 3,
|
|
|
|
LAND = 4,
|
|
|
|
ABORT_LANDING = 7
|
|
|
|
};
|
2024-07-25 16:29:22 -03:00
|
|
|
|
|
|
|
// Bitfields of TKOFF_OPTIONS
|
|
|
|
enum class TakeoffOption {
|
|
|
|
THROTTLE_RANGE = (1U << 0), // Unset: Max throttle. Set: Throttle range.
|
|
|
|
};
|
2022-09-29 20:10:41 -03:00
|
|
|
};
|