Merge branch 'master' of ssh://github.com/cthunter01/qtrocket

This commit is contained in:
Travis Hunter 2023-04-15 15:41:11 -06:00
commit 2b7606c417
28 changed files with 370 additions and 157 deletions

View File

@ -7,7 +7,7 @@
#include <thread>
#include "sim/USStandardAtmosphere.h"
#include "sim/ConstantAtmosphere.h"
#include "sim/ConstantGravityModel.h"
@ -69,7 +69,7 @@ QtRocket::QtRocket()
running = false;
atmosphere =
std::make_shared<sim::USStandardAtmosphere>();
std::make_shared<sim::ConstantAtmosphere>();
gravity =
std::make_shared<sim::ConstantGravityModel>();

View File

@ -9,6 +9,7 @@
#include <QTextStream>
#include <memory>
#include <iostream>
#include <cmath>
MainWindow::MainWindow(QtRocket* _qtRocket, QWidget *parent)
@ -82,24 +83,28 @@ void MainWindow::on_testButton2_clicked()
rocket.setDragCoefficient(dragCoeff);
rocket.launch();
const std::vector<std::vector<double>>& res = rocket.getStates();
const std::vector<std::pair<double, std::vector<double>>>& res = rocket.getStates();
for(const auto& i : res)
{
std::cout << i.first << ": " << "(" << i.second[0] << ", " << i.second[1] << ", " << i.second[2] << ")\n";
}
auto& plot = ui->plotWindow;
// generate some data:
QVector<double> xData(res.size()), yData(res.size());
for (int i = 0; i < xData.size(); ++i)
QVector<double> tData(res.size()), zData(res.size());
for (int i = 0; i < tData.size(); ++i)
{
xData[i] = res[i][0];
yData[i] = res[i][2];
tData[i] = res[i].first;
zData[i] = res[i].second[2];
}
// create graph and assign data to it:
plot->addGraph();
plot->graph(0)->setData(xData, yData);
plot->graph(0)->setData(tData, zData);
// give the axes some labels:
plot->xAxis->setLabel("x");
plot->yAxis->setLabel("y");
plot->xAxis->setLabel("time");
plot->yAxis->setLabel("Z");
// set axes ranges, so we see all data:
plot->xAxis->setRange(*std::min_element(std::begin(xData), std::end(xData)), *std::max_element(std::begin(xData), std::end(xData)));
plot->yAxis->setRange(*std::min_element(std::begin(yData), std::end(yData)), *std::max_element(std::begin(yData), std::end(yData)));
plot->xAxis->setRange(*std::min_element(std::begin(tData), std::end(tData)), *std::max_element(std::begin(tData), std::end(tData)));
plot->yAxis->setRange(*std::min_element(std::begin(zData), std::end(zData)), *std::max_element(std::begin(zData), std::end(zData)));
plot->replot();
}

View File

@ -119,7 +119,7 @@
<item row="0" column="1">
<widget class="QLineEdit" name="initialVelocity">
<property name="text">
<string>500.0</string>
<string>50.0</string>
</property>
</widget>
</item>
@ -133,7 +133,7 @@
<item row="1" column="1">
<widget class="QLineEdit" name="initialAngle">
<property name="text">
<string>45.0</string>
<string>90.0</string>
</property>
</widget>
</item>

View File

