Sailboat_VPP.m 5.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159
  1. clc
  2. clear all
  3. close all
  4. %{
  5. Very basic Velocity Prediction Program, this duplicates the physics used in the sailboat SITL model. It can be used to generate polar plots to check
  6. STIL physics is sensible.
  7. In the future it is hoped this program can be used as a comparison for a built in polar generator that is yet to be added to the ArduRover code.
  8. Alternatively a drag polar generated here can be used directly in the code to select optimal sailing angles.
  9. Sail lift, drag and Hull drag not considered properly, boat heel not considered. The polar generated is however realistic for a 'generic' sailboat.
  10. %}
  11. sail_aoa_in = [0, 10, 20, 30, 40, 50, 60, 70, 80, 90, 100, 110, 120, 130, 140, 150, 160, 170, 179.9]; % deg
  12. lift_curve_in = [0.00, 0.50, 1.00, 1.10, 0.95, 0.75, 0.60, 0.40, 0.20, 0.00, -0.20, -0.40, -0.60, -0.75, -0.95, -1.10, -1.00, -0.50, 0];
  13. drag_curve_in = [0.10, 0.10, 0.20, 0.40, 0.80, 1.20, 1.50, 1.70, 1.90, 1.95, 1.90, 1.70, 1.50, 1.20, 0.80, 0.40, 0.20, 0.10, 0.10];
  14. min_sail_angle = 0; % deg
  15. max_sail_angle = 90; % deg
  16. % intpolate to more detailed curves
  17. sail_aoa = sail_aoa_in(1):0.1:sail_aoa_in(end)-0.1;
  18. lift_curve = interp1(sail_aoa_in, lift_curve_in, sail_aoa);
  19. drag_curve = interp1(sail_aoa_in, drag_curve_in, sail_aoa);
  20. % Plot lift curve
  21. figure
  22. subplot(2,1,1)
  23. hold all
  24. title('Lift and Drag Curves')
  25. scatter(sail_aoa_in,lift_curve_in,'*','r')
  26. plot(sail_aoa,lift_curve,'r')
  27. ylabel('Cl')
  28. subplot(2,1,2)
  29. hold all
  30. scatter(sail_aoa_in,drag_curve_in,'*','b')
  31. plot(sail_aoa,drag_curve,'b')
  32. xlabel('AoA (deg)')
  33. ylabel('Cd')
  34. %% VPP
  35. % Do for range of sailing angles and wind speeds, increse speed until foward force equals zero
  36. wind_speed = 3:2:15; % m/s
  37. heading = 0:1:179; % deg
  38. speed_step = 0.01; % m/s
  39. for n = 1:length(wind_speed)
  40. for m = 1:length(heading)
  41. thrust = 1;
  42. boat_speed{n,m}(1) = 0;
  43. j = 0;
  44. while thrust > 0 && boat_speed{n,m}(end) < 10
  45. j = j + 1;
  46. if j == 1
  47. boat_speed{n,m}(j) = speed_step;
  48. else
  49. boat_speed{n,m}(j) = boat_speed{n,m}(j-1) + speed_step;
  50. end
  51. % calculate apparent wind in earth-frame (this is the direction the wind is coming from)
  52. wind_apparent_speed{n,m}(j) = sqrt(wind_speed(n)^2 + boat_speed{n,m}(j)^2 + 2 * wind_speed(n) * boat_speed{n,m}(j) * cosd(heading(m)));
  53. % Aparent wind angle in body frame
  54. wind_apparent_dir_bf{n,m}(j) = acosd((wind_speed(n) * cosd(heading(m)) + boat_speed{n,m}(j))/wind_apparent_speed{n,m}(j));
  55. % calculate lift at all angles-of-attack from wind to mainsail
  56. % calculate Lift force (perpendicular to wind direction) and Drag force (parallel to wind direction)
  57. lift = lift_curve * wind_apparent_speed{n,m}(j);
  58. drag = drag_curve * wind_apparent_speed{n,m}(j);
  59. % rotate lift and drag from wind frame into body frame
  60. sin_rot = sind(wind_apparent_dir_bf{n,m}(j));
  61. cos_rot = cosd(wind_apparent_dir_bf{n,m}(j));
  62. force_fwd = (lift * sin_rot) - (drag * cos_rot);
  63. % accel in body frame due acceleration from sail and deceleration from hull friction
  64. hull_drag = 0.5 * boat_speed{n,m}(j)^2;
  65. thrust_range = force_fwd - hull_drag;
  66. % angle of sail to boat
  67. sail_boat_angle = wind_apparent_dir_bf{n,m}(j) - sail_aoa;
  68. % discard imposible sail angles
  69. index = find(sail_boat_angle > max_sail_angle | sail_boat_angle < min_sail_angle);
  70. thrust_range(index) = NaN;
  71. % select sail angle that gives best thrust
  72. index = find(thrust_range == max(thrust_range),1);
  73. if ~isempty(index)
  74. thrust = thrust_range(index);
  75. sail_force{n,m}(j) = force_fwd(index);
  76. sail_angle_trim{n,m}(j) = sail_boat_angle(index);
  77. hull_drag_trim{n,m}(j) = hull_drag;
  78. else
  79. thrust = 0;
  80. end
  81. end
  82. max_boat_speed(n,m) = boat_speed{n,m}(j);
  83. % Set minumum values to NaN to make plot neater
  84. if max_boat_speed(n,m) == speed_step
  85. max_boat_speed(n,m) = NaN;
  86. end
  87. end
  88. end
  89. %% Polar plot
  90. figure
  91. for n = 1:length(wind_speed)
  92. polarplot(deg2rad(heading),max_boat_speed(n,:))
  93. hold on
  94. legend_val{n} = sprintf('%g m/s',wind_speed(n));
  95. end
  96. ax = gca;
  97. d = ax.ThetaDir;
  98. ax.ThetaDir = 'clockwise';
  99. ax.ThetaZeroLocation = 'top';
  100. legend(legend_val)
  101. title('Polar Plot, boat speed (m/s) vs heading (deg)')
  102. %% Plot sail thrust and hull drag for a given heading
  103. plot_heading = 50;
  104. plot_wind_speed = 5;
  105. % convet from values to indexs
  106. plot_heading = find(heading == plot_heading);
  107. plot_wind_speed = find(wind_speed == plot_wind_speed);
  108. if isempty(plot_heading) || isempty(plot_wind_speed)
  109. fprintf('Plot headings and or windspeed not within the range caulated')
  110. return
  111. end
  112. figure
  113. subplot(2,1,1)
  114. hold all
  115. title(sprintf('Thrust vs drag for heading of %g deg and wind speed of %g m/s',heading(plot_heading),wind_speed(plot_wind_speed)))
  116. yyaxis left
  117. plot(boat_speed{plot_wind_speed,plot_heading},wind_apparent_speed{plot_wind_speed,plot_heading})
  118. ylabel('Apparent wind speed (m/s)')
  119. yyaxis right
  120. plot(boat_speed{plot_wind_speed,plot_heading},wind_apparent_dir_bf{plot_wind_speed,plot_heading})
  121. ylabel('Apparent wind direction (deg)')
  122. subplot(2,1,2)
  123. hold all
  124. plot(boat_speed{plot_wind_speed,plot_heading},sail_force{plot_wind_speed,plot_heading})
  125. plot(boat_speed{plot_wind_speed,plot_heading},hull_drag_trim{plot_wind_speed,plot_heading})
  126. legend('Sail Forwards force','Hull drag','Location','northwest')
  127. ylabel('Force (N)')
  128. xlabel('Boat speed (m/s)')