SIM_Sailboat.cpp 9.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280
  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. Sailboat simulator class
  15. see explanation of lift and drag explained here: https://en.wikipedia.org/wiki/Forces_on_sails
  16. To-Do: add heel handling by calculating lateral force from wind vs gravity force from heel to arrive at roll rate or acceleration
  17. */
  18. #include "SIM_Sailboat.h"
  19. #include <AP_Math/AP_Math.h>
  20. #include <AP_AHRS/AP_AHRS.h>
  21. #include <string.h>
  22. #include <stdio.h>
  23. extern const AP_HAL::HAL& hal;
  24. namespace SITL {
  25. #define STEERING_SERVO_CH 0 // steering controlled by servo output 1
  26. #define MAINSAIL_SERVO_CH 3 // main sail controlled by servo output 4
  27. #define THROTTLE_SERVO_CH 2 // throttle controlled by servo output 3
  28. // very roughly sort of a stability factors for waves
  29. #define WAVE_ANGLE_GAIN 1
  30. #define WAVE_HEAVE_GAIN 1
  31. Sailboat::Sailboat(const char *frame_str) :
  32. Aircraft(frame_str),
  33. steering_angle_max(35),
  34. turning_circle(1.8)
  35. {
  36. motor_connected = (strcmp(frame_str, "sailboat-motor") == 0);
  37. }
  38. // calculate the lift and drag as values from 0 to 1
  39. // given an apparent wind speed in m/s and angle-of-attack in degrees
  40. void Sailboat::calc_lift_and_drag(float wind_speed, float angle_of_attack_deg, float& lift, float& drag) const
  41. {
  42. const uint16_t index_width_deg = 10;
  43. const uint8_t index_max = ARRAY_SIZE(lift_curve) - 1;
  44. // check extremes
  45. if (angle_of_attack_deg <= 0.0f) {
  46. lift = lift_curve[0];
  47. drag = drag_curve[0];
  48. } else if (angle_of_attack_deg >= index_max * index_width_deg) {
  49. lift = lift_curve[index_max];
  50. drag = drag_curve[index_max];
  51. } else {
  52. uint8_t index = constrain_int16(angle_of_attack_deg / index_width_deg, 0, index_max);
  53. float remainder = angle_of_attack_deg - (index * index_width_deg);
  54. lift = linear_interpolate(lift_curve[index], lift_curve[index+1], remainder, 0.0f, index_width_deg);
  55. drag = linear_interpolate(drag_curve[index], drag_curve[index+1], remainder, 0.0f, index_width_deg);
  56. }
  57. // apply scaling by wind speed
  58. lift *= wind_speed;
  59. drag *= wind_speed;
  60. }
  61. // return turning circle (diameter) in meters for steering angle proportion in the range -1 to +1
  62. float Sailboat::get_turn_circle(float steering) const
  63. {
  64. if (is_zero(steering)) {
  65. return 0;
  66. }
  67. return turning_circle * sinf(radians(steering_angle_max)) / sinf(radians(steering * steering_angle_max));
  68. }
  69. // return yaw rate in deg/sec given a steering input (in the range -1 to +1) and speed in m/s
  70. float Sailboat::get_yaw_rate(float steering, float speed) const
  71. {
  72. if (is_zero(steering) || is_zero(speed)) {
  73. return 0;
  74. }
  75. float d = get_turn_circle(steering);
  76. float c = M_PI * d;
  77. float t = c / speed;
  78. float rate = 360.0f / t;
  79. return rate;
  80. }
  81. // return lateral acceleration in m/s/s given a steering input (in the range -1 to +1) and speed in m/s
  82. float Sailboat::get_lat_accel(float steering, float speed) const
  83. {
  84. float yaw_rate = get_yaw_rate(steering, speed);
  85. float accel = radians(yaw_rate) * speed;
  86. return accel;
  87. }
  88. // simulate basic waves / swell
  89. void Sailboat::update_wave(float delta_time)
  90. {
  91. const float wave_heading = sitl->wave.direction;
  92. const float wave_speed = sitl->wave.speed;
  93. const float wave_lenght = sitl->wave.length;
  94. const float wave_amp = sitl->wave.amp;
  95. // apply rate propositional to error between boat angle and water angle
  96. // this gives a 'stability' effect
  97. float r, p, y;
  98. dcm.to_euler(&r, &p, &y);
  99. // if not armed don't do waves, to allow gyro init
  100. if (sitl->wave.enable == 0 || !hal.util->get_soft_armed() || is_zero(wave_amp) ) {
  101. wave_gyro = Vector3f(-r,-p,0.0f) * WAVE_ANGLE_GAIN;
  102. wave_heave = -velocity_ef.z * WAVE_HEAVE_GAIN;
  103. wave_phase = 0.0f;
  104. return;
  105. }
  106. // calculate the sailboat speed in the direction of the wave
  107. const float boat_speed = velocity_ef.x * sinf(radians(wave_heading)) + velocity_ef.y * cosf(radians(wave_heading));
  108. // update the wave phase
  109. const float aprarent_wave_distance = (wave_speed - boat_speed) * delta_time;
  110. const float apparent_wave_phase_change = (aprarent_wave_distance / wave_lenght) * M_2PI;
  111. wave_phase += apparent_wave_phase_change;
  112. wave_phase = wrap_2PI(wave_phase);
  113. // calculate the angles at this phase on the wave
  114. // use basic sine wave, dy/dx of sine = cosine
  115. // atan( cosine ) = wave angle
  116. const float wave_slope = (wave_amp * 0.5f) * (M_2PI / wave_lenght) * cosf(wave_phase);
  117. const float wave_angle = atanf(wave_slope);
  118. // convert wave angle to vehicle frame
  119. const float heading_dif = wave_heading - y;
  120. float angle_error_x = (sinf(heading_dif) * wave_angle) - r;
  121. float angle_error_y = (cosf(heading_dif) * wave_angle) - p;
  122. // apply gain
  123. wave_gyro.x = angle_error_x * WAVE_ANGLE_GAIN;
  124. wave_gyro.y = angle_error_y * WAVE_ANGLE_GAIN;
  125. wave_gyro.z = 0.0f;
  126. // calculate wave height (NED)
  127. if (sitl->wave.enable == 2) {
  128. wave_heave = (wave_slope - velocity_ef.z) * WAVE_HEAVE_GAIN;
  129. } else {
  130. wave_heave = 0.0f;
  131. }
  132. }
  133. /*
  134. update the sailboat simulation by one time step
  135. */
  136. void Sailboat::update(const struct sitl_input &input)
  137. {
  138. // update wind
  139. update_wind(input);
  140. // in sailboats the steering controls the rudder, the throttle controls the main sail position
  141. float steering = 2*((input.servos[STEERING_SERVO_CH]-1000)/1000.0f - 0.5f);
  142. // calculate mainsail angle from servo output 4, 0 to 90 degrees
  143. float mainsail_angle_bf = constrain_float((input.servos[MAINSAIL_SERVO_CH]-1000)/1000.0f * 90.0f, 0.0f, 90.0f);
  144. // calculate apparent wind in earth-frame (this is the direction the wind is coming from)
  145. // Note than the SITL wind direction is defined as the direction the wind is travelling to
  146. // This is accounted for in these calculations
  147. Vector3f wind_apparent_ef = wind_ef + velocity_ef;
  148. const float wind_apparent_dir_ef = degrees(atan2f(wind_apparent_ef.y, wind_apparent_ef.x));
  149. const float wind_apparent_speed = safe_sqrt(sq(wind_apparent_ef.x)+sq(wind_apparent_ef.y));
  150. const float wind_apparent_dir_bf = wrap_180(wind_apparent_dir_ef - degrees(AP::ahrs().yaw));
  151. // set RPM and airspeed from wind speed, allows to test RPM and Airspeed wind vane back end in SITL
  152. rpm1 = wind_apparent_speed;
  153. airspeed_pitot = wind_apparent_speed;
  154. // calculate angle-of-attack from wind to mainsail
  155. float aoa_deg = MAX(fabsf(wind_apparent_dir_bf) - mainsail_angle_bf, 0);
  156. // calculate Lift force (perpendicular to wind direction) and Drag force (parallel to wind direction)
  157. float lift_wf, drag_wf;
  158. calc_lift_and_drag(wind_apparent_speed, aoa_deg, lift_wf, drag_wf);
  159. // rotate lift and drag from wind frame into body frame
  160. const float sin_rot_rad = sinf(radians(wind_apparent_dir_bf));
  161. const float cos_rot_rad = cosf(radians(wind_apparent_dir_bf));
  162. const float force_fwd = fabsf(lift_wf * sin_rot_rad) - (drag_wf * cos_rot_rad);
  163. // how much time has passed?
  164. float delta_time = frame_time_us * 1.0e-6f;
  165. // speed in m/s in body frame
  166. Vector3f velocity_body = dcm.transposed() * velocity_ef_water;
  167. // speed along x axis, +ve is forward
  168. float speed = velocity_body.x;
  169. // yaw rate in degrees/s
  170. float yaw_rate = get_yaw_rate(steering, speed);
  171. gyro = Vector3f(0,0,radians(yaw_rate)) + wave_gyro;
  172. // update attitude
  173. dcm.rotate(gyro * delta_time);
  174. dcm.normalize();
  175. // hull drag
  176. float hull_drag = sq(speed) * 0.5f;
  177. if (!is_positive(speed)) {
  178. hull_drag *= -1.0f;
  179. }
  180. // throttle force (for motor sailing)
  181. // gives throttle force == hull drag at 10m/s
  182. float throttle_force = 0.0f;
  183. if (motor_connected) {
  184. const uint16_t throttle_out = constrain_int16(input.servos[THROTTLE_SERVO_CH], 1000, 2000);
  185. throttle_force = (throttle_out-1500) * 0.1f;
  186. }
  187. // accel in body frame due acceleration from sail and deceleration from hull friction
  188. accel_body = Vector3f((throttle_force + force_fwd) - hull_drag, 0, 0);
  189. accel_body /= mass;
  190. // add in accel due to direction change
  191. accel_body.y += radians(yaw_rate) * speed;
  192. // now in earth frame
  193. // remove roll and pitch effects from waves
  194. float r, p, y;
  195. dcm.to_euler(&r, &p, &y);
  196. Matrix3f temp_dcm;
  197. temp_dcm.from_euler(0.0f, 0.0f, y);
  198. Vector3f accel_earth = temp_dcm * accel_body;
  199. // we are on the ground, so our vertical accel is zero
  200. accel_earth.z = 0 + wave_heave;
  201. // work out acceleration as seen by the accelerometers. It sees the kinematic
  202. // acceleration (ie. real movement), plus gravity
  203. accel_body = dcm.transposed() * (accel_earth + Vector3f(0, 0, -GRAVITY_MSS));
  204. // tide calcs
  205. Vector3f tide_velocity_ef;
  206. if (hal.util->get_soft_armed() && !is_zero(sitl->tide.speed) ) {
  207. tide_velocity_ef.x = -cosf(radians(sitl->tide.direction)) * sitl->tide.speed;
  208. tide_velocity_ef.y = -sinf(radians(sitl->tide.direction)) * sitl->tide.speed;
  209. tide_velocity_ef.z = 0.0f;
  210. }
  211. // new velocity vector
  212. velocity_ef_water += accel_earth * delta_time;
  213. velocity_ef = velocity_ef_water + tide_velocity_ef;
  214. // new position vector
  215. position += velocity_ef * delta_time;
  216. // update lat/lon/altitude
  217. update_position();
  218. time_advance();
  219. // update magnetic field
  220. update_mag_field_bf();
  221. // update wave calculations
  222. update_wave(delta_time);
  223. }
  224. } // namespace SITL