@ -1,3 +1,6 @@
// This is not my file, so I don't want to mess with it. I want to silence these warnings
// so I don't miss any from my own code
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
/***************************************************************************
** **
** QCustomPlot, an easy to use, modern plotting widget for Qt **

View File

@ -1 +0,0 @@
#include "Motor.h"

View File

@ -1,67 +0,0 @@
#ifndef MODEL_MOTOR_H
#define MODEL_MOTOR_H
// For boost serialization. We're using boost::serialize to save
// and load Motor data to file
#include <boost/archive/text_iarchive.hpp>
#include <boost/archive/text_oarchive.hpp>
#include <string>
#include "Thrustcurve.h"
#include "MotorCase.h"
class Motor
{
public:
Motor();
~Motor();
private:
// Needed for boost serialize
friend class boost::serialization::access;
template<class Archive>
void serialize(Archive& ar, const unsigned int version);
std::string manufacturer;
std::string impulseClass; // 'A', 'B', '1/2A', 'M', etc
std::string propType;
bool sparky;
// Thrust parameters
double totalImpulse;
double avgImpulse;
int delay;
double burnTime;
double isp;
MotorCase motorCase;
Thrustcurve thrust;
// Physical dimensions
int diameter;
int length;
double totalWeight;
double propWeight;
};
template<class Archive>
void Motor::serialize(Archive& ar, const unsigned int version)
{
ar & manufacturer;
ar & impulseClass;
ar & propType;
ar & sparky;
ar & totalImpulse;
ar & avgImpulse;
ar & delay;
ar & burnTime;
ar & isp;
ar & motorCase;
ar & thrust;
ar & diameter;
ar & length;
ar & totalWeight;
ar & propWeight;
}
#endif // MODEL_MOTOR_H

17
model/MotorModel.cpp Normal file
View File

@ -0,0 +1,17 @@
#include "MotorModel.h"
MotorModel::MotorModel()
{
}
MotorModel::~MotorModel()
{
}
void MotorModel::setDataFromJsonString(const std::string& jsonString)
{
}

153
model/MotorModel.h Normal file
View File

@ -0,0 +1,153 @@
#ifndef MODEL_MOTORMODEL_H
#define MODEL_MOTORMODEL_H
// For boost serialization. We're using boost::serialize to save
// and load Motor data to file
#include <boost/archive/text_iarchive.hpp>
#include <boost/archive/text_oarchive.hpp>
#include <string>
#include "Thrustcurve.h"
#include "MotorCase.h"
class MotorModel
{
public:
MotorModel();
~MotorModel();
void setDataFromJsonString(const std::string& jsonString);
enum class AVAILABILITY
{
REGULAR, // available
OOP // Out of Production
};
enum class CERTORG
{
AMRS,
CAR,
NAR,
TRA,
UNC
};
enum class MOTORTYPE
{
SU,
RELOAD,
HYBRID
};
struct MotorAvailability
{
MotorAvailability(const AVAILABILITY& a) : availability(a) {}
MotorAvailability() : MotorAvailability(AVAILABILITY::REGULAR) {}
AVAILABILITY availability{AVAILABILITY::REGULAR};
std::string str()
{
if(availability == AVAILABILITY::REGULAR)
return std::string("regular");
else
return std::string("OOP");
}
};
struct CertOrg
{
CertOrg(const CERTORG& c) : org(c) {}
CertOrg() : CertOrg(CERTORG::UNC) {}
CERTORG org{CERTORG::UNC};
std::string str()
{
if(org == CERTORG::AMRS)
return std::string("Austrialian Model Rocket Society Inc.");
else if(org == CERTORG::CAR)
return std::string("Canadian Association of Rocketry");
else if(org == CERTORG::NAR)
return std::string("National Association of Rocketry");
else if(org == CERTORG::TRA)
return std::string("Tripoli Rocketry Association, Inc.");
else // Uncertified
return std::string("Uncertified");
}
};
struct MotorType
{
MotorType(const MOTORTYPE& t) : type(t) {}
MotorType() : MotorType(MOTORTYPE::SU) {}
MOTORTYPE type;
std::string str()
{
if(type == MOTORTYPE::SU)
return std::string("Single Use");
else if(type == MOTORTYPE::RELOAD)
return std::string("Reload");
else
return std::string("Hybrid");
}
};
private:
// Needed for boost serialize
friend class boost::serialization::access;
template<class Archive>
void serialize(Archive& ar, const unsigned int version);
MotorAvailability availability{AVAILABILITY::REGULAR};
double avgThrust{0.0};
double burnTime{0.0};
CertOrg certOrg{CERTORG::UNC};
std::string commonName{""};
// int dataFiles
std::vector<int> delays; // -1 delay means no ejection charge
std::string designation{""};
int diameter{0};
std::string impulseClass; // 'A', 'B', '1/2A', 'M', etc
std::string infoUrl{""};
int length;
std::string manufacturer;
double maxThrust{0.0};
std::string motorIdTC{""}; // 24 character hex string used by thrustcurve to ID a motor
std::string propType{""}; // black powder, etc
double propWeight{0.0};
bool sparky{false};
double totalImpulse;
double totalWeight;
MotorType type{MOTORTYPE::SU};
std::string lastUpdated{""};
// Thrust parameters
Thrustcurve thrust;
// Physical dimensions
};
template<class Archive>
void MotorModel::serialize(Archive& ar, const unsigned int version)
{
ar & manufacturer;
ar & impulseClass;
ar & propType;
ar & sparky;
ar & totalImpulse;
ar & delays;
ar & burnTime;
ar & thrust;
ar & diameter;
ar & length;
ar & totalWeight;
ar & propWeight;
}
#endif // MODEL_MOTORMODEL_H

View File

@ -9,5 +9,23 @@ Rocket::Rocket() : propagator(this)
void Rocket::launch()
{
tc.setIgnitionTime(5.0);
std::vector<std::pair<double, double>> temp;
temp.push_back(std::make_pair(0.0, 0.0));
temp.push_back(std::make_pair(0.1, 10.0));
temp.push_back(std::make_pair(0.2, 50.0));
temp.push_back(std::make_pair(1.2, 50.0));
temp.push_back(std::make_pair(1.3, 0.0));
tc.setThrustCurveVector(temp);
propagator.runUntilTerminate();
}
double Rocket::getThrust(double t)
{
return tc.getThrust(t);
}
void Rocket::setThrustCurve(const Thrustcurve& curve)
{
tc = curve;
}

View File

@ -2,6 +2,7 @@
#define ROCKET_H
#include "sim/Propagator.h"
#include "model/Thrustcurve.h"
#include <utility> // std::move
#include <memory>
@ -12,7 +13,7 @@ public:
Rocket();
void launch();
const std::vector<std::vector<double>>& getStates() const { return propagator.getStates(); }
const std::vector<std::pair<double, std::vector<double>>>& getStates() const { return propagator.getStates(); }
void setInitialState(const std::vector<double>& initState) { propagator.setInitialState(initState); }
@ -21,11 +22,17 @@ public:
void setDragCoefficient(double d) { dragCoeff = d; }
double getDragCoefficient() const { return dragCoeff; }
double getThrust(double t);
void setThrustCurve(const Thrustcurve& curve);
private:
sim::Propagator propagator;
double dragCoeff;
double mass;
Thrustcurve tc;
};
#endif // ROCKET_H

View File

@ -4,7 +4,8 @@
Thrustcurve::Thrustcurve(std::vector<std::pair<double, double>>& tc)
: thrustCurve(tc),
maxTime(0.0)
maxTime(0.0),
ignitionTime(0.0)
{
maxTime = std::max_element(thrustCurve.begin(),
thrustCurve.end(),
@ -23,8 +24,23 @@ Thrustcurve::Thrustcurve()
Thrustcurve::~Thrustcurve()
{}
void Thrustcurve::setThrustCurveVector(const std::vector<std::pair<double, double>>& v)
{
thrustCurve.clear();
thrustCurve.resize(v.size());
std::copy(v.begin(), v.end(), thrustCurve.begin());
}
void Thrustcurve::setIgnitionTime(double t)
{
ignitionTime = t;
maxTime += ignitionTime;
}
double Thrustcurve::getThrust(double t)
{
// calculate t relative to the start time of the motor
t -= ignitionTime;
if(t < 0.0 || t > maxTime)
{
return 0.0;

View File

@ -7,9 +7,6 @@
#include <boost/archive/text_iarchive.hpp>
#include <boost/archive/text_oarchive.hpp>
// No namespace. Maybe should be, but this is a model rocket program
// so model is sort of implied? Or I'm just making excuses for being lazy
class Thrustcurve
{
public:
@ -25,6 +22,18 @@ public:
Thrustcurve();
~Thrustcurve();
Thrustcurve& operator=(const Thrustcurve& rhs)
{
if(this != &rhs)
{
thrustCurve = rhs.thrustCurve;
maxTime = rhs.maxTime;
ignitionTime = rhs.ignitionTime;
}
return *this;
}
/**
* Assuming that the thrust is one dimensional. Seems reasonable, but just
* documenting that for the record. For timesteps between known points the thrust
@ -34,6 +43,14 @@ public:
*/
double getThrust(double t);
void setIgnitionTime(double t);
/**
* TODO: Get rid of this. This is for temporary testing
*/
void setThrustCurveVector(const std::vector<std::pair<double, double>>& v);
private:
// We're using boost::serialize for data storage and retrieval
friend class boost::serialization::access;
@ -41,7 +58,8 @@ private:
void serialize(Archive& ar, const unsigned int version);
std::vector<std::pair<double, double>> thrustCurve;
double maxTime;
double maxTime{0.0};
double ignitionTime{0.0};
};
template<class Archive>

