AP_Winch_Servo.cpp 2.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475
  1. #include <AP_Winch/AP_Winch_Servo.h>
  2. extern const AP_HAL::HAL& hal;
  3. void AP_Winch_Servo::init(const AP_WheelEncoder* wheel_encoder)
  4. {
  5. _wheel_encoder = wheel_encoder;
  6. // set servo output range
  7. SRV_Channels::set_angle(SRV_Channel::k_winch, 1000);
  8. }
  9. void AP_Winch_Servo::update()
  10. {
  11. // return immediately if no servo is assigned to control the winch
  12. if (!SRV_Channels::function_assigned(SRV_Channel::k_winch)) {
  13. return;
  14. }
  15. // return immediately if no wheel encoder
  16. if (_wheel_encoder == nullptr) {
  17. return;
  18. }
  19. // if not doing any control output trim value
  20. if (config.state == AP_Winch::STATE_RELAXED) {
  21. SRV_Channels::set_output_limit(SRV_Channel::k_winch, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM);
  22. return;
  23. }
  24. // calculate dt since last iteration
  25. uint32_t now = AP_HAL::millis();
  26. float dt = (now - last_update_ms) / 1000.0f;
  27. if (dt > 1.0f) {
  28. dt = 0.0f;
  29. }
  30. last_update_ms = now;
  31. // calculate latest rate
  32. float distance = _wheel_encoder->get_distance(0);
  33. float rate = 0.0f;
  34. if (is_positive(dt)) {
  35. rate = (distance - config.length_curr) / dt;
  36. }
  37. // update distance from wheel encoder
  38. config.length_curr = distance;
  39. // if doing position control, calculate position error to desired rate
  40. float rate_desired = 0.0f;
  41. if (config.state == AP_Winch::STATE_POSITION) {
  42. float position_error = config.length_desired - config.length_curr;
  43. rate_desired = constrain_float(position_error * config.pos_p, -config.rate_desired, config.rate_desired);
  44. }
  45. // if doing rate control, set desired rate
  46. if (config.state == AP_Winch::STATE_RATE) {
  47. rate_desired = config.rate_desired;
  48. }
  49. // calculate base output
  50. float base = 0.0f;
  51. if (is_positive(config.rate_max)) {
  52. base = rate_desired / config.rate_max;
  53. }
  54. // constrain and set limit flags
  55. float output = base + config.rate_pid.update_all(rate_desired, rate, (limit_low || limit_high));
  56. limit_low = (output <= -1.0f);
  57. limit_high = (output >= 1.0f);
  58. output = constrain_float(output, -1.0f, 1.0f);
  59. // output to servo
  60. SRV_Channels::set_output_scaled(SRV_Channel::k_winch, output * 1000);
  61. }