SoloGimbal_Parameters.h 2.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990
  1. #pragma once
  2. #include <AP_Math/AP_Math.h>
  3. #include <AP_Common/AP_Common.h>
  4. #include <GCS_MAVLink/GCS_MAVLink.h>
  5. enum gmb_param_state_t {
  6. GMB_PARAMSTATE_NOT_YET_READ=0, // parameter has yet to be initialized
  7. GMB_PARAMSTATE_FETCH_AGAIN=1, // parameter is being fetched
  8. GMB_PARAMSTATE_ATTEMPTING_TO_SET=2, // parameter is being set
  9. GMB_PARAMSTATE_CONSISTENT=3, // parameter is consistent
  10. GMB_PARAMSTATE_NONEXISTANT=4 // parameter does not seem to exist
  11. };
  12. enum gmb_param_t {
  13. GMB_PARAM_GMB_OFF_ACC_X=0,
  14. GMB_PARAM_GMB_OFF_ACC_Y,
  15. GMB_PARAM_GMB_OFF_ACC_Z,
  16. GMB_PARAM_GMB_GN_ACC_X,
  17. GMB_PARAM_GMB_GN_ACC_Y,
  18. GMB_PARAM_GMB_GN_ACC_Z,
  19. GMB_PARAM_GMB_OFF_GYRO_X,
  20. GMB_PARAM_GMB_OFF_GYRO_Y,
  21. GMB_PARAM_GMB_OFF_GYRO_Z,
  22. GMB_PARAM_GMB_OFF_JNT_X,
  23. GMB_PARAM_GMB_OFF_JNT_Y,
  24. GMB_PARAM_GMB_OFF_JNT_Z,
  25. GMB_PARAM_GMB_K_RATE,
  26. GMB_PARAM_GMB_POS_HOLD,
  27. GMB_PARAM_GMB_MAX_TORQUE,
  28. GMB_PARAM_GMB_SND_TORQUE,
  29. GMB_PARAM_GMB_SYSID,
  30. GMB_PARAM_GMB_FLASH,
  31. MAVLINK_GIMBAL_NUM_TRACKED_PARAMS
  32. };
  33. enum gmb_flashing_step_t {
  34. GMB_PARAM_NOT_FLASHING=0,
  35. GMB_PARAM_FLASHING_WAITING_FOR_SET,
  36. GMB_PARAM_FLASHING_WAITING_FOR_ACK
  37. };
  38. class SoloGimbal_Parameters
  39. {
  40. public:
  41. SoloGimbal_Parameters();
  42. void reset();
  43. bool initialized();
  44. bool received_all();
  45. void fetch_params();
  46. void get_param(gmb_param_t param, float& value, float def_val = 0.0f);
  47. void set_param(gmb_param_t param, float value);
  48. void update();
  49. void handle_param_value(const mavlink_message_t &msg);
  50. Vector3f get_accel_bias();
  51. Vector3f get_accel_gain();
  52. void set_accel_bias(const Vector3f& bias);
  53. void set_accel_gain(const Vector3f& gain);
  54. Vector3f get_gyro_bias();
  55. void set_gyro_bias(const Vector3f& bias);
  56. Vector3f get_joint_bias();
  57. float get_K_rate();
  58. void flash();
  59. bool flashing();
  60. void set_channel(mavlink_channel_t chan) { _chan = chan; }
  61. private:
  62. static const char* get_param_name(gmb_param_t param);
  63. static const uint32_t _retry_period;
  64. static const uint8_t _max_fetch_attempts;
  65. struct {
  66. float value;
  67. gmb_param_state_t state;
  68. uint8_t fetch_attempts;
  69. bool seen;
  70. } _params[MAVLINK_GIMBAL_NUM_TRACKED_PARAMS];
  71. uint32_t _last_request_ms;
  72. uint32_t _last_set_ms;
  73. gmb_flashing_step_t _flashing_step;
  74. mavlink_channel_t _chan;
  75. };