Copter: allow rangefinder to be disabled from definition

This commit is contained in:
Randy Mackay 2016-05-12 15:44:39 +09:00
parent e489c3184c
commit 8171532dc5
2 changed files with 4 additions and 2 deletions

View File

@ -246,6 +246,7 @@ float Copter::get_throttle_pre_takeoff(float input_thr)
// returns climb rate (in cm/s) which should be passed to the position controller // returns climb rate (in cm/s) which should be passed to the position controller
float Copter::get_surface_tracking_climb_rate(int16_t target_rate, float current_alt_target, float dt) float Copter::get_surface_tracking_climb_rate(int16_t target_rate, float current_alt_target, float dt)
{ {
#if RANGEFINDER_ENABLED == ENABLED
static uint32_t last_call_ms = 0; static uint32_t last_call_ms = 0;
float distance_error; float distance_error;
float velocity_correction; float velocity_correction;
@ -275,6 +276,9 @@ float Copter::get_surface_tracking_climb_rate(int16_t target_rate, float current
// return combined pilot climb rate + rate to correct rangefinder alt error // return combined pilot climb rate + rate to correct rangefinder alt error
return (target_rate + velocity_correction); return (target_rate + velocity_correction);
#else
return (float)target_rate;
#endif
} }
// set_accel_throttle_I_from_pilot_throttle - smoothes transition from pilot controlled throttle to autopilot throttle // set_accel_throttle_I_from_pilot_throttle - smoothes transition from pilot controlled throttle to autopilot throttle

View File

@ -169,7 +169,6 @@ private:
Compass compass; Compass compass;
AP_InertialSensor ins; AP_InertialSensor ins;
#if RANGEFINDER_ENABLED == ENABLED
RangeFinder rangefinder {serial_manager}; RangeFinder rangefinder {serial_manager};
struct { struct {
bool enabled:1; bool enabled:1;
@ -178,7 +177,6 @@ private:
uint32_t last_healthy_ms; uint32_t last_healthy_ms;
LowPassFilterFloat alt_cm_filt; // altitude filter LowPassFilterFloat alt_cm_filt; // altitude filter
} rangefinder_state = { false, false, 0, 0 }; } rangefinder_state = { false, false, 0, 0 };
#endif
AP_RPM rpm_sensor; AP_RPM rpm_sensor;