AC_PID_test.cpp 2.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108
  1. /*
  2. * Example of PID library.
  3. * 2012 Code by Jason Short, Randy Mackay. DIYDrones.com
  4. */
  5. #include <AP_HAL/AP_HAL.h>
  6. #include <AC_PID/AC_PID.h>
  7. #include <AC_PID/AC_HELI_PID.h>
  8. #include <RC_Channel/RC_Channel.h>
  9. // we need a boardconfig created so that the io processor is available
  10. #if HAL_WITH_IO_MCU
  11. #include <AP_BoardConfig/AP_BoardConfig.h>
  12. #include <AP_IOMCU/AP_IOMCU.h>
  13. AP_BoardConfig BoardConfig;
  14. #endif
  15. void setup();
  16. void loop();
  17. const AP_HAL::HAL& hal = AP_HAL::get_HAL();
  18. class RC_Channel_PIDTest : public RC_Channel
  19. {
  20. };
  21. class RC_Channels_PIDTest : public RC_Channels
  22. {
  23. public:
  24. RC_Channel *channel(uint8_t chan) override {
  25. return &obj_channels[chan];
  26. }
  27. RC_Channel_PIDTest obj_channels[NUM_RC_CHANNELS];
  28. private:
  29. int8_t flight_mode_channel_number() const override { return -1; };
  30. };
  31. #define RC_CHANNELS_SUBCLASS RC_Channels_PIDTest
  32. #define RC_CHANNEL_SUBCLASS RC_Channel_PIDTest
  33. #include <RC_Channel/RC_Channels_VarInfo.h>
  34. RC_Channels_PIDTest _rc;
  35. // default PID values
  36. #define TEST_P 1.0f
  37. #define TEST_I 0.01f
  38. #define TEST_D 0.2f
  39. #define TEST_IMAX 10
  40. #define TEST_FILTER 5.0f
  41. #define TEST_DT 0.01f
  42. #define TEST_INITIAL_FF 0.0f
  43. // setup function
  44. void setup()
  45. {
  46. hal.console->printf("ArduPilot AC_PID library test\n");
  47. #if HAL_WITH_IO_MCU
  48. BoardConfig.init();
  49. #endif
  50. rc().init();
  51. hal.scheduler->delay(1000);
  52. }
  53. // main loop
  54. void loop()
  55. {
  56. // setup (unfortunately must be done here as we cannot create a global AC_PID object)
  57. AC_PID pid(TEST_P, TEST_I, TEST_D, 0.0f, TEST_IMAX * 100.0f, 0.0f, 0.0f, TEST_FILTER, TEST_DT);
  58. AC_HELI_PID heli_pid(TEST_P, TEST_I, TEST_D, TEST_INITIAL_FF, TEST_IMAX * 100, 0.0f, 0.0f, TEST_FILTER, TEST_DT);
  59. // display PID gains
  60. hal.console->printf("P %f I %f D %f imax %f\n", (double)pid.kP(), (double)pid.kI(), (double)pid.kD(), (double)pid.imax());
  61. RC_Channel *c = rc().channel(0);
  62. if (c == nullptr) {
  63. while (true) {
  64. hal.console->printf("No channel 0?");
  65. hal.scheduler->delay(1000);
  66. }
  67. }
  68. // capture radio trim
  69. const uint16_t radio_trim = c->get_radio_in();
  70. while (true) {
  71. rc().read_input(); // poll the radio for new values
  72. const uint16_t radio_in = c->get_radio_in();
  73. const int16_t error = radio_in - radio_trim;
  74. pid.update_error(error);
  75. const float control_P = pid.get_p();
  76. const float control_I = pid.get_i();
  77. const float control_D = pid.get_d();
  78. // display pid results
  79. hal.console->printf("radio: %d\t err: %d\t pid:%4.2f (p:%4.2f i:%4.2f d:%4.2f)\n",
  80. (int)radio_in, (int)error,
  81. (double)(control_P+control_I+control_D),
  82. (double)control_P, (double)control_I, (double)control_D);
  83. hal.scheduler->delay(50);
  84. }
  85. }
  86. AP_HAL_MAIN();