View File

@ -16,11 +16,10 @@ SOURCES += \
main.cpp \
gui/RocketTreeView.cpp \
gui/MainWindow.cpp \
model/Motor.cpp \
model/MotorCase.cpp \
model/MotorModel.cpp \
model/Rocket.cpp \
model/Thrustcurve.cpp \
sim/AtmosphericModel.cpp \
sim/ConstantGravityModel.cpp \
sim/GravityModel.cpp \
sim/Propagator.cpp \
@ -44,11 +43,12 @@ HEADERS += \
gui/RocketTreeView.h \
gui/MainWindow.h \
gui/qcustomplot.h \
model/Motor.h \
model/MotorCase.h \
model/MotorModel.h \
model/Rocket.h \
model/Thrustcurve.h \
sim/AtmosphericModel.h \
sim/ConstantAtmosphere.h \
sim/ConstantGravityModel.h \
sim/DESolver.h \
sim/GeoidModel.h \
@ -66,6 +66,7 @@ HEADERS += \
utils/TSQueue.h \
utils/ThreadPool.h \
utils/ThrustCurveAPI.h \
utils/Triplet.h \
utils/math/Constants.h \
utils/math/Quaternion.h \
utils/math/Vector3.h

View File

@ -1,14 +0,0 @@
#include "AtmosphericModel.h"
namespace sim
{
AtmosphericModel::AtmosphericModel()
{
}
AtmosphericModel::~AtmosphericModel()
{
}
} // namespace sim

