From 817e000459b523d6cb79530a398e9ab490a51914 Mon Sep 17 00:00:00 2001 From: jmvegh Date: Thu, 26 Jan 2017 11:35:53 -0800 Subject: [PATCH 1/7] began restructuring --- Lithium_Air_Sizing/Mission.py.py | 184 +++ Lithium_Air_Sizing/Sizing.py.py | 711 ++++++++++ Lithium_Air_Sizing/Vehicle.py.py | 390 ++++++ .../Optimize_Surrogate.py | 28 +- tut_lithium_air_jet_sizing.py | 1228 ----------------- 5 files changed, 1304 insertions(+), 1237 deletions(-) create mode 100644 Lithium_Air_Sizing/Mission.py.py create mode 100644 Lithium_Air_Sizing/Sizing.py.py create mode 100644 Lithium_Air_Sizing/Vehicle.py.py delete mode 100644 tut_lithium_air_jet_sizing.py diff --git a/Lithium_Air_Sizing/Mission.py.py b/Lithium_Air_Sizing/Mission.py.py new file mode 100644 index 0000000..4d8f5b8 --- /dev/null +++ b/Lithium_Air_Sizing/Mission.py.py @@ -0,0 +1,184 @@ +# Missions.py +# +# Created: May 2015, T. Lukaczyk +# Modified: + + +# ---------------------------------------------------------------------- +# Imports +# ---------------------------------------------------------------------- + +import SUAVE +from SUAVE.Core import Units + +import numpy as np + +# ---------------------------------------------------------------------- +# Define the Mission +# ---------------------------------------------------------------------- + +def setup(analyses): + + # the mission container + missions = SUAVE.Analyses.Mission.Mission.Container() + + # ------------------------------------------------------------------ + # Base Mission + # ------------------------------------------------------------------ + base_mission = base(analyses) + missions.base = base_mission + + + return missions + + +def base(analyses): + + # ------------------------------------------------------------------ + # Initialize the Mission + # ------------------------------------------------------------------ + sol_tol = 1E-12 + mission = SUAVE.Analyses.Mission.Sequential_Segments() + mission.tag = 'embraer_e190ar test mission' + + # atmospheric model + atmosphere = SUAVE.Attributes.Atmospheres.Earth.US_Standard_1976() + planet = SUAVE.Attributes.Planets.Earth() + + #airport + airport = SUAVE.Attributes.Airports.Airport() + airport.altitude = 0.0 * Units.ft + airport.delta_isa = 0.0 + airport.atmosphere = SUAVE.Analyses.Atmospheric.US_Standard_1976() + mission.airport = airport + + # unpack Segments module + Segments = SUAVE.Analyses.Mission.Segments + + + # ------------------------------------------------------------------ + # First Climb Segment: constant Mach, constant segment angle + # ------------------------------------------------------------------ + + segment = Segments.Climb.Constant_Speed_Constant_Rate() + segment.tag = "climb_1" + + segment.analyses.extend( analyses.takeoff ) + + segment.altitude_start = 0.0 * Units.km + segment.altitude_end = 1.0 * Units.km + segment.air_speed = 80. * Units['m/s'] + segment.climb_rate = 6.0 * Units['m/s'] + segment.state.numerics.tolerance_solution = sol_tol + # add to misison + mission.append_segment(segment) + + + # ------------------------------------------------------------------ + # Second Climb Segment: constant Speed, constant segment angle + # ------------------------------------------------------------------ + + segment = Segments.Climb.Constant_Speed_Constant_Rate() + segment.tag = "climb_2" + + segment.analyses.extend( analyses.cruise ) + + segment.altitude_end = 2.0 * Units.km + segment.air_speed = 80.* Units['m/s'] + segment.climb_rate = 6.0 * Units['m/s'] + segment.state.numerics.tolerance_solution = sol_tol + # add to mission + mission.append_segment(segment) + + + # ------------------------------------------------------------------ + # Third Climb Segment: constant Mach, constant segment angle + # ------------------------------------------------------------------ + + segment = Segments.Climb.Constant_Speed_Constant_Rate() + segment.tag = "climb_3" + + segment.analyses.extend( analyses.cruise ) + + segment.altitude_end = 3. * Units.km + segment.air_speed =140* Units['m/s'] + segment.climb_rate = 3.0 * Units['m/s'] + segment.state.numerics.tolerance_solution = sol_tol + # add to mission + mission.append_segment(segment) + + + # ------------------------------------------------------------------ + # Cruise Segment: constant speed, constant altitude + # ------------------------------------------------------------------ + + segment = Segments.Cruise.Constant_Speed_Constant_Altitude() + segment.tag = "cruise" + + segment.analyses.extend( analyses.cruise ) + + segment.air_speed = 147.1479 * Units['m/s'] + segment.distance = 300 * Units.nautical_miles + segment.state.numerics.tolerance_solution = sol_tol + mission.append_segment(segment) + + + # ------------------------------------------------------------------ + # First Descent Segment: consant speed, constant segment rate + # ------------------------------------------------------------------ + + segment = Segments.Descent.Constant_Speed_Constant_Rate() + segment.tag = "descent_1" + + segment.analyses.extend( analyses.cruise ) + + segment.altitude_end = 2. * Units.km + segment.air_speed = 120.0 * Units['m/s'] + segment.descent_rate = 5.0 * Units['m/s'] + segment.state.numerics.tolerance_solution = sol_tol + + # add to mission + mission.append_segment(segment) + + + # ------------------------------------------------------------------ + # Second Descent Segment: consant speed, constant segment rate + # ------------------------------------------------------------------ + + segment = Segments.Descent.Constant_Speed_Constant_Rate() + segment.tag = "descent_2" + + segment.analyses.extend( analyses.cruise ) + + segment.altitude_end = 0.0 * Units.km + segment.air_speed = 100.0 * Units['m/s'] + segment.descent_rate = 5.0 * Units['m/s'] + segment.state.numerics.tolerance_solution = sol_tol + + # append to mission + mission.append_segment(segment) + + # ------------------------------------------------------------------ + # Mission definition complete + # ------------------------------------------------------------------ + + + return mission + +# ---------------------------------------------------------------------- +# Call Main +# ---------------------------------------------------------------------- + +if __name__ == '__main__': + import vehicles + import analyses + + vehicles = vehicles.setup() + analyses = analyses.setup(vehicles) + missions = setup(analyses) + + vehicles.finalize() + analyses.finalize() + missions.finalize() + + missions.base.evaluate() \ No newline at end of file diff --git a/Lithium_Air_Sizing/Sizing.py.py b/Lithium_Air_Sizing/Sizing.py.py new file mode 100644 index 0000000..66d7362 --- /dev/null +++ b/Lithium_Air_Sizing/Sizing.py.py @@ -0,0 +1,711 @@ +# tut_lithium_air_jet.py +# +# Created: Jun 2015, SUAVE Team +# Modified: + +""" setup file for a mission with an all electric airliner +""" + + +# ---------------------------------------------------------------------- +# Imports +# ---------------------------------------------------------------------- + +import SUAVE +from SUAVE.Core import Units, Data + +import numpy as np +import copy, time + +import matplotlib +import pylab as plt + +from SUAVE.Analyses.Process import Process +from SUAVE.Methods.Performance import estimate_take_off_field_length +from SUAVE.Methods.Performance import estimate_landing_field_length +from SUAVE.Methods.Geometry.Two_Dimensional.Planform import wing_planform +from SUAVE.Methods.Propulsion.ducted_fan_sizing import ducted_fan_sizing +from SUAVE.Methods.Geometry.Two_Dimensional.Cross_Section.Propulsion.compute_ducted_fan_geometry import compute_ducted_fan_geometry +matplotlib.interactive(True) + +# ---------------------------------------------------------------------- +# Main +# ---------------------------------------------------------------------- + +def main(): + + problem = setup() + output = problem.objective() + plot_mission(output) + + + + +# ---------------------------------------------------------------------- +# Setup +# ---------------------------------------------------------------------- + +def setup(): + + # ------------------------------------------------------------------ + # Analysis Procedure + # ------------------------------------------------------------------ + + # size the base config + procedure = Process() + procedure.run_sizing_loop = run_sizing_loop #size aircraft and run mission + procedure.evaluate_field_length = evaluate_field_length + procedure.evaluate_constraints = evaluate_constraints + + return procedure + + + + +def run_sizing_loop(nexus): + vehicle = nexus.vehicle_configurations.base + configs = nexus.vehicle_configurations + analyses = nexus.analyses + mission = nexus.missions.base + + battery = configs.base.energy_network['battery'] + ducted_fan = configs.base.propulsors['ducted_fan'] + + #make it so all configs handle the exact same battery object + configs.cruise.energy_network['battery'] = battery + configs.takeoff.energy_network['battery'] = battery + configs.landing.energy_network['battery'] = battery + + + + + #initial guesses + m_guess = 60000. + Ereq_guess = 100000000000. + Preq_guess= 200000. + + + + mass = [ m_guess ] + + scaling = np.array([1E4,1E9,1E6]) + y = np.array([m_guess, Ereq_guess, Preq_guess])/scaling + min_y = [.05, 1E-5,10.] + max_y = [10., 10., 10.] + + + #create sizing loop object + sizing_loop = nexus.sizing_loop + #assign to sizing loop + + sizing_loop.tolerance = nexus.tol #percentage difference in mass and energy between iterations + sizing_loop.initial_step = 'Default' #Default, Table, SVR + sizing_loop.update_method = 'fixed_point' #'fixed_point','newton-raphson', 'broyden' + sizing_loop.default_y = y + sizing_loop.min_y = min_y + sizing_loop.max_y = max_y + sizing_loop.default_scaling = scaling + sizing_loop.maximum_iterations = 50 + sizing_loop.write_threshhold = 50. + sizing_loop.output_filename = 'y_values_%(range)d_nautical_mile_range.txt' %{'range':nexus.target_range/Units.nautical_miles} + sizing_loop.sizing_evaluation = sizing_evaluation + sizing_loop.iteration_options.h = 1E-6 + sizing_loop.iteration_options.min_fix_point_iterations = 2 + sizing_loop.iteration_options.initialize_jacobian = 'newton-raphson' #appr + sizing_loop.iteration_options.max_newton_raphson_tolerance = nexus.tol*2 #threshhold at which to switch to fixed point (to prevent overshooting) + sizing_loop.iteration_options.min_surrogate_length = 3 #best for svr =3 + sizing_loop.iteration_options.min_surrogate_step = .03 #best for svr =.011 (.02) + sizing_loop.iteration_options.min_write_step = .011#best for svr =.011 + sizing_loop.iteration_options.n_neighbors = 5 + sizing_loop.iteration_options.neighbors_weighted_distance = True + + nexus.max_iter = sizing_loop.maximum_iterations #used to pass it to constraints + nexus.update_method = sizing_loop.update_method + nexus.initial_step = sizing_loop.initial_step + #nexus.sizing_loop = sizing_loop + nexus = sizing_loop(nexus) + return nexus + + +# ---------------------------------------------------------------------- +# Sizing +# ---------------------------------------------------------------------- + +def simple_sizing(nexus): + from SUAVE.Methods.Geometry.Two_Dimensional.Planform import wing_planform + configs=nexus.vehicle_configurations + analyses=nexus.analyses + m_guess=nexus.m_guess + Ereq=nexus.Ereq + Preq=nexus.Preq + +# ------------------------------------------------------------------ + # Define New Gross Takeoff Weight + # ------------------------------------------------------------------ + #now add component weights to the gross takeoff weight of the vehicle + + base = configs.base + #base.pull_base() + base.mass_properties.max_takeoff=m_guess + base.mass_properties.max_zero_fuel=m_guess #just used for weight calculation + Sref=m_guess/base.wing_loading + design_thrust=base.thrust_loading*m_guess*9.81 #four engines + + mission=nexus.missions.base.segments + + airport=nexus.missions.base.airport + atmo = airport.atmosphere + + + base.reference_area = Sref + base.wings['main_wing'].areas.reference = base.reference_area + + #determine geometry of fuselage as well as wings + fuselage=base.fuselages['fuselage'] + SUAVE.Methods.Geometry.Two_Dimensional.Planform.fuselage_planform(fuselage) + fuselage.areas.side_projected = fuselage.heights.maximum*fuselage.lengths.cabin*1.1 # Not correct + base.wings['main_wing'] = wing_planform(base.wings['main_wing']) + base.wings['horizontal_stabilizer'] = wing_planform(base.wings['horizontal_stabilizer']) + + base.wings['vertical_stabilizer'] = wing_planform(base.wings['vertical_stabilizer']) + #calculate position of horizontal stabilizer + base.wings['horizontal_stabilizer'].aerodynamic_center[0]= base.w2h- \ + (base.wings['horizontal_stabilizer'].origin[0] + \ + base.wings['horizontal_stabilizer'].aerodynamic_center[0] - \ + base.wings['main_wing'].origin[0] - base.wings['main_wing'].aerodynamic_center[0]) + #wing areas + for wing in base.wings: + wing.areas.wetted = 2.00 * wing.areas.reference + wing.areas.affected = 0.60 * wing.areas.reference + wing.areas.exposed = 0.75 * wing.areas.wetted + + #compute conditions for aircraft sizing + cruise_altitude= mission['climb_3'].altitude_end + + conditions = atmo.compute_values(cruise_altitude) + conditions.velocity = mission['cruise'].air_speed + + mach_number = conditions.velocity/conditions.speed_of_sound + + conditions.mach_number = mach_number + conditions.gravity = 9.81 + + prop_conditions=SUAVE.Analyses.Mission.Segments.Conditions.Aerodynamics() #assign conditions in form for propulsor sizing + prop_conditions.freestream=conditions + + + conditions0 = atmo.compute_values(12500.*Units.ft) #cabin pressure + p0 = conditions0.pressure + fuselage_diff_pressure=max(conditions0.pressure-conditions.pressure,0) + fuselage.differential_pressure = fuselage_diff_pressure + + battery =base.energy_network['battery'] + ducted_fan=base.propulsors['ducted_fan'] + SUAVE.Methods.Power.Battery.Sizing.initialize_from_energy_and_power(battery,Ereq,Preq, max='soft') + battery.current_energy=[battery.max_energy] #initialize list of current energy + + + m_air =SUAVE.Methods.Power.Battery.Variable_Mass.find_total_mass_gain(battery) + + #now add the electric motor weight + motor_mass=ducted_fan.number_of_engines*SUAVE.Methods.Weights.Correlations.Propulsion.air_cooled_motor((Preq)*Units.watts/ducted_fan.number_of_engines,.1783, .9884 ) + propulsion_mass=SUAVE.Methods.Weights.Correlations.Propulsion.integrated_propulsion(motor_mass/ducted_fan.number_of_engines,ducted_fan.number_of_engines) + + ducted_fan.mass_properties.mass = propulsion_mass + ducted_fan.thrust.total_design = design_thrust + + ducted_fan_sizing(ducted_fan, mach_number,cruise_altitude) + compute_ducted_fan_geometry(ducted_fan, conditions = prop_conditions) + + # --------------------------- + breakdown = analyses.base.weights.evaluate() + #breakdown = analyses.configs.base.weights.evaluate() + breakdown.battery=battery.mass_properties.mass + breakdown.air=m_air + base.mass_properties.breakdown=breakdown + m_fuel=0. + #print breakdown + base.mass_properties.operating_empty = breakdown.empty + m_full=breakdown.empty+battery.mass_properties.mass+breakdown.payload + m_end=m_full+m_air + base.mass_properties.takeoff = m_full + base.store_diff() + + # Update all configs with new base data + for config in configs: + config.pull_base() + + + ############################################################################## + # ------------------------------------------------------------------ + # Define Configurations + # ------------------------------------------------------------------ + landing_config=configs.landing + landing_config.wings['main_wing'].flaps.angle = 20. * Units.deg + landing_config.wings['main_wing'].slats.angle = 25. * Units.deg + landing_config.mass_properties.landing = m_end + landing_config.store_diff() + + return nexus + +def sizing_evaluation(y,nexus, scaling): + #unpack inputs + m_guess = y[0]*scaling[0] + Ereq_guess = y[1]*scaling[1] + Preq_guess = y[2]*scaling[2] + + + print 'm_guess =', m_guess + print 'Ereq_guess =', Ereq_guess + print 'Preq_guess =', Preq_guess + + + nexus.m_guess = m_guess + nexus.Ereq = Ereq_guess + nexus.Preq = Preq_guess + + configs = nexus.vehicle_configurations + analyses = nexus.analyses + mission = nexus.missions.base + battery = configs.base.energy_network['battery'] + + simple_sizing(nexus) + analyses.finalize() #wont run without this + + results = evaluate_mission(configs,mission) + + + + #handle outputs + + mass_out = results.segments[-1].conditions.weights.total_mass[-1,0] + Ereq_out = results.e_total + Preq_out = results.Pmax + + + dm = (mass_out-m_guess)/m_guess + dE_total = (Ereq_out-Ereq_guess)/Ereq_guess + dPower = (Preq_out-Preq_guess)/Preq_guess + + #err=(np.abs(dm)+np.abs(dE_primary)+np.abs(dE_auxiliary))/3. + #err=(np.abs(dE_primary)+np.abs(dE_auxiliary))/2. + #err = np.abs(dE_auxiliary) + #handle weird problem where one of the battery energies is ~0; use total energy + + + + nexus.dm = dm + nexus.dE_total = dE_total + nexus.Preq = Preq_out + + + + nexus.results = results #pack up results + + f = np.array([dm, dE_total, dPower]) + y_out = np.array([mass_out, Ereq_out, Preq_out ])/scaling + print 'y=', y + print 'y_out=', y_out + print 'scaling=', scaling + print 'f=', f + print 'number_of_surrogate_calls ', nexus.sizing_loop.iteration_options.number_of_surrogate_calls + return f, y_out + +# ---------------------------------------------------------------------- +# Finalizing Function (make part of optimization nexus)[needs to come after simple sizing doh] +# ---------------------------------------------------------------------- + +def finalize(nexus): + + #nexus.vehicle_configurations.finalize() + nexus.analyses.finalize() + + return nexus + + + +def evaluate_mission(configs,mission): + + # ------------------------------------------------------------------ + # Run Mission + # ------------------------------------------------------------------ + + results = mission.evaluate() + + #determine energy characteristiscs + e_current_min=1E14 + Pmax=0. + max_alpha=np.zeros(len(results.segments)) + min_alpha=np.zeros(len(results.segments)) + + for i in range(len(results.segments)): + + if np.min(results.segments[i].conditions.propulsion.battery_energy)Pmax: + Pmax=np.max(np.abs(results.segments[i].conditions.propulsion.battery_draw)) + aoa=results.segments[i].conditions.aerodynamics.angle_of_attack[:,0] / Units.deg + max_alpha[i]=max(aoa) + min_alpha[i]=min(aoa) + + max_alpha = max(max_alpha) + min_alpha = min(min_alpha) + total_range=results.segments[-1].conditions.frames.inertial.position_vector[-1,0] + results.total_range=total_range + results.e_total=results.segments[0].conditions.propulsion.battery_energy[0,0]-e_current_min + results.Pmax=Pmax + results.max_alpha=max_alpha + results.min_alpha=min_alpha + print 'e_current_min=',e_current_min + print "e_total=", results.e_total + print "Pmax=", Pmax + + + return results + + + + + +def evaluate_constraints(nexus): + #optimizer may not be able to handle constraints from inputs + vehicle=nexus.vehicle_configurations.base + analyses=nexus.analyses + mission=nexus.missions.base.segments + + results=nexus.results + motor_power=nexus.Preq + print 'motor_power=', motor_power + print 'results.Pmax=', results.Pmax + #make sure motor can handle power requirements + results.range_margin=results.total_range-nexus.target_range + results.power_margin=motor_power-results.Pmax + #results.segments[-1].conditions.weights.total_mass[-1,0]+=abs(min(0, motor_power-results.Pmax)) + #make sure there is some washout + alpha_rc=vehicle['wings'].main_wing.twists.root + alpha_tc=vehicle['wings'].main_wing.twists.tip + results.washout=alpha_rc-alpha_tc + + results.max_alpha_constraint =15.-results.max_alpha + results.min_alpha_constraint=15+results.min_alpha + + + + #now make sure there is consistency in the mission profile + climb_alt_1 =mission['climb_1'].altitude_end + climb_alt_2 =mission['climb_2'].altitude_end + climb_alt_3 =mission['climb_3'].altitude_end + + descent_alt_1=mission['descent_1'].altitude_end + descent_alt_2=mission['descent_2'].altitude_end + results.climb_constraint_1=climb_alt_2-climb_alt_1 + results.climb_constraint_2=climb_alt_3-climb_alt_2 + + + + results.descent_constraint_1=climb_alt_3-descent_alt_1 + results.descent_constraint_2=descent_alt_1-descent_alt_2 + + climb_velocity_1=mission['climb_1'].air_speed + climb_velocity_2=mission['climb_2'].air_speed + climb_velocity_3=mission['climb_3'].air_speed + + results.climb_velocity_constraint_1=climb_velocity_2-climb_velocity_1 + results.climb_velocity_constraint_2=climb_velocity_3-climb_velocity_2 + + + results.takeoff_field_constraint= 2500.- results.field_length.takeoff + results.landing_field_constraint= 2500.- results.field_length.landing + + max_throttle = 0. + for segment in results.segments.values(): + max_segment_throttle=np.max(segment.conditions.propulsion.throttle[:,0]) + if max_segment_throttle>max_throttle: + max_throttle=max_segment_throttle + + results.max_throttle_constraint=1-max_throttle + + nexus.iteration_constraint=((nexus.max_iter-5)-nexus.number_of_iterations)/(1.*nexus.max_iter) #give it some slack to help constraints converge + + return nexus + + + +def evaluate_field_length(nexus): + configs = nexus.vehicle_configurations + analyses = nexus.analyses + mission = nexus.missions.base + results = nexus.results + + # unpack + airport = mission.airport + + takeoff_config = configs.takeoff + landing_config = configs.landing + + # evaluate + TOFL = estimate_take_off_field_length(takeoff_config,analyses,airport) + LFL = estimate_landing_field_length (landing_config, analyses,airport) + + # pack + field_length = SUAVE.Core.Data() + field_length.takeoff = TOFL[0] + field_length.landing = LFL[0] + + results.field_length = field_length + nexus.results = results + + return nexus + + + + +# ---------------------------------------------------------------------- +# Plot Mission +# ---------------------------------------------------------------------- + +def plot_mission(results,configs,line_style='bo-'): + + if line_style == 'k-': + line_width = 2. + else: + line_width = 1. + + + # ------------------------------------------------------------------ + # Throttle + # ------------------------------------------------------------------ + plt.figure("Throttle History") + axes = plt.gca() + for i in range(len(results.segments)): + time = results.segments[i].conditions.frames.inertial.time[:,0] / Units.min + eta = results.segments[i].conditions.propulsion.throttle[:,0] + axes.plot(time, eta, line_style) + axes.set_xlabel('Time (mins)') + axes.set_ylabel('Throttle') + axes.grid(True) + + + # ------------------------------------------------------------------ + # Angle of Attack + # ------------------------------------------------------------------ + + plt.figure("Angle of Attack History") + axes = plt.gca() + for i in range(len(results.segments)): + time = results.segments[i].conditions.frames.inertial.time[:,0] / Units.min + aoa = results.segments[i].conditions.aerodynamics.angle_of_attack[:,0] / Units.deg + axes.plot(time, aoa, line_style) + axes.set_xlabel('Time (mins)') + axes.set_ylabel('Angle of Attack (deg)') + axes.grid(True) + + + # ------------------------------------------------------------------ + # Mass Rate + # ------------------------------------------------------------------ + plt.figure("Mass Rate") + axes = plt.gca() + for i in range(len(results.segments)): + time = results.segments[i].conditions.frames.inertial.time[:,0] / Units.min + mdot = -results.segments[i].conditions.weights.vehicle_mass_rate[:,0] + axes.plot(time, mdot, line_style) + axes.set_xlabel('Time (mins)') + axes.set_ylabel('Mass Rate (kg/s)') + axes.grid(True) + + + # ------------------------------------------------------------------ + # Altitude + # ------------------------------------------------------------------ + plt.figure("Altitude") + axes = plt.gca() + for i in range(len(results.segments)): + time = results.segments[i].conditions.frames.inertial.time[:,0] / Units.min + altitude = results.segments[i].conditions.freestream.altitude[:,0] / Units.km + axes.plot(time, altitude, line_style) + axes.set_xlabel('Time (mins)') + axes.set_ylabel('Altitude (km)') + axes.grid(True) + + + # ------------------------------------------------------------------ + # Vehicle Mass + # ------------------------------------------------------------------ + plt.figure("Vehicle Mass") + axes = plt.gca() + for i in range(len(results.segments)): + time = results.segments[i].conditions.frames.inertial.time[:,0] / Units.min + mass = results.segments[i].conditions.weights.total_mass[:,0] + axes.plot(time, mass, line_style) + axes.set_xlabel('Time (mins)') + axes.set_ylabel('Vehicle Mass (kg)') + axes.grid(True) + + + # ------------------------------------------------------------------ + # Aerodynamics + # ------------------------------------------------------------------ + fig = plt.figure("Aerodynamic Forces") + for segment in results.segments.values(): + + time = segment.conditions.frames.inertial.time[:,0] / Units.min + Lift = -segment.conditions.frames.wind.lift_force_vector[:,2] + Drag = -segment.conditions.frames.wind.drag_force_vector[:,0] + Thrust = segment.conditions.frames.body.thrust_force_vector[:,0] + + axes = fig.add_subplot(3,1,1) + axes.plot( time , Lift , line_style ) + axes.set_xlabel('Time (min)') + axes.set_ylabel('Lift (N)') + axes.grid(True) + + axes = fig.add_subplot(3,1,2) + axes.plot( time , Drag , line_style ) + axes.set_xlabel('Time (min)') + axes.set_ylabel('Drag (N)') + axes.grid(True) + + axes = fig.add_subplot(3,1,3) + axes.plot( time , Thrust , line_style ) + axes.set_xlabel('Time (min)') + axes.set_ylabel('Thrust (N)') + axes.grid(True) + + + # ------------------------------------------------------------------ + # Aerodynamics 2 + # ------------------------------------------------------------------ + fig = plt.figure("Aerodynamic Coefficients") + for segment in results.segments.values(): + + time = segment.conditions.frames.inertial.time[:,0] / Units.min + CLift = segment.conditions.aerodynamics.lift_coefficient[:,0] + CDrag = segment.conditions.aerodynamics.drag_coefficient[:,0] + Drag = -segment.conditions.frames.wind.drag_force_vector[:,0] + Thrust = segment.conditions.frames.body.thrust_force_vector[:,0] + + axes = fig.add_subplot(3,1,1) + axes.plot( time , CLift , line_style ) + axes.set_xlabel('Time (min)') + axes.set_ylabel('CL') + axes.grid(True) + + axes = fig.add_subplot(3,1,2) + axes.plot( time , CDrag , line_style ) + axes.set_xlabel('Time (min)') + axes.set_ylabel('CD') + axes.grid(True) + + axes = fig.add_subplot(3,1,3) + axes.plot( time , Drag , line_style ) + axes.plot( time , Thrust , 'ro-' ) + axes.set_xlabel('Time (min)') + axes.set_ylabel('Drag and Thrust (N)') + axes.grid(True) + + + # ------------------------------------------------------------------ + # Aerodynamics 3 + # ------------------------------------------------------------------ + fig = plt.figure("Drag Components") + axes = plt.gca() + for i, segment in enumerate(results.segments.values()): + + time = segment.conditions.frames.inertial.time[:,0] / Units.min + drag_breakdown = segment.conditions.aerodynamics.drag_breakdown + cdp = drag_breakdown.parasite.total[:,0] + cdi = drag_breakdown.induced.total[:,0] + cdc = drag_breakdown.compressible.total[:,0] + cdm = drag_breakdown.miscellaneous.total[:,0] + cd = drag_breakdown.total[:,0] + + if line_style == 'bo-': + axes.plot( time , cdp , 'ko-', label='CD_P' ) + axes.plot( time , cdi , 'bo-', label='CD_I' ) + axes.plot( time , cdc , 'go-', label='CD_C' ) + axes.plot( time , cdm , 'yo-', label='CD_M' ) + axes.plot( time , cd , 'ro-', label='CD' ) + if i == 0: + axes.legend(loc='upper center') + else: + axes.plot( time , cdp , line_style ) + axes.plot( time , cdi , line_style ) + axes.plot( time , cdc , line_style ) + axes.plot( time , cdm , line_style ) + axes.plot( time , cd , line_style ) + + axes.set_xlabel('Time (min)') + axes.set_ylabel('CD') + axes.grid(True) + + + # ------------------------------------------------------------------ + # Flight Conditions + # ------------------------------------------------------------------ + fig = plt.figure("Flight Conditions",figsize=(6.5,10)) + for segment in results.segments.values(): + + time = segment.conditions.frames.inertial.time[:,0] / Units.min + altitude = segment.conditions.freestream.altitude[:,0] / Units.km + mach = segment.conditions.freestream.mach_number[:,0] + distance = segment.conditions.frames.inertial.position_vector[:,0] / Units.km + + axes = fig.add_subplot(3,1,1) + axes.plot( time, distance, line_style ) + axes.set_ylabel('Distance (km)') + axes.grid(True) + + axes = fig.add_subplot(3,1,2) + axes.plot( time , altitude , line_style , lw=line_width ) + axes.set_ylabel('Altitude (km)') + axes.grid(True) + + axes = fig.add_subplot(3,1,3) + axes.plot( time , mach, line_style , lw=line_width ) + axes.set_xlabel('Time (min)') + axes.set_ylabel('Mach Number (-)') + axes.grid(True) + + # ------------------------------------------------------------------ + # Mass, State of Charge, Power + # ------------------------------------------------------------------ + + fig = plt.figure("Electric Aircraft Outputs",figsize=(6.5,10)) + for segment in results.segments.values(): + + time = segment.conditions.frames.inertial.time[:,0] / Units.min + mass = segment.conditions.weights.total_mass[:,0] + + axes = fig.add_subplot(3,1,1) + axes.plot( time , mass , line_style , lw=line_width ) + axes.set_ylabel('Vehicle Mass (kg)') + axes.grid(True) + + try: + battery=configs.base.energy_network['battery'] + state_of_charge=segment.conditions.propulsion.battery_energy/battery.max_energy + battery_power=-segment.conditions.propulsion.battery_draw/Units.MW + except: + continue + + axes = fig.add_subplot(3,1,2) + axes.plot( time , state_of_charge , line_style , lw=line_width ) + axes.set_ylabel('State of Charge (-)') + axes.set_ylim([-0.005,1.005]) + axes.grid(True) + + axes = fig.add_subplot(3,1,3) + axes.plot( time , battery_power , line_style , lw=line_width ) + axes.set_xlabel('Time (min)') + axes.set_ylabel('Discharge Power (MW)') + axes.grid(True) + + + raw_input('Press Enter To Quit') + return + + +if __name__ == '__main__': + main() + plt.show() \ No newline at end of file diff --git a/Lithium_Air_Sizing/Vehicle.py.py b/Lithium_Air_Sizing/Vehicle.py.py new file mode 100644 index 0000000..b9d06d0 --- /dev/null +++ b/Lithium_Air_Sizing/Vehicle.py.py @@ -0,0 +1,390 @@ +# Vehicles.py +# +# Created: May 2015, E. Botero +# Modified: + +# ---------------------------------------------------------------------- +# Imports +# ---------------------------------------------------------------------- + +import SUAVE +from SUAVE.Core import Units, Data +from SUAVE.Methods.Propulsion.ducted_fan_sizing import ducted_fan_sizing + +# ---------------------------------------------------------------------- +# Define the Vehicle +# ---------------------------------------------------------------------- + +def setup(): + + base_vehicle = base_setup() + configs = configs_setup(base_vehicle) + + return configs + + +def base_setup(): + + vehicle = SUAVE.Vehicle() + vehicle.tag = 'Embraer_E190' + + # ------------------------------------------------------------------ + # Vehicle-level Properties + # ------------------------------------------------------------------ + ''' + # mass properties + vehicle.mass_properties.max_takeoff = 92110. #use landing mass as + vehicle.mass_properties.operating_empty = 34551. + vehicle.mass_properties.takeoff = 80721. + vehicle.mass_properties.max_zero_fuel = 92110. #equivalent landing mass + vehicle.mass_properties.cargo = 0.0 + vehicle.mass_properties.max_payload = 0.0 + vehicle.mass_properties.max_fuel = 0.0 + ''' + + # envelope properties + vehicle.envelope.ultimate_load = 3.5 + vehicle.envelope.limit_load = 1.5 + + # basic parameters + vehicle.reference_area = 100.0 + vehicle.thrust_loading =.25 + vehicle.wing_loading = 400.*Units.kg/Units.m**2 + vehicle.passengers = 114 + vehicle.systems.control = "partially powered" + vehicle.systems.accessories = "medium range" + vehicle.w2h = 16. * Units.meters # Length from the mean aerodynamic center of wing to mean aerodynamic center of the horizontal tail + vehicle.w2v = 20. * Units.meters # Length from the mean aerodynamic center of wing to mean aerodynamic center of the vertical tail + vehicle.motor_power = 80 * Units.MW + # ------------------------------------------------------------------ + # Main Wing + # ------------------------------------------------------------------ + + wing = SUAVE.Components.Wings.Wing() + wing.tag = 'main_wing' + + wing.aspect_ratio = 8.3 + wing.sweeps.quarter_chord = 0.002 * Units.deg + wing.thickness_to_chord = 0.105 + wing.taper = 0.28 + wing.span_efficiency = 1.0 + + wing.spans.projected = 28.81 + + wing.chords.root = 5.4 + wing.chords.tip = 1.5185 + wing.chords.mean_aerodynamic = 3.8371 + + wing.areas.reference = 100.0 + wing.areas.wetted = 2.0 * wing.areas.reference + wing.areas.exposed = 150.0 + wing.areas.affected = .6*wing.areas.reference + + wing.twists.root = -0.311 * Units.degrees + wing.twists.tip = -0.315 * Units.degrees + + wing.origin = [00,0,0] + wing.aerodynamic_center = [0.914,0,0] + + wing.vertical = False + wing.symmetric = True + wing.high_lift = True + + wing.dynamic_pressure_ratio = 1.0 + + # add to vehicle + vehicle.append_component(wing) + + # ------------------------------------------------------------------ + # Horizontal Stabilizer + # ------------------------------------------------------------------ + + wing = SUAVE.Components.Wings.Wing() + wing.tag = 'horizontal_stabilizer' + + wing.aspect_ratio = 5.5 + wing.sweeps.quarter_chord = 0.002 * Units.deg + wing.thickness_to_chord = 0.11 + wing.taper = 0.11 + wing.span_efficiency = 0.9 + + wing.spans.projected = 11.213 + + wing.chords.root = 3.6733 + wing.chords.tip = 0.4040 + wing.chords.mean_aerodynamic = 2.4755 + + wing.areas.reference = 22.85 + wing.areas.wetted = 45.71 + wing.areas.exposed = 34.28 + wing.areas.affected = 13.71 + + wing.twists.root = 0.0 * Units.degrees + wing.twists.tip = 0.0 * Units.degrees + + wing.origin = [50,0,0] + wing.aerodynamic_center = [16.9144, 0.0, 0.0] + + wing.vertical = False + wing.symmetric = True + + wing.dynamic_pressure_ratio = 0.9 + + # add to vehicle + vehicle.append_component(wing) + + # ------------------------------------------------------------------ + # Vertical Stabilizer + # ------------------------------------------------------------------ + + wing = SUAVE.Components.Wings.Wing() + wing.tag = 'vertical_stabilizer' + + wing.aspect_ratio = 1.7 # + wing.sweeps.quarter_chord = 0. * Units.deg + wing.thickness_to_chord = 0.12 + wing.taper = 0.10 + wing.span_efficiency = 0.9 + + wing.spans.projected = 4.6945 # + + wing.chords.root = 5.0209 + wing.chords.tip = 0.5020 + wing.chords.mean_aerodynamic = 3.3777 + + wing.areas.reference = 12.96 + wing.areas.wetted = 25.92 + wing.areas.exposed = 19.44 + wing.areas.affected = 7.778 + + wing.twists.root = 0.0 * Units.degrees + wing.twists.tip = 0.0 * Units.degrees + + wing.origin = [0,0,0] + wing.aerodynamic_center = [0,0,0] + + wing.vertical = True + wing.symmetric = False + + wing.dynamic_pressure_ratio = 1.0 + + # add to vehicle + vehicle.append_component(wing) + + # ------------------------------------------------------------------ + # Fuselage + # ------------------------------------------------------------------ + + fuselage = SUAVE.Components.Fuselages.Fuselage() + fuselage.tag = 'fuselage' + + fuselage.number_coach_seats = vehicle.passengers + fuselage.seats_abreast = 4 + fuselage.seat_pitch = 0.7455 + + fuselage.fineness.nose = 1.5 + fuselage.fineness.tail = 1.8 + + fuselage.lengths.nose = 4.5 + fuselage.lengths.tail = 5.4 + fuselage.lengths.cabin = 21.24675 + fuselage.lengths.total = 31.14675 + fuselage.lengths.fore_space = 0. + fuselage.lengths.aft_space = 0. + + fuselage.width = 3.0 + + fuselage.heights.maximum = 3.4 # + fuselage.heights.at_quarter_length = 3.4 + fuselage.heights.at_three_quarters_length = 3.4 + fuselage.heights.at_wing_root_quarter_chord = 3.4 + + fuselage.areas.side_projected = 79.462 + fuselage.areas.wetted = 288.521422366 + fuselage.areas.front_projected = 8.011 + + fuselage.effective_diameter = 3.2 + + fuselage.differential_pressure = 10**5 * Units.pascal + + # add to vehicle + vehicle.append_component(fuselage) + + # ------------------------------------------------------------------ + # Propulsion + + + #create battery + battery = SUAVE.Components.Energy.Storages.Batteries.Variable_Mass.Lithium_Air() + battery.tag = 'battery' + + #Build Ducted_Fan Network + ducted_fan= SUAVE.Components.Energy.Networks.Ducted_Fan() + #set the working fluid for the network + working_fluid = SUAVE.Attributes.Gases.Air + + #add working fluid to the network + ducted_fan.working_fluid = working_fluid + + + #Component 1 : ram, to convert freestream static to stagnation quantities + ram = SUAVE.Components.Energy.Converters.Ram() + ram.tag = 'ram' + + #add ram to the network + ducted_fan.ram = ram + + + #Component 2 : inlet nozzle + inlet_nozzle = SUAVE.Components.Energy.Converters.Compression_Nozzle() + inlet_nozzle.tag = 'inlet nozzle' + + inlet_nozzle.polytropic_efficiency = 0.98 + inlet_nozzle.pressure_ratio = 0.98 # turbofan.fan_nozzle_pressure_ratio = 0.98 #0.98 + + #add inlet nozzle to the network + ducted_fan.inlet_nozzle = inlet_nozzle + + + #Component 8 :fan nozzle + fan_nozzle = SUAVE.Components.Energy.Converters.Expansion_Nozzle() + fan_nozzle.tag = 'fan nozzle' + + fan_nozzle.polytropic_efficiency = 0.95 + fan_nozzle.pressure_ratio = 0.99 + + #add the fan nozzle to the network + ducted_fan.fan_nozzle = fan_nozzle + + + + #Component 9 : fan + fan = SUAVE.Components.Energy.Converters.Fan() + fan.tag = 'fan' + + fan.polytropic_efficiency = 0.93 + fan.pressure_ratio = 1.5 + + #add the fan to the network + ducted_fan.fan = fan + + #Component 10 : thrust (to compute the thrust) + thrust = SUAVE.Components.Energy.Processes.Thrust() + thrust.tag ='compute_thrust' + thrust.total_design = 121979.18 # Preq*1.5/V_cruise + ducted_fan.thrust = thrust + #ducted_fan.design_thrust = + + + + atm = SUAVE.Analyses.Atmospheric.US_Standard_1976() + p1, T1, rho1, a1, mew1 = atm.compute_values(0.) + p2, T2, rho2, a2, mew2 = atm.compute_values(6.255*Units.km) + + #create sizing segment + ''' + state = Data() + conditions = Data() + numerics = Data() + + conditions.M = 0.729 + conditions.alt = 7*Units.km + conditions.T = T2 + conditions.p = p2 + state.conditions = conditions + state.numerics = numerics + ''' + mach_number =0.729 + altitude = 7*Units.km + + ducted_fan.number_of_engines = 2.0 + ducted_fan_sizing(ducted_fan, mach_number, altitude) #calling the engine sizing method + + # ------------------------------------------------------------------ + # Energy Network + # ------------------------------------------------------------------ + + #define the energy network + net = SUAVE.Components.Energy.Networks.Battery_Ducted_Fan() + net.tag = 'network' + + net.propulsor = ducted_fan + net.append(ducted_fan) + net.battery = battery + + net.nacelle_diameter = ducted_fan.nacelle_diameter + net.engine_length = ducted_fan.engine_length + net.number_of_engines = ducted_fan.number_of_engines + net.motor_efficiency =.95 + vehicle.propulsors.append(ducted_fan) + vehicle.energy_network = net + + + # ------------------------------------------------------------------ + # Vehicle Definition Complete + # ------------------------------------------------------------------ + + return vehicle + + + +# ---------------------------------------------------------------------- +# Define the Configurations +# --------------------------------------------------------------------- + +def configs_setup(vehicle): + + # ------------------------------------------------------------------ + # Initialize Configurations + # ------------------------------------------------------------------ + + configs = SUAVE.Components.Configs.Config.Container() + + base_config = SUAVE.Components.Configs.Config(vehicle) + base_config.tag = 'base' + configs.append(base_config) + + # ------------------------------------------------------------------ + # Cruise Configuration + # ------------------------------------------------------------------ + + config = SUAVE.Components.Configs.Config(base_config) + config.tag = 'cruise' + + configs.append(config) + + + # ------------------------------------------------------------------ + # Takeoff Configuration + # ------------------------------------------------------------------ + + config = SUAVE.Components.Configs.Config(base_config) + config.tag = 'takeoff' + + config.wings['main_wing'].flaps.angle = 20. * Units.deg + config.wings['main_wing'].slats.angle = 25. * Units.deg + + config.V2_VS_ratio = 1.21 + #config.maximum_lift_coefficient = 2. + + configs.append(config) + + + # ------------------------------------------------------------------ + # Landing Configuration + # ------------------------------------------------------------------ + + config = SUAVE.Components.Configs.Config(base_config) + config.tag = 'landing' + + config.wings['main_wing'].flaps_angle = 30. * Units.deg + config.wings['main_wing'].slats_angle = 25. * Units.deg + + config.Vref_VS_ratio = 1.23 + #config.maximum_lift_coefficient = 2. + + configs.append(config) + + + # done! + return configs diff --git a/Regional_Jet_Optimization/Optimize_Surrogate.py b/Regional_Jet_Optimization/Optimize_Surrogate.py index 8b166ec..2347485 100644 --- a/Regional_Jet_Optimization/Optimize_Surrogate.py +++ b/Regional_Jet_Optimization/Optimize_Surrogate.py @@ -26,8 +26,8 @@ def main(): problem = setup() number_of_points = 10 - build_surrogate(problem, number_of_points) - output = problem.objective() #uncomment this line when using the default inputs + #build_surrogate(problem, number_of_points) + #output = problem.objective() #uncomment this line when using the default inputs ''' #uncomment these lines when you want to start an optimization problem from a different initial guess @@ -40,7 +40,7 @@ def main(): - #variable_sweep(problem) #uncomment this to view some contours of the problem + variable_sweep(problem) #uncomment this to view some contours of the problem print 'fuel burn=', problem.summary.base_mission_fuelburn print 'fuel margin=', problem.all_constraints() @@ -137,7 +137,7 @@ def setup(): return nexus def variable_sweep(problem): - number_of_points=5 + number_of_points=20 outputs=carpet_plot(problem, number_of_points, 0, 0) #run carpet plot, suppressing default plots inputs =outputs.inputs objective=outputs.objective @@ -157,14 +157,19 @@ def variable_sweep(problem): plt.xlabel('wing area (m^2)') plt.ylabel('cruise_altitude (km)') - ''' + #now plot optimization path (note that these data points were post-processed into a plottable format) wing_1 = [95 , 95.00000149 , 95 , 95 , 95.00000149 , 95 , 95 , 95.00000149 , 95 , 106.674165 , 106.6741665 , 106.674165 , 106.674165 , 106.6741665 , 106.674165 , 106.674165 , 106.6741665 , 106.674165 , 105.6274294 , 105.6274309 , 105.6274294 , 105.6274294 , 105.6274309 , 105.6274294 , 105.6274294 , 105.6274309 , 105.6274294 , 106.9084316 , 106.9084331 , 106.9084316 , 106.9084316 , 106.9084331 , 106.9084316 , 106.9084316 , 106.9084331 , 106.9084316 , 110.520489 , 110.5204905 , 110.520489 , 110.520489 , 110.5204905 , 110.520489 , 110.520489 , 110.5204905 , 110.520489 , 113.2166831 , 113.2166845 , 113.2166831 , 113.2166831 , 113.2166845 , 113.2166831 , 113.2166831 , 113.2166845 , 113.2166831 , 114.1649262 , 114.1649277 , 114.1649262 , 114.1649262 , 114.1649277 , 114.1649262 , 114.1649262 , 114.1649277 , 114.1649262 , 114.2149828] alt_1 = [11.0 , 11.0 , 11.000000149011612, 11.0 , 11.0 , 11.000000149011612, 11.0 , 11.0 , 11.000000149011612, 9.540665954351425 , 9.540665954351425 , 9.540666103363037 , 9.540665954351425 , 9.540665954351425 , 9.540666103363037 , 9.540665954351425 , 9.540665954351425 , 9.540666103363037 , 10.023015652305284, 10.023015652305284, 10.023015801316896, 10.023015652305284, 10.023015652305284, 10.023015801316896, 10.023015652305284, 10.023015652305284, 10.023015801316896, 10.190994033521863, 10.190994033521863, 10.190994182533474, 10.190994033521863, 10.190994033521863, 10.190994182533474, 10.190994033521863, 10.190994033521863, 10.190994182533474, 10.440582829327589, 10.440582829327589, 10.4405829783392 , 10.440582829327589, 10.440582829327589, 10.4405829783392 , 10.440582829327589, 10.440582829327589, 10.4405829783392 , 10.536514606250261, 10.536514606250261, 10.536514755261873, 10.536514606250261, 10.536514606250261, 10.536514755261873, 10.536514606250261, 10.536514606250261, 10.536514755261873, 10.535957839878783, 10.535957839878783, 10.535957988890395, 10.535957839878783, 10.535957839878783, 10.535957988890395, 10.535957839878783, 10.535957839878783, 10.535957988890395, 10.52829047] wing_2 = [128 , 128.0000015, 128 , 128 , 128.0000015, 128 , 128 , 128.0000015, 128 , 130 , 130.0000015, 130 , 130 , 130.0000015, 130 , 130 , 130.0000015, 130 , 122.9564124, 122.9564139, 122.9564124, 122.9564124, 122.9564139, 122.9564124, 122.9564124, 122.9564139, 122.9564124, 116.5744347, 116.5744362, 116.5744347, 116.5744347, 116.5744362, 116.5744347, 116.5744347, 116.5744362, 116.5744347, 116.3530891, 116.3530906, 116.3530891, 116.3530891, 116.3530906, 116.3530891, 116.3530891, 116.3530906, 116.3530891] alt_2 = [13.8, 13.799999999999999, 13.80000014901161, 13.799999999999999, 13.799999999999999, 13.80000014901161, 13.799999999999999, 13.799999999999999, 13.80000014901161, 11.302562430674953, 11.302562430674953, 11.302562579686565, 11.302562430674953, 11.302562430674953, 11.302562579686565, 11.302562430674953, 11.302562430674953, 11.302562579686565, 11.158808932491421, 11.158808932491421, 11.158809081503033, 11.158808932491421, 11.158808932491421, 11.158809081503033, 11.158808932491421, 11.158808932491421, 11.158809081503033, 11.412913394878741, 11.412913394878741, 11.412913543890353, 11.412913394878741, 11.412913394878741, 11.412913543890353, 11.412913394878741, 11.412913394878741, 11.412913543890353, 11.402627869388722, 11.402627869388722, 11.402628018400334, 11.402627869388722, 11.402627869388722, 11.402628018400334, 11.402627869388722, 11.402627869388722, 11.402628018400334] - + wing_svr = [130 , 125.0751993] + alt_svr = [9, 11.04626064] + + wing_kr = [116.6769711,116.2164679,115.9754664,116.2195897, 116.1905471,116.359759] + alt_kr = [11.38542103 , 11.40737539 , 11.41546813 , 11.40717703, 11.4081656,11.40240001] + opt_1 = plt.plot(wing_1, alt_1, label='optimization path 1') init_1 = plt.plot(wing_1[0], alt_1[0], 'ko') final_1 = plt.plot(wing_1[-1], alt_1[-1], 'kx') @@ -172,21 +177,26 @@ def variable_sweep(problem): opt_2 = plt.plot(wing_2, alt_2, 'k--', label='optimization path 2') init_2 = plt.plot(wing_2[0], alt_2[0], 'ko', label= 'initial points') final_2 = plt.plot(wing_2[-1], alt_2[-1], 'kx', label= 'final points') - ''' + + svr_plt = plt.plot(wing_svr, alt_svr, 'kd', markersize = 10., label='svr') + + kr_plt = plt.plot(wing_kr, alt_kr, 'rs', markersize = 5., label='kriging') + plt.legend(loc='upper left') plt.show() return + def build_surrogate(problem, number_of_points): surrogate_optimization = Surrogate_Optimization() #create surrogate optimization_problem - surrogate_optimization.sample_plan = VyPy.sampling.lhc_uniform + surrogate_optimization.sample_plan = VyPy.sampling.lhc_uniform surrogate_optimization.optimizer = pyOpt.pySNOPT.SNOPT() surrogate_optimization.problem = problem surrogate_optimization.number_of_points = number_of_points - surrogate_optimization.surrogate_model = 'GPR' + surrogate_optimization.surrogate_model = 'SVR' surrogate_optimization.optimization_filename = 'results.txt' surrogate_optimization.build_surrogate() output, surrogate_problem = surrogate_optimization.iterative_optimization() diff --git a/tut_lithium_air_jet_sizing.py b/tut_lithium_air_jet_sizing.py deleted file mode 100644 index 37272e6..0000000 --- a/tut_lithium_air_jet_sizing.py +++ /dev/null @@ -1,1228 +0,0 @@ -# tut_lithium_air_jet.py -# -# Created: Jun 2015, SUAVE Team -# Modified: - -""" setup file for a mission with an all electric airliner -""" - - -# ---------------------------------------------------------------------- -# Imports -# ---------------------------------------------------------------------- - -import SUAVE -from SUAVE.Core import Units, Data - -import numpy as np -import copy, time - -import matplotlib -import pylab as plt - - -from SUAVE.Methods.Performance import estimate_take_off_field_length -from SUAVE.Methods.Performance import estimate_landing_field_length -from SUAVE.Methods.Geometry.Two_Dimensional.Planform import wing_planform -from SUAVE.Methods.Propulsion.ducted_fan_sizing import ducted_fan_sizing -from SUAVE.Methods.Geometry.Two_Dimensional.Cross_Section.Propulsion.compute_ducted_fan_geometry import compute_ducted_fan_geometry -matplotlib.interactive(True) - -# ---------------------------------------------------------------------- -# Main -# ---------------------------------------------------------------------- - -def main(): - - # define the problem - #initial guesses - m_guess = 64204.6490117 - Ereq_guess =251.58 * 10.**9. - Pmotor =13.78 * 10.**6. - - tol=.01 #percentage difference in mass and energy between iterations - dm=10000. #initialize error - dE=10000. - - max_iter=10 - Ereq=[Ereq_guess] - Preq=[] - mass=[ m_guess ] - cruise_alt=10.255*Units.km #cruise altitude - j=0 - - - while abs(dm)>tol or abs(dE)>tol: #size the vehicle - m_guess=mass[j] - Ereq_guess=Ereq[j] - configs, analyses = full_setup(m_guess, Ereq_guess, Pmotor, cruise_alt) - simple_sizing(configs,analyses, m_guess,Ereq_guess,Pmotor) - mission = analyses.missions.base - battery=configs.base.energy_network['battery'] - battery.current_energy=battery.max_energy - configs.finalize() - analyses.finalize() - configs.cruise.energy_network['battery']=battery #make it so all configs handle the exact same battery object - configs.takeoff.energy_network['battery']=battery - configs.landing.energy_network['battery']=battery - #initialize battery in mission - mission.segments[0].battery_energy=battery.max_energy - results = evaluate_mission(configs,mission) - - mass.append(results.segments[-1].conditions.weights.total_mass[-1,0] ) - Ereq.append(results.e_total) - - #Preq.append(results.Pmax) - dm=(mass[j+1]-mass[j])/mass[j] - dE=(Ereq[j+1]-Ereq[j])/Ereq[j] - - - #display convergence of aircraft - print 'mass=', mass[j+1] - print 'dm=', dm - print 'dE=', dE - print 'Ereq_guess=', Ereq_guess - print 'Preq=', results.Pmax - j+=1 - if j>max_iter: - print "maximum number of iterations exceeded" - break - #vehicle sized:now find field length - print 'total range=', results.segments[-1].conditions.frames.inertial.position_vector[-1,0]/1000. - results = evaluate_field_length(configs,analyses, mission,results) #now evaluate field length - plot_mission(results,configs) - - return - - -# ---------------------------------------------------------------------- -# Analysis Setup -# ---------------------------------------------------------------------- - -def full_setup(m_guess, Ereq_guess, Preq_guess, cruise_altitude): - - # vehicle data - vehicle = vehicle_setup(cruise_altitude) - configs = configs_setup(vehicle) - - # vehicle analyses - configs_analyses = analyses_setup(configs, Ereq_guess, Preq_guess) - - # mission analyses - mission = mission_setup(configs_analyses) - missions_analyses = missions_setup(mission) - - #initialize battery in mission - mission.segments[0].battery_energy=configs.base.energy_network.battery.max_energy - - analyses = SUAVE.Analyses.Analysis.Container() - analyses.configs = configs_analyses - analyses.missions = missions_analyses - - return configs, analyses - - -# ---------------------------------------------------------------------- -# Define the Vehicle Analyses -# ---------------------------------------------------------------------- - -def analyses_setup(configs, Ereq, Preq): - - analyses = SUAVE.Analyses.Analysis.Container() - - # build a base analysis for each config - for tag,config in configs.items(): - analysis = base_analysis(config) - analyses[tag] = analysis - - # adjust analyses for configs - - # takeoff_analysis - analyses.takeoff.aerodynamics.drag_coefficient_increment = 0.0000 - - # landing analysis - aerodynamics = analyses.landing.aerodynamics - - - # ----------------------------------- - # Battery Setup - # ----------------------------------- - - # required mission energy, chosen via guess and check - - # initialize the battery - battery = configs.base.energy_network['battery'] - battery.specific_energy= 2000*Units.Wh/Units.kg - battery.specific_power = .67*Units.kW/Units.kg - SUAVE.Methods.Power.Battery.Sizing.initialize_from_energy_and_power(battery,Ereq,Preq) - battery.current_energy= [battery.max_energy] - configs.base.store_diff() - - # Update all configs with new base data - for config in configs: - config.pull_base() - - return analyses - -def base_analysis(vehicle): - - # ------------------------------------------------------------------ - # Initialize the Analyses - # ------------------------------------------------------------------ - analyses = SUAVE.Analyses.Vehicle() - - # ------------------------------------------------------------------ - # Basic Geometry Relations - sizing = SUAVE.Analyses.Sizing.Sizing() - sizing.features.vehicle = vehicle - analyses.append(sizing) - - # ------------------------------------------------------------------ - # Weights - weights = SUAVE.Analyses.Weights.Weights() - weights.settings.empty_weight_method= \ - SUAVE.Methods.Weights.Correlations.Tube_Wing.empty - weights.vehicle = vehicle - analyses.append(weights) - - # ------------------------------------------------------------------ - # Aerodynamics Analysis - aerodynamics = SUAVE.Analyses.Aerodynamics.Fidelity_Zero() - aerodynamics.geometry = vehicle - aerodynamics.settings.drag_coefficient_increment = 0.0000 - analyses.append(aerodynamics) - - # ------------------------------------------------------------------ - # Stability Analysis - stability = SUAVE.Analyses.Stability.Fidelity_Zero() - stability.geometry = vehicle - analyses.append(stability) - - # ------------------------------------------------------------------ - # Propulsion Analysis - energy= SUAVE.Analyses.Energy.Energy() - energy.network = vehicle.energy_network # SEE THIS - analyses.append(energy) - - # ------------------------------------------------------------------ - # Planet Analysis - planet = SUAVE.Analyses.Planets.Planet() - analyses.append(planet) - - # ------------------------------------------------------------------ - # Atmosphere Analysis - atmosphere = SUAVE.Analyses.Atmospheric.US_Standard_1976() - atmosphere.features.planet = planet.features - analyses.append(atmosphere) - - # done! - return analyses - - -# ---------------------------------------------------------------------- -# Define the Vehicle -# ---------------------------------------------------------------------- - -def vehicle_setup(cruise_altitude): - - # ------------------------------------------------------------------ - # Initialize the Vehicle - # ------------------------------------------------------------------ - - vehicle = SUAVE.Vehicle() - vehicle.tag = 'Embraer_E190' - - # ------------------------------------------------------------------ - # Vehicle-level Properties - # ------------------------------------------------------------------ - ''' - # mass properties - vehicle.mass_properties.max_takeoff = 92110. #use landing mass as - vehicle.mass_properties.operating_empty = 34551. - vehicle.mass_properties.takeoff = 80721. - vehicle.mass_properties.max_zero_fuel = 92110. #equivalent landing mass - vehicle.mass_properties.cargo = 0.0 - vehicle.mass_properties.max_payload = 0.0 - vehicle.mass_properties.max_fuel = 0.0 - ''' - - # envelope properties - vehicle.envelope.ultimate_load = 3.5 - vehicle.envelope.limit_load = 1.5 - - # basic parameters - vehicle.reference_area = 100.0 - vehicle.passengers = 114 - vehicle.systems.control = "partially powered" - vehicle.systems.accessories = "medium range" - vehicle.w2h = 16. * Units.meters # Length from the mean aerodynamic center of wing to mean aerodynamic center of the horizontal tail - vehicle.w2v = 20. * Units.meters # Length from the mean aerodynamic center of wing to mean aerodynamic center of the vertical tail - # ------------------------------------------------------------------ - # Main Wing - # ------------------------------------------------------------------ - - wing = SUAVE.Components.Wings.Wing() - wing.tag = 'main_wing' - - wing.aspect_ratio = 8.3 - wing.sweep = 0.002 * Units.deg - wing.thickness_to_chord = 0.105 - wing.taper = 0.28 - wing.span_efficiency = 1.0 - - wing.spans.projected = 28.81 - - wing.chords.root = 5.4 - wing.chords.tip = 1.5185 - wing.chords.mean_aerodynamic = 3.8371 - - wing.areas.reference = 100.0 - wing.areas.wetted = 2.0 * wing.areas.reference - wing.areas.exposed = 150.0 - wing.areas.affected = 60.0 - - wing.twists.root = -0.311 * Units.degrees - wing.twists.tip = -0.315 * Units.degrees - - wing.origin = [00,0,0] - wing.aerodynamic_center = [0.914,0,0] - - wing.vertical = False - wing.symmetric = True - - wing.dynamic_pressure_ratio = 1.0 - - # add to vehicle - vehicle.append_component(wing) - - # ------------------------------------------------------------------ - # Horizontal Stabilizer - # ------------------------------------------------------------------ - - wing = SUAVE.Components.Wings.Wing() - wing.tag = 'horizontal_stabilizer' - - wing.aspect_ratio = 5.5 - wing.sweep = 0.002 * Units.deg - wing.thickness_to_chord = 0.11 - wing.taper = 0.11 - wing.span_efficiency = 0.9 - - wing.spans.projected = 11.213 - - wing.chords.root = 3.6733 - wing.chords.tip = 0.4040 - wing.chords.mean_aerodynamic = 2.4755 - - wing.areas.reference = 22.85 - wing.areas.wetted = 45.71 - wing.areas.exposed = 34.28 - wing.areas.affected = 13.71 - - wing.twists.root = 0.0 * Units.degrees - wing.twists.tip = 0.0 * Units.degrees - - wing.origin = [50,0,0] - wing.aerodynamic_center = [16.9144, 0.0, 0.0] - - wing.vertical = False - wing.symmetric = True - - wing.dynamic_pressure_ratio = 0.9 - - # add to vehicle - vehicle.append_component(wing) - - # ------------------------------------------------------------------ - # Vertical Stabilizer - # ------------------------------------------------------------------ - - wing = SUAVE.Components.Wings.Wing() - wing.tag = 'vertical_stabilizer' - - wing.aspect_ratio = 1.7 # - wing.sweep = 0.001 * Units.deg - wing.thickness_to_chord = 0.12 - wing.taper = 0.10 - wing.span_efficiency = 0.9 - - wing.spans.projected = 4.6945 # - - wing.chords.root = 5.0209 - wing.chords.tip = 0.5020 - wing.chords.mean_aerodynamic = 3.3777 - - wing.areas.reference = 12.96 - wing.areas.wetted = 25.92 - wing.areas.exposed = 19.44 - wing.areas.affected = 7.778 - - wing.twists.root = 0.0 * Units.degrees - wing.twists.tip = 0.0 * Units.degrees - - wing.origin = [0,0,0] - wing.aerodynamic_center = [0,0,0] - - wing.vertical = True - wing.symmetric = False - - wing.dynamic_pressure_ratio = 1.0 - - # add to vehicle - vehicle.append_component(wing) - - # ------------------------------------------------------------------ - # Fuselage - # ------------------------------------------------------------------ - - fuselage = SUAVE.Components.Fuselages.Fuselage() - fuselage.tag = 'fuselage' - - fuselage.number_coach_seats = vehicle.passengers - fuselage.seats_abreast = 4 - fuselage.seat_pitch = 0.7455 - - fuselage.fineness.nose = 1.5 - fuselage.fineness.tail = 1.8 - - fuselage.lengths.nose = 4.5 - fuselage.lengths.tail = 5.4 - fuselage.lengths.cabin = 21.24675 - fuselage.lengths.total = 31.14675 - fuselage.lengths.fore_space = 0. - fuselage.lengths.aft_space = 0. - - fuselage.width = 3.0 - - fuselage.heights.maximum = 3.4 # - fuselage.heights.at_quarter_length = 3.4 - fuselage.heights.at_three_quarters_length = 3.4 - fuselage.heights.at_wing_root_quarter_chord = 3.4 - - fuselage.areas.side_projected = 79.462 - fuselage.areas.wetted = 288.521422366 - fuselage.areas.front_projected = 8.011 - - fuselage.effective_diameter = 3.2 - - fuselage.differential_pressure = 10**5 * Units.pascal - - # add to vehicle - vehicle.append_component(fuselage) - - # ------------------------------------------------------------------ - # Propulsion - # ------------------------------------------------------------------ - - atm = SUAVE.Analyses.Atmospheric.US_Standard_1976() - p1, T1, rho1, a1, mu1 = atm.compute_values(0.) - p2, T2, rho2, a2, mu2 = atm.compute_values(cruise_altitude) - - - mach_number = .729 - #Create Energy Network - #create battery - battery = SUAVE.Components.Energy.Storages.Batteries.Variable_Mass.Lithium_Air() - battery.tag = 'battery' - - ducted_fan = SUAVE.Components.Energy.Networks.Ducted_Fan() - network = SUAVE.Components.Energy.Networks.Battery_Ducted_Fan() - working_fluid = SUAVE.Attributes.Gases.Air - - #add working fluid to the network - ducted_fan.working_fluid = working_fluid - - - #Component 1 : ram, to convert freestream static to stagnation quantities - ram = SUAVE.Components.Energy.Converters.Ram() - ram.tag = 'ram' - - #add ram to the network - ducted_fan.ram = ram - - - #Component 2 : inlet nozzle - inlet_nozzle = SUAVE.Components.Energy.Converters.Compression_Nozzle() - inlet_nozzle.tag = 'inlet nozzle' - - inlet_nozzle.polytropic_efficiency = 0.98 - inlet_nozzle.pressure_ratio = 0.98 # turbofan.fan_nozzle_pressure_ratio = 0.98 #0.98 - - #add inlet nozzle to the network - ducted_fan.inlet_nozzle = inlet_nozzle - - - #Component 8 :fan nozzle - fan_nozzle = SUAVE.Components.Energy.Converters.Expansion_Nozzle() - fan_nozzle.tag = 'fan nozzle' - - fan_nozzle.polytropic_efficiency = 0.95 - fan_nozzle.pressure_ratio = 0.99 - - #add the fan nozzle to the network - ducted_fan.fan_nozzle = fan_nozzle - - - - #Component 9 : fan - fan = SUAVE.Components.Energy.Converters.Fan() - fan.tag = 'fan' - - fan.polytropic_efficiency = 0.93 - fan.pressure_ratio = 1.5 - - #add the fan to the network - ducted_fan.fan = fan - - #Component 10 : thrust (to compute the thrust) - thrust = SUAVE.Components.Energy.Processes.Thrust() - thrust.tag ='compute_thrust' - thrust.total_design = 121979.18 # Preq*1.5/V_cruise - ducted_fan.thrust = thrust - ducted_fan.tag ='ducted_fan' - ducted_fan.number_of_engines = 2.0 - - - #compute conditions for engine - conditions = SUAVE.Analyses.Mission.Segments.Conditions.Aerodynamics() - conditions.freestream.altitude = np.atleast_1d(cruise_altitude) - conditions.freestream.mach_number = np.atleast_1d(mach_number) - conditions.freestream.pressure = np.atleast_1d(p2) - conditions.freestream.temperature = np.atleast_1d(T2) - conditions.freestream.density = np.atleast_1d(rho2) - conditions.freestream.dynamic_viscosity = np.atleast_1d(mu2) - conditions.freestream.gravity = np.atleast_1d(9.81) - conditions.freestream.gamma = np.atleast_1d(1.4) - conditions.freestream.Cp = 1.4*287.87/(1.4-1) - conditions.freestream.R = 287.87 - conditions.freestream.speed_of_sound = np.atleast_1d(a2) - conditions.freestream.velocity = conditions.freestream.mach_number * conditions.freestream.speed_of_sound - - #size mass flow - ducted_fan_sizing(ducted_fan, mach_number, cruise_altitude) - #now size geometry - compute_ducted_fan_geometry(ducted_fan, conditions) - - # ------------------------------------------------------------------ - # Energy Network - # ------------------------------------------------------------------ - - #define the energy network - net = SUAVE.Components.Energy.Networks.Battery_Ducted_Fan() - net.tag = 'network' - - net.propulsor = ducted_fan - net.append(ducted_fan) - net.battery = battery - - net.nacelle_diameter = ducted_fan.nacelle_diameter - net.engine_length = ducted_fan.engine_length - net.number_of_engines = ducted_fan.number_of_engines - net.motor_efficiency =.95 - vehicle.propulsors.append(ducted_fan) - vehicle.energy_network = net - - - # ------------------------------------------------------------------ - # Vehicle Definition Complete - # ------------------------------------------------------------------ - - - return vehicle - -def evaluate_field_length(configs,analyses,mission,results): - - # unpack - airport = mission.airport - - takeoff_config = configs.takeoff - landing_config = configs.landing - - # evaluate - - TOFL = estimate_take_off_field_length(takeoff_config,analyses.configs,airport) - LFL = estimate_landing_field_length (landing_config, analyses.configs,airport) - - # pack - field_length = SUAVE.Core.Data() - field_length.takeoff = TOFL[0] - field_length.landing = LFL[0] - - results.field_length = field_length - - - return results - - - -# ---------------------------------------------------------------------- -# Define the Configurations -# --------------------------------------------------------------------- - -def configs_setup(vehicle): - - # ------------------------------------------------------------------ - # Initialize Configurations - # ------------------------------------------------------------------ - - configs = SUAVE.Components.Configs.Config.Container() - - base_config = SUAVE.Components.Configs.Config(vehicle) - base_config.tag = 'base' - configs.append(base_config) - - # ------------------------------------------------------------------ - # Cruise Configuration - # ------------------------------------------------------------------ - - config = SUAVE.Components.Configs.Config(base_config) - config.tag = 'cruise' - - configs.append(config) - - - # ------------------------------------------------------------------ - # Takeoff Configuration - # ------------------------------------------------------------------ - - config = SUAVE.Components.Configs.Config(base_config) - config.tag = 'takeoff' - - config.wings['main_wing'].flaps.angle = 20. * Units.deg - config.wings['main_wing'].slats.angle = 25. * Units.deg - - config.V2_VS_ratio = 1.21 - config.maximum_lift_coefficient = 2. - - configs.append(config) - - - # ------------------------------------------------------------------ - # Landing Configuration - # ------------------------------------------------------------------ - - config = SUAVE.Components.Configs.Config(base_config) - config.tag = 'landing' - - config.wings['main_wing'].flaps_angle = 30. * Units.deg - config.wings['main_wing'].slats_angle = 25. * Units.deg - - config.Vref_VS_ratio = 1.23 - config.maximum_lift_coefficient = 2. - - configs.append(config) - - - # done! - return configs - - - -def simple_sizing(configs, analyses, m_guess, Ereq, Preq): - from SUAVE.Methods.Geometry.Two_Dimensional.Planform import wing_planform - -# ------------------------------------------------------------------ - # Define New Gross Takeoff Weight - # ------------------------------------------------------------------ - #now add component weights to the gross takeoff weight of the vehicle - - base = configs.base - base.pull_base() - base.mass_properties.max_takeoff=m_guess - base.mass_properties.max_zero_fuel=m_guess #just used for weight calculation - mission=analyses.missions.base.segments - airport=analyses.missions.base.airport - atmo = airport.atmosphere - #determine geometry of fuselage as well as wings - fuselage=base.fuselages['fuselage'] - SUAVE.Methods.Geometry.Two_Dimensional.Planform.fuselage_planform(fuselage) - fuselage.areas.side_projected = fuselage.heights.maximum*fuselage.lengths.cabin*1.1 # Not correct - base.wings['main_wing'] = wing_planform(base.wings['main_wing']) - base.wings['horizontal_stabilizer'] = wing_planform(base.wings['horizontal_stabilizer']) - - base.wings['vertical_stabilizer'] = wing_planform(base.wings['vertical_stabilizer']) - #calculate position of horizontal stabilizer - base.wings['horizontal_stabilizer'].aerodynamic_center[0]= base.w2h- \ - (base.wings['horizontal_stabilizer'].origin[0] + \ - base.wings['horizontal_stabilizer'].aerodynamic_center[0] - \ - base.wings['main_wing'].origin[0] - base.wings['main_wing'].aerodynamic_center[0]) - #wing areas - for wing in base.wings: - wing.areas.wetted = 2.00 * wing.areas.reference - wing.areas.affected = 0.60 * wing.areas.reference - wing.areas.exposed = 0.75 * wing.areas.wetted - - - cruise_altitude= mission['climb_5'].altitude_end - conditions = atmo.compute_values(cruise_altitude) - sizing_segment = SUAVE.Core.Data() - sizing_segment.M = mission['cruise'].air_speed/conditions.speed_of_sound - sizing_segment.alt = cruise_altitude - sizing_segment.T = conditions.temperature - sizing_segment.p = conditions.pressure - conditions0 = atmo.compute_values(12500.*Units.ft) #cabin pressure - p0 = conditions0.pressure - fuselage_diff_pressure= max(conditions0.pressure-conditions.pressure,0) - fuselage.differential_pressure = fuselage_diff_pressure - - battery =base.energy_network['battery'] - ducted_fan=base.propulsors['ducted_fan'] - SUAVE.Methods.Power.Battery.Sizing.initialize_from_energy_and_power(battery,Ereq,Preq) - - battery.current_energy =[battery.max_energy] #initialize list of current energy - m_air =SUAVE.Methods.Power.Battery.Variable_Mass.find_total_mass_gain(battery) - #now add the electric motor weight - motor_mass=ducted_fan.number_of_engines*SUAVE.Methods.Weights.Correlations.Propulsion.air_cooled_motor((Preq)*Units.watts/ducted_fan.number_of_engines) - propulsion_mass=SUAVE.Methods.Weights.Correlations.Propulsion.integrated_propulsion(motor_mass/ducted_fan.number_of_engines,ducted_fan.number_of_engines) - - ducted_fan.mass_properties.mass=propulsion_mass - - breakdown = analyses.configs.base.weights.evaluate() - breakdown.battery=battery.mass_properties.mass - breakdown.air=m_air - base.mass_properties.breakdown=breakdown - m_fuel=0. - #print breakdown - base.mass_properties.operating_empty = breakdown.empty - #weight =SUAVE.Methods.Weights.Correlations.Tube_Wing.empty_custom_eng(vehicle, ducted_fan) - m_full=breakdown.empty+battery.mass_properties.mass+breakdown.payload - m_end=m_full+m_air - base.mass_properties.takeoff = m_full - base.store_diff() - - # Update all configs with new base data - for config in configs: - config.pull_base() - - - ############################################################################## - # ------------------------------------------------------------------ - # Define Configurations - # ------------------------------------------------------------------ - landing_config=configs.landing - landing_config.wings['main_wing'].flaps.angle = 20. * Units.deg - landing_config.wings['main_wing'].slats.angle = 25. * Units.deg - landing_config.mass_properties.landing = m_end - landing_config.store_diff() - # ------------------------------------------------------------------ - # Vehicle Definition Complete - # ------------------------------------------------------------------ - - return - - - - - - -# ---------------------------------------------------------------------- -# Define the Mission -# ---------------------------------------------------------------------- -def mission_setup(analyses): - - # ------------------------------------------------------------------ - # Initialize the Mission - # ------------------------------------------------------------------ - - mission = SUAVE.Analyses.Mission.Sequential_Segments() - mission.tag = 'embraer_e190ar test mission' - - # atmospheric model - atmosphere = SUAVE.Attributes.Atmospheres.Earth.US_Standard_1976() - planet = SUAVE.Attributes.Planets.Earth() - - #airport - airport = SUAVE.Attributes.Airports.Airport() - airport.altitude = 0.0 * Units.ft - airport.delta_isa = 0.0 - airport.atmosphere = SUAVE.Analyses.Atmospheric.US_Standard_1976() - mission.airport = airport - - # unpack Segments module - Segments = SUAVE.Analyses.Mission.Segments - - - # ------------------------------------------------------------------ - # First Climb Segment: Constant Speed, Constant Throttle - # ------------------------------------------------------------------ - - segment = Segments.Climb.Constant_Speed_Constant_Rate() - segment.tag = "climb_1" - - # connect vehicle configuration - segment.analyses.extend( analyses.takeoff ) - - # define segment attributes - segment.atmosphere = atmosphere - segment.planet = planet - - segment.altitude_start = 0.0 * Units.km - segment.altitude_end = 0.353 * Units.km - segment.air_speed = 111.932 - segment.climb_rate = 3000. * Units['ft/min'] - - # add to misison - mission.append_segment(segment) - - # ------------------------------------------------------------------ - # Second Climb Segment: Constant Speed, Constant Throttle - # ------------------------------------------------------------------ - - segment = Segments.Climb.Constant_Speed_Constant_Rate() - segment.tag = "climb_2" - - # connect vehicle configuration - segment.analyses.extend( analyses.cruise ) - - # segment attributes - segment.atmosphere = atmosphere - segment.planet = planet - - segment.altitude_end = 1.157 * Units.km - segment.air_speed = 163.71 - segment.climb_rate = 2500. * Units['ft/min'] - - # add to mission - mission.append_segment(segment) - - # ------------------------------------------------------------------ - # Third Climb Segment: Constant Speed, Constant Throttle - # ------------------------------------------------------------------ - - segment = Segments.Climb.Constant_Speed_Constant_Rate() - segment.tag = "climb_3" - - # connect vehicle configuration - segment.analyses.extend( analyses.cruise ) - - # segment attributes - segment.atmosphere = atmosphere - segment.planet = planet - - segment.altitude_end = 1.236 * Units.km - segment.air_speed = 193.25 - segment.climb_rate = 1800. * Units['ft/min'] - - # add to mission - mission.append_segment(segment) - - # ------------------------------------------------------------------ - # Fourth Climb Segment: Constant Speed, Constant Throttle - # ------------------------------------------------------------------ - - segment = Segments.Climb.Constant_Speed_Constant_Rate() - segment.tag = "climb_4" - - # connect vehicle configuration - segment.analyses.extend( analyses.cruise ) - - # segment attributes - segment.atmosphere = atmosphere - segment.planet = planet - - segment.altitude_end = 1.807 * Units.km - segment.air_speed = 194.17 - segment.climb_rate = 900. * Units['ft/min'] - - # add to mission - mission.append_segment(segment) - - # ------------------------------------------------------------------ - # Fifth Climb Segment: Constant Speed, Constant Throttle - # ------------------------------------------------------------------ - - segment = Segments.Climb.Constant_Speed_Constant_Rate() - segment.tag = "climb_5" - - # connect vehicle configuration - segment.analyses.extend( analyses.cruise ) - - # segment attributes - segment.atmosphere = atmosphere - segment.planet = planet - - segment.altitude_end = 6.255 * Units.km - segment.air_speed = 176.03 - segment.climb_rate = 300. * Units['ft/min'] - - # add to mission - mission.append_segment(segment) - - # ------------------------------------------------------------------ - # Cruise Segment: constant speed, constant altitude - # ------------------------------------------------------------------ - - segment = Segments.Cruise.Constant_Speed_Constant_Altitude() - segment.tag = "cruise" - - # connect vehicle configuration - segment.analyses.extend( analyses.cruise ) - - # segment attributes - segment.atmosphere = atmosphere - segment.planet = planet - - segment.air_speed = 230. - segment.distance = 1947. * Units.nmi - - # add to mission - mission.append_segment(segment) - - # ------------------------------------------------------------------ - # First Descent Segment: consant speed, constant segment rate - # ------------------------------------------------------------------ - - segment = Segments.Descent.Constant_Speed_Constant_Rate() - segment.tag = "descent_1" - - # connect vehicle configuration - segment.analyses.extend( analyses.cruise ) - - # segment attributes - segment.atmosphere = atmosphere - segment.planet = planet - - segment.altitude_end = 6.26 * Units.km - segment.air_speed = 440.0 * Units.knots - segment.descent_rate = 2400. * Units['ft/min'] - - # add to mission - mission.append_segment(segment) - - - # ------------------------------------------------------------------ - # Second Descent Segment: consant speed, constant segment rate - # ------------------------------------------------------------------ - - segment = Segments.Descent.Constant_Speed_Constant_Rate() - segment.tag = "descent_2" - - # connect vehicle configuration - segment.analyses.extend( analyses.cruise ) - - # segment attributes - segment.atmosphere = atmosphere - segment.planet = planet - - segment.altitude_end = 2.132 * Units.km - segment.air_speed = 365.0 * Units.knots - segment.descent_rate = 2000. * Units['ft/min'] - - # append to mission - mission.append_segment(segment) - - - # ------------------------------------------------------------------ - # Third Descent Segment: consant speed, constant segment rate - # ------------------------------------------------------------------ - - segment = Segments.Descent.Constant_Speed_Constant_Rate() - segment.tag = "descent_3" - - # connect vehicle configuration - segment.analyses.extend( analyses.cruise ) - - # segment attributes - segment.atmosphere = atmosphere - segment.planet = planet - - segment.altitude_end = 0.0 * Units.km - segment.air_speed = 250.0 * Units.knots - segment.descent_rate = 1500. * Units['ft/min'] - - # append to mission - mission.append_segment(segment) - - - # ------------------------------------------------------------------ - # Mission definition complete - # ------------------------------------------------------------------ - - return mission - -#: def define_mission() - -# ---------------------------------------------------------------------- -# Evaluate the Mission -# ---------------------------------------------------------------------- -def evaluate_mission(configs,mission): - - # ------------------------------------------------------------------ - # Run Mission - # ------------------------------------------------------------------ - - - results = mission.evaluate() - - #determine energy characteristiscs - e_current_min=1E14 - Pmax=0. - for i in range(len(results.segments)): - if np.min(results.segments[i].conditions.propulsion.battery_energy)Pmax: - Pmax=np.max(np.abs(results.segments[i].conditions.propulsion.battery_draw)) - results.e_total=results.segments[0].conditions.propulsion.battery_energy[0,0]-e_current_min - results.Pmax=Pmax - print 'e_current_min=',e_current_min - print "e_total=", results.e_total - print "Pmax=", Pmax - return results - - -def missions_setup(base_mission): - - # the mission container - missions = SUAVE.Analyses.Mission.Mission.Container() - missions.base = base_mission - - return missions -# ---------------------------------------------------------------------- -# Plot Mission -# ---------------------------------------------------------------------- - -def plot_mission(results,configs,line_style='bo-'): - - if line_style == 'k-': - line_width = 2. - else: - line_width = 1. - - - # ------------------------------------------------------------------ - # Throttle - # ------------------------------------------------------------------ - plt.figure("Throttle History") - axes = plt.gca() - for i in range(len(results.segments)): - time = results.segments[i].conditions.frames.inertial.time[:,0] / Units.min - eta = results.segments[i].conditions.propulsion.throttle[:,0] - axes.plot(time, eta, line_style) - axes.set_xlabel('Time (mins)') - axes.set_ylabel('Throttle') - axes.grid(True) - - - # ------------------------------------------------------------------ - # Angle of Attack - # ------------------------------------------------------------------ - - plt.figure("Angle of Attack History") - axes = plt.gca() - for i in range(len(results.segments)): - time = results.segments[i].conditions.frames.inertial.time[:,0] / Units.min - aoa = results.segments[i].conditions.aerodynamics.angle_of_attack[:,0] / Units.deg - axes.plot(time, aoa, line_style) - axes.set_xlabel('Time (mins)') - axes.set_ylabel('Angle of Attack (deg)') - axes.grid(True) - - - # ------------------------------------------------------------------ - # Mass Rate - # ------------------------------------------------------------------ - plt.figure("Mass Rate") - axes = plt.gca() - for i in range(len(results.segments)): - time = results.segments[i].conditions.frames.inertial.time[:,0] / Units.min - mdot = -results.segments[i].conditions.weights.vehicle_mass_rate[:,0] - axes.plot(time, mdot, line_style) - axes.set_xlabel('Time (mins)') - axes.set_ylabel('Mass Rate (kg/s)') - axes.grid(True) - - - # ------------------------------------------------------------------ - # Altitude - # ------------------------------------------------------------------ - plt.figure("Altitude") - axes = plt.gca() - for i in range(len(results.segments)): - time = results.segments[i].conditions.frames.inertial.time[:,0] / Units.min - altitude = results.segments[i].conditions.freestream.altitude[:,0] / Units.km - axes.plot(time, altitude, line_style) - axes.set_xlabel('Time (mins)') - axes.set_ylabel('Altitude (km)') - axes.grid(True) - - - # ------------------------------------------------------------------ - # Vehicle Mass - # ------------------------------------------------------------------ - plt.figure("Vehicle Mass") - axes = plt.gca() - for i in range(len(results.segments)): - time = results.segments[i].conditions.frames.inertial.time[:,0] / Units.min - mass = results.segments[i].conditions.weights.total_mass[:,0] - axes.plot(time, mass, line_style) - axes.set_xlabel('Time (mins)') - axes.set_ylabel('Vehicle Mass (kg)') - axes.grid(True) - - - # ------------------------------------------------------------------ - # Aerodynamics - # ------------------------------------------------------------------ - fig = plt.figure("Aerodynamic Forces") - for segment in results.segments.values(): - - time = segment.conditions.frames.inertial.time[:,0] / Units.min - Lift = -segment.conditions.frames.wind.lift_force_vector[:,2] - Drag = -segment.conditions.frames.wind.drag_force_vector[:,0] - Thrust = segment.conditions.frames.body.thrust_force_vector[:,0] - - axes = fig.add_subplot(3,1,1) - axes.plot( time , Lift , line_style ) - axes.set_xlabel('Time (min)') - axes.set_ylabel('Lift (N)') - axes.grid(True) - - axes = fig.add_subplot(3,1,2) - axes.plot( time , Drag , line_style ) - axes.set_xlabel('Time (min)') - axes.set_ylabel('Drag (N)') - axes.grid(True) - - axes = fig.add_subplot(3,1,3) - axes.plot( time , Thrust , line_style ) - axes.set_xlabel('Time (min)') - axes.set_ylabel('Thrust (N)') - axes.grid(True) - - - # ------------------------------------------------------------------ - # Aerodynamics 2 - # ------------------------------------------------------------------ - fig = plt.figure("Aerodynamic Coefficients") - for segment in results.segments.values(): - - time = segment.conditions.frames.inertial.time[:,0] / Units.min - CLift = segment.conditions.aerodynamics.lift_coefficient[:,0] - CDrag = segment.conditions.aerodynamics.drag_coefficient[:,0] - Drag = -segment.conditions.frames.wind.drag_force_vector[:,0] - Thrust = segment.conditions.frames.body.thrust_force_vector[:,0] - - axes = fig.add_subplot(3,1,1) - axes.plot( time , CLift , line_style ) - axes.set_xlabel('Time (min)') - axes.set_ylabel('CL') - axes.grid(True) - - axes = fig.add_subplot(3,1,2) - axes.plot( time , CDrag , line_style ) - axes.set_xlabel('Time (min)') - axes.set_ylabel('CD') - axes.grid(True) - - axes = fig.add_subplot(3,1,3) - axes.plot( time , Drag , line_style ) - axes.plot( time , Thrust , 'ro-' ) - axes.set_xlabel('Time (min)') - axes.set_ylabel('Drag and Thrust (N)') - axes.grid(True) - - - # ------------------------------------------------------------------ - # Aerodynamics 3 - # ------------------------------------------------------------------ - fig = plt.figure("Drag Components") - axes = plt.gca() - for i, segment in enumerate(results.segments.values()): - - time = segment.conditions.frames.inertial.time[:,0] / Units.min - drag_breakdown = segment.conditions.aerodynamics.drag_breakdown - cdp = drag_breakdown.parasite.total[:,0] - cdi = drag_breakdown.induced.total[:,0] - cdc = drag_breakdown.compressible.total[:,0] - cdm = drag_breakdown.miscellaneous.total[:,0] - cd = drag_breakdown.total[:,0] - - if line_style == 'bo-': - axes.plot( time , cdp , 'ko-', label='CD_P' ) - axes.plot( time , cdi , 'bo-', label='CD_I' ) - axes.plot( time , cdc , 'go-', label='CD_C' ) - axes.plot( time , cdm , 'yo-', label='CD_M' ) - axes.plot( time , cd , 'ro-', label='CD' ) - if i == 0: - axes.legend(loc='upper center') - else: - axes.plot( time , cdp , line_style ) - axes.plot( time , cdi , line_style ) - axes.plot( time , cdc , line_style ) - axes.plot( time , cdm , line_style ) - axes.plot( time , cd , line_style ) - - axes.set_xlabel('Time (min)') - axes.set_ylabel('CD') - axes.grid(True) - - - # ------------------------------------------------------------------ - # Flight Conditions - # ------------------------------------------------------------------ - fig = plt.figure("Flight Conditions",figsize=(6.5,10)) - for segment in results.segments.values(): - - time = segment.conditions.frames.inertial.time[:,0] / Units.min - altitude = segment.conditions.freestream.altitude[:,0] / Units.km - mach = segment.conditions.freestream.mach_number[:,0] - distance = segment.conditions.frames.inertial.position_vector[:,0] / Units.km - - axes = fig.add_subplot(3,1,1) - axes.plot( time, distance, line_style ) - axes.set_ylabel('Distance (km)') - axes.grid(True) - - axes = fig.add_subplot(3,1,2) - axes.plot( time , altitude , line_style , lw=line_width ) - axes.set_ylabel('Altitude (km)') - axes.grid(True) - - axes = fig.add_subplot(3,1,3) - axes.plot( time , mach, line_style , lw=line_width ) - axes.set_xlabel('Time (min)') - axes.set_ylabel('Mach Number (-)') - axes.grid(True) - - # ------------------------------------------------------------------ - # Mass, State of Charge, Power - # ------------------------------------------------------------------ - - fig = plt.figure("Electric Aircraft Outputs",figsize=(6.5,10)) - for segment in results.segments.values(): - - time = segment.conditions.frames.inertial.time[:,0] / Units.min - mass = segment.conditions.weights.total_mass[:,0] - - axes = fig.add_subplot(3,1,1) - axes.plot( time , mass , line_style , lw=line_width ) - axes.set_ylabel('Vehicle Mass (kg)') - axes.grid(True) - - try: - battery=configs.base.energy_network['battery'] - state_of_charge=segment.conditions.propulsion.battery_energy/battery.max_energy - battery_power=-segment.conditions.propulsion.battery_draw/Units.MW - except: - continue - - axes = fig.add_subplot(3,1,2) - axes.plot( time , state_of_charge , line_style , lw=line_width ) - axes.set_ylabel('State of Charge (-)') - axes.set_ylim([-0.005,1.005]) - axes.grid(True) - - axes = fig.add_subplot(3,1,3) - axes.plot( time , battery_power , line_style , lw=line_width ) - axes.set_xlabel('Time (min)') - axes.set_ylabel('Discharge Power (MW)') - axes.grid(True) - - - raw_input('Press Enter To Quit') - return - - -if __name__ == '__main__': - main() - plt.show() \ No newline at end of file From 9adab337667b902cd325862a806a37a0b66f0b5c Mon Sep 17 00:00:00 2001 From: jmvegh Date: Thu, 26 Jan 2017 14:53:48 -0800 Subject: [PATCH 2/7] it's working! --- Lithium_Air_Sizing/Analyses.py | 91 +++++++++++++ .../{Mission.py.py => Mission.py} | 2 +- .../{Sizing.py.py => Sizing.py} | 121 +++++++++++------- .../{Vehicle.py.py => Vehicle.py} | 2 +- 4 files changed, 165 insertions(+), 51 deletions(-) create mode 100644 Lithium_Air_Sizing/Analyses.py rename Lithium_Air_Sizing/{Mission.py.py => Mission.py} (99%) rename Lithium_Air_Sizing/{Sizing.py.py => Sizing.py} (91%) rename Lithium_Air_Sizing/{Vehicle.py.py => Vehicle.py} (99%) diff --git a/Lithium_Air_Sizing/Analyses.py b/Lithium_Air_Sizing/Analyses.py new file mode 100644 index 0000000..4d9d7c6 --- /dev/null +++ b/Lithium_Air_Sizing/Analyses.py @@ -0,0 +1,91 @@ +# Analyses.py +# +# Created: May 2015, E. Botero +# Modified: + +# ---------------------------------------------------------------------- +# Imports +# ---------------------------------------------------------------------- + +import SUAVE + +# ---------------------------------------------------------------------- +# Setup Analyses +# ---------------------------------------------------------------------- + +def setup(configs): + #Ereq=configs.Ereq + #Preq=configs.Preq + analyses = SUAVE.Analyses.Analysis.Container() + + # build a base analysis for each config + for tag,config in configs.items(): + analysis = base(config) + analyses[tag] = analysis + + # adjust analyses for configs + + # takeoff_analysis + analyses.takeoff.aerodynamics.settings.drag_coefficient_increment = 0.0000 + + # landing analysis + aerodynamics = analyses.landing.aerodynamics + + return analyses + +# ---------------------------------------------------------------------- +# Define Base Analysis +# ---------------------------------------------------------------------- + +def base(vehicle): + + # ------------------------------------------------------------------ + # Initialize the Analyses + # ------------------------------------------------------------------ + analyses = SUAVE.Analyses.Vehicle() + + # ------------------------------------------------------------------ + # Basic Geometry Relations + sizing = SUAVE.Analyses.Sizing.Sizing() + sizing.features.vehicle = vehicle + analyses.append(sizing) + + # ------------------------------------------------------------------ + # Weights + weights = SUAVE.Analyses.Weights.Weights() + weights.settings.empty_weight_method= \ + SUAVE.Methods.Weights.Correlations.Tube_Wing.empty + weights.vehicle = vehicle + analyses.append(weights) + + # ------------------------------------------------------------------ + # Aerodynamics Analysis + aerodynamics = SUAVE.Analyses.Aerodynamics.Fidelity_Zero() + aerodynamics.geometry = vehicle + aerodynamics.settings.drag_coefficient_increment = 0.0000 + analyses.append(aerodynamics) + + # ------------------------------------------------------------------ + # Stability Analysis + stability = SUAVE.Analyses.Stability.Fidelity_Zero() + stability.geometry = vehicle + analyses.append(stability) + + # ------------------------------------------------------------------ + # Propulsion Analysis + energy= SUAVE.Analyses.Energy.Energy() + energy.network = vehicle.energy_network # SEE THIS + analyses.append(energy) + + # ------------------------------------------------------------------ + # Planet Analysis + planet = SUAVE.Analyses.Planets.Planet() + analyses.append(planet) + + # ------------------------------------------------------------------ + # Atmosphere Analysis + atmosphere = SUAVE.Analyses.Atmospheric.US_Standard_1976() + atmosphere.features.planet = planet.features + analyses.append(atmosphere) + # done! + return analyses \ No newline at end of file diff --git a/Lithium_Air_Sizing/Mission.py.py b/Lithium_Air_Sizing/Mission.py similarity index 99% rename from Lithium_Air_Sizing/Mission.py.py rename to Lithium_Air_Sizing/Mission.py index 4d8f5b8..a04828d 100644 --- a/Lithium_Air_Sizing/Mission.py.py +++ b/Lithium_Air_Sizing/Mission.py @@ -118,7 +118,7 @@ def base(analyses): segment.analyses.extend( analyses.cruise ) segment.air_speed = 147.1479 * Units['m/s'] - segment.distance = 300 * Units.nautical_miles + segment.distance = 1000 * Units.nautical_miles segment.state.numerics.tolerance_solution = sol_tol mission.append_segment(segment) diff --git a/Lithium_Air_Sizing/Sizing.py.py b/Lithium_Air_Sizing/Sizing.py similarity index 91% rename from Lithium_Air_Sizing/Sizing.py.py rename to Lithium_Air_Sizing/Sizing.py index 66d7362..e0d9810 100644 --- a/Lithium_Air_Sizing/Sizing.py.py +++ b/Lithium_Air_Sizing/Sizing.py @@ -20,11 +20,20 @@ import matplotlib import pylab as plt +import Vehicle +import Analyses +import Mission + +from SUAVE.Optimization.Nexus import Nexus from SUAVE.Analyses.Process import Process from SUAVE.Methods.Performance import estimate_take_off_field_length from SUAVE.Methods.Performance import estimate_landing_field_length from SUAVE.Methods.Geometry.Two_Dimensional.Planform import wing_planform +from SUAVE.Methods.Geometry.Two_Dimensional.Planform import wing_planform from SUAVE.Methods.Propulsion.ducted_fan_sizing import ducted_fan_sizing +from SUAVE.Sizing.Sizing_Loop import Sizing_Loop + + from SUAVE.Methods.Geometry.Two_Dimensional.Cross_Section.Propulsion.compute_ducted_fan_geometry import compute_ducted_fan_geometry matplotlib.interactive(True) @@ -33,14 +42,35 @@ # ---------------------------------------------------------------------- def main(): - - problem = setup() - output = problem.objective() - plot_mission(output) - - + #initialize the problem + nexus = Nexus() + nexus.vehicle_configurations = Vehicle.setup() + nexus.analyses = Analyses.setup(nexus.vehicle_configurations) + nexus.missions = Mission.setup(nexus.analyses) + + + #problem = Data() + #nexus.optimization_problem = problem + nexus.procedure = setup() + nexus.sizing_loop = Sizing_Loop() + nexus.total_number_of_iterations = 0 + + evaluate_problem(nexus) + results = nexus.results + plot_mission(results, nexus.vehicle_configurations) + #output=nexus._really_evaluate() #run; use optimization setup without inputs + return + +def evaluate_problem(nexus): + for key,step in nexus.procedure.items(): + if hasattr(step,'evaluate'): + self = step.evaluate(nexus) + else: + nexus = step(nexus) + self = nexus + return nexus # ---------------------------------------------------------------------- # Setup # ---------------------------------------------------------------------- @@ -52,6 +82,8 @@ def setup(): # ------------------------------------------------------------------ # size the base config + + procedure = Process() procedure.run_sizing_loop = run_sizing_loop #size aircraft and run mission procedure.evaluate_field_length = evaluate_field_length @@ -86,7 +118,7 @@ def run_sizing_loop(nexus): - mass = [ m_guess ] + #mass = [ m_guess ] scaling = np.array([1E4,1E9,1E6]) y = np.array([m_guess, Ereq_guess, Preq_guess])/scaling @@ -98,30 +130,35 @@ def run_sizing_loop(nexus): sizing_loop = nexus.sizing_loop #assign to sizing loop - sizing_loop.tolerance = nexus.tol #percentage difference in mass and energy between iterations + sizing_loop.tolerance = 1E-4 #percentage difference in mass and energy between iterations sizing_loop.initial_step = 'Default' #Default, Table, SVR - sizing_loop.update_method = 'fixed_point' #'fixed_point','newton-raphson', 'broyden' + sizing_loop.update_method = 'successive_substitution' #'successive_substitution','newton-raphson', 'broyden' sizing_loop.default_y = y sizing_loop.min_y = min_y sizing_loop.max_y = max_y sizing_loop.default_scaling = scaling + + sizing_loop.maximum_iterations = 50 sizing_loop.write_threshhold = 50. - sizing_loop.output_filename = 'y_values_%(range)d_nautical_mile_range.txt' %{'range':nexus.target_range/Units.nautical_miles} + + sizing_loop.output_filename = 'sizing_outputs.txt' sizing_loop.sizing_evaluation = sizing_evaluation sizing_loop.iteration_options.h = 1E-6 sizing_loop.iteration_options.min_fix_point_iterations = 2 - sizing_loop.iteration_options.initialize_jacobian = 'newton-raphson' #appr - sizing_loop.iteration_options.max_newton_raphson_tolerance = nexus.tol*2 #threshhold at which to switch to fixed point (to prevent overshooting) - sizing_loop.iteration_options.min_surrogate_length = 3 #best for svr =3 - sizing_loop.iteration_options.min_surrogate_step = .03 #best for svr =.011 (.02) - sizing_loop.iteration_options.min_write_step = .011#best for svr =.011 + sizing_loop.iteration_options.initialize_jacobian = 'newton-raphson' #approximate #option for Broyden's Method, not used here + ''' + #option if using surrogates to inform your initial guess + sizing_loop.iteration_options.max_newton_raphson_tolerance = nexus.tol*2 #threshhold at which to switch to successive substitution (to prevent overshooting) + sizing_loop.iteration_options.min_surrogate_length = 3 #default + sizing_loop.iteration_options.min_surrogate_step = .03 + sizing_loop.iteration_options.min_write_step = .011#default sizing_loop.iteration_options.n_neighbors = 5 - sizing_loop.iteration_options.neighbors_weighted_distance = True - + sizing_loop.iteration_options.neighbors_weighted_distance = True #option for using K Nearest Neighbors + ''' nexus.max_iter = sizing_loop.maximum_iterations #used to pass it to constraints - nexus.update_method = sizing_loop.update_method - nexus.initial_step = sizing_loop.initial_step + + #nexus.sizing_loop = sizing_loop nexus = sizing_loop(nexus) return nexus @@ -132,12 +169,12 @@ def run_sizing_loop(nexus): # ---------------------------------------------------------------------- def simple_sizing(nexus): - from SUAVE.Methods.Geometry.Two_Dimensional.Planform import wing_planform + configs=nexus.vehicle_configurations analyses=nexus.analyses - m_guess=nexus.m_guess - Ereq=nexus.Ereq - Preq=nexus.Preq + m_guess=configs.base.m_guess + Ereq=configs.base.Ereq + Preq=configs.base.Preq # ------------------------------------------------------------------ # Define New Gross Takeoff Weight @@ -149,7 +186,7 @@ def simple_sizing(nexus): base.mass_properties.max_takeoff=m_guess base.mass_properties.max_zero_fuel=m_guess #just used for weight calculation Sref=m_guess/base.wing_loading - design_thrust=base.thrust_loading*m_guess*9.81 #four engines + design_thrust=base.thrust_loading*m_guess*9.81 mission=nexus.missions.base.segments @@ -249,6 +286,7 @@ def simple_sizing(nexus): return nexus def sizing_evaluation(y,nexus, scaling): + configs = nexus.vehicle_configurations #unpack inputs m_guess = y[0]*scaling[0] Ereq_guess = y[1]*scaling[1] @@ -260,9 +298,9 @@ def sizing_evaluation(y,nexus, scaling): print 'Preq_guess =', Preq_guess - nexus.m_guess = m_guess - nexus.Ereq = Ereq_guess - nexus.Preq = Preq_guess + configs.base.m_guess = m_guess + configs.base.Ereq = Ereq_guess + configs.base.Preq = Preq_guess configs = nexus.vehicle_configurations analyses = nexus.analyses @@ -294,9 +332,9 @@ def sizing_evaluation(y,nexus, scaling): - nexus.dm = dm - nexus.dE_total = dE_total - nexus.Preq = Preq_out + configs.base.dm = dm + configs.base.dE_total = dE_total + configs.base.Preq = Preq_out @@ -373,12 +411,10 @@ def evaluate_constraints(nexus): analyses=nexus.analyses mission=nexus.missions.base.segments - results=nexus.results - motor_power=nexus.Preq - print 'motor_power=', motor_power - print 'results.Pmax=', results.Pmax + results = nexus.results + motor_power = vehicle.Preq #make sure motor can handle power requirements - results.range_margin=results.total_range-nexus.target_range + results.power_margin=motor_power-results.Pmax #results.segments[-1].conditions.weights.total_mass[-1,0]+=abs(min(0, motor_power-results.Pmax)) #make sure there is some washout @@ -425,7 +461,7 @@ def evaluate_constraints(nexus): results.max_throttle_constraint=1-max_throttle - nexus.iteration_constraint=((nexus.max_iter-5)-nexus.number_of_iterations)/(1.*nexus.max_iter) #give it some slack to help constraints converge + nexus.iteration_constraint= nexus.sizing_loop.tolerance-nexus.sizing_loop.norm_error#((nexus.max_iter-5)-nexus.number_of_iterations)/(1.*nexus.max_iter) #give it some slack to help constraints converge return nexus @@ -472,19 +508,6 @@ def plot_mission(results,configs,line_style='bo-'): line_width = 1. - # ------------------------------------------------------------------ - # Throttle - # ------------------------------------------------------------------ - plt.figure("Throttle History") - axes = plt.gca() - for i in range(len(results.segments)): - time = results.segments[i].conditions.frames.inertial.time[:,0] / Units.min - eta = results.segments[i].conditions.propulsion.throttle[:,0] - axes.plot(time, eta, line_style) - axes.set_xlabel('Time (mins)') - axes.set_ylabel('Throttle') - axes.grid(True) - # ------------------------------------------------------------------ # Angle of Attack diff --git a/Lithium_Air_Sizing/Vehicle.py.py b/Lithium_Air_Sizing/Vehicle.py similarity index 99% rename from Lithium_Air_Sizing/Vehicle.py.py rename to Lithium_Air_Sizing/Vehicle.py index b9d06d0..b81ee58 100644 --- a/Lithium_Air_Sizing/Vehicle.py.py +++ b/Lithium_Air_Sizing/Vehicle.py @@ -48,7 +48,7 @@ def base_setup(): # basic parameters vehicle.reference_area = 100.0 - vehicle.thrust_loading =.25 + vehicle.thrust_loading =.2 vehicle.wing_loading = 400.*Units.kg/Units.m**2 vehicle.passengers = 114 vehicle.systems.control = "partially powered" From 2692654dba0cc8baf585a84d285e7de8b857001f Mon Sep 17 00:00:00 2001 From: jmvegh Date: Fri, 27 Jan 2017 10:29:10 -0800 Subject: [PATCH 3/7] some code cleanup --- Lithium_Air_Sizing/Mission.py | 6 +-- Lithium_Air_Sizing/Sizing.py | 80 ++++++++++++++++------------------- Lithium_Air_Sizing/Vehicle.py | 2 +- 3 files changed, 41 insertions(+), 47 deletions(-) diff --git a/Lithium_Air_Sizing/Mission.py b/Lithium_Air_Sizing/Mission.py index a04828d..3e4b3bf 100644 --- a/Lithium_Air_Sizing/Mission.py +++ b/Lithium_Air_Sizing/Mission.py @@ -100,7 +100,7 @@ def base(analyses): segment.analyses.extend( analyses.cruise ) - segment.altitude_end = 3. * Units.km + segment.altitude_end = 10. * Units.km segment.air_speed =140* Units['m/s'] segment.climb_rate = 3.0 * Units['m/s'] segment.state.numerics.tolerance_solution = sol_tol @@ -117,8 +117,8 @@ def base(analyses): segment.analyses.extend( analyses.cruise ) - segment.air_speed = 147.1479 * Units['m/s'] - segment.distance = 1000 * Units.nautical_miles + segment.air_speed = 230 * Units['m/s'] + segment.distance = 2000 * Units.nautical_miles segment.state.numerics.tolerance_solution = sol_tol mission.append_segment(segment) diff --git a/Lithium_Air_Sizing/Sizing.py b/Lithium_Air_Sizing/Sizing.py index e0d9810..9665778 100644 --- a/Lithium_Air_Sizing/Sizing.py +++ b/Lithium_Air_Sizing/Sizing.py @@ -100,15 +100,6 @@ def run_sizing_loop(nexus): analyses = nexus.analyses mission = nexus.missions.base - battery = configs.base.energy_network['battery'] - ducted_fan = configs.base.propulsors['ducted_fan'] - - #make it so all configs handle the exact same battery object - configs.cruise.energy_network['battery'] = battery - configs.takeoff.energy_network['battery'] = battery - configs.landing.energy_network['battery'] = battery - - #initial guesses @@ -116,9 +107,6 @@ def run_sizing_loop(nexus): Ereq_guess = 100000000000. Preq_guess= 200000. - - - #mass = [ m_guess ] scaling = np.array([1E4,1E9,1E6]) y = np.array([m_guess, Ereq_guess, Preq_guess])/scaling @@ -169,66 +157,72 @@ def run_sizing_loop(nexus): # ---------------------------------------------------------------------- def simple_sizing(nexus): + #unpack nexus + configs = nexus.vehicle_configurations + analyses = nexus.analyses + mission = nexus.missions.base.segments + airport = nexus.missions.base.airport + atmo = airport.atmosphere + + + #make it so all configs handle the exact same battery object + battery = configs.base.energy_network['battery'] + configs.cruise.energy_network['battery'] = battery + configs.takeoff.energy_network['battery'] = battery + configs.landing.energy_network['battery'] = battery - configs=nexus.vehicle_configurations - analyses=nexus.analyses + #unpack guesses m_guess=configs.base.m_guess Ereq=configs.base.Ereq Preq=configs.base.Preq -# ------------------------------------------------------------------ + # ------------------------------------------------------------------ # Define New Gross Takeoff Weight # ------------------------------------------------------------------ - #now add component weights to the gross takeoff weight of the vehicle - base = configs.base - #base.pull_base() - base.mass_properties.max_takeoff=m_guess - base.mass_properties.max_zero_fuel=m_guess #just used for weight calculation - Sref=m_guess/base.wing_loading - design_thrust=base.thrust_loading*m_guess*9.81 - - mission=nexus.missions.base.segments + base.mass_properties.max_takeoff = m_guess + base.mass_properties.max_zero_fuel = m_guess #just used for weight calculation + Sref = m_guess/base.wing_loading + design_thrust = base.thrust_loading*m_guess*9.81 - airport=nexus.missions.base.airport - atmo = airport.atmosphere - - + #assign area base.reference_area = Sref base.wings['main_wing'].areas.reference = base.reference_area - #determine geometry of fuselage as well as wings - fuselage=base.fuselages['fuselage'] + #determine geometry of fuselage, wing, and tail + fuselage = base.fuselages['fuselage'] SUAVE.Methods.Geometry.Two_Dimensional.Planform.fuselage_planform(fuselage) - fuselage.areas.side_projected = fuselage.heights.maximum*fuselage.lengths.cabin*1.1 # Not correct - base.wings['main_wing'] = wing_planform(base.wings['main_wing']) - base.wings['horizontal_stabilizer'] = wing_planform(base.wings['horizontal_stabilizer']) + fuselage.areas.side_projected = fuselage.heights.maximum*fuselage.lengths.cabin*1.1 #guess + #create wing platforms based on geometry + base.wings['main_wing'] = wing_planform(base.wings['main_wing']) + base.wings['horizontal_stabilizer'] = wing_planform(base.wings['horizontal_stabilizer']) base.wings['vertical_stabilizer'] = wing_planform(base.wings['vertical_stabilizer']) + #calculate position of horizontal stabilizer - base.wings['horizontal_stabilizer'].aerodynamic_center[0]= base.w2h- \ + base.wings['horizontal_stabilizer'].aerodynamic_center[0] = base.w2h- \ (base.wings['horizontal_stabilizer'].origin[0] + \ base.wings['horizontal_stabilizer'].aerodynamic_center[0] - \ base.wings['main_wing'].origin[0] - base.wings['main_wing'].aerodynamic_center[0]) - #wing areas + + #wing areas based on correlations for wing in base.wings: wing.areas.wetted = 2.00 * wing.areas.reference wing.areas.affected = 0.60 * wing.areas.reference wing.areas.exposed = 0.75 * wing.areas.wetted - #compute conditions for aircraft sizing - cruise_altitude= mission['climb_3'].altitude_end - - conditions = atmo.compute_values(cruise_altitude) + #compute conditions for aircraft propulsor sizing + cruise_altitude = mission['climb_3'].altitude_end + conditions = atmo.compute_values(cruise_altitude) conditions.velocity = mission['cruise'].air_speed + mach_number = conditions.velocity/conditions.speed_of_sound - mach_number = conditions.velocity/conditions.speed_of_sound - + # assign conditions conditions.mach_number = mach_number conditions.gravity = 9.81 - prop_conditions=SUAVE.Analyses.Mission.Segments.Conditions.Aerodynamics() #assign conditions in form for propulsor sizing - prop_conditions.freestream=conditions + prop_conditions = SUAVE.Analyses.Mission.Segments.Conditions.Aerodynamics() #assign conditions in form for propulsor sizing + prop_conditions.freestream = conditions conditions0 = atmo.compute_values(12500.*Units.ft) #cabin pressure diff --git a/Lithium_Air_Sizing/Vehicle.py b/Lithium_Air_Sizing/Vehicle.py index b81ee58..c1ed9cf 100644 --- a/Lithium_Air_Sizing/Vehicle.py +++ b/Lithium_Air_Sizing/Vehicle.py @@ -295,7 +295,7 @@ def base_setup(): state.numerics = numerics ''' mach_number =0.729 - altitude = 7*Units.km + altitude = 30000*Units.ft ducted_fan.number_of_engines = 2.0 ducted_fan_sizing(ducted_fan, mach_number, altitude) #calling the engine sizing method From 50a1fb7e67ccc2312b2ee80ce5aa6ae35019a649 Mon Sep 17 00:00:00 2001 From: jmvegh Date: Fri, 27 Jan 2017 10:54:43 -0800 Subject: [PATCH 4/7] some more code cleanup --- Lithium_Air_Sizing/Sizing.py | 159 +++++++++++++++-------------------- 1 file changed, 69 insertions(+), 90 deletions(-) diff --git a/Lithium_Air_Sizing/Sizing.py b/Lithium_Air_Sizing/Sizing.py index 9665778..d232346 100644 --- a/Lithium_Air_Sizing/Sizing.py +++ b/Lithium_Air_Sizing/Sizing.py @@ -158,28 +158,32 @@ def run_sizing_loop(nexus): def simple_sizing(nexus): #unpack nexus - configs = nexus.vehicle_configurations - analyses = nexus.analyses - mission = nexus.missions.base.segments - airport = nexus.missions.base.airport - atmo = airport.atmosphere - - + configs = nexus.vehicle_configurations + analyses = nexus.analyses + mission = nexus.missions.base.segments + airport = nexus.missions.base.airport + atmo = airport.atmosphere + base = configs.base + ducted_fan =base.propulsors['ducted_fan'] + battery = base.energy_network['battery'] + fuselage = base.fuselages['fuselage'] + #make it so all configs handle the exact same battery object - battery = configs.base.energy_network['battery'] + configs.cruise.energy_network['battery'] = battery configs.takeoff.energy_network['battery'] = battery configs.landing.energy_network['battery'] = battery + #unpack guesses - m_guess=configs.base.m_guess - Ereq=configs.base.Ereq - Preq=configs.base.Preq + m_guess = base.m_guess + Ereq = base.Ereq + Preq = base.Preq # ------------------------------------------------------------------ # Define New Gross Takeoff Weight # ------------------------------------------------------------------ - base = configs.base + base.mass_properties.max_takeoff = m_guess base.mass_properties.max_zero_fuel = m_guess #just used for weight calculation Sref = m_guess/base.wing_loading @@ -190,7 +194,6 @@ def simple_sizing(nexus): base.wings['main_wing'].areas.reference = base.reference_area #determine geometry of fuselage, wing, and tail - fuselage = base.fuselages['fuselage'] SUAVE.Methods.Geometry.Two_Dimensional.Planform.fuselage_planform(fuselage) fuselage.areas.side_projected = fuselage.heights.maximum*fuselage.lengths.cabin*1.1 #guess @@ -218,48 +221,42 @@ def simple_sizing(nexus): mach_number = conditions.velocity/conditions.speed_of_sound # assign conditions - conditions.mach_number = mach_number - conditions.gravity = 9.81 - - prop_conditions = SUAVE.Analyses.Mission.Segments.Conditions.Aerodynamics() #assign conditions in form for propulsor sizing - prop_conditions.freestream = conditions - - - conditions0 = atmo.compute_values(12500.*Units.ft) #cabin pressure - p0 = conditions0.pressure - fuselage_diff_pressure=max(conditions0.pressure-conditions.pressure,0) + conditions.mach_number = mach_number + conditions.gravity = 9.81 + prop_conditions = SUAVE.Analyses.Mission.Segments.Conditions.Aerodynamics() #assign conditions in form for propulsor sizing + prop_conditions.freestream = conditions + conditions0 = atmo.compute_values(12500.*Units.ft) #cabin pressure + p0 = conditions0.pressure + fuselage_diff_pressure = max(conditions0.pressure-conditions.pressure,0) fuselage.differential_pressure = fuselage_diff_pressure - - battery =base.energy_network['battery'] - ducted_fan=base.propulsors['ducted_fan'] + + # battery calcs SUAVE.Methods.Power.Battery.Sizing.initialize_from_energy_and_power(battery,Ereq,Preq, max='soft') - battery.current_energy=[battery.max_energy] #initialize list of current energy - - - m_air =SUAVE.Methods.Power.Battery.Variable_Mass.find_total_mass_gain(battery) + battery.current_energy = [battery.max_energy] #initialize list of current energy + m_air =SUAVE.Methods.Power.Battery.Variable_Mass.find_total_mass_gain(battery) #now add the electric motor weight - motor_mass=ducted_fan.number_of_engines*SUAVE.Methods.Weights.Correlations.Propulsion.air_cooled_motor((Preq)*Units.watts/ducted_fan.number_of_engines,.1783, .9884 ) - propulsion_mass=SUAVE.Methods.Weights.Correlations.Propulsion.integrated_propulsion(motor_mass/ducted_fan.number_of_engines,ducted_fan.number_of_engines) - + motor_mass = ducted_fan.number_of_engines*SUAVE.Methods.Weights.Correlations.Propulsion.air_cooled_motor((Preq)*Units.watts/ducted_fan.number_of_engines,.1783, .9884 ) + propulsion_mass = SUAVE.Methods.Weights.Correlations.Propulsion.integrated_propulsion(motor_mass/ducted_fan.number_of_engines,ducted_fan.number_of_engines) ducted_fan.mass_properties.mass = propulsion_mass ducted_fan.thrust.total_design = design_thrust + #compute geometries ducted_fan_sizing(ducted_fan, mach_number,cruise_altitude) compute_ducted_fan_geometry(ducted_fan, conditions = prop_conditions) - # --------------------------- - breakdown = analyses.base.weights.evaluate() - #breakdown = analyses.configs.base.weights.evaluate() - breakdown.battery=battery.mass_properties.mass - breakdown.air=m_air - base.mass_properties.breakdown=breakdown - m_fuel=0. - #print breakdown - base.mass_properties.operating_empty = breakdown.empty - m_full=breakdown.empty+battery.mass_properties.mass+breakdown.payload - m_end=m_full+m_air - base.mass_properties.takeoff = m_full + #evaluate total mass breakdown + breakdown = analyses.base.weights.evaluate() + breakdown.battery = battery.mass_properties.mass + breakdown.air = m_air + base.mass_properties.breakdown = breakdown + m_fuel = 0. + base.mass_properties.operating_empty = breakdown.empty + + #m_full = GTOW, m_end = GLW + m_full = breakdown.empty+battery.mass_properties.mass+breakdown.payload + m_end = m_full+m_air + base.mass_properties.takeoff = m_full base.store_diff() # Update all configs with new base data @@ -267,40 +264,33 @@ def simple_sizing(nexus): config.pull_base() - ############################################################################## - # ------------------------------------------------------------------ - # Define Configurations - # ------------------------------------------------------------------ - landing_config=configs.landing - landing_config.wings['main_wing'].flaps.angle = 20. * Units.deg - landing_config.wings['main_wing'].slats.angle = 25. * Units.deg - landing_config.mass_properties.landing = m_end - landing_config.store_diff() - + return nexus def sizing_evaluation(y,nexus, scaling): - configs = nexus.vehicle_configurations + #unpack inputs - m_guess = y[0]*scaling[0] - Ereq_guess = y[1]*scaling[1] - Preq_guess = y[2]*scaling[2] + m_guess = y[0]*scaling[0] + Ereq_guess = y[1]*scaling[1] + Preq_guess = y[2]*scaling[2] - + #print guesses print 'm_guess =', m_guess print 'Ereq_guess =', Ereq_guess print 'Preq_guess =', Preq_guess - - configs.base.m_guess = m_guess - configs.base.Ereq = Ereq_guess - configs.base.Preq = Preq_guess - + #unpack guesses configs = nexus.vehicle_configurations analyses = nexus.analyses mission = nexus.missions.base battery = configs.base.energy_network['battery'] + #assing guesses to aircraft + configs.base.m_guess = m_guess + configs.base.Ereq = Ereq_guess + configs.base.Preq = Preq_guess + + #run size aircraft geometry/mass based on buess simple_sizing(nexus) analyses.finalize() #wont run without this @@ -310,37 +300,26 @@ def sizing_evaluation(y,nexus, scaling): #handle outputs - mass_out = results.segments[-1].conditions.weights.total_mass[-1,0] - Ereq_out = results.e_total - Preq_out = results.Pmax + mass_out = results.segments[-1].conditions.weights.total_mass[-1,0] #actual landing weight + Ereq_out = results.e_total + Preq_out = results.Pmax + + #errors + dm = (mass_out-m_guess)/m_guess + dE_total = (Ereq_out-Ereq_guess)/Ereq_guess + dPower = (Preq_out-Preq_guess)/Preq_guess - - dm = (mass_out-m_guess)/m_guess - dE_total = (Ereq_out-Ereq_guess)/Ereq_guess - dPower = (Preq_out-Preq_guess)/Preq_guess + #pack up results + nexus.results = results - #err=(np.abs(dm)+np.abs(dE_primary)+np.abs(dE_auxiliary))/3. - #err=(np.abs(dE_primary)+np.abs(dE_auxiliary))/2. - #err = np.abs(dE_auxiliary) - #handle weird problem where one of the battery energies is ~0; use total energy - - - - configs.base.dm = dm - configs.base.dE_total = dE_total - configs.base.Preq = Preq_out - - - - nexus.results = results #pack up results - - f = np.array([dm, dE_total, dPower]) + # return it to sizing loop (within SUAVE/Sizing/Sizing_Loop.py + f = np.array([dm, dE_total, dPower]) y_out = np.array([mass_out, Ereq_out, Preq_out ])/scaling + + #print sizing print 'y=', y print 'y_out=', y_out - print 'scaling=', scaling print 'f=', f - print 'number_of_surrogate_calls ', nexus.sizing_loop.iteration_options.number_of_surrogate_calls return f, y_out # ---------------------------------------------------------------------- From 78f8229d5043957d32c4ed14e9f646b64aa73fae Mon Sep 17 00:00:00 2001 From: jmvegh Date: Fri, 27 Jan 2017 12:18:01 -0800 Subject: [PATCH 5/7] some more code cleanup --- Lithium_Air_Sizing/Sizing.py | 57 ++++++++++++++++-------------------- 1 file changed, 26 insertions(+), 31 deletions(-) diff --git a/Lithium_Air_Sizing/Sizing.py b/Lithium_Air_Sizing/Sizing.py index d232346..3f36a1d 100644 --- a/Lithium_Air_Sizing/Sizing.py +++ b/Lithium_Air_Sizing/Sizing.py @@ -125,25 +125,18 @@ def run_sizing_loop(nexus): sizing_loop.min_y = min_y sizing_loop.max_y = max_y sizing_loop.default_scaling = scaling - + sizing_loop.sizing_evaluation = sizing_evaluation sizing_loop.maximum_iterations = 50 sizing_loop.write_threshhold = 50. - sizing_loop.output_filename = 'sizing_outputs.txt' - sizing_loop.sizing_evaluation = sizing_evaluation + sizing_loop.output_filename = 'sizing_outputs.txt' #used if you run optimization + + sizing_loop.iteration_options.h = 1E-6 sizing_loop.iteration_options.min_fix_point_iterations = 2 sizing_loop.iteration_options.initialize_jacobian = 'newton-raphson' #approximate #option for Broyden's Method, not used here - ''' - #option if using surrogates to inform your initial guess - sizing_loop.iteration_options.max_newton_raphson_tolerance = nexus.tol*2 #threshhold at which to switch to successive substitution (to prevent overshooting) - sizing_loop.iteration_options.min_surrogate_length = 3 #default - sizing_loop.iteration_options.min_surrogate_step = .03 - sizing_loop.iteration_options.min_write_step = .011#default - sizing_loop.iteration_options.n_neighbors = 5 - sizing_loop.iteration_options.neighbors_weighted_distance = True #option for using K Nearest Neighbors - ''' + nexus.max_iter = sizing_loop.maximum_iterations #used to pass it to constraints @@ -168,27 +161,26 @@ def simple_sizing(nexus): battery = base.energy_network['battery'] fuselage = base.fuselages['fuselage'] - #make it so all configs handle the exact same battery object + #unpack guesses + m_guess = base.m_guess + Ereq = base.Ereq + Preq = base.Preq + #make it so all configs handle the exact same battery object configs.cruise.energy_network['battery'] = battery configs.takeoff.energy_network['battery'] = battery configs.landing.energy_network['battery'] = battery - #unpack guesses - m_guess = base.m_guess - Ereq = base.Ereq - Preq = base.Preq - # ------------------------------------------------------------------ # Define New Gross Takeoff Weight # ------------------------------------------------------------------ base.mass_properties.max_takeoff = m_guess base.mass_properties.max_zero_fuel = m_guess #just used for weight calculation - Sref = m_guess/base.wing_loading design_thrust = base.thrust_loading*m_guess*9.81 - + Sref = m_guess/base.wing_loading + #assign area base.reference_area = Sref base.wings['main_wing'].areas.reference = base.reference_area @@ -285,15 +277,14 @@ def sizing_evaluation(y,nexus, scaling): mission = nexus.missions.base battery = configs.base.energy_network['battery'] - #assing guesses to aircraft + #assign guesses to aircraft configs.base.m_guess = m_guess configs.base.Ereq = Ereq_guess configs.base.Preq = Preq_guess - #run size aircraft geometry/mass based on buess + #run size aircraft geometry/mass based on guess simple_sizing(nexus) analyses.finalize() #wont run without this - results = evaluate_mission(configs,mission) @@ -359,14 +350,18 @@ def evaluate_mission(configs,mission): max_alpha[i]=max(aoa) min_alpha[i]=min(aoa) - max_alpha = max(max_alpha) - min_alpha = min(min_alpha) - total_range=results.segments[-1].conditions.frames.inertial.position_vector[-1,0] - results.total_range=total_range - results.e_total=results.segments[0].conditions.propulsion.battery_energy[0,0]-e_current_min - results.Pmax=Pmax - results.max_alpha=max_alpha - results.min_alpha=min_alpha + max_alpha = max(max_alpha) + min_alpha = min(min_alpha) + total_range = results.segments[-1].conditions.frames.inertial.position_vector[-1,0] + + #pack up results + results.total_range = total_range + results.e_total = results.segments[0].conditions.propulsion.battery_energy[0,0]-e_current_min + results.Pmax = Pmax + results.max_alpha = max_alpha + results.min_alpha = min_alpha + + #print to make sure it's working correctly print 'e_current_min=',e_current_min print "e_total=", results.e_total print "Pmax=", Pmax From b7f35e28b43f96a2f9ed583b3926d7bef9fa6813 Mon Sep 17 00:00:00 2001 From: jmvegh Date: Fri, 27 Jan 2017 15:41:39 -0800 Subject: [PATCH 6/7] added Optimize.py and Plot_Mission.py --- Lithium_Air_Sizing/Mission.py | 4 +- Lithium_Air_Sizing/Optimize.py | 204 +++++++++++++++++++++++ Lithium_Air_Sizing/Plot_Mission.py | 227 ++++++++++++++++++++++++++ Lithium_Air_Sizing/Sizing.py | 253 ++--------------------------- Lithium_Air_Sizing/Vehicle.py | 16 +- 5 files changed, 448 insertions(+), 256 deletions(-) create mode 100644 Lithium_Air_Sizing/Optimize.py create mode 100644 Lithium_Air_Sizing/Plot_Mission.py diff --git a/Lithium_Air_Sizing/Mission.py b/Lithium_Air_Sizing/Mission.py index 3e4b3bf..62ad52b 100644 --- a/Lithium_Air_Sizing/Mission.py +++ b/Lithium_Air_Sizing/Mission.py @@ -1,6 +1,6 @@ # Missions.py # -# Created: May 2015, T. Lukaczyk +# Created: Jan 2017, M. Vegh # Modified: @@ -84,7 +84,7 @@ def base(analyses): segment.analyses.extend( analyses.cruise ) segment.altitude_end = 2.0 * Units.km - segment.air_speed = 80.* Units['m/s'] + segment.air_speed = 100.* Units['m/s'] segment.climb_rate = 6.0 * Units['m/s'] segment.state.numerics.tolerance_solution = sol_tol # add to mission diff --git a/Lithium_Air_Sizing/Optimize.py b/Lithium_Air_Sizing/Optimize.py new file mode 100644 index 0000000..f9e63cc --- /dev/null +++ b/Lithium_Air_Sizing/Optimize.py @@ -0,0 +1,204 @@ +# Optimize.py +# +# Created: Jan 2017, M. Vegh +# Modified: + +# ---------------------------------------------------------------------- +# Imports +# ---------------------------------------------------------------------- + +import SUAVE +from SUAVE.Core import Units, Data +import numpy as np +import Vehicle +import Analyses +import Mission +import Sizing as Procedure +import Plot_Mission +from SUAVE.Optimization.Nexus import Nexus +import SUAVE.Optimization.Package_Setups.pyopt_setup as pyopt_setup +from SUAVE.Sizing.Sizing_Loop import Sizing_Loop +# ---------------------------------------------------------------------- +# Run the whole thing +# ---------------------------------------------------------------------- +def main(): + + problem = setup() + + output = pyopt_setup.Pyopt_Solve(problem, sense_step = 1E-2, solver='SNOPT') + print output + + Plot_Mission.plot_mission(problem) + + + return + +# ---------------------------------------------------------------------- +# Inputs, Objective, & Constraints +# ---------------------------------------------------------------------- + +def setup(): + + nexus = Nexus() + problem = Data() + nexus.optimization_problem = problem + nexus.sizing_loop = Sizing_Loop() + + # ------------------------------------------------------------------- + # Inputs + # ------------------------------------------------------------------- + + # [ tag , initial, [lb,ub], scaling, units ] + problem.inputs = np.array([ + [ 'thrust_loading' , .2 , (.05 , .3 ) , .1, 'continuous', Units.less], + [ 'fan_pressure_ratio' , 1.5 , (1.05 , 2.6 ) , 1., 'continuous', Units.less], + #[ 'aspect_ratio' , 14. , (5. , 14. ) , 10., 'continuous', Units.less], + [ 'wing_loading' , 400. , (200. , 800. ) , 100.,'continuous', Units.kg/Units.meter**2.], + #[ 'taper' , 0.1000 , (.1 , .3 ) , .1, 'continuous', Units.less ], + [ 'wing_thickness' , .105 , (0.07 , 0.20 ) , .1, 'continuous', Units.less ], + [ 'v_climb_1' , 80. , (50. , 230. ) , 1E2, 'continuous', Units.meter/Units.second], + [ 'v_climb_2' , 100. , (50. , 230 ) , 1E2, 'continuous', Units.meter/Units.second], + [ 'v_climb_3' , 140 , (50. , 230 ) , 1E2, 'continuous', Units.meter/Units.second], + [ 'cruise_altitude' , 33000. , (20000. , 35000 ) , 1E4, 'continuous', Units.ft], + [ 'climb_alt_fraction_1' , 0.1 , (.1 , 1. ) , 1., 'continuous', Units.less], + [ 'climb_alt_fraction_2' , .2 , (.2 , 1. ) , 1., 'continuous', Units.less], + [ 'descent_alt_fraction_1' , .2 , (.1 , 1. ) , 1., 'continuous', Units.less], + ]) + + + + + + + # ------------------------------------------------------------------- + # Objective + # ------------------------------------------------------------------- + + # throw an error if the user isn't specific about wildcards + # [ tag, scaling, units ] + problem.objective = np.array([ + [ 'landing_weight', 1E4, Units.kg ] + ]) + + + # ------------------------------------------------------------------- + # Constraints + # ------------------------------------------------------------------- + + # [ tag, sense, edge, scaling, units ] + + problem.constraints = np.array([ + #[ 'power_margin' , '>', 0 , 1E6 , Units.meters], + #['lithium_ion_energy_margin' , '>', 0 , 1E0 , Units.less], + [ 'climb_constraint_1' , '>', 0 , 1E2 , Units.meters], + [ 'climb_constraint_2' , '>', 0 , 1E3 , Units.meters], #handled by bounds + [ 'descent_constraint_1' , '>', 0 , 1E2 , Units.meters], + [ 'min_alpha_constraint' , '>', 0 , 1E1 , Units.degrees], + [ 'max_alpha_constraint' , '>', 0 , 1E1 , Units.degrees], + [ 'takeoff_field_constraint' , '>', 0 , 1E3 , Units.ft], + [ 'landing_field_constraint' , '>', 0 , 1E3 , Units.ft], + [ 'max_throttle_constraint' , '>', 0 , 1 , Units.less], + ['climb_velocity_constraint_1' , '>', 0 , 1E2 , Units.meters/Units.second], + ['climb_velocity_constraint_2' , '>', 0 , 1E2 , Units.meters/Units.second], + [ 'iteration_constraint' , '>', 0 , 1 , Units.less], + + ]) + + ''' + problem.constraints = np.array([ + [ 'power_margin' , '>', 0 , 1E6 , Units.meters], + #[ 'range_margin' , '>', 0 , 1E6 , Units.meters], + [ 'washout' , '>', 0 , 1E0 , Units.radians], + [ 'climb_constraint_1' , '>', 0 , 1E3 , Units.km], + [ 'climb_constraint_2' , '>', 0 , 1E3 , Units.km], + [ 'climb_constraint_3' , '>', 0 , 1E3 , Units.km], + [ 'climb_constraint_4' , '>', 0 , 1E3 , Units.km], + [ 'descent_constraint_1' , '>', 0 , 1E3 , Units.km], + [ 'descent_constraint_2' , '>', 0 , 1E3 , Units.km], + [ 'min_alpha_constraint' , '>', 0 , 1E1 , Units.degrees], + [ 'max_alpha_constraint' , '>', 0 , 1E1 , Units.degrees], + #[ 'takeoff_field_constraint' , '>', 0 , 1E3 , Units.ft], + #[ 'landing_field_constraint' , '>', 0 , 1E3 , Units.ft], + + ]) + ''' + # ------------------------------------------------------------------- + # Aliases + # ------------------------------------------------------------------- + + # [ 'alias' , ['data.path1.name','data.path2.name'] ] + + problem.aliases = [ + #Inputs + + + [ 'thrust_loading' , 'vehicle_configurations.*.thrust_loading' ], + [ 'fan_pressure_ratio' , 'vehicle_configurations.*.energy_network.propulsor.fan.pressure_ratio'], + + [ 'aspect_ratio' , 'vehicle_configurations.*.wings.main_wing.aspect_ratio' ], + + [ 'wing_loading' , 'vehicle_configurations.*.wing_loading'], + [ 'wing_thickness' , 'vehicle_configurations.*.wings.main_wing.thickness_to_chord'], + [ 'taper' , 'vehicle_configurations.*.wings.main_wing.taper'], + + [ 'climb_alt_fraction_1' , 'missions.base.climb_alt_fraction_1'], + [ 'climb_alt_fraction_2' , 'missions.base.climb_alt_fraction_2'], + [ 'descent_alt_fraction_1' , 'missions.base.descent_alt_fraction_1' ], + [ 'cruise_altitude' , 'missions.base.segments.climb_3.altitude_end' ], + [ 'v_climb_1' , 'missions.base.segments.climb_1.air_speed'], + [ 'v_climb_2' , 'missions.base.segments.climb_2.air_speed'], + [ 'v_climb_3' , 'missions.base.segments.climb_3.air_speed'], + + + #outputs + [ 'landing_weight' , 'results.segments[-1].conditions.weights.total_mass[-1,0]' ], + [ 'total_range' , 'results.total_range' ], + [ 'max_power' , 'results.Pmax' ], + + #constraints + [ 'max_throttle_constraint' , 'results.max_throttle_constraint' ], + [ 'climb_constraint_1' , 'results.climb_constraint_1' ], + [ 'climb_constraint_2' , 'results.climb_constraint_2' ], + [ 'descent_constraint_1' , 'results.descent_constraint_1' ], + [ 'max_alpha_constraint' , 'results.max_alpha_constraint' ], + [ 'min_alpha_constraint' , 'results.min_alpha_constraint' ], + [ 'takeoff_field_constraint' , 'results.takeoff_field_constraint' ], + [ 'landing_field_constraint' , 'results.landing_field_constraint' ], + [ 'cost_constraint' , 'results.cost_constraint' ], + [ 'climb_velocity_constraint_1' , 'results.climb_velocity_constraint_1' ], + [ 'climb_velocity_constraint_2' , 'results.climb_velocity_constraint_2' ], + [ 'iteration_constraint' , 'iteration_constraint'], + + ] + + # ------------------------------------------------------------------- + # Vehicles + # ------------------------------------------------------------------- + nexus.vehicle_configurations = Vehicle.setup() + + + # ------------------------------------------------------------------- + # Analyses + # ------------------------------------------------------------------- + nexus.analyses = Analyses.setup(nexus.vehicle_configurations) + + + # ------------------------------------------------------------------- + # Missions + # ------------------------------------------------------------------- + nexus.missions = Mission.setup(nexus.analyses) + + + # ------------------------------------------------------------------- + # Procedure + # ------------------------------------------------------------------- + nexus.procedure = Procedure.setup() + nexus.total_number_of_iterations = 0 + + return nexus + + +if __name__ == '__main__': + main() + + diff --git a/Lithium_Air_Sizing/Plot_Mission.py b/Lithium_Air_Sizing/Plot_Mission.py new file mode 100644 index 0000000..d97c37a --- /dev/null +++ b/Lithium_Air_Sizing/Plot_Mission.py @@ -0,0 +1,227 @@ +# Plot_Mission.py +# +# Created: May 2015, E. Botero +# Modified: + +# ---------------------------------------------------------------------- +# Imports +# ---------------------------------------------------------------------- + +import SUAVE +from SUAVE.Core import Units + +import pylab as plt + +# ---------------------------------------------------------------------- +# Plot Mission +# ---------------------------------------------------------------------- + +def plot_mission(nexus,line_style='bo-'): + results=nexus.results + vehicle=nexus.vehicle_configurations.base + battery=vehicle.energy_network['battery'] + line_width=2 + axis_font = {'fontname':'Arial', 'size':'14'} + + # ------------------------------------------------------------------ + # Aerodynamics + # ------------------------------------------------------------------ + + + fig = plt.figure("Aerodynamic Forces",figsize=(8,6)) + for segment in results.segments.values(): + + time = segment.conditions.frames.inertial.time[:,0] / Units.min + Lift = -segment.conditions.frames.wind.lift_force_vector[:,2] + Drag = -segment.conditions.frames.wind.drag_force_vector[:,0] / Units.lbf + Thrust = segment.conditions.frames.body.thrust_force_vector[:,0] / Units.lbf + eta = segment.conditions.propulsion.throttle[:,0] + mdot = segment.conditions.weights.vehicle_mass_rate[:,0] + thrust = segment.conditions.frames.body.thrust_force_vector[:,0] + sfc = 3600. * mdot / 0.1019715 / thrust + + + axes = fig.add_subplot(2,1,1) + axes.plot( time , Thrust , line_style ) + axes.set_ylabel('Thrust (lbf)',axis_font) + axes.grid(True) + + axes = fig.add_subplot(2,1,2) + axes.plot( time , sfc , line_style ) + axes.set_xlabel('Time (min)',axis_font) + axes.set_ylabel('sfc (lb/lbf-hr)',axis_font) + axes.grid(True) + + + # ------------------------------------------------------------------ + # Aerodynamics 2 + # ------------------------------------------------------------------ + fig = plt.figure("Aerodynamic Coefficients",figsize=(8,10)) + for segment in results.segments.values(): + + time = segment.conditions.frames.inertial.time[:,0] / Units.min + CLift = segment.conditions.aerodynamics.lift_coefficient[:,0] + CDrag = segment.conditions.aerodynamics.drag_coefficient[:,0] + Drag = -segment.conditions.frames.wind.drag_force_vector[:,0] + Thrust = segment.conditions.frames.body.thrust_force_vector[:,0] + aoa = segment.conditions.aerodynamics.angle_of_attack[:,0] / Units.deg + l_d = CLift/CDrag + + + axes = fig.add_subplot(3,1,1) + axes.plot( time , CLift , line_style ) + axes.set_ylabel('Lift Coefficient',axis_font) + axes.grid(True) + + axes = fig.add_subplot(3,1,2) + axes.plot( time , l_d , line_style ) + axes.set_ylabel('L/D',axis_font) + axes.grid(True) + + axes = fig.add_subplot(3,1,3) + axes.plot( time , aoa , 'ro-' ) + axes.set_xlabel('Time (min)',axis_font) + axes.set_ylabel('AOA (deg)',axis_font) + axes.grid(True) + + # ------------------------------------------------------------------ + # Aerodynamics 2 + # ------------------------------------------------------------------ + fig = plt.figure("Drag Components",figsize=(8,10)) + axes = plt.gca() + for i, segment in enumerate(results.segments.values()): + + time = segment.conditions.frames.inertial.time[:,0] / Units.min + drag_breakdown = segment.conditions.aerodynamics.drag_breakdown + cdp = drag_breakdown.parasite.total[:,0] + cdi = drag_breakdown.induced.total[:,0] + cdc = drag_breakdown.compressible.total[:,0] + cdm = drag_breakdown.miscellaneous.total[:,0] + cd = drag_breakdown.total[:,0] + + if line_style == 'bo-': + axes.plot( time , cdp , 'ko-', label='CD parasite' ) + axes.plot( time , cdi , 'bo-', label='CD induced' ) + axes.plot( time , cdc , 'go-', label='CD compressibility' ) + axes.plot( time , cdm , 'yo-', label='CD miscellaneous' ) + axes.plot( time , cd , 'ro-', label='CD total' ) + if i == 0: + axes.legend(loc='upper center') + else: + axes.plot( time , cdp , line_style ) + axes.plot( time , cdi , line_style ) + axes.plot( time , cdc , line_style ) + axes.plot( time , cdm , line_style ) + axes.plot( time , cd , line_style ) + + axes.set_xlabel('Time (min)') + axes.set_ylabel('CD') + axes.grid(True) + + # ------------------------------------------------------------------ + # Altitude, sfc, vehicle weight + # ------------------------------------------------------------------ + + fig = plt.figure("Battery outputs",figsize=(8,10)) + for segment in results.segments.values(): + + time = segment.conditions.frames.inertial.time[:,0] / Units.min + CLift = segment.conditions.aerodynamics.lift_coefficient[:,0] + CDrag = segment.conditions.aerodynamics.drag_coefficient[:,0] + Drag = -segment.conditions.frames.wind.drag_force_vector[:,0] + Thrust = segment.conditions.frames.body.thrust_force_vector[:,0] + aoa = segment.conditions.aerodynamics.angle_of_attack[:,0] / Units.deg + l_d = CLift/CDrag + mass = segment.conditions.weights.total_mass[:,0] / Units.lb + altitude = segment.conditions.freestream.altitude[:,0] / Units.ft + mdot = segment.conditions.weights.vehicle_mass_rate[:,0] + thrust = segment.conditions.frames.body.thrust_force_vector[:,0] + sfc = 3600. * mdot / 0.1019715 / thrust + + axes = fig.add_subplot(3,1,1) + axes.plot( time , altitude , line_style ) + axes.set_ylabel('Altitude (ft)',axis_font) + axes.grid(True) + + axes = fig.add_subplot(3,1,3) + axes.plot( time , sfc , line_style ) + axes.set_xlabel('Time (min)',axis_font) + axes.set_ylabel('sfc (lb/lbf-hr)',axis_font) + axes.grid(True) + + axes = fig.add_subplot(3,1,2) + axes.plot( time , mass , 'ro-' ) + axes.set_ylabel('Weight (lb)',axis_font) + axes.grid(True) + + fig = plt.figure("Electric Aircraft Outputs",figsize=(8,10)) + line_width=2 + for segment in results.segments.values(): + + time = segment.conditions.frames.inertial.time[:,0] / Units.min + mass = segment.conditions.weights.total_mass[:,0] + + axes = fig.add_subplot(3,1,1) + axes.plot( time , mass , line_style , lw=line_width ) + axes.set_ylabel('Vehicle Mass (kg)') + axes.grid(True) + + try: + battery=configs.base.energy_network['battery'] + state_of_charge=segment.conditions.propulsion.battery_energy/battery.max_energy + + battery_power=-segment.conditions.propulsion.battery_draw/Units.MW + except: + continue + + axes = fig.add_subplot(3,1,2) + axes.plot( time , state_of_charge , line_style , lw=line_width ) + axes.set_ylabel('State of Charge (-)') + axes.set_ylim([-0.005,1.005]) + axes.grid(True) + + axes = fig.add_subplot(3,1,3) + axes.plot( time , battery_power , line_style , lw=line_width ) + axes.set_xlabel('Time (min)') + axes.set_ylabel('Discharge Power (MW)') + axes.grid(True) + + fig = plt.figure("Electric Aircraft Outputs",figsize=(8,10)) + + for segment in results.segments.values(): + + time = segment.conditions.frames.inertial.time[:,0] / Units.min + mass = segment.conditions.weights.total_mass[:,0] + + axes = fig.add_subplot(3,1,1) + axes.plot( time , mass , line_style , lw=line_width ) + axes.set_ylabel('Vehicle Mass (kg)') + axes.grid(True) + + + state_of_charge=segment.conditions.propulsion.battery_energy/battery.max_energy + + battery_power=-segment.conditions.propulsion.battery_draw/Units.MW + + + axes = fig.add_subplot(3,1,2) + axes.plot( time , state_of_charge , line_style , lw=line_width ) + axes.set_ylabel('State of Charge (-)') + axes.set_ylim([-0.005,1.005]) + axes.grid(True) + + axes = fig.add_subplot(3,1,3) + axes.plot( time , battery_power , line_style , lw=line_width ) + axes.set_xlabel('Time (min)') + axes.set_ylabel('Discharge Power (MW)') + axes.grid(True) + + + plt.show(block=True) + + + return + +if __name__ == '__main__': + main() + plt.show() \ No newline at end of file diff --git a/Lithium_Air_Sizing/Sizing.py b/Lithium_Air_Sizing/Sizing.py index 3f36a1d..5777459 100644 --- a/Lithium_Air_Sizing/Sizing.py +++ b/Lithium_Air_Sizing/Sizing.py @@ -23,8 +23,9 @@ import Vehicle import Analyses import Mission +import Plot_Mission + -from SUAVE.Optimization.Nexus import Nexus from SUAVE.Analyses.Process import Process from SUAVE.Methods.Performance import estimate_take_off_field_length from SUAVE.Methods.Performance import estimate_landing_field_length @@ -32,7 +33,8 @@ from SUAVE.Methods.Geometry.Two_Dimensional.Planform import wing_planform from SUAVE.Methods.Propulsion.ducted_fan_sizing import ducted_fan_sizing from SUAVE.Sizing.Sizing_Loop import Sizing_Loop - +from SUAVE.Optimization.Nexus import Nexus +from SUAVE.Optimization.write_optimization_outputs import write_optimization_outputs from SUAVE.Methods.Geometry.Two_Dimensional.Cross_Section.Propulsion.compute_ducted_fan_geometry import compute_ducted_fan_geometry matplotlib.interactive(True) @@ -59,7 +61,7 @@ def main(): evaluate_problem(nexus) results = nexus.results - plot_mission(results, nexus.vehicle_configurations) + Plot_Mission.plot_mission(nexus) #output=nexus._really_evaluate() #run; use optimization setup without inputs return @@ -88,7 +90,7 @@ def setup(): procedure.run_sizing_loop = run_sizing_loop #size aircraft and run mission procedure.evaluate_field_length = evaluate_field_length procedure.evaluate_constraints = evaluate_constraints - + #procedure.write_optimization = write_optimization #only use when writing an optimization problem return procedure @@ -108,7 +110,7 @@ def run_sizing_loop(nexus): Preq_guess= 200000. - scaling = np.array([1E4,1E9,1E6]) + scaling = np.array([1E4,1E11,1E7]) y = np.array([m_guess, Ereq_guess, Preq_guess])/scaling min_y = [.05, 1E-5,10.] max_y = [10., 10., 10.] @@ -284,7 +286,7 @@ def sizing_evaluation(y,nexus, scaling): #run size aircraft geometry/mass based on guess simple_sizing(nexus) - analyses.finalize() #wont run without this + analyses.finalize() results = evaluate_mission(configs,mission) @@ -429,7 +431,7 @@ def evaluate_constraints(nexus): results.max_throttle_constraint=1-max_throttle - nexus.iteration_constraint= nexus.sizing_loop.tolerance-nexus.sizing_loop.norm_error#((nexus.max_iter-5)-nexus.number_of_iterations)/(1.*nexus.max_iter) #give it some slack to help constraints converge + nexus.iteration_constraint= nexus.sizing_loop.tolerance-nexus.sizing_loop.max_error return nexus @@ -461,241 +463,12 @@ def evaluate_field_length(nexus): return nexus - - - -# ---------------------------------------------------------------------- -# Plot Mission -# ---------------------------------------------------------------------- - -def plot_mission(results,configs,line_style='bo-'): - - if line_style == 'k-': - line_width = 2. - else: - line_width = 1. - - - - # ------------------------------------------------------------------ - # Angle of Attack - # ------------------------------------------------------------------ - - plt.figure("Angle of Attack History") - axes = plt.gca() - for i in range(len(results.segments)): - time = results.segments[i].conditions.frames.inertial.time[:,0] / Units.min - aoa = results.segments[i].conditions.aerodynamics.angle_of_attack[:,0] / Units.deg - axes.plot(time, aoa, line_style) - axes.set_xlabel('Time (mins)') - axes.set_ylabel('Angle of Attack (deg)') - axes.grid(True) - - - # ------------------------------------------------------------------ - # Mass Rate - # ------------------------------------------------------------------ - plt.figure("Mass Rate") - axes = plt.gca() - for i in range(len(results.segments)): - time = results.segments[i].conditions.frames.inertial.time[:,0] / Units.min - mdot = -results.segments[i].conditions.weights.vehicle_mass_rate[:,0] - axes.plot(time, mdot, line_style) - axes.set_xlabel('Time (mins)') - axes.set_ylabel('Mass Rate (kg/s)') - axes.grid(True) - - - # ------------------------------------------------------------------ - # Altitude - # ------------------------------------------------------------------ - plt.figure("Altitude") - axes = plt.gca() - for i in range(len(results.segments)): - time = results.segments[i].conditions.frames.inertial.time[:,0] / Units.min - altitude = results.segments[i].conditions.freestream.altitude[:,0] / Units.km - axes.plot(time, altitude, line_style) - axes.set_xlabel('Time (mins)') - axes.set_ylabel('Altitude (km)') - axes.grid(True) - - - # ------------------------------------------------------------------ - # Vehicle Mass - # ------------------------------------------------------------------ - plt.figure("Vehicle Mass") - axes = plt.gca() - for i in range(len(results.segments)): - time = results.segments[i].conditions.frames.inertial.time[:,0] / Units.min - mass = results.segments[i].conditions.weights.total_mass[:,0] - axes.plot(time, mass, line_style) - axes.set_xlabel('Time (mins)') - axes.set_ylabel('Vehicle Mass (kg)') - axes.grid(True) - - - # ------------------------------------------------------------------ - # Aerodynamics - # ------------------------------------------------------------------ - fig = plt.figure("Aerodynamic Forces") - for segment in results.segments.values(): - - time = segment.conditions.frames.inertial.time[:,0] / Units.min - Lift = -segment.conditions.frames.wind.lift_force_vector[:,2] - Drag = -segment.conditions.frames.wind.drag_force_vector[:,0] - Thrust = segment.conditions.frames.body.thrust_force_vector[:,0] - - axes = fig.add_subplot(3,1,1) - axes.plot( time , Lift , line_style ) - axes.set_xlabel('Time (min)') - axes.set_ylabel('Lift (N)') - axes.grid(True) - - axes = fig.add_subplot(3,1,2) - axes.plot( time , Drag , line_style ) - axes.set_xlabel('Time (min)') - axes.set_ylabel('Drag (N)') - axes.grid(True) - - axes = fig.add_subplot(3,1,3) - axes.plot( time , Thrust , line_style ) - axes.set_xlabel('Time (min)') - axes.set_ylabel('Thrust (N)') - axes.grid(True) - - - # ------------------------------------------------------------------ - # Aerodynamics 2 - # ------------------------------------------------------------------ - fig = plt.figure("Aerodynamic Coefficients") - for segment in results.segments.values(): - - time = segment.conditions.frames.inertial.time[:,0] / Units.min - CLift = segment.conditions.aerodynamics.lift_coefficient[:,0] - CDrag = segment.conditions.aerodynamics.drag_coefficient[:,0] - Drag = -segment.conditions.frames.wind.drag_force_vector[:,0] - Thrust = segment.conditions.frames.body.thrust_force_vector[:,0] - - axes = fig.add_subplot(3,1,1) - axes.plot( time , CLift , line_style ) - axes.set_xlabel('Time (min)') - axes.set_ylabel('CL') - axes.grid(True) - - axes = fig.add_subplot(3,1,2) - axes.plot( time , CDrag , line_style ) - axes.set_xlabel('Time (min)') - axes.set_ylabel('CD') - axes.grid(True) - - axes = fig.add_subplot(3,1,3) - axes.plot( time , Drag , line_style ) - axes.plot( time , Thrust , 'ro-' ) - axes.set_xlabel('Time (min)') - axes.set_ylabel('Drag and Thrust (N)') - axes.grid(True) - - - # ------------------------------------------------------------------ - # Aerodynamics 3 - # ------------------------------------------------------------------ - fig = plt.figure("Drag Components") - axes = plt.gca() - for i, segment in enumerate(results.segments.values()): - - time = segment.conditions.frames.inertial.time[:,0] / Units.min - drag_breakdown = segment.conditions.aerodynamics.drag_breakdown - cdp = drag_breakdown.parasite.total[:,0] - cdi = drag_breakdown.induced.total[:,0] - cdc = drag_breakdown.compressible.total[:,0] - cdm = drag_breakdown.miscellaneous.total[:,0] - cd = drag_breakdown.total[:,0] - - if line_style == 'bo-': - axes.plot( time , cdp , 'ko-', label='CD_P' ) - axes.plot( time , cdi , 'bo-', label='CD_I' ) - axes.plot( time , cdc , 'go-', label='CD_C' ) - axes.plot( time , cdm , 'yo-', label='CD_M' ) - axes.plot( time , cd , 'ro-', label='CD' ) - if i == 0: - axes.legend(loc='upper center') - else: - axes.plot( time , cdp , line_style ) - axes.plot( time , cdi , line_style ) - axes.plot( time , cdc , line_style ) - axes.plot( time , cdm , line_style ) - axes.plot( time , cd , line_style ) - - axes.set_xlabel('Time (min)') - axes.set_ylabel('CD') - axes.grid(True) - - - # ------------------------------------------------------------------ - # Flight Conditions - # ------------------------------------------------------------------ - fig = plt.figure("Flight Conditions",figsize=(6.5,10)) - for segment in results.segments.values(): - - time = segment.conditions.frames.inertial.time[:,0] / Units.min - altitude = segment.conditions.freestream.altitude[:,0] / Units.km - mach = segment.conditions.freestream.mach_number[:,0] - distance = segment.conditions.frames.inertial.position_vector[:,0] / Units.km - - axes = fig.add_subplot(3,1,1) - axes.plot( time, distance, line_style ) - axes.set_ylabel('Distance (km)') - axes.grid(True) - - axes = fig.add_subplot(3,1,2) - axes.plot( time , altitude , line_style , lw=line_width ) - axes.set_ylabel('Altitude (km)') - axes.grid(True) - - axes = fig.add_subplot(3,1,3) - axes.plot( time , mach, line_style , lw=line_width ) - axes.set_xlabel('Time (min)') - axes.set_ylabel('Mach Number (-)') - axes.grid(True) +def write_optimization(nexus): + filename = 'opt_outputs.txt' + write_optimization_outputs(nexus, filename) + return nexus - # ------------------------------------------------------------------ - # Mass, State of Charge, Power - # ------------------------------------------------------------------ - fig = plt.figure("Electric Aircraft Outputs",figsize=(6.5,10)) - for segment in results.segments.values(): - - time = segment.conditions.frames.inertial.time[:,0] / Units.min - mass = segment.conditions.weights.total_mass[:,0] - - axes = fig.add_subplot(3,1,1) - axes.plot( time , mass , line_style , lw=line_width ) - axes.set_ylabel('Vehicle Mass (kg)') - axes.grid(True) - - try: - battery=configs.base.energy_network['battery'] - state_of_charge=segment.conditions.propulsion.battery_energy/battery.max_energy - battery_power=-segment.conditions.propulsion.battery_draw/Units.MW - except: - continue - - axes = fig.add_subplot(3,1,2) - axes.plot( time , state_of_charge , line_style , lw=line_width ) - axes.set_ylabel('State of Charge (-)') - axes.set_ylim([-0.005,1.005]) - axes.grid(True) - - axes = fig.add_subplot(3,1,3) - axes.plot( time , battery_power , line_style , lw=line_width ) - axes.set_xlabel('Time (min)') - axes.set_ylabel('Discharge Power (MW)') - axes.grid(True) - - - raw_input('Press Enter To Quit') - return - if __name__ == '__main__': main() diff --git a/Lithium_Air_Sizing/Vehicle.py b/Lithium_Air_Sizing/Vehicle.py index c1ed9cf..0c2a2f9 100644 --- a/Lithium_Air_Sizing/Vehicle.py +++ b/Lithium_Air_Sizing/Vehicle.py @@ -1,6 +1,6 @@ # Vehicles.py # -# Created: May 2015, E. Botero +# Created: Jan 2017, M. Vegh # Modified: # ---------------------------------------------------------------------- @@ -281,19 +281,7 @@ def base_setup(): p1, T1, rho1, a1, mew1 = atm.compute_values(0.) p2, T2, rho2, a2, mew2 = atm.compute_values(6.255*Units.km) - #create sizing segment - ''' - state = Data() - conditions = Data() - numerics = Data() - - conditions.M = 0.729 - conditions.alt = 7*Units.km - conditions.T = T2 - conditions.p = p2 - state.conditions = conditions - state.numerics = numerics - ''' + mach_number =0.729 altitude = 30000*Units.ft From 30e07d66abf3609b8b38efb1d69b067ef30707d6 Mon Sep 17 00:00:00 2001 From: jmvegh Date: Tue, 31 Jan 2017 08:36:02 -0800 Subject: [PATCH 7/7] changed optimizer to slsqp --- Lithium_Air_Sizing/Optimize.py | 30 +++++------------------------- Lithium_Air_Sizing/Sizing.py | 2 -- 2 files changed, 5 insertions(+), 27 deletions(-) diff --git a/Lithium_Air_Sizing/Optimize.py b/Lithium_Air_Sizing/Optimize.py index f9e63cc..9f8051f 100644 --- a/Lithium_Air_Sizing/Optimize.py +++ b/Lithium_Air_Sizing/Optimize.py @@ -16,7 +16,8 @@ import Sizing as Procedure import Plot_Mission from SUAVE.Optimization.Nexus import Nexus -import SUAVE.Optimization.Package_Setups.pyopt_setup as pyopt_setup +#import SUAVE.Optimization.Package_Setups.pyopt_setup as pyopt_setup +import SUAVE.Optimization.Package_Setups.scipy_setup as scipy_setup from SUAVE.Sizing.Sizing_Loop import Sizing_Loop # ---------------------------------------------------------------------- # Run the whole thing @@ -25,7 +26,7 @@ def main(): problem = setup() - output = pyopt_setup.Pyopt_Solve(problem, sense_step = 1E-2, solver='SNOPT') + output = scipy_setup.SciPy_Solve(problem, sense_step = 1E-2, solver = 'SLSQP') print output Plot_Mission.plot_mission(problem) @@ -52,9 +53,7 @@ def setup(): problem.inputs = np.array([ [ 'thrust_loading' , .2 , (.05 , .3 ) , .1, 'continuous', Units.less], [ 'fan_pressure_ratio' , 1.5 , (1.05 , 2.6 ) , 1., 'continuous', Units.less], - #[ 'aspect_ratio' , 14. , (5. , 14. ) , 10., 'continuous', Units.less], - [ 'wing_loading' , 400. , (200. , 800. ) , 100.,'continuous', Units.kg/Units.meter**2.], - #[ 'taper' , 0.1000 , (.1 , .3 ) , .1, 'continuous', Units.less ], + [ 'wing_loading' , 400. , (200. , 800. ) , 100.,'continuous', Units.kg/Units.meter**2.],, [ 'wing_thickness' , .105 , (0.07 , 0.20 ) , .1, 'continuous', Units.less ], [ 'v_climb_1' , 80. , (50. , 230. ) , 1E2, 'continuous', Units.meter/Units.second], [ 'v_climb_2' , 100. , (50. , 230 ) , 1E2, 'continuous', Units.meter/Units.second], @@ -88,8 +87,6 @@ def setup(): # [ tag, sense, edge, scaling, units ] problem.constraints = np.array([ - #[ 'power_margin' , '>', 0 , 1E6 , Units.meters], - #['lithium_ion_energy_margin' , '>', 0 , 1E0 , Units.less], [ 'climb_constraint_1' , '>', 0 , 1E2 , Units.meters], [ 'climb_constraint_2' , '>', 0 , 1E3 , Units.meters], #handled by bounds [ 'descent_constraint_1' , '>', 0 , 1E2 , Units.meters], @@ -104,24 +101,7 @@ def setup(): ]) - ''' - problem.constraints = np.array([ - [ 'power_margin' , '>', 0 , 1E6 , Units.meters], - #[ 'range_margin' , '>', 0 , 1E6 , Units.meters], - [ 'washout' , '>', 0 , 1E0 , Units.radians], - [ 'climb_constraint_1' , '>', 0 , 1E3 , Units.km], - [ 'climb_constraint_2' , '>', 0 , 1E3 , Units.km], - [ 'climb_constraint_3' , '>', 0 , 1E3 , Units.km], - [ 'climb_constraint_4' , '>', 0 , 1E3 , Units.km], - [ 'descent_constraint_1' , '>', 0 , 1E3 , Units.km], - [ 'descent_constraint_2' , '>', 0 , 1E3 , Units.km], - [ 'min_alpha_constraint' , '>', 0 , 1E1 , Units.degrees], - [ 'max_alpha_constraint' , '>', 0 , 1E1 , Units.degrees], - #[ 'takeoff_field_constraint' , '>', 0 , 1E3 , Units.ft], - #[ 'landing_field_constraint' , '>', 0 , 1E3 , Units.ft], - - ]) - ''' + # ------------------------------------------------------------------- # Aliases # ------------------------------------------------------------------- diff --git a/Lithium_Air_Sizing/Sizing.py b/Lithium_Air_Sizing/Sizing.py index 5777459..bbd10c2 100644 --- a/Lithium_Air_Sizing/Sizing.py +++ b/Lithium_Air_Sizing/Sizing.py @@ -84,8 +84,6 @@ def setup(): # ------------------------------------------------------------------ # size the base config - - procedure = Process() procedure.run_sizing_loop = run_sizing_loop #size aircraft and run mission procedure.evaluate_field_length = evaluate_field_length