mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 18:48:30 -04:00
Plane: move struct Rangefinder_State to AP_Vehicle
This commit is contained in:
parent
0ffeed644c
commit
ce8db1fdba
@ -217,19 +217,7 @@ private:
|
||||
|
||||
RangeFinder rangefinder {serial_manager};
|
||||
|
||||
struct {
|
||||
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;
|
||||
} rangefinder_state;
|
||||
AP_Vehicle::FixedWing::Rangefinder_State rangefinder_state;
|
||||
|
||||
AP_RPM rpm_sensor;
|
||||
|
||||
|
@ -43,6 +43,20 @@ public:
|
||||
AP_Float land_flare_sec;
|
||||
AP_Float land_pre_flare_airspeed;
|
||||
AP_Int8 stall_prevention;
|
||||
|
||||
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;
|
||||
};
|
||||
};
|
||||
|
||||
/*
|
||||
|
Loading…
Reference in New Issue
Block a user