View File

@ -7,8 +7,8 @@ namespace sim
class AtmosphericModel
{
public:
AtmosphericModel();
virtual ~AtmosphericModel();
AtmosphericModel() {}
virtual ~AtmosphericModel() {}
virtual double getDensity(double altitude) = 0;
virtual double getPressure(double altitude) = 0;

21
sim/ConstantAtmosphere.h Normal file
View File

@ -0,0 +1,21 @@
#ifndef SIM_CONSTANTATMOSPHERE_H
#define SIM_CONSTANTATMOSPHERE_H
#include "AtmosphericModel.h"
namespace sim {
class ConstantAtmosphere : public AtmosphericModel
{
public:
ConstantAtmosphere() {}
virtual ~ConstantAtmosphere() {}
double getDensity(double) override { return 1.225; }
double getPressure(double) override { return 101325.0; }
double getTemperature(double) override { return 288.15; }
};
} // namespace sim
#endif // SIM_CONSTANTATMOSPHERE_H

View File

@ -2,6 +2,7 @@
#define SIM_CONSTANTGRAVITYMODEL_H
#include "GravityModel.h"
#include "utils/Triplet.h"
namespace sim {
@ -12,7 +13,7 @@ public:
virtual ~ConstantGravityModel() {}
std::tuple<double, double, double> getAccel(double, double, double) override { return std::make_tuple(0.0, 0.0, -9.8); }
TripletD getAccel(double, double, double) override { return TripletD(0.0, 0.0, -9.8); }
};
} // namespace sim

View File

@ -1,7 +1,7 @@
#ifndef SIM_GRAVITYMODEL_H
#define SIM_GRAVITYMODEL_H
#include <tuple>
#include "utils/Triplet.h"
namespace sim
{
@ -12,7 +12,8 @@ public:
GravityModel();
virtual ~GravityModel();
virtual std::tuple<double, double, double> getAccel(double x, double y, double z) = 0;
virtual TripletD getAccel(double x, double y, double z) = 0;
TripletD getAccel(const TripletD& t) { return this->getAccel(t.x1, t.x2, t.x3); }
};
} // namespace sim

View File

