AP_Tuning.h 2.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107
  1. #pragma once
  2. #include <AP_Param/AP_Param.h>
  3. #include "stdint.h"
  4. /*
  5. transmitter tuning library. Meant to be subclassed per vehicle type
  6. */
  7. class AP_Tuning
  8. {
  9. public:
  10. struct tuning_set {
  11. uint8_t set;
  12. uint8_t num_parms;
  13. const uint8_t *parms;
  14. };
  15. struct tuning_name {
  16. uint8_t parm;
  17. const char *name;
  18. };
  19. // constructor
  20. AP_Tuning(const struct tuning_set *sets, const struct tuning_name *names) :
  21. tuning_sets(sets),
  22. tuning_names(names) {
  23. AP_Param::setup_object_defaults(this, var_info);
  24. }
  25. // var_info for holding Parameter information
  26. static const struct AP_Param::GroupInfo var_info[];
  27. // update function called on new radio frames
  28. void check_input(uint8_t flightmode);
  29. // base parameter number for tuning sets of parameters in one flight
  30. const uint8_t set_base = 100;
  31. private:
  32. AP_Int8 channel;
  33. AP_Int16 channel_min;
  34. AP_Int16 channel_max;
  35. AP_Int8 selector;
  36. AP_Float range;
  37. AP_Int8 mode_revert;
  38. AP_Float error_threshold;
  39. // when selector was triggered
  40. uint32_t selector_start_ms;
  41. // are we waiting for channel mid-point?
  42. bool mid_point_wait;
  43. // last input from tuning channel
  44. float last_channel_value;
  45. // mid-value for current parameter
  46. float center_value;
  47. uint32_t last_check_ms;
  48. void Log_Write_Parameter_Tuning(float value);
  49. // the parameter we are tuning
  50. uint8_t current_parm;
  51. // current index into the parameter set
  52. uint8_t current_parm_index;
  53. // current parameter set
  54. uint8_t current_set;
  55. // true if tune has changed
  56. bool changed:1;
  57. // mask of params in set that need reverting
  58. uint32_t need_revert;
  59. // last flight mode we were tuning in
  60. uint8_t last_flightmode;
  61. // last time we reported controller error
  62. uint32_t last_controller_error_ms;
  63. const tuning_set *tuning_sets;
  64. const tuning_name *tuning_names;
  65. void check_selector_switch(void);
  66. void re_center(void);
  67. void next_parameter(void);
  68. void save_parameters(void);
  69. void revert_parameters(void);
  70. const char *get_tuning_name(uint8_t parm);
  71. void check_controller_error(void);
  72. protected:
  73. // virtual functions that must be implemented in vehicle subclass
  74. virtual AP_Float *get_param_pointer(uint8_t parm) = 0;
  75. virtual void save_value(uint8_t parm) = 0;
  76. virtual void reload_value(uint8_t parm) = 0;
  77. virtual void set_value(uint8_t parm, float value) = 0;
  78. virtual float controller_error(uint8_t parm) = 0;
  79. // parmset is in vehicle subclass var table
  80. AP_Int16 parmset;
  81. };