APM:Libraries
AP_Winch_Servo.cpp
Go to the documentation of this file.
2 
3 extern const AP_HAL::HAL& hal;
4 
5 void AP_Winch_Servo::init(const AP_WheelEncoder* wheel_encoder)
6 {
7  _wheel_encoder = wheel_encoder;
8 
9  // set servo output range
11 }
12 
14 {
15  // return immediately if no servo is assigned to control the winch
17  return;
18  }
19 
20  // return immediately if no wheel encoder
21  if (_wheel_encoder == nullptr) {
22  return;
23  }
24 
25  // if not doing any control output trim value
28  return;
29  }
30 
31  // calculate dt since last iteration
32  uint32_t now = AP_HAL::millis();
33  float dt = (now - last_update_ms) / 1000.0f;
34  if (dt > 1.0f) {
35  dt = 0.0f;
36  }
37  last_update_ms = now;
38 
39  // calculate latest rate
41  float rate = 0.0f;
42  if (is_positive(dt)) {
43  rate = (distance - config.length_curr) / dt;
44  }
45 
46  // update distance from wheel encoder
48 
49  // if doing position control, calculate position error to desired rate
50  float rate_desired = 0.0f;
52  float position_error = config.length_desired - config.length_curr;
53  rate_desired = constrain_float(position_error * config.pos_p, -config.rate_desired, config.rate_desired);
54  }
55 
56  // if doing rate control, set desired rate
58  rate_desired = config.rate_desired;
59  }
60 
61  // calculate rate error and pass to pid controller
62  float rate_error = rate_desired - rate;
64 
65  // get p
66  float p = config.rate_pid.get_p();
67 
68  // get i unless winch hit limit on last iteration
69  float i = config.rate_pid.get_integrator();
70  if (((is_negative(rate_error) && !limit_low) || (is_positive(rate_error) && !limit_high))) {
71  i = config.rate_pid.get_i();
72  }
73 
74  // get d
75  float d = config.rate_pid.get_d();
76 
77  // calculate base output
78  float base = 0.0f;
80  base = rate_desired / config.rate_max;
81  }
82 
83  // constrain and set limit flags
84  float output = base + p + i + d;
85  limit_low = (output <= -1.0f);
86  limit_high = (output >= 1.0f);
87  output = constrain_float(output, -1.0f, 1.0f);
88 
89  // output to servo
91 }
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
void update() override
float get_d()
Definition: AC_PID.cpp:155
bool is_positive(const T fVal1)
Definition: AP_Math.h:50
float distance
Definition: location.cpp:94
static void set_output_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::LimitValue limit)
uint32_t last_update_ms
void init(const AP_WheelEncoder *wheel_encoder) override
static void set_output_scaled(SRV_Channel::Aux_servo_function_t function, int16_t value)
#define f(i)
float get_distance(uint8_t instance) const
uint32_t millis()
Definition: system.cpp:157
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
void set_input_filter_all(float input)
Definition: AC_PID.cpp:87
bool is_negative(const T fVal1)
Definition: AP_Math.h:61
float get_integrator() const
Definition: AC_PID.h:76
float get_i()
Definition: AC_PID.cpp:140
float get_p()
Definition: AC_PID.cpp:134
static bool function_assigned(SRV_Channel::Aux_servo_function_t function)