@ -50,29 +50,19 @@ void Propagator::runUntilTerminate()
std::chrono::steady_clock::time_point startTime = std::chrono::steady_clock::now();
std::chrono::steady_clock::time_point endTime;
std::size_t j = 0;
while(true && j < 100000)
while(true)
{
// nextState gets overwritten
// tempRes gets overwritten
integrator->step(currentTime, currentState, tempRes);
/*
std::size_t size = currentState.size();
for(size_t i = 0; i < size; ++i)
{
currentState[i] = tempRes[i];
tempRes[i] = 0;
}
*/
std::swap(currentState, tempRes);
if(saveStates)
{
states.push_back(currentState);
states.push_back(std::make_pair(currentTime, currentState));
}
if(currentState[2] < 0.0)
break;
j++;
currentTime += timeStep;
}
endTime = std::chrono::steady_clock::now();
@ -91,19 +81,20 @@ double Propagator::getMass()
double Propagator::getForceX()
{
return -1.225 / 2.0 * 0.008107 * rocket->getDragCoefficient() * currentState[3]* currentState[3];
return - qtrocket->getAtmosphereModel()->getDensity(currentState[3])/ 2.0 * 0.008107 * rocket->getDragCoefficient() * currentState[3]* currentState[3];
}
double Propagator::getForceY()
{
return -1.225 / 2.0 * 0.008107 * rocket->getDragCoefficient() * currentState[4]* currentState[4];
return -qtrocket->getAtmosphereModel()->getDensity(currentState[3]) / 2.0 * 0.008107 * rocket->getDragCoefficient() * currentState[4]* currentState[4];
}
double Propagator::getForceZ()
{
double gravity = std::get<2>(qtrocket->getGravityModel()->getAccel(currentState[0], currentState[1], currentState[2]));
double airDrag = -1.225 / 2.0 * 0.008107 * rocket->getDragCoefficient() * currentState[5]* currentState[5];
return gravity + airDrag;
double gravity = (qtrocket->getGravityModel()->getAccel(currentState[0], currentState[1], currentState[2])).x3;
double airDrag = -qtrocket->getAtmosphereModel()->getDensity(currentState[3]) / 2.0 * 0.008107 * rocket->getDragCoefficient() * currentState[5]* currentState[5];
double thrust = rocket->getThrust(currentTime);
return gravity + airDrag + thrust;
}
double Propagator::getTorqueP() { return 0.0; }

View File

@ -41,7 +41,7 @@ public:
saveStates = s;
}
const std::vector<std::vector<double>>& getStates() const { return states; }
const std::vector<std::pair<double, std::vector<double>>>& getStates() const { return states; }
void setTimeStep(double ts) { timeStep = ts; }
@ -70,7 +70,7 @@ private:
bool saveStates{true};
double currentTime{0.0};
double timeStep{0.01};
std::vector<std::vector<double>> states;
std::vector<std::pair<double, std::vector<double>>> states;
};
} // namespace sim

View File

@ -3,7 +3,6 @@
#include "utils/math/Constants.h"
#include <cmath>
#include <tuple>
namespace sim
{
@ -18,7 +17,7 @@ SphericalGravityModel::~SphericalGravityModel()
}
std::tuple<double, double, double> SphericalGravityModel::getAccel(double x, double y, double z)
TripletD SphericalGravityModel::getAccel(double x, double y, double z)
{
// Convert x, y, z from meters to km. This is to avoid potential precision losses
// with using the earth's gravitation parameter in meters (14 digit number).
@ -36,7 +35,7 @@ std::tuple<double, double, double> SphericalGravityModel::getAccel(double x, dou
double ay = accelFactor * y_km * 1000.0;
double az = accelFactor * z_km * 1000.0;
return std::make_tuple(ax, ay, az);
return TripletD(ax, ay, az);
}

View File

@ -3,8 +3,6 @@
#include "GravityModel.h"
#include <tuple>
namespace sim
{
@ -14,7 +12,7 @@ public:
SphericalGravityModel();
virtual ~SphericalGravityModel();
std::tuple<double, double, double> getAccel(double x, double y, double z) override;
TripletD getAccel(double x, double y, double z) override;
};
} // namespace sim

View File

