SIM_QuadPlane.cpp 4.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. /*
  14. simple quadplane simulator class
  15. */
  16. #include "SIM_QuadPlane.h"
  17. #include <stdio.h>
  18. using namespace SITL;
  19. QuadPlane::QuadPlane(const char *frame_str) :
  20. Plane(frame_str)
  21. {
  22. // default to X frame
  23. const char *frame_type = "x";
  24. uint8_t motor_offset = 4;
  25. if (strstr(frame_str, "-octa-quad")) {
  26. frame_type = "octa-quad";
  27. } else if (strstr(frame_str, "-octaquad")) {
  28. frame_type = "octa-quad";
  29. } else if (strstr(frame_str, "-octa")) {
  30. frame_type = "octa";
  31. } else if (strstr(frame_str, "-hexax")) {
  32. frame_type = "hexax";
  33. } else if (strstr(frame_str, "-hexa")) {
  34. frame_type = "hexa";
  35. } else if (strstr(frame_str, "-plus")) {
  36. frame_type = "+";
  37. } else if (strstr(frame_str, "-y6")) {
  38. frame_type = "y6";
  39. } else if (strstr(frame_str, "-tri")) {
  40. frame_type = "tri";
  41. } else if (strstr(frame_str, "-tilttrivec")) {
  42. frame_type = "tilttrivec";
  43. // fwd motor gives zero thrust
  44. thrust_scale = 0;
  45. } else if (strstr(frame_str, "-tilthvec")) {
  46. frame_type = "tilthvec";
  47. } else if (strstr(frame_str, "-tilttri")) {
  48. frame_type = "tilttri";
  49. // fwd motor gives zero thrust
  50. thrust_scale = 0;
  51. } else if (strstr(frame_str, "firefly")) {
  52. frame_type = "firefly";
  53. // elevon style surfaces
  54. elevons = true;
  55. // fwd motor gives zero thrust
  56. thrust_scale = 0;
  57. // vtol motors start at 2
  58. motor_offset = 2;
  59. } else if (strstr(frame_str, "cl84")) {
  60. frame_type = "tilttri";
  61. // fwd motor gives zero thrust
  62. thrust_scale = 0;
  63. }
  64. frame = Frame::find_frame(frame_type);
  65. if (frame == nullptr) {
  66. printf("Failed to find frame '%s'\n", frame_type);
  67. exit(1);
  68. }
  69. if (strstr(frame_str, "cl84")) {
  70. // setup retract servos at front
  71. frame->motors[0].servo_type = Motor::SERVO_RETRACT;
  72. frame->motors[0].servo_rate = 7*60.0/90; // 7 seconds to change
  73. frame->motors[1].servo_type = Motor::SERVO_RETRACT;
  74. frame->motors[1].servo_rate = 7*60.0/90; // 7 seconds to change
  75. }
  76. // leave first 4 servos free for plane
  77. frame->motor_offset = motor_offset;
  78. // we use zero terminal velocity to let the plane model handle the drag
  79. frame->init(mass, 0.51, 0, 0);
  80. ground_behavior = GROUND_BEHAVIOR_NO_MOVEMENT;
  81. }
  82. /*
  83. update the quadplane simulation by one time step
  84. */
  85. void QuadPlane::update(const struct sitl_input &input)
  86. {
  87. // get wind vector setup
  88. update_wind(input);
  89. // first plane forces
  90. Vector3f rot_accel;
  91. calculate_forces(input, rot_accel, accel_body);
  92. // now quad forces
  93. Vector3f quad_rot_accel;
  94. Vector3f quad_accel_body;
  95. frame->calculate_forces(*this, input, quad_rot_accel, quad_accel_body);
  96. // estimate voltage and current
  97. frame->current_and_voltage(input, battery_voltage, battery_current);
  98. float throttle;
  99. if (reverse_thrust) {
  100. throttle = filtered_servo_angle(input, 2);
  101. } else {
  102. throttle = filtered_servo_range(input, 2);
  103. }
  104. // assume 20A at full fwd throttle
  105. throttle = fabsf(throttle);
  106. battery_current += 20 * throttle;
  107. rot_accel += quad_rot_accel;
  108. accel_body += quad_accel_body;
  109. update_dynamics(rot_accel);
  110. // update lat/lon/altitude
  111. update_position();
  112. time_advance();
  113. // update magnetic field
  114. update_mag_field_bf();
  115. }