Commit b5bc2f03 authored by Julian Zobel's avatar Julian Zobel
Browse files

Multicoper Models, Intel RTF model, inclusion commencing for movement models

parent 2292013b
......@@ -32,11 +32,7 @@ import de.tudarmstadt.maki.simonstrator.api.uavsupport.callbacks.ReachedLocation
* @version 1.0, 20.01.2020
*/
public interface UAVMovementModel {
// NO - NO CHANGY
public final double AIRDENSITY = 1.2045; // kg/m^3
public final double GRAVITY = 9.807; // m/s^2
public void setMotorControl(ActuatorComponent motor);
/**
......@@ -45,19 +41,9 @@ public interface UAVMovementModel {
* @param targetVelocity
*/
public void setTargetVelocity(double targetVelocity);
public double getVerticalAscentMaxVelocity();
public double getHorizontalMaxVelocity();
public double getCurrentVelocity();
public double getHorizontalMinVelocity();
/**
* Estimate the power consumption for a given velocity
* @param velocity
* @return The power consumption in W for the given velocity.
*/
public double estimatePowerConsumptionWatt(double velocity);
public double estimateOptimalSpeed();
public double getMinimumVelocity();
public double getMaxiumumVelocity();
public void move(long timeBetweenMovementOperations);
......
/*
* Copyright (c) 2005-2010 KOM – Multimedia Communications Lab
*
* This file is part of PeerfactSim.KOM.
*
* PeerfactSim.KOM is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* any later version.
*
* PeerfactSim.KOM is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with PeerfactSim.KOM. If not, see <http://www.gnu.org/licenses/>.
*
*/
package de.tud.kom.p2psim.api.uav;
import de.tud.kom.p2psim.impl.energy.components.ActuatorComponent;
/**
* Interface for UAV models. Multicopter!
*
* @author Julian Zobel
* @version 1.0, 19.01.2022
*/
public interface MulticopterModel {
// NO - NO CHANGY
public final double AIRDENSITY = 1.2045; // kg/m^3
public final double GRAVITY = 9.807; // m/s^2
public double hoverThrustRequired();
public double getMaximumTurnAngle();
// v
public double verticalAscentMaxVelocity();
public double horizontalMaxVelocity();
public double horizontalMinVelocity();
// acc
public double horizontalMaxAcceleration();
public double powerConsumptionWatt(double velocity);
public double optimalSpeed();
public void setMotor(ActuatorComponent motor);
public interface Factory {
public MulticopterModel createComponent();
}
}
......@@ -128,7 +128,7 @@ public class UAVTopologyComponent extends AbstractTopologyComponent implements S
@Override
public double getMinMovementSpeed() {
return movement.getHorizontalMinVelocity();
return movement.horizontalMinVelocity();
}
@Override
......
......@@ -31,7 +31,7 @@ import javax.persistence.Table;
import org.apache.commons.math3.geometry.euclidean.twod.Vector2D;
import de.tud.kom.p2psim.api.topology.movement.UAVMovementModel;
import de.tud.kom.p2psim.api.uav.UAVModel;
import de.tud.kom.p2psim.api.uav.MulticopterModel;
import de.tud.kom.p2psim.impl.energy.components.ActuatorComponent;
import de.tud.kom.p2psim.impl.energy.components.StatelessActuatorComponent;
import de.tud.kom.p2psim.impl.topology.component.UAVTopologyComponent;
......@@ -61,7 +61,7 @@ public class StateMulticopterMovement implements UAVMovementModel {
private UAVTopologyComponent topologyComponent;
private UAVModel model;
private MulticopterModel uav;
private double currentAngleOfAttack;
......@@ -72,20 +72,9 @@ public class StateMulticopterMovement implements UAVMovementModel {
private LinkedList<PositionVector> route = new LinkedList<>();
private Map<PositionVector, ReachedLocationCallback> locationCallbacks = new LinkedHashMap<>(); // TODO callback interface
private StatelessActuatorComponent motor;
private double mass; // kg
private double areaTop; // m^2
private double areaFront; // m^2
private double dragCoefficient;
private double maximumPitchAngleAllowed; // ° max angle
private double maximumVerticalVelocityAllowed; // m/s
private double optimalVelocity = -1;
// TODO currently not used
private double maximumTurnAngle; // 90° per second turn angle
private final double MARGIN = Math.pow(10, -2);
......@@ -96,20 +85,9 @@ public class StateMulticopterMovement implements UAVMovementModel {
private PositionVector accelerationVector = new PositionVector(0,0,0);
public StateMulticopterMovement(UAVTopologyComponent topologyComponent, double massTotal,
double areaTop, double areaFront, double UAVDragCoefficient, double maximumPitchAngleAllowed,
double maximumDescentVelocityAllowed, double maximumTurnAngle) {
public StateMulticopterMovement(UAVTopologyComponent topologyComponent, MulticopterModel uav) {
this.topologyComponent = topologyComponent;
this.mass = massTotal;
this.areaTop = areaTop;
this.areaFront = areaFront;
this.dragCoefficient = UAVDragCoefficient;
this.maximumPitchAngleAllowed = maximumPitchAngleAllowed;
this.maximumVerticalVelocityAllowed = maximumDescentVelocityAllowed;
this.maximumTurnAngle = maximumTurnAngle;
//positionVector = topologyComponent.getCurrentLocation();
//directionVector = topologyComponent.getCurrentDirection();
this.uav = uav;
}
......@@ -457,7 +435,7 @@ public class StateMulticopterMovement implements UAVMovementModel {
*/
private long hoverTurn(long time) {
double rotation = horizontalAngleToPosition(currentTargetPosition);
double turnTime = Math.abs(rotation) / maximumTurnAngle;
double turnTime = Math.abs(rotation) / uav.getMaximumTurnAngle();
long turnPhaseTime = (long) (turnTime * Time.SECOND);
if(turnPhaseTime > time) {
......@@ -469,7 +447,7 @@ public class StateMulticopterMovement implements UAVMovementModel {
// limit the turn rotation angle with limited time
turnTime = (double) turnPhaseTime / Time.SECOND;
rotation = rotation * ( turnTime / (Math.abs(rotation) / maximumTurnAngle));
rotation = rotation * ( turnTime / (Math.abs(rotation) / uav.getMaximumTurnAngle()));
// x' = x cos θ − y sin θ
// y' = x sin θ + y cos θ
......@@ -490,7 +468,7 @@ public class StateMulticopterMovement implements UAVMovementModel {
double curveVelocity = Math.min(estimateOptimalSpeed(), flightVelocity());
// estimation for the turn radius based on the available, free thrust potential of the motors
double curveThrust = getHorizontalComponentMaxThrust() - estimateRequiredThrust(curveVelocity);
double curveThrust = horizontalComponentMaxThrust() - estimateRequiredThrust(curveVelocity);
double turnRadius = ( mass * Math.pow(curveVelocity, 2)) / curveThrust;
// calculate turn circle
......@@ -559,7 +537,7 @@ public class StateMulticopterMovement implements UAVMovementModel {
directionVector.normalize();
velocityVector = directionVector.scale(curveVelocity);
accelerationVector = directionToCircleCenter.scale(curveThrust);
accelerationVector = directionToCircleCenter.scale(curveThrust / mass);
if(Math.abs(positionVector.distanceTo(tangentPoint)) < MARGIN) {
positionVector = tangentPoint.clone();
......@@ -569,7 +547,7 @@ public class StateMulticopterMovement implements UAVMovementModel {
}
// thrust includes energy calculation; accelerate against flight direction
motor.requestThrust(getHorizontalComponentMaxThrust(), constantPhaseTime);
motor.requestThrust(horizontalComponentMaxThrust(), constantPhaseTime);
// remaining time
return time - constantPhaseTime;
......@@ -917,103 +895,9 @@ public class StateMulticopterMovement implements UAVMovementModel {
//////////
/*
*
*/
// Thrust required to hold the maximum allowed descent velocity
protected double verticalDescentThrust() {
return hoverThrustRequired() - verticalDescentDrag();
}
// Drag (upward lift) induced on the frame by moving with the maximum allowed descent velocity
// 0.5 * p * C * A * v^2
protected double verticalDescentDrag() {
return 0.5 * bodyDrag(0, new PositionVector(0,0,1)) * maximumVerticalVelocityAllowed * maximumVerticalVelocityAllowed;
}
protected double verticalDescentMaxAcceleration() {
return verticalDescentDrag() / mass;
}
protected double verticalAscentMaxAcceleration() {
return (motor.getMaxThrust() - hoverThrustRequired()) / mass;
}
@Override
public double getVerticalAscentMaxVelocity() {
double maxThrust = motor.getMaxThrust();
return Math.sqrt(2.0 * (maxThrust - hoverThrustRequired()) / bodyDrag(0, new PositionVector(0,0,1)));
}
protected double hoverThrustRequired() {
return mass * GRAVITY;
}
@Override
public double getHorizontalMaxVelocity() {
double horizontalThrust = getHorizontalComponentMaxThrust();
double maxVelocity = Math.sqrt( (2.0 * horizontalThrust) / bodyDrag(maximumPitchAngleAllowed, new PositionVector(1,0,0)));
return maxVelocity;
}
protected double getHorizontalComponentMaxThrust() {
// hoverthrust / cos => amount of thrust in horizonal direction with °angle
double stableAltitudeMaximumTotalThrust = getHorizontalMaxVelocityRequiredTotalThrust();
// fraction of total thrust in horizonal (forward) direction with °angle
double maximumHorizontalThrustStableAltitude = stableAltitudeMaximumTotalThrust * Math.sin(maximumPitchAngleAllowed);
return maximumHorizontalThrustStableAltitude;
}
protected double getHorizontalMaxAcceleration() {
return getHorizontalComponentMaxThrust() / mass;
}
protected double getHorizontalMaxVelocityRequiredTotalThrust() {
return hoverThrustRequired() / Math.cos(maximumPitchAngleAllowed);
}
protected double bodyDrag(double angleRadians, PositionVector direction) {
return AIRDENSITY * dragCoefficient * areaExposedToDrag(angleRadians, direction);
}
protected double areaExposedToDrag(double angleRadians, PositionVector direction) {
Vector2D v = new Vector2D(Math.abs(direction.getX()) + Math.abs(direction.getY()), Math.abs(direction.getZ()));
v = v.normalize();
double areaExposedFront = v.getX() * (Math.sin(angleRadians) * areaTop + Math.cos(angleRadians) * areaFront );
double areaExposedTop = v.getY() * (Math.cos(angleRadians) * areaTop + Math.sin(angleRadians) * areaFront);
return areaExposedFront + areaExposedTop;
}
/*
* F_drag [N] = 0.5 * p * C_drag * A * v^2
*/
protected double currentDrag() {
return 0.5 * bodyDrag(currentAngleOfAttack, directionVector) * velocityVector.getLength() * velocityVector.getLength();
}
/**
* Calculate the drag induced on the UAV with a given velocity and an angle of attack (in radians) moving forward horizontally.
*
* @param velocity
* @param angleInRadians
* @return
*/
protected double forwardDrag(double velocity, double angleInRadians) {
return 0.5 * bodyDrag(angleInRadians, new PositionVector(1,0,0)) * velocity * velocity;
}
/*
*
*/
@Override
public void setMotorControl(ActuatorComponent motor) {
this.motor = (StatelessActuatorComponent) motor;
public void setMotorControl(ActuatorComponent motor) {
uav.setMotor(motor);
}
@Override
......@@ -1094,107 +978,10 @@ public class StateMulticopterMovement implements UAVMovementModel {
locationCallbacks.clear();
}
@Override
public double getHorizontalMinVelocity() {
return Math.sqrt(2 * hoverThrustRequired() * Math.tan(Math.toRadians(0.25)) / bodyDrag(Math.toRadians(0.25), new PositionVector(1,0,0)));
}
@Override
public double estimatePowerConsumptionWatt(double velocity) {
if(velocity == 0) {
return motor.estimatePowerConsumptionWatt(hoverThrustRequired());
}
else if(velocity > getHorizontalMaxVelocity()) {
return -1;
}
else if(velocity < getHorizontalMinVelocity()) {
return -1;
}
else {
double requiredThrust = estimateRequiredThrust(velocity);
double wattage = motor.estimatePowerConsumptionWatt(requiredThrust);
return wattage;
}
}
protected double estimateRequiredThrust(double velocity) {
if(velocity == 0) {
return motor.estimatePowerConsumptionWatt(hoverThrustRequired());
}
else if(velocity > getHorizontalMaxVelocity()) {
return -1;
}
else if(velocity < getHorizontalMinVelocity()) {
return -1;
}
else {
double estimateAngle = estimatePitchAngleForVelocity(velocity);
double estimatedDrag = forwardDrag(velocity, estimateAngle);
double requiredThrust = Math.sqrt(hoverThrustRequired() * hoverThrustRequired() + estimatedDrag * estimatedDrag);
return requiredThrust;
}
}
/**
* Estimate the pitch angle (angle of attack) required to get the target velocity.
* Angle precision is 1/4 degree.
*
* @param velocity
* @return
*/
protected double estimatePitchAngleForVelocity(double velocity) {
int low = 0;
int high = Integer.MAX_VALUE;
double vsquared = (velocity * velocity);
for(int i = 0; i <= ((int) Math.toDegrees(maximumPitchAngleAllowed)); i++) {
double v2 = 2 * hoverThrustRequired() * Math.tan(Math.toRadians(i)) / bodyDrag(Math.toRadians(i), new PositionVector(1,0,0));
if(v2 > vsquared && i < high) {
high = i;
}
else if(v2 < vsquared && i >= low) {
low = i;
}
else if(v2 == vsquared ) {
return Math.toRadians(i);
}
}
if(high < Integer.MAX_VALUE) {
double lo = low;
double hi = high;
double nearest = -1;
double nearestDiff = Double.MAX_VALUE;
double step = (hi - lo) / 4;
for(int i = 0; i < 4; i++) {
double d = lo + i * step;
double v2 = 2 * hoverThrustRequired() * Math.tan(Math.toRadians(d)) / bodyDrag(Math.toRadians(d), new PositionVector(1,0,0));
double diff = Math.abs(((velocity * velocity) - v2));
if(diff < nearestDiff || (lo == 0 && i == 1)) {
nearestDiff = diff;
nearest = d;
}
}
return Math.toRadians(nearest);
}
return maximumPitchAngleAllowed;
}
private double flightVelocity() {
if(targetVelocity > 0 && targetVelocity < getHorizontalMaxVelocity()) {
......@@ -1213,47 +1000,15 @@ public class StateMulticopterMovement implements UAVMovementModel {
* @version 1.0, 14.01.2020
*/
public static class Factory implements AerialMovementModelFactory {
private MulticopterModel uav;
private double massTotal = 1.465; // kg
private double areaTop = 0.245; // m^2
private double areaFront = 0.1; // m^2
private double UAVDragCoefficient = 0.7;
private double maximumPitchAngleAllowed = Math.toRadians(60); // ° max angle
private double maximumDecentVelocityAllowed = 5; // m/s
private double maximumTurnAngle = Math.toRadians(90); // 90° per second turn angle
public void setMassTotal(double massTotal) {
this.massTotal = massTotal;
}
public void setAreaTop(double areaTop) {
this.areaTop = areaTop;
}
public void setAreaFront(double areaFront) {
this.areaFront = areaFront;
}
public void setUAVDragCoefficient(double uAVDragCoefficient) {
UAVDragCoefficient = uAVDragCoefficient;
}
public void setMaximumPitchAngleAllowed(double maximumPitchAngleAllowed) {
this.maximumPitchAngleAllowed = Math.toRadians(maximumPitchAngleAllowed);
}
public void setMaximumDecentVelocityAllowed(
double maximumDecentVelocityAllowed) {
this.maximumDecentVelocityAllowed = maximumDecentVelocityAllowed;
}
public void setMaximumTurnAngle(double maximumTurnAngle) {
this.maximumTurnAngle = Math.toRadians(maximumTurnAngle);
public void setUAVModel(MulticopterModel uav) {
this.uav = uav;
}
public UAVMovementModel createComponent(UAVTopologyComponent topologyComponent) {
return new StateMulticopterMovement(topologyComponent, massTotal, areaTop, areaFront,
UAVDragCoefficient, maximumPitchAngleAllowed, maximumDecentVelocityAllowed, maximumTurnAngle);
return new StateMulticopterMovement(topologyComponent, uav);
}
}
......@@ -1315,32 +1070,17 @@ public class StateMulticopterMovement implements UAVMovementModel {
}
@Override
public double estimateOptimalSpeed() {
if(optimalVelocity == -1) {
double MIN = Double.MAX_VALUE;
double opt = -1;
double min = getHorizontalMinVelocity();
double max = getHorizontalMaxVelocity();
int steps = 50;
double stepsize = ( max-min) / steps;
for (int i = 0; i < steps; i++) {
double speed = min + i * stepsize;
double energyPerMeter = estimatePowerConsumptionWatt(speed) / speed ;
if(energyPerMeter < MIN) {
MIN = energyPerMeter;
opt = speed;
}
}
optimalVelocity = opt;
}
return optimalVelocity;
public double getMinimumVelocity() {
// TODO Auto-generated method stub
return 0;
}
@Override
public double getMaxiumumVelocity() {
// TODO Auto-generated method stub
return 0;
}
}
/*
* Copyright (c) 2005-2010 KOM – Multimedia Communications Lab
*
* This file is part of PeerfactSim.KOM.
*
* PeerfactSim.KOM is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* any later version.
*
* PeerfactSim.KOM is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with PeerfactSim.KOM. If not, see <http://www.gnu.org/licenses/>.
*
*/
package de.tud.kom.p2psim.impl.uav;
import org.apache.commons.math3.geometry.euclidean.twod.Vector2D;
import de.tud.kom.p2psim.api.topology.movement.UAVMovementModel;
import de.tud.kom.p2psim.api.uav.MulticopterModel;
import de.tud.kom.p2psim.impl.energy.components.ActuatorComponent;
import de.tud.kom.p2psim.impl.energy.components.StatelessActuatorComponent;
import de.tud.kom.p2psim.impl.topology.component.UAVTopologyComponent;
import de.tud.kom.p2psim.impl.topology.movement.aerial.AerialMovementModelFactory;
import de.tud.kom.p2psim.impl.topology.movement.aerial.StateMulticopterMovement;
import de.tud.kom.p2psim.impl.topology.util.PositionVector;
public class IntelAeroRTF implements MulticopterModel {
private double mass; // kg
private double areaTop; // m^2
private double areaFront; // m^2
private double dragCoefficient;
private double maximumPitchAngleAllowed; // ° max angle
private double maximumVerticalVelocityAllowed; // m/s
private double optimalVelocity = -1;
private double maximumTurnAngle; // 90° per second turn angle
private StatelessActuatorComponent motor;
public IntelAeroRTF(double massTotal,
double areaTop, double areaFront, double UAVDragCoefficient, double maximumPitchAngleAllowed,
double maximumDescentVelocityAllowed, double maximumTurnAngle) {
this.mass = massTotal;
this.areaTop = areaTop;
this.areaFront = areaFront;
this.dragCoefficient = UAVDragCoefficient;
this.maximumPitchAngleAllowed = maximumPitchAngleAllowed;
this.maximumVerticalVelocityAllowed = maximumDescentVelocityAllowed;
this.maximumTurnAngle = maximumTurnAngle;
}
/**
* Estimate the pitch angle (angle of attack) required to get the target velocity.
* Angle precision is 1/4 degree.
*
* @param velocity
* @return
*/
public double pitchAngleForHorizontalVelocity(double velocity) {
int low = 0;
int high = Integer.MAX_VALUE;
double vsquared = (velocity * velocity);
for(int i = 0; i <= ((int) Math.toDegrees(maximumPitchAngleAllowed)); i++) {
double v2 = 2 * hoverThrustRequired() * Math.tan(Math.toRadians(i)) / bodyDrag(Math.toRadians(i), new PositionVector(1,0,0));
if(v2 > vsquared && i < high) {
high = i;
}
else if(v2 < vsquared && i >= low) {
low = i;
}
else if(v2 == vsquared ) {
return Math.toRadians(i);
}
}
if(high < Integer.MAX_VALUE) {
double lo = low;
double hi = high;
double nearest = -1;
double nearestDiff = Double.MAX_VALUE;
double step = (hi - lo) / 4;
for(int i = 0; i < 4; i++) {
double d = lo + i * step;
double v2 = 2 * hoverThrustRequired() * Math.tan(Math.toRadians(d)) / bodyDrag(Math.toRadians(d), new PositionVector(1,0,0));
double diff = Math.abs(((velocity * velocity) - v2));
if(diff < nearestDiff || (lo == 0 && i == 1)) {
nearestDiff = diff;
nearest = d;
}
}
return Math.toRadians(nearest);
}
return maximumPitchAngleAllowed;
}
public double thrustForHorizontalVelocity(double velocity) {
if(velocity == 0) {
return motor.estimatePowerConsumptionWatt(hoverThrustRequired());
}
else if(velocity > horizontalMaxVelocity()) {
return -1;
}
else if(velocity < horizontalMinVelocity()) {
return -1;
}
else {
double estimateAngle = pitchAngleForHorizontalVelocity(velocity);
double estimatedDrag = forwardDrag(velocity, estimateAngle);
double requiredThrust = Math.sqrt(hoverThrustRequired() * hoverThrustRequired() + estimatedDrag * estimatedDrag);
return requiredThrust;
}
}
public double horizontalMinVelocity() {
return Math.sqrt(2 * hoverThrustRequired() * Math.tan(Math.toRadians(0.25)) / bodyDrag(Math.toRadians(0.25), new PositionVector(1,0,0)));
}
public double powerConsumptionWatt(double velocity) {
if(velocity == 0) {
return motor.estimatePowerConsumptionWatt(hoverThrustRequired());
}
else if(velocity > horizontalMaxVelocity()) {
return -1;
}
else if(velocity < horizontalMinVelocity()) {
return -1;
}
else {
double requiredThrust = thrustForHorizontalVelocity(velocity);
double wattage = motor.estimatePowerConsumptionWatt(requiredThrust);
return wattage;
}
}
/*
*
*/
// Thrust required to hold the maximum allowed descent velocity
public double verticalDescentThrust() {
return hoverThrustRequired() - verticalDescentDrag();
}
// Drag (upward lift) induced on the frame by moving with the maximum allowed descent velocity
// 0.5 * p * C * A * v^2
public double verticalDescentDrag() {
return 0.5 * bodyDrag(0, new PositionVector(0,0,1)) * maximumVerticalVelocityAllowed * maximumVerticalVelocityAllowed;
}
public double verticalDescentMaxAcceleration() {
return verticalDescentDrag() / mass;
}
public double verticalAscentMaxAcceleration() {
return (motor.getMaxThrust() - hoverThrustRequired()) / mass;
}
@Override
public double verticalAscentMaxVelocity() {
double maxThrust = motor.getMaxThrust();
return Math.sqrt(2.0 * (maxThrust - hoverThrustRequired()) / bodyDrag(0, new PositionVector(0,0,1)));
}
@Override
public double hoverThrustRequired() {
return mass * GRAVITY;
}
@Override
public double horizontalMaxVelocity() {
double horizontalThrust = horizontalComponentMaxThrust();
double maxVelocity = Math.sqrt( (2.0 * horizontalThrust) / bodyDrag(maximumPitchAngleAllowed, new PositionVector(1,0,0)));
return maxVelocity;
}
protected double horizontalComponentMaxThrust() {
// hoverthrust / cos => amount of thrust in horizonal direction with °angle
double stableAltitudeMaximumTotalThrust = getHorizontalMaxVelocityRequiredTotalThrust();
// fraction of total thrust in horizonal (forward) direction with °angle
double maximumHorizontalThrustStableAltitude = stableAltitudeMaximumTotalThrust * Math.sin(maximumPitchAngleAllowed);
return maximumHorizontalThrustStableAltitude;
}
public double horizontalMaxAcceleration() {
return horizontalComponentMaxThrust() / mass;
}
protected double getHorizontalMaxVelocityRequiredTotalThrust() {
return hoverThrustRequired() / Math.cos(maximumPitchAngleAllowed);
}
public double bodyDrag(double angleRadians, PositionVector direction) {
return AIRDENSITY * dragCoefficient * areaExposedToDrag(angleRadians, direction);
}
protected double areaExposedToDrag(double angleRadians, PositionVector direction) {
Vector2D v = new Vector2D(Math.abs(direction.getX()) + Math.abs(direction.getY()), Math.abs(direction.getZ()));
v = v.normalize();
double areaExposedFront = v.getX() * (Math.sin(angleRadians) * areaTop + Math.cos(angleRadians) * areaFront );
double areaExposedTop = v.getY() * (Math.cos(angleRadians) * areaTop + Math.sin(angleRadians) * areaFront);
return areaExposedFront + areaExposedTop;
}
/*
* F_drag [N] = 0.5 * p * C_drag * A * v^2
*/
public double dragInducedByMovement(double angleOfAttack, PositionVector direction, double velocity) {
return 0.5 * bodyDrag(angleOfAttack, direction) * velocity * velocity;
}
/**
* Calculate the drag induced on the UAV with a given velocity and an angle of attack (in radians) moving forward horizontally.
*
* @param velocity
* @param angleInRadians
* @return
*/
public double forwardDrag(double velocity, double angleInRadians) {
return dragInducedByMovement(angleInRadians, new PositionVector(1,0,0), velocity);
}
@Override
public double optimalSpeed() {
if(optimalVelocity == -1) {
double MIN = Double.MAX_VALUE;
double opt = -1;
double min = horizontalMinVelocity();
double max = horizontalMaxVelocity();
int steps = 50;
double stepsize = ( max-min) / steps;
for (int i = 0; i < steps; i++) {
double speed = min + i * stepsize;
double energyPerMeter = powerConsumptionWatt(speed) / speed ;
if(energyPerMeter < MIN) {
MIN = energyPerMeter;
opt = speed;
}
}
optimalVelocity = opt;
}
return optimalVelocity;
}
/////
@Override
public void setMotor(ActuatorComponent actuator) {
assert actuator instanceof StatelessActuatorComponent;
this.motor = (StatelessActuatorComponent) motor;
}
/**
* Factory for this movement model
*
* @author Julian Zobel
* @version 1.0, 14.01.2020
*/
public static class Factory implements MulticopterModel.Factory {
// standard values
private double massTotal = 1.465; // kg
private double areaTop = 0.245; // m^2
private double areaFront = 0.1; // m^2
private double UAVDragCoefficient = 0.7;
private double maximumPitchAngleAllowed = Math.toRadians(60); // ° max angle
private double maximumVerticalVelocityAllowed = 10; // m/s
private double maximumTurnAngle = Math.toRadians(90); // 90° per second turn angle
public void setMassTotal(double massTotal) {
this.massTotal = massTotal;
}
public void setAreaTop(double areaTop) {
this.areaTop = areaTop;
}
public void setAreaFront(double areaFront) {
this.areaFront = areaFront;
}
public void setUAVDragCoefficient(double uAVDragCoefficient) {
UAVDragCoefficient = uAVDragCoefficient;
}
public void setMaximumPitchAngleAllowed(double maximumPitchAngleAllowed) {
this.maximumPitchAngleAllowed = Math.toRadians(maximumPitchAngleAllowed);
}
public void setMaximumVerticalVelocityAllowed(
double maximumDecentVelocityAllowed) {
this.maximumVerticalVelocityAllowed = maximumDecentVelocityAllowed;
}
public void setMaximumTurnAngle(double maximumTurnAngle) {
this.maximumTurnAngle = Math.toRadians(maximumTurnAngle);
}
public MulticopterModel createComponent() {
return new IntelAeroRTF(massTotal, areaTop, areaFront,
UAVDragCoefficient, maximumPitchAngleAllowed, maximumVerticalVelocityAllowed, maximumTurnAngle);
}
}
}
Markdown is supported
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment