SoloGimbal.h 4.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149
  1. /************************************************************
  2. * SoloGimbal -- library to control a 3 axis rate gimbal. *
  3. * *
  4. * Author: Arthur Benemann, Paul Riseborough; *
  5. * *
  6. ************************************************************/
  7. #pragma once
  8. #include <AP_HAL/AP_HAL.h>
  9. #include <AP_AHRS/AP_AHRS.h>
  10. #if AP_AHRS_NAVEKF_AVAILABLE
  11. #include "AP_Mount.h"
  12. #include "SoloGimbalEKF.h"
  13. #include <AP_Math/AP_Math.h>
  14. #include <AP_Common/AP_Common.h>
  15. #include <GCS_MAVLink/GCS_MAVLink.h>
  16. #include <AP_AccelCal/AP_AccelCal.h>
  17. #include "SoloGimbal_Parameters.h"
  18. enum gimbal_state_t {
  19. GIMBAL_STATE_NOT_PRESENT = 0,
  20. GIMBAL_STATE_PRESENT_INITIALIZING,
  21. GIMBAL_STATE_PRESENT_ALIGNING,
  22. GIMBAL_STATE_PRESENT_RUNNING
  23. };
  24. enum gimbal_mode_t {
  25. GIMBAL_MODE_IDLE = 0,
  26. GIMBAL_MODE_POS_HOLD,
  27. GIMBAL_MODE_POS_HOLD_FF,
  28. GIMBAL_MODE_STABILIZE
  29. };
  30. class SoloGimbal : AP_AccelCal_Client
  31. {
  32. public:
  33. //Constructor
  34. SoloGimbal() :
  35. _ekf(),
  36. _state(GIMBAL_STATE_NOT_PRESENT),
  37. _vehicle_yaw_rate_ef_filt(0.0f),
  38. _vehicle_to_gimbal_quat(),
  39. _vehicle_to_gimbal_quat_filt(),
  40. _filtered_joint_angles(),
  41. _last_report_msg_ms(0),
  42. _max_torque(5000.0f),
  43. _ang_vel_mag_filt(0),
  44. _lockedToBody(false),
  45. _log_dt(0),
  46. _log_del_ang(),
  47. _log_del_vel()
  48. {
  49. AP_AccelCal::register_client(this);
  50. }
  51. void update_target(const Vector3f &newTarget);
  52. void receive_feedback(mavlink_channel_t chan, const mavlink_message_t &msg);
  53. void update_fast();
  54. bool present();
  55. bool aligned();
  56. void set_lockedToBody(bool val) { _lockedToBody = val; }
  57. void write_logs();
  58. float get_log_dt() { return _log_dt; }
  59. void disable_torque_report() { _gimbalParams.set_param(GMB_PARAM_GMB_SND_TORQUE, 0); }
  60. void fetch_params() { _gimbalParams.fetch_params(); }
  61. void handle_param_value(const mavlink_message_t &msg) {
  62. _gimbalParams.handle_param_value(msg);
  63. }
  64. private:
  65. // private methods
  66. void update_estimators();
  67. void send_controls(mavlink_channel_t chan);
  68. void extract_feedback(const mavlink_gimbal_report_t& report_msg);
  69. void update_joint_angle_est();
  70. Vector3f get_ang_vel_dem_yaw(const Quaternion &quatEst);
  71. Vector3f get_ang_vel_dem_tilt(const Quaternion &quatEst);
  72. Vector3f get_ang_vel_dem_feedforward(const Quaternion &quatEst);
  73. Vector3f get_ang_vel_dem_gyro_bias();
  74. Vector3f get_ang_vel_dem_body_lock();
  75. void gimbal_ang_vel_to_joint_rates(const Vector3f& ang_vel, Vector3f& joint_rates);
  76. void joint_rates_to_gimbal_ang_vel(const Vector3f& joint_rates, Vector3f& ang_vel);
  77. void readVehicleDeltaAngle(uint8_t ins_index, Vector3f &dAng);
  78. void _acal_save_calibrations() override;
  79. bool _acal_get_ready_to_sample() override;
  80. bool _acal_get_saving() override;
  81. AccelCalibrator* _acal_get_calibrator(uint8_t instance) override;
  82. gimbal_mode_t get_mode();
  83. bool joints_near_limits();
  84. // private member variables
  85. SoloGimbalEKF _ekf; // state of small EKF for gimbal
  86. gimbal_state_t _state;
  87. struct {
  88. float delta_time;
  89. Vector3f delta_angles;
  90. Vector3f delta_velocity;
  91. Vector3f joint_angles;
  92. } _measurement;
  93. float _vehicle_yaw_rate_ef_filt;
  94. static const uint8_t _compid = MAV_COMP_ID_GIMBAL;
  95. // joint angle filter states
  96. Vector3f _vehicle_delta_angles;
  97. Quaternion _vehicle_to_gimbal_quat;
  98. Quaternion _vehicle_to_gimbal_quat_filt;
  99. Vector3f _filtered_joint_angles;
  100. uint32_t _last_report_msg_ms;
  101. float _max_torque;
  102. float _ang_vel_mag_filt;
  103. Vector3f _ang_vel_dem_rads; // rad/s
  104. Vector3f _att_target_euler_rad; // desired earth-frame roll, tilt and pan angles in radians
  105. bool _lockedToBody;
  106. SoloGimbal_Parameters _gimbalParams;
  107. AccelCalibrator _calibrator;
  108. float _log_dt;
  109. Vector3f _log_del_ang;
  110. Vector3f _log_del_vel;
  111. };
  112. #endif // AP_AHRS_NAVEKF_AVAILABLE