Commit 749d8f28 authored by Julian Zobel's avatar Julian Zobel 🦄
Browse files

Lots of documentation

Adaption of movement models and UAV models
parent 1f6666e1
......@@ -43,7 +43,7 @@ public interface UAVMovementModel {
public void setTargetVelocity(double targetVelocity);
public double getCurrentVelocity();
public double getMinimumVelocity();
public double getMaxiumumVelocity();
public double getMaximumVelocity();
public void move(long timeBetweenMovementOperations);
......@@ -59,4 +59,9 @@ public interface UAVMovementModel {
public LinkedList<PositionVector> getTargetLocations();
public void removeTargetLocations();
public double powerConsumptionWatt(double velocity);
public double optimalSpeed();
}
......@@ -24,7 +24,7 @@ package de.tud.kom.p2psim.api.uav;
import de.tud.kom.p2psim.impl.energy.components.ActuatorComponent;
/**
* Interface for UAV models. Multicopter!
* Interface for thrust/acceleration-based UAV models. Multicopter!
*
* @author Julian Zobel
* @version 1.0, 19.01.2022
......@@ -34,27 +34,181 @@ public interface MulticopterModel {
public final double AIRDENSITY = 1.2045; // kg/m^3
public final double GRAVITY = 9.807; // m/s^2
public double hoverThrustRequired();
/**
* Query if the multicopter's motors are active and usable.
*
* @return
*/
public boolean isOn();
/**
* Maximum provided thrust by the multicopter motors (full throttle, maximum rotation).
*
* @return
*/
public double maxThrust();
/**
* Minimum provided thrust by the multicopter motors (idle, minimum rotation)
*
* @return
*/
public double minThrust();
// v
public double verticalAscentMaxVelocity();
/**
* Thrust requires to hold the multicopter on a stable level in the air.
*
* @return
*/
public double hoverThrust();
/**
* Thrust required for a certain horizontal velocity. Includes vertical thrust component.
*
* @param velocity
* @return
*/
public double thrustForHorizontalVelocity(double velocity);
/**
* Thrust required for the maximum possible horizontal velocity. Includes vertical
* thrust component.
*
* @return
*/
public double thrustForHorizontalMaxVelocity();
/**
* Thrust required for a controlled vertical descent.
*
* @param velocity
* @return
*/
public double verticalDescentThrust(double velocity);
/**
* Thrust required for vertical ascent.
*
* @param velocity
* @return
*/
public double verticalAscentThrust(double velocity);
/**
* Optimal horizontal speed of the multicopter w.r.t. energy consumption.
* @return
*/
public double optimalSpeed();
/**
* Maximum horizontal velocity.
* @return
*/
public double horizontalMaxVelocity();
/**
* Minimum horizontal velocity.
* @return
*/
public double horizontalMinVelocity();
// acc
/**
* Maximum velocity for vertical ascent.
* @return
*/
public double verticalAscentMaxVelocity();
/**
* Maximum velocity for vertical descent.
* @return
*/
public double verticalDescentMaxVelocity();
/**
* Optimal velocity when flying a curve.
* @return
*/
public double curveVelocity();
/**
* Maximum acceleration for horizontal flight.
* @return
*/
public double horizontalMaxAcceleration();
// curve
/**
* Maximum deceleration in horizontal flight.
* @return
*/
public double horizontalMaxDeceleration();
/**
* Maximum acceleration for vertical descent.
* @return
*/
public double verticalDescentMaxAcceleration();
/**
* Maximum acceleration for vertical ascent.
* @return
*/
public double verticalAscentMaxAcceleration();
/**
* Maximum turn angle (rad per second), that the multicopter can change its facing while hovering.
* @return
*/
public double getMaximumTurnAngle();
/**
* The radius of the curve/circle the multicopter can fly with a given velocity.
* @param curveVelocity
* @return
*/
public double getCurveRadius(double curveVelocity);
/**
* The acceleration, the multicopter is subject to when flying a curve/in a circle with a given velocity.
* @param curveVelocity
* @return
*/
public double getCurveCentripedalAcceleration(double curveVelocity);
/**
* Pitch angle (Angle of attack) required to achieve a given velocity.
* @param velocity
* @return
*/
public double pitchAngleForHorizontalVelocity(double velocity);
/**
* Power consumption in watt, when flying a given velocity.
* @param velocity
* @return
*/
public double powerConsumptionWatt(double velocity);
public double optimalSpeed();
/**
* Sets the actuator of the multicopter.
* @param motor
*/
public void setMotor(ActuatorComponent motor);
/**
* Puts load on the multicopter's motors for a given phase time, such that the
* given thrust is provided within that time.
*
* @param thrust
* @param phaseTime
*/
public void thrust(double thrust, long phaseTime);
/**
* Hacky factory interface for multicopter model factories.
*
* @author Julian Zobel
* @version 1.0, 20.01.2022
*/
public interface Factory {
public MulticopterModel createComponent();
}
......
......@@ -128,12 +128,12 @@ public class UAVTopologyComponent extends AbstractTopologyComponent implements S
@Override
public double getMinMovementSpeed() {
return movement.horizontalMinVelocity();
return movement.getMinimumVelocity();
}
@Override
public double getMaxMovementSpeed() {
return movement.getHorizontalMaxVelocity();
return movement.getMaximumVelocity();
}
@Override
......@@ -339,8 +339,7 @@ public class UAVTopologyComponent extends AbstractTopologyComponent implements S
&& state == UAVstate.BASE_CONNECTION_READY
&& activate()) {
disconnectFromBase();
movement.setTargetVelocity(movement.getVerticalAscentMaxVelocity());
movement.setTargetLocation(getBaseHoverLocation(), cb);
return true;
......@@ -442,7 +441,7 @@ public class UAVTopologyComponent extends AbstractTopologyComponent implements S
@Override
public double estimatePowerConsumptionWatt(double velocity) {
return movement.estimatePowerConsumptionWatt(velocity);
return movement.powerConsumptionWatt(velocity);
}
@Override
......@@ -460,7 +459,7 @@ public class UAVTopologyComponent extends AbstractTopologyComponent implements S
}
public double getOptimalMovementSpeed() {
return movement.estimateOptimalSpeed();
return movement.optimalSpeed();
}
@Override
......
......@@ -28,10 +28,9 @@ import java.util.Map;
import javax.persistence.Column;
import javax.persistence.Entity;
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.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.util.PositionVector;
import de.tud.kom.p2psim.impl.util.db.metric.CustomMeasurement;
......@@ -53,40 +52,19 @@ public class MulticopterMovement implements UAVMovementModel {
private UAVTopologyComponent topologyComponent;
private double currentAngleOfAttack;
private double velocity;
private double targetVelocity;
private LinkedList<PositionVector> route = new LinkedList<>();
private Map<PositionVector, ReachedLocationCallback> locationCallbacks = new LinkedHashMap<>(); // TODO callback interface
private MulticopterModel uav;
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 maximumDecentVelocityAllowed; // m/s
private double optimalVelocity = -1;
// TODO currently not used
private double maximumTurnAngle; // 90° per second turn angle
public MulticopterMovement(UAVTopologyComponent topologyComponent, double massTotal,
double areaTop, double areaFront, double UAVDragCoefficient, double maximumPitchAngleAllowed,
double maximumDecentVelocityAllowed, double maximumTurnAngle) {
public MulticopterMovement(UAVTopologyComponent topologyComponent, MulticopterModel uav) {
this.topologyComponent = topologyComponent;
this.mass = massTotal;
this.areaTop = areaTop;
this.areaFront = areaFront;
this.dragCoefficient = UAVDragCoefficient;
this.maximumPitchAngleAllowed = maximumPitchAngleAllowed;
this.maximumDecentVelocityAllowed = maximumDecentVelocityAllowed;
this.maximumTurnAngle = maximumTurnAngle;
this.uav = uav;
}
boolean first = true;
......@@ -94,7 +72,7 @@ public class MulticopterMovement implements UAVMovementModel {
@Override
public void move(long timeBetweenMovementOperations) {
if(motor.isOn() && !route.isEmpty()) {
if(uav.isOn() && !route.isEmpty()) {
PositionVector position = new PositionVector(topologyComponent.getRealPosition());
PositionVector target = route.getFirst();
......@@ -112,8 +90,8 @@ public class MulticopterMovement implements UAVMovementModel {
// go to hover mode
topologyComponent.updateCurrentLocation(target.clone());
velocity = 0;
motor.requestThrust(hoverThrustRequired(), timeBetweenMovementOperations);
velocity = 0;
uav.thrust(uav.hoverThrust(), timeBetweenMovementOperations);
PositionVector direction = topologyComponent.getCurrentDirection().clone();
direction.setEntry(2, 0);
......@@ -125,13 +103,15 @@ public class MulticopterMovement implements UAVMovementModel {
else {
// get to speed
if(targetVelocity > 0 && targetVelocity < getHorizontalMaxVelocity()) {
motor.requestThrust(estimateRequiredThrust(targetVelocity), timeBetweenMovementOperations);
if(targetVelocity > 0 && targetVelocity < getMaximumVelocity()) {
uav.thrust(uav.thrustForHorizontalVelocity(targetVelocity), timeBetweenMovementOperations);
velocity = targetVelocity;
}
else {
motor.requestThrust(getHorizontalMaxVelocityRequiredTotalThrust(), timeBetweenMovementOperations);
velocity = getHorizontalMaxVelocity();
uav.thrust(uav.thrustForHorizontalMaxVelocity(), timeBetweenMovementOperations);
velocity = getMaximumVelocity();
}
long timeUntilReachedLocation = (long) (distanceToTargetPosition / velocity) * Time.SECOND;
......@@ -162,13 +142,13 @@ public class MulticopterMovement implements UAVMovementModel {
double timefactor = timeBetweenMovementOperations / Time.SECOND;
// get to speed
if(targetVelocity > 0 && targetVelocity < getHorizontalMaxVelocity()) {
motor.requestThrust(estimateRequiredThrust(targetVelocity), timeBetweenMovementOperations);
if(targetVelocity > 0 && targetVelocity < getMaximumVelocity()) {
uav.thrust(uav.thrustForHorizontalVelocity(targetVelocity), timeBetweenMovementOperations);
velocity = targetVelocity;
}
else {
motor.requestThrust(getHorizontalMaxVelocityRequiredTotalThrust(), timeBetweenMovementOperations);
velocity = getHorizontalMaxVelocity();
uav.thrust(uav.thrustForHorizontalMaxVelocity(), timeBetweenMovementOperations);
velocity = getMaximumVelocity();
}
PositionVector directionToTarget = new PositionVector(target);
......@@ -189,7 +169,7 @@ public class MulticopterMovement implements UAVMovementModel {
}
}
else if(motor.isOn()) {
else if(uav.isOn()) {
if(velocity != 0) {
throw new UnsupportedOperationException("[MulticopterMovement] no route but speed not 0?");
......@@ -198,10 +178,10 @@ public class MulticopterMovement implements UAVMovementModel {
PositionVector position = new PositionVector(topologyComponent.getRealPosition());
if(position.getAltitude() == 0) {
motor.requestThrust(0, timeBetweenMovementOperations);
uav.thrust(0, timeBetweenMovementOperations);
}
else {
motor.requestThrust(hoverThrustRequired(), timeBetweenMovementOperations);
uav.thrust(uav.hoverThrust(), timeBetweenMovementOperations);
}
topologyComponent.updateCurrentLocation(position);
......@@ -212,92 +192,9 @@ public class MulticopterMovement implements UAVMovementModel {
*
*/
protected double verticalDescentMaxThrust() {
// m * g - 0.5 * p * C * A * v^2
return hoverThrustRequired() - 0.5 * bodyDrag(0, new PositionVector(0,0,1)) * maximumDecentVelocityAllowed * maximumDecentVelocityAllowed;
}
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 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, topologyComponent.getCurrentDirection()) * 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
*/
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;
uav.setMotor(motor);
}
@Override
......@@ -366,107 +263,28 @@ public class MulticopterMovement implements UAVMovementModel {
}
@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)));
public double getMinimumVelocity() {
return uav.horizontalMinVelocity();
}
@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;
}
public double optimalSpeed() {
return uav.optimalSpeed();
}
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;
}
@Override
public double getMaximumVelocity() {
return uav.horizontalMaxVelocity();
}
@Override
public double powerConsumptionWatt(double velocity) {
return uav.powerConsumptionWatt(velocity);
}
/**
* 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;
}
/**
* Factory for this movement model
*
......@@ -474,47 +292,15 @@ public class MulticopterMovement implements UAVMovementModel {
* @version 1.0, 14.01.2020
*/
public static class Factory implements AerialMovementModelFactory {
private MulticopterModel.Factory factory;
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.Factory uavFactory) {
this.factory = uavFactory;
}
public UAVMovementModel createComponent(UAVTopologyComponent topologyComponent) {
return new MulticopterMovement(topologyComponent, massTotal, areaTop, areaFront,
UAVDragCoefficient, maximumPitchAngleAllowed, maximumDecentVelocityAllowed, maximumTurnAngle);
return new MulticopterMovement(topologyComponent, factory.createComponent());
}
}
......@@ -559,49 +345,12 @@ public class MulticopterMovement implements UAVMovementModel {
}
public static EnergyModelPropertyMeasurement getPropoertyMeasurement(MulticopterMovement m, double velocity) {
double th = m.estimateRequiredThrust(velocity);
if (th == -1) {
return null;
}
double w = m.estimatePowerConsumptionWatt(velocity);
double amp = w / 14.8;
return new EnergyModelPropertyMeasurement(velocity, th, amp, w);
public static EnergyModelPropertyMeasurement getPropoertyMeasurement(StateMulticopterMovement m, double velocity, double thrust, double watt) {
// FIXME
double amp = watt / 14.8;
return new EnergyModelPropertyMeasurement(velocity, thrust, amp, watt);
}
}
@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;
}
}
......@@ -47,9 +47,9 @@ public class SimpleMulticopterMovement implements UAVMovementModel {
private double targetVelocity;
private double maximumHorizontalVelocity;
private double maximumVerticalVelocity;
// TODO currently not used
private double maximumVerticalVelocity;
private double minimumHorizontalVelocity;
private double minimumVerticalVelocity;
......@@ -198,7 +198,7 @@ public class SimpleMulticopterMovement implements UAVMovementModel {
}
@Override
public double estimatePowerConsumptionWatt(double velocity) {
public double powerConsumptionWatt(double velocity) {
double wattage = 0;
......@@ -220,21 +220,7 @@ public class SimpleMulticopterMovement implements UAVMovementModel {
this.motor = (StatefulActuatorComponent) motor;
}
@Override
public double getVerticalAscentMaxVelocity() {
return maximumVerticalVelocity;
}
@Override
public double getHorizontalMaxVelocity() {
return maximumHorizontalVelocity;
}
@Override
public double getHorizontalMinVelocity() {
return 0;
}
/**
* Factory for this movement model
*
......@@ -279,8 +265,19 @@ public class SimpleMulticopterMovement implements UAVMovementModel {
}
}
@Override
public double getMinimumVelocity() {
return 0;
}
@Override
public double getMaximumVelocity() {
return maximumHorizontalVelocity;
}
@Override
public double estimateOptimalSpeed() {
public double optimalSpeed() {
return optimalHorizontalVelocity;
}
}
......@@ -27,6 +27,12 @@ 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.util.PositionVector;
/**
* A model for the Intel Aero Ready-to-Fly multicopter UAV.
*
* @author Julian Zobel
* @version 20.01.2022
*/
public class IntelAeroRTF implements MulticopterModel {
private double mass; // kg
......@@ -36,6 +42,7 @@ public class IntelAeroRTF implements MulticopterModel {
private double maximumPitchAngleAllowed; // ° max angle
private double maximumVerticalVelocityAllowed; // m/s
private double optimalCurveVelocity;
private double optimalVelocity = -1;
private double maximumTurnAngle; // 90° per second turn angle
......@@ -44,14 +51,15 @@ public class IntelAeroRTF implements MulticopterModel {
public IntelAeroRTF(double massTotal,
double areaTop, double areaFront, double UAVDragCoefficient, double maximumPitchAngleAllowed,
double maximumDescentVelocityAllowed, double maximumTurnAngle) {
double maximumDescentVelocityAllowed, double maximumTurnAngle, double optimalCurveVelocity) {
this.mass = massTotal;
this.areaTop = areaTop;
this.areaFront = areaFront;
this.dragCoefficient = UAVDragCoefficient;
this.maximumPitchAngleAllowed = maximumPitchAngleAllowed;
this.maximumVerticalVelocityAllowed = maximumDescentVelocityAllowed;
this.maximumTurnAngle = maximumTurnAngle;
this.maximumTurnAngle = maximumTurnAngle;
this.optimalCurveVelocity = optimalCurveVelocity;
}
/**
......@@ -61,6 +69,7 @@ public class IntelAeroRTF implements MulticopterModel {
* @param velocity
* @return
*/
@Override
public double pitchAngleForHorizontalVelocity(double velocity) {
int low = 0;
......@@ -70,7 +79,7 @@ public class IntelAeroRTF implements MulticopterModel {
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));
double v2 = 2 * hoverThrust() * Math.tan(Math.toRadians(i)) / bodyDrag(Math.toRadians(i), new PositionVector(1,0,0));
if(v2 > vsquared && i < high) {
high = i;
......@@ -97,7 +106,7 @@ public class IntelAeroRTF implements MulticopterModel {
double d = lo + i * step;
double v2 = 2 * hoverThrustRequired() * Math.tan(Math.toRadians(d)) / bodyDrag(Math.toRadians(d), new PositionVector(1,0,0));
double v2 = 2 * hoverThrust() * Math.tan(Math.toRadians(d)) / bodyDrag(Math.toRadians(d), new PositionVector(1,0,0));
double diff = Math.abs(((velocity * velocity) - v2));
......@@ -113,9 +122,10 @@ public class IntelAeroRTF implements MulticopterModel {
return maximumPitchAngleAllowed;
}
@Override
public double thrustForHorizontalVelocity(double velocity) {
if(velocity == 0) {
return motor.estimatePowerConsumptionWatt(hoverThrustRequired());
return hoverThrust();
}
else if(velocity > horizontalMaxVelocity()) {
return -1;
......@@ -126,21 +136,21 @@ public class IntelAeroRTF implements MulticopterModel {
else {
double estimateAngle = pitchAngleForHorizontalVelocity(velocity);
double estimatedDrag = forwardDrag(velocity, estimateAngle);
double requiredThrust = Math.sqrt(hoverThrustRequired() * hoverThrustRequired() + estimatedDrag * estimatedDrag);
double requiredThrust = Math.sqrt(hoverThrust() * hoverThrust() + estimatedDrag * estimatedDrag);
return requiredThrust;
}
}
@Override
public double horizontalMinVelocity() {
return Math.sqrt(2 * hoverThrustRequired() * Math.tan(Math.toRadians(0.25)) / bodyDrag(Math.toRadians(0.25), new PositionVector(1,0,0)));
return Math.sqrt(2 * hoverThrust() * Math.tan(Math.toRadians(0.25)) / bodyDrag(Math.toRadians(0.25), new PositionVector(1,0,0)));
}
@Override
public double powerConsumptionWatt(double velocity) {
if(velocity == 0) {
return motor.estimatePowerConsumptionWatt(hoverThrustRequired());
return motor.estimatePowerConsumptionWatt(hoverThrust());
}
else if(velocity > horizontalMaxVelocity()) {
return -1;
......@@ -159,32 +169,51 @@ public class IntelAeroRTF implements MulticopterModel {
*
*/
// Thrust required to hold the maximum allowed descent velocity
public double verticalDescentThrust() {
return hoverThrustRequired() - verticalDescentDrag();
@Override
public double verticalDescentThrust(double velocity) {
return hoverThrust() - verticalDrag(velocity);
}
// 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;
private double verticalDrag(double velocity) {
assert velocity <= maximumVerticalVelocityAllowed;
assert velocity > 0;
return dragInducedByMovement(0, new PositionVector(0,0,1), velocity);
}
@Override
public double verticalDescentMaxAcceleration() {
return verticalDescentDrag() / mass;
return GRAVITY - verticalDrag(maximumVerticalVelocityAllowed) / mass;
}
@Override
public double verticalDescentMaxVelocity() {
double technicalMaximum = Math.sqrt(2.0 * (hoverThrust()) / bodyDrag(0, new PositionVector(0,0,-1)));
return Math.min(technicalMaximum, maximumVerticalVelocityAllowed);
}
@Override
public double verticalAscentMaxAcceleration() {
return (motor.getMaxThrust() - hoverThrustRequired()) / mass;
return (motor.getMaxThrust() - hoverThrust()) / mass;
}
@Override
public double verticalAscentMaxVelocity() {
double maxThrust = motor.getMaxThrust();
return Math.sqrt(2.0 * (maxThrust - hoverThrustRequired()) / bodyDrag(0, new PositionVector(0,0,1)));
public double verticalAscentMaxVelocity() {
double technicalMaximum = Math.sqrt(2.0 * (motor.getMaxThrust() - hoverThrust()) / bodyDrag(0, new PositionVector(0,0,1)));
return Math.min(technicalMaximum, maximumVerticalVelocityAllowed);
}
@Override
public double hoverThrustRequired() {
public double verticalAscentThrust(double velocity) {
return hoverThrust() + verticalDrag(velocity);
}
@Override
public double hoverThrust() {
return mass * GRAVITY;
}
......@@ -194,28 +223,43 @@ public class IntelAeroRTF implements MulticopterModel {
double maxVelocity = Math.sqrt( (2.0 * horizontalThrust) / bodyDrag(maximumPitchAngleAllowed, new PositionVector(1,0,0)));
return maxVelocity;
}
protected double horizontalComponentMaxThrust() {
private double horizontalComponentMaxThrust() {
// hoverthrust / cos => amount of thrust in horizonal direction with °angle
double stableAltitudeMaximumTotalThrust = getHorizontalMaxVelocityRequiredTotalThrust();
double stableAltitudeMaximumTotalThrust = thrustForHorizontalMaxVelocity();
// fraction of total thrust in horizonal (forward) direction with °angle
double maximumHorizontalThrustStableAltitude = stableAltitudeMaximumTotalThrust * Math.sin(maximumPitchAngleAllowed);
return maximumHorizontalThrustStableAltitude;
}
/**
* Acceleration is thrust from motors minus drag from speed
* Drag: rough approximation for velocity induced drag when accelerating (half of maximum velocity drag)
*/
@Override
public double horizontalMaxAcceleration() {
return horizontalComponentMaxThrust() / mass;
return horizontalComponentMaxThrust() - forwardDrag(horizontalMaxVelocity() / 2, maximumPitchAngleAllowed) / mass;
}
/**
* Acceleration is thrust from motors minus drag from speed
* Drag: rough approximation for velocity induced drag when accelerating (half of maximum velocity drag)
*/
@Override
public double horizontalMaxDeceleration() {
return horizontalComponentMaxThrust() + forwardDrag(horizontalMaxVelocity() / 2, maximumPitchAngleAllowed) / mass;
}
protected double getHorizontalMaxVelocityRequiredTotalThrust() {
return hoverThrustRequired() / Math.cos(maximumPitchAngleAllowed);
@Override
public double thrustForHorizontalMaxVelocity() {
return hoverThrust() / Math.cos(maximumPitchAngleAllowed);
}
public double bodyDrag(double angleRadians, PositionVector direction) {
private double bodyDrag(double angleRadians, PositionVector direction) {
return AIRDENSITY * dragCoefficient * areaExposedToDrag(angleRadians, direction);
}
protected double areaExposedToDrag(double angleRadians, PositionVector direction) {
private 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();
......@@ -229,7 +273,7 @@ public class IntelAeroRTF implements MulticopterModel {
/*
* F_drag [N] = 0.5 * p * C_drag * A * v^2
*/
public double dragInducedByMovement(double angleOfAttack, PositionVector direction, double velocity) {
private double dragInducedByMovement(double angleOfAttack, PositionVector direction, double velocity) {
return 0.5 * bodyDrag(angleOfAttack, direction) * velocity * velocity;
}
......@@ -240,7 +284,7 @@ public class IntelAeroRTF implements MulticopterModel {
* @param angleInRadians
* @return
*/
public double forwardDrag(double velocity, double angleInRadians) {
private double forwardDrag(double velocity, double angleInRadians) {
return dragInducedByMovement(angleInRadians, new PositionVector(1,0,0), velocity);
}
......@@ -273,17 +317,55 @@ public class IntelAeroRTF implements MulticopterModel {
return optimalVelocity;
}
@Override
public boolean isOn() {
return motor.isOn();
}
/////
@Override
public void setMotor(ActuatorComponent actuator) {
assert actuator instanceof StatelessActuatorComponent;
this.motor = (StatelessActuatorComponent) motor;
this.motor = (StatelessActuatorComponent) actuator;
}
@Override
public double getMaximumTurnAngle() {
return maximumTurnAngle;
}
@Override
public void thrust(double thrust, long phaseTime) {
motor.requestThrust(thrust, phaseTime);
}
@Override
public double getCurveRadius(double curveVelocity) {
return Math.pow(curveVelocity, 2) / getCurveCentripedalAcceleration(curveVelocity);
}
@Override
public double getCurveCentripedalAcceleration(double curveVelocity) {
return (horizontalComponentMaxThrust() - thrustForHorizontalVelocity(curveVelocity)) / mass;
}
@Override
public double maxThrust() {
return motor.getMaxThrust();
}
@Override
public double minThrust() {
return motor.getMinThrust();
}
@Override
public double curveVelocity() {
return optimalCurveVelocity;
}
/**
* Factory for this movement model
* Factory for the Intel UAV
*
* @author Julian Zobel
* @version 1.0, 14.01.2020
......@@ -298,6 +380,7 @@ public class IntelAeroRTF implements MulticopterModel {
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
private double optimalCurveVelocity = 8;
public void setMassTotal(double massTotal) {
this.massTotal = massTotal;
......@@ -330,7 +413,11 @@ public class IntelAeroRTF implements MulticopterModel {
public MulticopterModel createComponent() {
return new IntelAeroRTF(massTotal, areaTop, areaFront,
UAVDragCoefficient, maximumPitchAngleAllowed, maximumVerticalVelocityAllowed, maximumTurnAngle);
UAVDragCoefficient, maximumPitchAngleAllowed, maximumVerticalVelocityAllowed, maximumTurnAngle, optimalCurveVelocity);
}
public void setOptimalCurveVelocity(double optimalCurveVelocity) {
this.optimalCurveVelocity = optimalCurveVelocity;
}
}
}
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