@ -27,13 +27,13 @@ utils::BinMap initTemps()
utils::BinMap initLapseRates()
{
utils::BinMap map;
map.insert(std::make_pair(0.0, -0.0019812));
map.insert(std::make_pair(0.0, 0.0065));
map.insert(std::make_pair(11000.0, 0.0));
map.insert(std::make_pair(20000.0, 0.001));
map.insert(std::make_pair(32000.0, 0.0028));
map.insert(std::make_pair(20000.0, -0.001));
map.insert(std::make_pair(32000.0, -0.0028));
map.insert(std::make_pair(47000.0, 0.0));
map.insert(std::make_pair(51000.0, -0.0028));
map.insert(std::make_pair(71000.0, -0.002));
map.insert(std::make_pair(51000.0, 0.0028));
map.insert(std::make_pair(71000.0, 0.002));
return map;
}
@ -72,7 +72,8 @@ double USStandardAtmosphere::getDensity(double altitude)
{
if(temperatureLapseRate[altitude] == 0.0)
{
return standardDensity[altitude] * std::exp((-Constants::g0 * Constants::airMolarMass * altitude) / (Constants::Rstar * standardTemperature[altitude]));
return standardDensity[altitude] * std::exp((-Constants::g0 * Constants::airMolarMass * (altitude - standardDensity.getBinBase(altitude)))
/ (Constants::Rstar * standardTemperature[altitude]));
}
else
@ -88,11 +89,11 @@ double USStandardAtmosphere::getDensity(double altitude)
}
}
double USStandardAtmosphere::getTemperature(double altitude)
double USStandardAtmosphere::getTemperature(double /*altitude*/)
{
return 0.0;
}
double USStandardAtmosphere::getPressure(double altitude)
double USStandardAtmosphere::getPressure(double /* altitude */)
{
return 0.0;
}

View File

@ -11,9 +11,9 @@ WindModel::~WindModel()
{
}
std::tuple<double, double, double> WindModel::getWindSpeed(double x, double y, double z)
TripletD WindModel::getWindSpeed(double /* x */, double /* y */ , double /* z */)
{
return std::make_tuple<double, double, double>(0.0, 0.0, 0.0);
return TripletD(0.0, 0.0, 0.0);
}
} // namespace sim

View File

@ -1,7 +1,7 @@
#ifndef SIM_WINDMODEL_H
#define SIM_WINDMODEL_H
#include <tuple>
#include "utils/Triplet.h"
namespace sim
{
@ -12,7 +12,7 @@ public:
WindModel();
virtual ~WindModel();
virtual std::tuple<double, double, double> getWindSpeed(double x, double y, double z);
virtual TripletD getWindSpeed(double x, double y, double z);
};

View File

@ -15,4 +15,18 @@ ThrustCurveAPI::~ThrustCurveAPI()
}
MotorModel ThrustCurveAPI::getMotorData(const std::string& motorId)
{
std::stringstream endpoint;
endpoint << hostname << "download.json?motorId=" << motorId << "&data=samples";
std::vector<std::string> extraHeaders = {};
std::string res = curlConnection.get(endpoint.str(), extraHeaders);
MotorModel mm;
mm.setDataFromJsonString(res);
return mm;
}
} // namespace utils

View File

@ -5,13 +5,15 @@
#include <string>
#include "CurlConnection.h"
#include "model/MotorModel.h"
#include "model/Thrustcurve.h"
namespace utils
{
/**
* @brief This is a bit more than just an API for Thrustcurve.org, so the name is unfortunate
* It is also an internal database of motor data that it grabs from Thrustcurve.org
* @brief This API for Thrustcurve.org - It will provide an interface for querying thrustcurve.org
* for motor data
*
*/
class ThrustCurveAPI
@ -21,6 +23,14 @@ public:
~ThrustCurveAPI();
/**
* @brief getThrustCurve will download the thrust data for the given Motor using the motorId
* @param m MotorModel to populate
*/
MotorModel getMotorData(const std::string& motorId);
private:

21
utils/Triplet.h Normal file
View File

@ -0,0 +1,21 @@
#ifndef TRIPLET_H
#define TRIPLET_H
/**
* The purpose of this class is to get rid of using std::tuple for coordinate triplets.
*/
template<typename T>
struct Triplet
{
Triplet(const T& a, const T& b, const T& c)
: x1(a), x2(b), x3(c)
{}
T x1;
T x2;
T x3;
};
using TripletD = Triplet<double>;
#endif // TRIPLET_H