AP_Mount_Backend.cpp 6.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158
  1. #include "AP_Mount_Backend.h"
  2. #include <AP_AHRS/AP_AHRS.h>
  3. extern const AP_HAL::HAL& hal;
  4. // set_angle_targets - sets angle targets in degrees
  5. void AP_Mount_Backend::set_angle_targets(float roll, float tilt, float pan)
  6. {
  7. // set angle targets
  8. _angle_ef_target_rad.x = radians(roll);
  9. _angle_ef_target_rad.y = radians(tilt);
  10. _angle_ef_target_rad.z = radians(pan);
  11. // set the mode to mavlink targeting
  12. _frontend.set_mode(_instance, MAV_MOUNT_MODE_MAVLINK_TARGETING);
  13. }
  14. // set_roi_target - sets target location that mount should attempt to point towards
  15. void AP_Mount_Backend::set_roi_target(const struct Location &target_loc)
  16. {
  17. // set the target gps location
  18. _state._roi_target = target_loc;
  19. // set the mode to GPS tracking mode
  20. _frontend.set_mode(_instance, MAV_MOUNT_MODE_GPS_POINT);
  21. }
  22. // process MOUNT_CONFIGURE messages received from GCS. deprecated.
  23. void AP_Mount_Backend::handle_mount_configure(const mavlink_mount_configure_t &packet)
  24. {
  25. set_mode((MAV_MOUNT_MODE)packet.mount_mode);
  26. _state._stab_roll = packet.stab_roll;
  27. _state._stab_tilt = packet.stab_pitch;
  28. _state._stab_pan = packet.stab_yaw;
  29. }
  30. // process MOUNT_CONTROL messages received from GCS. deprecated.
  31. void AP_Mount_Backend::handle_mount_control(const mavlink_mount_control_t &packet)
  32. {
  33. control((int32_t)packet.input_a, (int32_t)packet.input_b, (int32_t)packet.input_c, _state._mode);
  34. }
  35. void AP_Mount_Backend::control(int32_t pitch_or_lat, int32_t roll_or_lon, int32_t yaw_or_alt, MAV_MOUNT_MODE mount_mode)
  36. {
  37. _frontend.set_mode(_instance, mount_mode);
  38. // interpret message fields based on mode
  39. switch (_frontend.get_mode(_instance)) {
  40. case MAV_MOUNT_MODE_RETRACT:
  41. case MAV_MOUNT_MODE_NEUTRAL:
  42. // do nothing with request if mount is retracted or in neutral position
  43. break;
  44. // set earth frame target angles from mavlink message
  45. case MAV_MOUNT_MODE_MAVLINK_TARGETING:
  46. set_angle_targets(roll_or_lon*0.01f, pitch_or_lat*0.01f, yaw_or_alt*0.01f);
  47. break;
  48. // Load neutral position and start RC Roll,Pitch,Yaw control with stabilization
  49. case MAV_MOUNT_MODE_RC_TARGETING:
  50. // do nothing if pilot is controlling the roll, pitch and yaw
  51. break;
  52. // set lat, lon, alt position targets from mavlink message
  53. case MAV_MOUNT_MODE_GPS_POINT: {
  54. const Location target_location{
  55. pitch_or_lat,
  56. roll_or_lon,
  57. yaw_or_alt,
  58. Location::AltFrame::ABOVE_HOME
  59. };
  60. set_roi_target(target_location);
  61. break;
  62. }
  63. default:
  64. // do nothing
  65. break;
  66. }
  67. }
  68. void AP_Mount_Backend::rate_input_rad(float &out, const RC_Channel *chan, float min, float max) const
  69. {
  70. if ((chan == nullptr) || (chan->get_radio_in() == 0)) {
  71. return;
  72. }
  73. out += chan->norm_input_dz() * 0.0001f * _frontend._joystick_speed;
  74. out = constrain_float(out, radians(min*0.01f), radians(max*0.01f));
  75. }
  76. // update_targets_from_rc - updates angle targets using input from receiver
  77. void AP_Mount_Backend::update_targets_from_rc()
  78. {
  79. const RC_Channel *roll_ch = rc().channel(_state._roll_rc_in - 1);
  80. const RC_Channel *tilt_ch = rc().channel(_state._tilt_rc_in - 1);
  81. const RC_Channel *pan_ch = rc().channel(_state._pan_rc_in - 1);
  82. // if joystick_speed is defined then pilot input defines a rate of change of the angle
  83. if (_frontend._joystick_speed) {
  84. // allow pilot position input to come directly from an RC_Channel
  85. rate_input_rad(_angle_ef_target_rad.x,
  86. roll_ch,
  87. _state._roll_angle_min,
  88. _state._roll_angle_max);
  89. rate_input_rad(_angle_ef_target_rad.y,
  90. tilt_ch,
  91. _state._tilt_angle_min,
  92. _state._tilt_angle_max);
  93. rate_input_rad(_angle_ef_target_rad.z,
  94. pan_ch,
  95. _state._pan_angle_min,
  96. _state._pan_angle_max);
  97. } else {
  98. // allow pilot rate input to come directly from an RC_Channel
  99. if ((roll_ch != nullptr) && (roll_ch->get_radio_in() != 0)) {
  100. _angle_ef_target_rad.x = angle_input_rad(roll_ch, _state._roll_angle_min, _state._roll_angle_max);
  101. }
  102. if ((tilt_ch != nullptr) && (tilt_ch->get_radio_in() != 0)) {
  103. _angle_ef_target_rad.y = angle_input_rad(tilt_ch, _state._tilt_angle_min, _state._tilt_angle_max);
  104. }
  105. if ((pan_ch != nullptr) && (pan_ch->get_radio_in() != 0)) {
  106. _angle_ef_target_rad.z = angle_input_rad(pan_ch, _state._pan_angle_min, _state._pan_angle_max);
  107. }
  108. }
  109. }
  110. // returns the angle (radians) that the RC_Channel input is receiving
  111. float AP_Mount_Backend::angle_input_rad(const RC_Channel* rc, int16_t angle_min, int16_t angle_max)
  112. {
  113. return radians(((rc->norm_input() + 1.0f) * 0.5f * (angle_max - angle_min) + angle_min)*0.01f);
  114. }
  115. // calc_angle_to_location - calculates the earth-frame roll, tilt and pan angles (and radians) to point at the given target
  116. void AP_Mount_Backend::calc_angle_to_location(const struct Location &target, Vector3f& angles_to_target_rad, bool calc_tilt, bool calc_pan, bool relative_pan)
  117. {
  118. float GPS_vector_x = (target.lng-_frontend._current_loc.lng)*cosf(ToRad((_frontend._current_loc.lat+target.lat)*0.00000005f))*0.01113195f;
  119. float GPS_vector_y = (target.lat-_frontend._current_loc.lat)*0.01113195f;
  120. float GPS_vector_z = (target.alt-_frontend._current_loc.alt); // baro altitude(IN CM) should be adjusted to known home elevation before take off (Set altimeter).
  121. float target_distance = 100.0f*norm(GPS_vector_x, GPS_vector_y); // Careful , centimeters here locally. Baro/alt is in cm, lat/lon is in meters.
  122. // initialise all angles to zero
  123. angles_to_target_rad.zero();
  124. // tilt calcs
  125. if (calc_tilt) {
  126. angles_to_target_rad.y = atan2f(GPS_vector_z, target_distance);
  127. }
  128. // pan calcs
  129. if (calc_pan) {
  130. // calc absolute heading and then onvert to vehicle relative yaw
  131. angles_to_target_rad.z = atan2f(GPS_vector_x, GPS_vector_y);
  132. if (relative_pan) {
  133. angles_to_target_rad.z = wrap_PI(angles_to_target_rad.z - AP::ahrs().yaw);
  134. }
  135. }
  136. }