62 float rate_error = rate_desired - rate;
84 float output = base + p + i + d;
static void set_angle(SRV_Channel::Aux_servo_function_t function, uint16_t angle)
const AP_WheelEncoder * _wheel_encoder
struct AP_Winch::Backend_Config & config
bool is_positive(const T fVal1)
static void set_output_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::LimitValue limit)
void init(const AP_WheelEncoder *wheel_encoder) override
static void set_output_scaled(SRV_Channel::Aux_servo_function_t function, int16_t value)
float get_distance(uint8_t instance) const
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
float constrain_float(const float amt, const float low, const float high)
void set_input_filter_all(float input)
bool is_negative(const T fVal1)
float get_integrator() const
static bool function_assigned(SRV_Channel::Aux_servo_function_t function)