AP_Mount_SoloGimbal.cpp 4.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157
  1. #include <AP_HAL/AP_HAL.h>
  2. #include <AP_AHRS/AP_AHRS.h>
  3. #if AP_AHRS_NAVEKF_AVAILABLE
  4. #include "AP_Mount_SoloGimbal.h"
  5. #include "SoloGimbal.h"
  6. #include <AP_Logger/AP_Logger.h>
  7. #include <GCS_MAVLink/GCS_MAVLink.h>
  8. #include <GCS_MAVLink/GCS.h>
  9. #include <AP_GPS/AP_GPS.h>
  10. extern const AP_HAL::HAL& hal;
  11. AP_Mount_SoloGimbal::AP_Mount_SoloGimbal(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance) :
  12. AP_Mount_Backend(frontend, state, instance),
  13. _gimbal()
  14. {}
  15. // init - performs any required initialisation for this instance
  16. void AP_Mount_SoloGimbal::init()
  17. {
  18. _initialised = true;
  19. set_mode((enum MAV_MOUNT_MODE)_state._default_mode.get());
  20. }
  21. void AP_Mount_SoloGimbal::update_fast()
  22. {
  23. _gimbal.update_fast();
  24. }
  25. // update mount position - should be called periodically
  26. void AP_Mount_SoloGimbal::update()
  27. {
  28. // exit immediately if not initialised
  29. if (!_initialised) {
  30. return;
  31. }
  32. // update based on mount mode
  33. switch(get_mode()) {
  34. // move mount to a "retracted" position. we do not implement a separate servo based retract mechanism
  35. case MAV_MOUNT_MODE_RETRACT:
  36. _gimbal.set_lockedToBody(true);
  37. break;
  38. // move mount to a neutral position, typically pointing forward
  39. case MAV_MOUNT_MODE_NEUTRAL:
  40. {
  41. _gimbal.set_lockedToBody(false);
  42. const Vector3f &target = _state._neutral_angles.get();
  43. _angle_ef_target_rad.x = ToRad(target.x);
  44. _angle_ef_target_rad.y = ToRad(target.y);
  45. _angle_ef_target_rad.z = ToRad(target.z);
  46. }
  47. break;
  48. // point to the angles given by a mavlink message
  49. case MAV_MOUNT_MODE_MAVLINK_TARGETING:
  50. _gimbal.set_lockedToBody(false);
  51. // do nothing because earth-frame angle targets (i.e. _angle_ef_target_rad) should have already been set by a MOUNT_CONTROL message from GCS
  52. break;
  53. // RC radio manual angle control, but with stabilization from the AHRS
  54. case MAV_MOUNT_MODE_RC_TARGETING:
  55. _gimbal.set_lockedToBody(false);
  56. // update targets using pilot's rc inputs
  57. update_targets_from_rc();
  58. break;
  59. // point mount to a GPS point given by the mission planner
  60. case MAV_MOUNT_MODE_GPS_POINT:
  61. _gimbal.set_lockedToBody(false);
  62. if(AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D) {
  63. calc_angle_to_location(_state._roi_target, _angle_ef_target_rad, true, true);
  64. }
  65. break;
  66. default:
  67. // we do not know this mode so do nothing
  68. break;
  69. }
  70. }
  71. // has_pan_control - returns true if this mount can control it's pan (required for multicopters)
  72. bool AP_Mount_SoloGimbal::has_pan_control() const
  73. {
  74. // we do not have yaw control
  75. return false;
  76. }
  77. // set_mode - sets mount's mode
  78. void AP_Mount_SoloGimbal::set_mode(enum MAV_MOUNT_MODE mode)
  79. {
  80. // exit immediately if not initialised
  81. if (!_initialised) {
  82. return;
  83. }
  84. // record the mode change
  85. _state._mode = mode;
  86. }
  87. // send_mount_status - called to allow mounts to send their status to GCS using the MOUNT_STATUS message
  88. void AP_Mount_SoloGimbal::send_mount_status(mavlink_channel_t chan)
  89. {
  90. if (_gimbal.aligned()) {
  91. mavlink_msg_mount_status_send(chan, 0, 0, degrees(_angle_ef_target_rad.y)*100, degrees(_angle_ef_target_rad.x)*100, degrees(_angle_ef_target_rad.z)*100);
  92. }
  93. // block heartbeat from transmitting to the GCS
  94. GCS_MAVLINK::disable_channel_routing(chan);
  95. }
  96. /*
  97. handle a GIMBAL_REPORT message
  98. */
  99. void AP_Mount_SoloGimbal::handle_gimbal_report(mavlink_channel_t chan, const mavlink_message_t &msg)
  100. {
  101. _gimbal.update_target(_angle_ef_target_rad);
  102. _gimbal.receive_feedback(chan,msg);
  103. AP_Logger *logger = AP_Logger::get_singleton();
  104. if (logger == nullptr) {
  105. return;
  106. }
  107. if(!_params_saved && logger->logging_started()) {
  108. _gimbal.fetch_params(); //last parameter save might not be stored in logger so retry
  109. _params_saved = true;
  110. }
  111. if (_gimbal.get_log_dt() > 1.0f/25.0f) {
  112. _gimbal.write_logs();
  113. }
  114. }
  115. void AP_Mount_SoloGimbal::handle_param_value(const mavlink_message_t &msg)
  116. {
  117. _gimbal.handle_param_value(msg);
  118. }
  119. /*
  120. handle a GIMBAL_REPORT message
  121. */
  122. void AP_Mount_SoloGimbal::handle_gimbal_torque_report(mavlink_channel_t chan, const mavlink_message_t &msg)
  123. {
  124. _gimbal.disable_torque_report();
  125. }
  126. /*
  127. send a GIMBAL_REPORT message to the GCS
  128. */
  129. void AP_Mount_SoloGimbal::send_gimbal_report(mavlink_channel_t chan)
  130. {
  131. }
  132. #endif // AP_AHRS_NAVEKF_AVAILABLE