AP_Mount_Servo.cpp 8.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203
  1. #include "AP_Mount_Servo.h"
  2. #include <AP_GPS/AP_GPS.h>
  3. extern const AP_HAL::HAL& hal;
  4. // init - performs any required initialisation for this instance
  5. void AP_Mount_Servo::init()
  6. {
  7. if (_instance == 0) {
  8. _roll_idx = SRV_Channel::k_mount_roll;
  9. _tilt_idx = SRV_Channel::k_mount_tilt;
  10. _pan_idx = SRV_Channel::k_mount_pan;
  11. _open_idx = SRV_Channel::k_mount_open;
  12. } else {
  13. // this must be the 2nd mount
  14. _roll_idx = SRV_Channel::k_mount2_roll;
  15. _tilt_idx = SRV_Channel::k_mount2_tilt;
  16. _pan_idx = SRV_Channel::k_mount2_pan;
  17. _open_idx = SRV_Channel::k_mount2_open;
  18. }
  19. // check which servos have been assigned
  20. check_servo_map();
  21. }
  22. // update mount position - should be called periodically
  23. void AP_Mount_Servo::update()
  24. {
  25. static bool mount_open = 0; // 0 is closed
  26. // check servo map every three seconds to allow users to modify parameters
  27. uint32_t now = AP_HAL::millis();
  28. if (now - _last_check_servo_map_ms > 3000) {
  29. check_servo_map();
  30. _last_check_servo_map_ms = now;
  31. }
  32. switch(get_mode()) {
  33. // move mount to a "retracted position" or to a position where a fourth servo can retract the entire mount into the fuselage
  34. case MAV_MOUNT_MODE_RETRACT:
  35. {
  36. _angle_bf_output_deg = _state._retract_angles.get();
  37. break;
  38. }
  39. // move mount to a neutral position, typically pointing forward
  40. case MAV_MOUNT_MODE_NEUTRAL:
  41. {
  42. _angle_bf_output_deg = _state._neutral_angles.get();
  43. break;
  44. }
  45. // point to the angles given by a mavlink message
  46. case MAV_MOUNT_MODE_MAVLINK_TARGETING:
  47. {
  48. // earth-frame angle targets (i.e. _angle_ef_target_rad) should have already been set by a MOUNT_CONTROL message from GCS
  49. stabilize();
  50. break;
  51. }
  52. // RC radio manual angle control, but with stabilization from the AHRS
  53. case MAV_MOUNT_MODE_RC_TARGETING:
  54. {
  55. // update targets using pilot's rc inputs
  56. update_targets_from_rc();
  57. stabilize();
  58. break;
  59. }
  60. // point mount to a GPS point given by the mission planner
  61. case MAV_MOUNT_MODE_GPS_POINT:
  62. {
  63. if(AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D) {
  64. calc_angle_to_location(_state._roi_target, _angle_ef_target_rad, _flags.tilt_control, _flags.pan_control, false);
  65. stabilize();
  66. }
  67. break;
  68. }
  69. default:
  70. //do nothing
  71. break;
  72. }
  73. // move mount to a "retracted position" into the fuselage with a fourth servo
  74. bool mount_open_new = (get_mode() == MAV_MOUNT_MODE_RETRACT) ? 0 : 1;
  75. if (mount_open != mount_open_new) {
  76. mount_open = mount_open_new;
  77. move_servo(_open_idx, mount_open_new, 0, 1);
  78. }
  79. // write the results to the servos
  80. move_servo(_roll_idx, _angle_bf_output_deg.x*10, _state._roll_angle_min*0.1f, _state._roll_angle_max*0.1f);
  81. move_servo(_tilt_idx, _angle_bf_output_deg.y*10, _state._tilt_angle_min*0.1f, _state._tilt_angle_max*0.1f);
  82. move_servo(_pan_idx, _angle_bf_output_deg.z*10, _state._pan_angle_min*0.1f, _state._pan_angle_max*0.1f);
  83. }
  84. // set_mode - sets mount's mode
  85. void AP_Mount_Servo::set_mode(enum MAV_MOUNT_MODE mode)
  86. {
  87. // record the mode change and return success
  88. _state._mode = mode;
  89. }
  90. // private methods
  91. // check_servo_map - detects which axis we control using the functions assigned to the servos in the RC_Channel_aux
  92. // should be called periodically (i.e. 1hz or less)
  93. void AP_Mount_Servo::check_servo_map()
  94. {
  95. _flags.roll_control = SRV_Channels::function_assigned(_roll_idx);
  96. _flags.tilt_control = SRV_Channels::function_assigned(_tilt_idx);
  97. _flags.pan_control = SRV_Channels::function_assigned(_pan_idx);
  98. }
  99. // send_mount_status - called to allow mounts to send their status to GCS using the MOUNT_STATUS message
  100. void AP_Mount_Servo::send_mount_status(mavlink_channel_t chan)
  101. {
  102. mavlink_msg_mount_status_send(chan, 0, 0, _angle_bf_output_deg.y*100, _angle_bf_output_deg.x*100, _angle_bf_output_deg.z*100);
  103. }
  104. // stabilize - stabilizes the mount relative to the Earth's frame
  105. // input: _angle_ef_target_rad (earth frame targets in radians)
  106. // output: _angle_bf_output_deg (body frame angles in degrees)
  107. void AP_Mount_Servo::stabilize()
  108. {
  109. AP_AHRS &ahrs = AP::ahrs();
  110. // only do the full 3D frame transform if we are doing pan control
  111. if (_state._stab_pan) {
  112. Matrix3f m; ///< holds 3 x 3 matrix, var is used as temp in calcs
  113. Matrix3f cam; ///< Rotation matrix earth to camera. Desired camera from input.
  114. Matrix3f gimbal_target; ///< Rotation matrix from plane to camera. Then Euler angles to the servos.
  115. m = ahrs.get_rotation_body_to_ned();
  116. m.transpose();
  117. cam.from_euler(_angle_ef_target_rad.x, _angle_ef_target_rad.y, _angle_ef_target_rad.z);
  118. gimbal_target = m * cam;
  119. gimbal_target.to_euler(&_angle_bf_output_deg.x, &_angle_bf_output_deg.y, &_angle_bf_output_deg.z);
  120. _angle_bf_output_deg.x = _state._stab_roll ? degrees(_angle_bf_output_deg.x) : degrees(_angle_ef_target_rad.x);
  121. _angle_bf_output_deg.y = _state._stab_tilt ? degrees(_angle_bf_output_deg.y) : degrees(_angle_ef_target_rad.y);
  122. _angle_bf_output_deg.z = degrees(_angle_bf_output_deg.z);
  123. } else {
  124. // otherwise base mount roll and tilt on the ahrs
  125. // roll/tilt attitude, plus any requested angle
  126. _angle_bf_output_deg.x = degrees(_angle_ef_target_rad.x);
  127. _angle_bf_output_deg.y = degrees(_angle_ef_target_rad.y);
  128. _angle_bf_output_deg.z = degrees(_angle_ef_target_rad.z);
  129. if (_state._stab_roll) {
  130. _angle_bf_output_deg.x -= degrees(ahrs.roll);
  131. }
  132. if (_state._stab_tilt) {
  133. _angle_bf_output_deg.y -= degrees(ahrs.pitch);
  134. }
  135. // lead filter
  136. const Vector3f &gyro = ahrs.get_gyro();
  137. if (_state._stab_roll && !is_zero(_state._roll_stb_lead) && fabsf(ahrs.pitch) < M_PI/3.0f) {
  138. // Compute rate of change of euler roll angle
  139. float roll_rate = gyro.x + (ahrs.sin_pitch() / ahrs.cos_pitch()) * (gyro.y * ahrs.sin_roll() + gyro.z * ahrs.cos_roll());
  140. _angle_bf_output_deg.x -= degrees(roll_rate) * _state._roll_stb_lead;
  141. }
  142. if (_state._stab_tilt && !is_zero(_state._pitch_stb_lead)) {
  143. // Compute rate of change of euler pitch angle
  144. float pitch_rate = ahrs.cos_pitch() * gyro.y - ahrs.sin_roll() * gyro.z;
  145. _angle_bf_output_deg.y -= degrees(pitch_rate) * _state._pitch_stb_lead;
  146. }
  147. }
  148. }
  149. // closest_limit - returns closest angle to 'angle' taking into account limits. all angles are in degrees * 10
  150. int16_t AP_Mount_Servo::closest_limit(int16_t angle, int16_t angle_min, int16_t angle_max)
  151. {
  152. // Make sure the angle lies in the interval [-180 .. 180[ degrees
  153. while (angle < -1800) angle += 3600;
  154. while (angle >= 1800) angle -= 3600;
  155. // Make sure the angle limits lie in the interval [-180 .. 180[ degrees
  156. while (angle_min < -1800) angle_min += 3600;
  157. while (angle_min >= 1800) angle_min -= 3600;
  158. while (angle_max < -1800) angle_max += 3600;
  159. while (angle_max >= 1800) angle_max -= 3600;
  160. // If the angle is outside servo limits, saturate the angle to the closest limit
  161. // On a circle the closest angular position must be carefully calculated to account for wrap-around
  162. if ((angle < angle_min) && (angle > angle_max)) {
  163. // angle error if min limit is used
  164. int16_t err_min = angle_min - angle + (angle<angle_min ? 0 : 3600); // add 360 degrees if on the "wrong side"
  165. // angle error if max limit is used
  166. int16_t err_max = angle - angle_max + (angle>angle_max ? 0 : 3600); // add 360 degrees if on the "wrong side"
  167. angle = err_min<err_max ? angle_min : angle_max;
  168. }
  169. return angle;
  170. }
  171. // move_servo - moves servo with the given id to the specified angle. all angles are in degrees * 10
  172. void AP_Mount_Servo::move_servo(uint8_t function_idx, int16_t angle, int16_t angle_min, int16_t angle_max)
  173. {
  174. // saturate to the closest angle limit if outside of [min max] angle interval
  175. int16_t servo_out = closest_limit(angle, angle_min, angle_max);
  176. SRV_Channels::move_servo((SRV_Channel::Aux_servo_function_t)function_idx, servo_out, angle_min, angle_max);
  177. }