Browse Source

Plane: move struct Rangefinder_State to AP_Vehicle

master
Tom Pittenger 8 years ago committed by Tom Pittenger
parent
commit
ce8db1fdba
  1. 14
      ArduPlane/Plane.h
  2. 14
      libraries/AP_Vehicle/AP_Vehicle.h

14
ArduPlane/Plane.h

@ -217,19 +217,7 @@ private: @@ -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;

14
libraries/AP_Vehicle/AP_Vehicle.h

@ -43,6 +43,20 @@ public: @@ -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…
Cancel
Save