SIM_Submarine.cpp 8.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237
  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. Submarine simulator class
  15. */
  16. #include "SIM_Submarine.h"
  17. #include <AP_Motors/AP_Motors.h>
  18. #include <stdio.h>
  19. using namespace SITL;
  20. static Thruster vectored_thrusters[] =
  21. { // Motor # Roll Factor Pitch Factor Yaw Factor Throttle Factor Forward Factor Lateral Factor
  22. Thruster(0, 0, 0, 1.0f, 0, -1.0f, 1.0f),
  23. Thruster(1, 0, 0, -1.0f, 0, -1.0f, -1.0f),
  24. Thruster(2, 0, 0, -1.0f, 0, 1.0f, 1.0f),
  25. Thruster(3, 0, 0, 1.0f, 0, 1.0f, -1.0f),
  26. Thruster(4, 1.0f, 0, 0, -1.0f, 0, 0),
  27. Thruster(5, -1.0f, 0, 0, -1.0f, 0, 0)
  28. };
  29. static Thruster vectored_6dof_thrusters[] =
  30. {
  31. // Motor # Roll Factor Pitch Factor Yaw Factor Throttle Factor Forward Factor Lateral Factor
  32. Thruster(0, 0, 0, 1.0f, 0, -1.0f, 1.0f),
  33. Thruster(1, 0, 0, -1.0f, 0, -1.0f, -1.0f),
  34. Thruster(2, 0, 0, -1.0f, 0, 1.0f, 1.0f),
  35. Thruster(3, 0, 0, 1.0f, 0, 1.0f, -1.0f),
  36. Thruster(4, 1.0f, -1.0f, 0, -1.0f, 0, 0),
  37. Thruster(5, -1.0f, -1.0f, 0, -1.0f, 0, 0),
  38. Thruster(6, 1.0f, 1.0f, 0, -1.0f, 0, 0),
  39. Thruster(7, -1.0f, 1.0f, 0, -1.0f, 0, 0)
  40. };
  41. Submarine::Submarine(const char *frame_str) :
  42. Aircraft(frame_str),
  43. frame(NULL)
  44. {
  45. frame_height = 0.0;
  46. ground_behavior = GROUND_BEHAVIOR_NONE;
  47. // default to vectored frame
  48. thrusters = vectored_thrusters;
  49. n_thrusters = 6;
  50. if (strstr(frame_str, "vectored_6dof")) {
  51. thrusters = vectored_6dof_thrusters;
  52. n_thrusters = 8;
  53. }
  54. }
  55. // calculate rotational and linear accelerations
  56. void Submarine::calculate_forces(const struct sitl_input &input, Vector3f &rot_accel, Vector3f &body_accel)
  57. {
  58. rot_accel = Vector3f(0,0,0);
  59. // slight positive buoyancy
  60. body_accel = dcm.transposed() * Vector3f(0, 0, -calculate_buoyancy_acceleration());
  61. for (int i = 0; i < n_thrusters; i++) {
  62. Thruster t = thrusters[i];
  63. int16_t pwm = input.servos[t.servo];
  64. float output = 0;
  65. // if valid pwm and not in the esc deadzone
  66. // TODO: extract deadzone from parameters/vehicle code
  67. if (pwm < 2000 && pwm > 1000 && (pwm < 1475 || pwm > 1525)) {
  68. output = (pwm - 1500) / 400.0; // range -1~1
  69. }
  70. // 2.5 scalar for approximate real-life performance of T200 thruster
  71. body_accel += t.linear * output * frame_property.thrust / frame_property.weight;
  72. rot_accel += t.rotational * output * frame_property.thrust * frame_property.thruster_mount_radius / frame_property.moment_of_inertia;
  73. }
  74. // Limit movement at the sea floor
  75. if (position.z > 100 && body_accel.z > -GRAVITY_MSS) {
  76. body_accel.z = -GRAVITY_MSS;
  77. }
  78. // Calculate linear drag forces
  79. Vector3f linear_drag_forces;
  80. calculate_drag_force(velocity_air_bf, frame_property.linear_drag_coefficient, linear_drag_forces);
  81. // Add forces in body frame accel
  82. body_accel -= linear_drag_forces / frame_property.weight;
  83. // Calculate angular drag forces
  84. // TODO: This results in the wrong units. Fix the math.
  85. Vector3f angular_drag_torque;
  86. calculate_angular_drag_torque(gyro, frame_property.angular_drag_coefficient, angular_drag_torque);
  87. // Calculate torque induced by buoyancy foams on the frame
  88. Vector3f buoyancy_torque;
  89. calculate_buoyancy_torque(buoyancy_torque);
  90. // Add forces in body frame accel
  91. rot_accel -= angular_drag_torque / frame_property.moment_of_inertia;
  92. rot_accel += buoyancy_torque / frame_property.moment_of_inertia;
  93. }
  94. /**
  95. * @brief Calculate the torque induced by buoyancy foam
  96. *
  97. * @param torque Output torques
  98. */
  99. void Submarine::calculate_buoyancy_torque(Vector3f &torque)
  100. {
  101. // Let's assume 2 Liters water displacement at the top, and ~ 2kg of weight at the bottom.
  102. const Vector3f force_up(0,0,-40); // 40 N upwards
  103. const Vector3f force_position = dcm.transposed() * Vector3f(0, 0, 0.15); // offset in meters
  104. torque = force_position % force_up;
  105. }
  106. /**
  107. * @brief Calculate drag force against body
  108. *
  109. * @param velocity Body frame velocity of fluid
  110. * @param drag_coefficient Drag coefficient of body
  111. * @param force Output forces
  112. * $ F_D = rho * v^2 * A * C_D / 2 $
  113. * rho = water density (kg/m^3), V = velocity (m/s), A = area (m^2), C_D = drag_coefficient
  114. */
  115. void Submarine::calculate_drag_force(const Vector3f &velocity, const Vector3f &drag_coefficient, Vector3f &force)
  116. {
  117. /**
  118. * @brief It's necessary to keep the velocity orientation from the body frame.
  119. * To do so, a mathematical artifice is used to do velocity square but without loosing the direction.
  120. * $(|V|/V)*V^2$ = $|V|*V$
  121. */
  122. const Vector3f velocity_2(
  123. fabsf(velocity.x) * velocity.x,
  124. fabsf(velocity.y) * velocity.y,
  125. fabsf(velocity.z) * velocity.z
  126. );
  127. force = (velocity_2 * water_density) * frame_property.equivalent_sphere_area / 2.0f;
  128. force *= drag_coefficient;
  129. }
  130. /**
  131. * @brief Calculate angular drag torque using the equivalente sphere area and assuming a laminar external flow.
  132. *
  133. * $F_D = C_D*A*\rho*V^2/2$
  134. * where:
  135. * $F_D$ is the drag force
  136. * $C_D$ is the drag coefficient
  137. * $A$ is the surface area in contact with the fluid
  138. * $/rho$ is the fluid density (1000kg/m³ for water)
  139. * $V$ is the fluid velocity velocity relative to the surface
  140. *
  141. * @param angular_velocity Body frame velocity of fluid
  142. * @param drag_coefficient Rotational drag coefficient of body
  143. */
  144. void Submarine::calculate_angular_drag_torque(const Vector3f &angular_velocity, const Vector3f &drag_coefficient, Vector3f &torque)
  145. {
  146. /**
  147. * @brief It's necessary to keep the velocity orientation from the body frame.
  148. * To do so, a mathematical artifice is used to do velocity square but without loosing the direction.
  149. * $(|V|/V)*V^2$ = $|V|*V$
  150. */
  151. Vector3f v_2(
  152. fabsf(angular_velocity.x) * angular_velocity.x,
  153. fabsf(angular_velocity.y) * angular_velocity.y,
  154. fabsf(angular_velocity.z) * angular_velocity.z
  155. );
  156. Vector3f f_d = v_2 *= drag_coefficient * frame_property.equivalent_sphere_area * 1000 / 2;
  157. torque = f_d * frame_property.equivalent_sphere_radius;
  158. }
  159. /**
  160. * @brief Calculate buoyancy force of the frame
  161. *
  162. * @return float
  163. */
  164. float Submarine::calculate_buoyancy_acceleration()
  165. {
  166. float below_water_level = position.z - frame_property.height/2;
  167. // Completely above water level
  168. if (below_water_level < 0) {
  169. return 0.0f;
  170. }
  171. // Completely below water level
  172. if (below_water_level > frame_property.height/2) {
  173. return frame_property.buoyancy_acceleration;
  174. }
  175. // bouyant force is proportional to fraction of height in water
  176. return frame_property.buoyancy_acceleration * below_water_level/frame_property.height;
  177. };
  178. /*
  179. update the Submarine simulation by one time step
  180. */
  181. void Submarine::update(const struct sitl_input &input)
  182. {
  183. // get wind vector setup
  184. update_wind(input);
  185. Vector3f rot_accel;
  186. calculate_forces(input, rot_accel, accel_body);
  187. update_dynamics(rot_accel);
  188. // update lat/lon/altitude
  189. update_position();
  190. time_advance();
  191. // update magnetic field
  192. update_mag_field_bf();
  193. }
  194. /*
  195. return true if we are on the ground
  196. */
  197. bool Submarine::on_ground() const
  198. {
  199. return false;
  200. }