refactor: glide_computer refactored and extended with geographical coordinates

This commit is contained in:
Mateusz Pusz
2021-02-26 14:10:36 +01:00
parent 929c197fff
commit cdba0cdbc4
7 changed files with 726 additions and 383 deletions

View File

@@ -5,12 +5,22 @@ glide_computer
This example presents the usage of:
- different kinds for length, time, and velocity,
- quantities text output formatting,
- `quantity_point` to mark "absolute" quantities like ``timestamp``
- `quantity_point_kind` to mark "absolute" kinds of quantities like ``altitude`` (as opposed to ``height``),
- different kinds for length, time, and speed,
- the use of quantity kinds to show how to handle 3D space for aviation needs,
- `quantity_point_kind` to mark "absolute" values like ``altitude`` (as opposed to ``height``).
- unit constants to initialize the database
- quantities text output formatting,
- cooperation with `std::chrono`.
The use of `quantity_kind` and `quantity_point_kind` provide strong typing
.. literalinclude:: ../../example/glide_computer.h
:caption: glide_computer.h
:start-at: #include
:end-before: using namespace units;
:linenos:
:lineno-match:
The use of `quantity_kind` and `quantity_point_kind` provides strong typing
that divide quantities and quantity points to the ones on a horizontal (X, Y) plane and vertical (Z) axis.
Their purpose is to make different kinds of quantity
(i.e. length) separate strong types (i.e. distance, height).
@@ -18,27 +28,26 @@ Additionally, separating a quantity from its quantity point
means that we can define a ``height`` and ``altitude`` as different strong types.
A quantity point provides a more restricted interface meant for absolute calculations.
.. literalinclude:: ../../example/glide_computer.cpp
:caption: glide_computer.cpp
:start-at: #include
:end-before: // custom types
:linenos:
:lineno-match:
The next part of the example defines strong types used by the glide calculator engine. For example
we have 3 :term:`kinds of quantities <kind>` for a quantity of length:
The glide calculator engine also take benefits from different :term:`kinds of quantities <kind>`.
For example we have 3 for a quantity of length:
- ``distance`` - a relative horizontal distance between 2 points on Earth
- ``height`` - a relative altitude difference between 2 points in the air
- ``altitude`` - an absolute altitude value measured form the mean sea level (AMSL).
For the last case a custom text output is provided both for C++ output streams and the text formatting
facility.
.. literalinclude:: ../../example/glide_computer.h
:caption: glide_computer.h
:start-at: using namespace units;
:end-before: // text output
:linenos:
:lineno-match:
.. literalinclude:: ../../example/glide_computer.cpp
:caption: glide_computer.cpp
:start-at: // custom types
:end-before: // An example of a really
Next a custom text output is provided both for C++ output streams and the text formatting facility.
.. literalinclude:: ../../example/glide_computer.h
:caption: glide_computer.h
:start-at: // text output
:end-before: // definition of glide computer databases and utilities
:linenos:
:lineno-match:
@@ -46,12 +55,27 @@ The engine of this simple glide computer works on quantities of the SI units wit
representation. The user can pass any unit valid for a given quantity and the library will automatically
convert it to the one required by the engine interface.
The glide calculator estimates the number of flight phases (towing, circling, gliding, final glide) needed
to finish a task and the duration needed to finish it while flying a selected glider in the specific weather
conditions.
The glide calculator takes task created as a list of waypoints, glider performance data, weather conditions,
safety constraints, and a towing height.
.. literalinclude:: ../../example/glide_computer.h
:caption: glide_computer.h
:start-at: // definition of glide computer databases and utilities
:linenos:
:lineno-match:
.. literalinclude:: ../../example/glide_computer_example.cpp
:caption: glide_computer_example.cpp
:start-at: #include
:linenos:
:lineno-match:
Having all of that it estimates the number of flight phases (towing, circling, gliding, final glide)
needed to finish a task. As an output it provides the duration needed to finish the task while
flying a selected glider in the specific weather conditions.
.. literalinclude:: ../../example/glide_computer.cpp
:caption: glide_computer.cpp
:start-at: // An example of a really simplified tactical glide computer
:start-at: #include
:linenos:
:lineno-match:

View File

@@ -44,10 +44,16 @@ if(NOT CMAKE_CXX_COMPILER_ID STREQUAL "MSVC")
# TODO Those examples use Concepts terse syntax not yet supported by MSVC
add_example(avg_speed)
add_example(glide_computer)
add_example(hello_units)
add_example(total_energy)
add_executable(glide_computer
geographic.cpp geographic.h
glide_computer.cpp glide_computer.h
glide_computer_example.cpp
)
target_link_libraries(glide_computer PRIVATE mp-units::mp-units)
# TODO "atomic constraint should be a constant expression" error in std::invocable
find_package(linear_algebra CONFIG REQUIRED)

55
example/geographic.cpp Normal file
View File

@@ -0,0 +1,55 @@
// The MIT License (MIT)
//
// Copyright (c) 2018 Mateusz Pusz
//
// Permission is hereby granted, free of charge, to any person obtaining a copy
// of this software and associated documentation files (the "Software"), to deal
// in the Software without restriction, including without limitation the rights
// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
// copies of the Software, and to permit persons to whom the Software is
// furnished to do so, subject to the following conditions:
//
// The above copyright notice and this permission notice shall be included in all
// copies or substantial portions of the Software.
//
// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
// SOFTWARE.
#include "geographic.h"
#include <cmath>
#include <numbers>
namespace geographic {
distance spherical_distance(position from, position to)
{
using rep = std::common_type_t<latitude::value_type, longitude::value_type>;
constexpr auto p = std::numbers::pi_v<rep> / 180;
const auto lat1 = from.lat.value() * p;
const auto lon1 = from.lon.value() * p;
const auto lat2 = to.lat.value() * p;
const auto lon2 = to.lon.value() * p;
using std::sin, std::cos, std::asin, std::sqrt;
// https://en.wikipedia.org/wiki/Great-circle_distance#Formulae
if constexpr (sizeof(rep) >= 8) {
// spherical law of cosines
const auto central_angle = acos(sin(lat1) * sin(lat2) + cos(lat1) * cos(lat2) * cos(lon2 - lon1));
// const auto central_angle = 2 * asin(sqrt(0.5 - cos(lat2 - lat1) / 2 + cos(lat1) * cos(lat2) * (1 - cos(lon2 - lon1)) / 2));
return distance(earth_radius * central_angle);
} else {
// the haversine formula
const auto sin_lat = sin(lat2 - lat1) / 2;
const auto sin_lon = sin(lon2 - lon1) / 2;
const auto central_angle = 2 * asin(sqrt(sin_lat * sin_lat + cos(lat1) * cos(lat2) * sin_lon * sin_lon));
return distance(earth_radius * central_angle);
}
}
} // namespace geographic

132
example/geographic.h Normal file
View File

@@ -0,0 +1,132 @@
// The MIT License (MIT)
//
// Copyright (c) 2018 Mateusz Pusz
//
// Permission is hereby granted, free of charge, to any person obtaining a copy
// of this software and associated documentation files (the "Software"), to deal
// in the Software without restriction, including without limitation the rights
// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
// copies of the Software, and to permit persons to whom the Software is
// furnished to do so, subject to the following conditions:
//
// The above copyright notice and this permission notice shall be included in all
// copies or substantial portions of the Software.
//
// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
// SOFTWARE.
#pragma once
#include <units/format.h>
#include <units/physical/si/base/length.h>
#include <units/quantity_kind.h>
#include <compare>
namespace geographic {
template<typename Derived, typename Rep>
struct coordinate {
using value_type = Rep;
constexpr explicit coordinate(value_type v) : value_(v) {}
value_type value() const { return value_; }
auto operator<=>(const coordinate&) const = default;
private:
value_type value_;
};
struct latitude : coordinate<struct latitude_, double> {
using coordinate::coordinate;
};
struct longitude : coordinate<struct longitude_, double> {
using coordinate::coordinate;
};
template<class CharT, class Traits>
std::basic_ostream<CharT, Traits>& operator<<(std::basic_ostream<CharT, Traits>& os, const latitude& lat)
{
if (lat.value() > 0)
return os << "N" << lat.value();
else
return os << "S" << -lat.value();
}
template<class CharT, class Traits>
std::basic_ostream<CharT, Traits>& operator<<(std::basic_ostream<CharT, Traits>& os, const longitude& lon)
{
if (lon.value() > 0)
return os << "E" << lon.value();
else
return os << "W" << -lon.value();
}
inline namespace literals {
constexpr auto operator"" _N(unsigned long long v) { return latitude(static_cast<latitude::value_type>(v)); }
constexpr auto operator"" _N(long double v) { return latitude(static_cast<latitude::value_type>(v)); }
constexpr auto operator"" _S(unsigned long long v) { return latitude(static_cast<latitude::value_type>(-v)); }
constexpr auto operator"" _S(long double v) { return latitude(static_cast<latitude::value_type>(-v)); }
constexpr auto operator"" _E(unsigned long long v) { return longitude(static_cast<longitude::value_type>(v)); }
constexpr auto operator"" _E(long double v) { return longitude(static_cast<longitude::value_type>(v)); }
constexpr auto operator"" _W(unsigned long long v) { return longitude(static_cast<longitude::value_type>(-v)); }
constexpr auto operator"" _W(long double v) { return longitude(static_cast<longitude::value_type>(-v)); }
} // namespace literals
} // namespace geographic
template<>
class std::numeric_limits<geographic::latitude> : public numeric_limits<geographic::latitude::value_type> {
static constexpr auto min() noexcept { return geographic::latitude(-90); }
static constexpr auto lowest() noexcept { return geographic::latitude(-90); }
static constexpr auto max() noexcept { return geographic::latitude(90); }
};
template<>
class std::numeric_limits<geographic::longitude> : public numeric_limits<geographic::longitude::value_type> {
static constexpr auto min() noexcept { return geographic::longitude(-180); }
static constexpr auto lowest() noexcept { return geographic::longitude(-180); }
static constexpr auto max() noexcept { return geographic::longitude(180); }
};
template<>
struct fmt::formatter<geographic::latitude> : formatter<geographic::latitude::value_type> {
template<typename FormatContext>
auto format(geographic::latitude lat, FormatContext& ctx)
{
format_to(ctx.out(), lat.value() > 0 ? "N" : "S");
return formatter<geographic::latitude::value_type>::format(lat.value() > 0 ? lat.value() : -lat.value(), ctx);
}
};
template<>
struct fmt::formatter<geographic::longitude> : formatter<geographic::longitude::value_type> {
template<typename FormatContext>
auto format(geographic::longitude lon, FormatContext& ctx)
{
format_to(ctx.out(), lon.value() > 0 ? "E" : "W");
return formatter<geographic::longitude::value_type>::format(lon.value() > 0 ? lon.value() : -lon.value(), ctx);
}
};
namespace geographic {
struct horizontal_kind : units::kind<horizontal_kind, units::physical::si::dim_length> {};
using distance = units::quantity_kind<horizontal_kind, units::physical::si::kilometre>;
using namespace units::physical::si::unit_constants;
inline constexpr auto earth_radius = 6371 * km;
struct position {
latitude lat;
longitude lon;
};
distance spherical_distance(position from, position to);
} // namespace geographic

View File

@@ -20,407 +20,143 @@
// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
// SOFTWARE.
#include <units/format.h>
#include <units/math.h>
#include <units/physical/si/international/base/length.h>
#include <units/physical/si/derived/speed.h>
#include <units/quantity_point_kind.h>
#include <array>
#include <compare>
#include <iostream>
#include "glide_computer.h"
template<units::QuantityKind QK>
struct fmt::formatter<QK> : formatter<typename QK::quantity_type> {
template <typename FormatContext>
auto format(const QK& v, FormatContext& ctx)
{
return formatter<typename QK::quantity_type>::format(v.common(), ctx);
}
};
namespace glide_computer {
// custom types
namespace {
using namespace units::physical;
using namespace units;
struct horizontal_vector : kind<horizontal_vector, si::dim_length> {};
struct vertical_vector : kind<vertical_vector, si::dim_length> {};
struct vertical_point : point_kind<vertical_point, vertical_vector> {};
struct velocity_vector : derived_kind<velocity_vector, horizontal_vector, si::dim_speed> {};
struct rate_of_climb_vector : derived_kind<rate_of_climb_vector, vertical_vector, si::dim_speed> {};
using distance = quantity_kind<horizontal_vector, si::kilometre>;
using height = quantity_kind<vertical_vector, si::metre>;
using altitude = quantity_point_kind<vertical_point, si::metre>;
using duration = si::time<si::second>;
using velocity = quantity_kind<velocity_vector, si::kilometre_per_hour>;
using rate_of_climb = quantity_kind<rate_of_climb_vector, si::metre_per_second>;
template<class CharT, class Traits>
std::basic_ostream<CharT, Traits>& operator<<(std::basic_ostream<CharT, Traits>& os, const altitude& a)
task::legs task::make_legs(const waypoints& wpts)
{
return os << a.relative().common() << " AMSL";
task::legs res;
res.reserve(wpts.size() - 1);
auto to_leg = [](const waypoint& w1, const waypoint& w2) { return task::leg(w1, w2); };
std::ranges::transform(wpts.cbegin(), prev(wpts.cend()), next(wpts.cbegin()), wpts.cend(), std::back_inserter(res), to_leg);
return res;
}
} // namespace
template<>
struct fmt::formatter<altitude> : formatter<si::length<si::metre>> {
template <typename FormatContext>
auto format(altitude a, FormatContext& ctx)
{
formatter<si::length<si::metre>>::format(a.relative().common(), ctx);
return format_to(ctx.out(), " AMSL");
}
};
// An example of a really simplified tactical glide computer
// Simplifications:
// - glider 100% clean and with full factory performance (brand new painting)
// - no influence of the ballast (pilot weight, water, etc) to glider performance
// - only one point on a glider polar curve
// - no influence of bank angle (during circling) on a glider performance
// - no wind
// - constant thermals strength
// - thermals exactly where and when we need them ;-)
// - no airspaces
// - Earth is flat
// - ground level changes linearly between airports
// - no ground obstacles (i.e. mountains) to pass
// - flight path exactly on a shortest possible line to destination
// gliders database
namespace {
using namespace si::literals;
using namespace si::international::literals;
using namespace si::unit_constants;
template<QuantityKind QK1, QuantityKind QK2>
constexpr Dimensionless auto operator/(const QK1& lhs, const QK2& rhs)
requires (!units::QuantityKindRelatedTo<QK1, QK2>) && requires { lhs.common() / rhs.common(); } {
return lhs.common() / rhs.common();
std::vector<distance> task::make_leg_total_distances(const legs& legs)
{
std::vector<distance> res;
res.reserve(legs.size());
auto to_length = [](const leg& l) { return l.get_length(); };
std::transform_inclusive_scan(legs.cbegin(), legs.cend(), std::back_inserter(res), std::plus(), to_length);
return res;
}
struct glider {
struct polar_point {
velocity v;
rate_of_climb climb;
};
std::string name;
std::array<polar_point, 1> polar;
};
auto get_gliders()
altitude terrain_level_alt(const task& t, const flight_point& pos)
{
const std::array gliders = {
glider{"SZD-30 Pirat", {velocity(83 * km / h), rate_of_climb(-0.7389 * m / s)}},
glider{"SZD-51 Junior", {velocity(80 * km / h), rate_of_climb(-0.6349 * m / s)}},
glider{"SZD-48 Jantar Std 3", {velocity(110 * km / h), rate_of_climb(-0.77355 * m / s)}},
glider{"SZD-56 Diana", {velocity(110 * km / h), rate_of_climb(-0.63657 * m / s)}}
};
return gliders;
}
constexpr Dimensionless auto glide_ratio(const glider::polar_point& polar)
{
return polar.v / -polar.climb;
}
template<std::ranges::forward_range R>
requires std::same_as<std::ranges::range_value_t<R>, glider>
void print(const R& gliders)
{
std::cout << "Gliders:\n";
std::cout << "========\n";
for(const auto& g : gliders) {
std::cout << "- Name: " << g.name << "\n";
std::cout << "- Polar:\n";
for(const auto& p : g.polar)
fmt::print(" * {:%.4Q %q} @ {:%.1Q %q} -> {:.1f}\n", p.climb, p.v, glide_ratio(g.polar[0]));
std::cout << "\n";
}
}
} // namespace
// weather conditions
namespace {
struct weather {
height cloud_base;
rate_of_climb thermal_strength;
};
auto get_weather_conditions()
{
const std::array weather_conditions = {
std::pair("Good", weather{height(1900 * m), rate_of_climb(4.3 * m / s)}),
std::pair("Medium", weather{height(1550 * m), rate_of_climb(2.8 * m / s)}),
std::pair("Bad", weather{height(850 * m), rate_of_climb(1.8 * m / s)})
};
return weather_conditions;
}
template<std::ranges::forward_range R>
requires std::same_as<std::ranges::range_value_t<R>, std::pair<const char*, weather>>
void print(const R& conditions)
{
std::cout << "Weather:\n";
std::cout << "========\n";
for(const auto& c : conditions) {
std::cout << "- Kind: " << c.first << "\n";
const auto& w = c.second;
std::cout << "- Cloud base: " << fmt::format("{:%.0Q %q}", w.cloud_base) << " AGL\n";
std::cout << "- Thermals strength: " << fmt::format("{:%.1Q %q}", w.thermal_strength) << "\n";
std::cout << "\n";
}
}
} // namespace
// task
namespace {
struct waypoint {
std::string name;
altitude alt;
};
struct task {
waypoint start;
waypoint finish;
distance dist;
};
void print(const task& t)
{
std::cout << "Task:\n";
std::cout << "=====\n";
std::cout << "- Start: " << t.start.name << " (" << fmt::format("{:%.1Q %q}", t.start.alt) << ")\n";
std::cout << "- Finish: " << t.finish.name << " (" << fmt::format("{:%.1Q %q}", t.finish.alt) << ")\n";
std::cout << "- Distance: " << fmt::format("{:%.1Q %q}", t.dist) << "\n";
std::cout << "\n";
}
} // namespace
// safety params
namespace {
struct safety {
height min_agl_height;
};
void print(const safety& s)
{
std::cout << "Safety:\n";
std::cout << "=======\n";
std::cout << "- Min AGL separation: " << fmt::format("{:%.0Q %q}", s.min_agl_height) << "\n";
std::cout << "\n";
}
} // namespace
// tow parameters
namespace {
struct aircraft_tow {
height height_agl;
rate_of_climb performance;
};
void print(const aircraft_tow& tow)
{
std::cout << "Tow:\n";
std::cout << "====\n";
std::cout << " - Type: aircraft\n" ;
std::cout << " - Height: " << fmt::format("{:%.0Q %q}", tow.height_agl) <<"\n";
std::cout << " - Performance: " << fmt::format("{:%.1Q %q}", tow.performance) <<"\n";
std::cout << "\n";
}
} // namespace
// tactical flight computer basics
namespace {
struct flight_point {
duration dur;
distance dist;
altitude alt;
};
constexpr altitude terrain_level_alt(const task& t, distance dist)
{
const height alt_diff = t.finish.alt - t.start.alt;
return t.start.alt + alt_diff * (dist / t.dist).common();
}
constexpr height agl(altitude glider_alt, altitude terrain_level)
{
return glider_alt - terrain_level;
}
flight_point takeoff(const task& t)
{
const flight_point new_point{{}, {}, t.start.alt};
return new_point;
}
void print(std::string_view phase_name, const flight_point& point, const flight_point& new_point)
{
fmt::print("| {:<12} | {:>9%.1Q %q} (Total: {:>9%.1Q %q}) | {:>8%.1Q %q} (Total: {:>8%.1Q %q}) | {:>7%.0Q %q} ({:>6%.0Q %q}) |\n",
phase_name,
quantity_cast<si::minute>(new_point.dur - point.dur), quantity_cast<si::minute>(new_point.dur),
new_point.dist - point.dist, new_point.dist,
new_point.alt - point.alt, new_point.alt);
}
flight_point tow(const flight_point& point, const aircraft_tow& at)
{
const duration d = (at.height_agl / at.performance).common();
const flight_point new_point{point.dur + d, point.dist, point.alt + at.height_agl};
print("Tow", point, new_point);
return new_point;
}
flight_point circle(const flight_point& point, const glider& g, const weather& w, const task& t, height& height_to_gain)
{
const height h_agl = agl(point.alt, terrain_level_alt(t, point.dist));
const height circle_height = std::min(w.cloud_base - h_agl, height_to_gain);
const rate_of_climb circling_rate = w.thermal_strength + g.polar[0].climb;
const duration d = (circle_height / circling_rate).common();
const flight_point new_point{point.dur + d, point.dist, point.alt + circle_height};
height_to_gain -= circle_height;
print("Circle", point, new_point);
return new_point;
const task::leg& l = t.get_legs()[pos.leg_idx];
const height alt_diff = l.end().alt - l.begin().alt;
return l.begin().alt + alt_diff * ((pos.dist - t.get_leg_dist_offset(pos.leg_idx)) / l.get_length()).common();
}
// Returns `x` of the intersection of a glide line and a terrain line.
// y = -x / glide_ratio + point.alt;
// y = -x / glide_ratio + pos.alt;
// y = (finish_alt - ground_alt) / dist_to_finish * x + ground_alt + min_agl_height;
constexpr distance glide_distance(const flight_point& point, const glider& g, const task& t, const safety& s, altitude ground_alt)
distance glide_distance(const flight_point& pos, const glider& g, const task& t, const safety& s, altitude ground_alt)
{
const auto dist_to_finish = t.dist - point.dist;
return distance((ground_alt + s.min_agl_height - point.alt).common() / ((ground_alt - t.finish.alt) / dist_to_finish - 1 / glide_ratio(g.polar[0])));
const auto dist_to_finish = t.get_length() - pos.dist;
return distance((ground_alt + s.min_agl_height - pos.alt).common() /
((ground_alt - t.get_finish().alt) / dist_to_finish - 1 / glide_ratio(g.polar[0])));
}
inline si::length<si::kilometre> length_3d(distance dist, height h)
{
return sqrt(pow<2>(dist.common()) + pow<2>(h.common()));
}
flight_point glide(const flight_point& point, const glider& g, const task& t, const safety& s)
namespace {
using namespace glide_computer;
void print(std::string_view phase_name, timestamp start_ts, const glide_computer::flight_point& point, const glide_computer::flight_point& new_point)
{
const auto ground_alt = terrain_level_alt(t, point.dist);
const auto dist = glide_distance(point, g, t, s, ground_alt);
fmt::print(
"| {:<12} | {:>9%.1Q %q} (Total: {:>9%.1Q %q}) | {:>8%.1Q %q} (Total: {:>8%.1Q %q}) | {:>7%.0Q %q} ({:>6%.0Q %q}) |\n",
phase_name, quantity_cast<si::minute>(new_point.ts - point.ts), quantity_cast<si::minute>(new_point.ts - start_ts),
new_point.dist - point.dist, new_point.dist, new_point.alt - point.alt, new_point.alt);
}
flight_point takeoff(timestamp start_ts, const task& t)
{
return {start_ts, t.get_start().alt};
}
flight_point tow(timestamp start_ts, const flight_point& pos, const aircraft_tow& at)
{
const duration d = (at.height_agl / at.performance).common();
const flight_point new_pos{pos.ts + d, pos.alt + at.height_agl, pos.leg_idx, pos.dist};
print("Tow", start_ts, pos, new_pos);
return new_pos;
}
flight_point circle(timestamp start_ts, const flight_point& pos, const glider& g, const weather& w, const task& t, height& height_to_gain)
{
const height h_agl = agl(pos.alt, terrain_level_alt(t, pos));
const height circling_height = std::min(w.cloud_base - h_agl, height_to_gain);
const rate_of_climb circling_rate = w.thermal_strength + g.polar[0].climb;
const duration d = (circling_height / circling_rate).common();
const flight_point new_pos{pos.ts + d, pos.alt + circling_height, pos.leg_idx, pos.dist};
height_to_gain -= circling_height;
print("Circle", start_ts, pos, new_pos);
return new_pos;
}
flight_point glide(timestamp start_ts, const flight_point& pos, const glider& g, const task& t, const safety& s)
{
const auto ground_alt = terrain_level_alt(t, pos);
const auto dist = glide_distance(pos, g, t, s, ground_alt);
const auto new_distance = pos.dist + dist;
const auto alt = ground_alt + s.min_agl_height;
const auto l3d = length_3d(dist, point.alt - alt);
const auto l3d = length_3d(dist, pos.alt - alt);
const duration d = l3d / g.polar[0].v.common();
const flight_point new_point{point.dur + d, point.dist + dist, terrain_level_alt(t, point.dist + dist) + s.min_agl_height};
const flight_point new_pos{pos.ts + d, terrain_level_alt(t, pos) + s.min_agl_height, t.get_leg_index(new_distance), new_distance};
print("Glide", point, new_point);
return new_point;
print("Glide", start_ts, pos, new_pos);
return new_pos;
}
flight_point final_glide(const flight_point& point, const glider& g, const task& t)
flight_point final_glide(timestamp start_ts, const flight_point& pos, const glider& g, const task& t)
{
const auto dist = t.dist - point.dist;
const auto l3d = length_3d(dist, point.alt - t.finish.alt);
const auto dist = t.get_length() - pos.dist;
const auto l3d = length_3d(dist, pos.alt - t.get_finish().alt);
const duration d = l3d / g.polar[0].v.common();
const flight_point new_point{point.dur + d, point.dist + dist, t.finish.alt};
const flight_point new_pos{pos.ts + d, t.get_finish().alt, t.get_legs().size() - 1, pos.dist + dist};
print("Final Glide", point, new_point);
return new_point;
print("Final Glide", start_ts, pos, new_pos);
return new_pos;
}
void estimate(const glider& g, const weather& w, const task& t, const safety& s, const aircraft_tow& at)
} // namespace
namespace glide_computer {
void estimate(timestamp start_ts, const glider& g, const weather& w, const task& t, const safety& s, const aircraft_tow& at)
{
fmt::print("| {:<12} | {:^28} | {:^26} | {:^21} |\n", "Flight phase", "Duration", "Distance", "Height");
fmt::print("|{0:-^14}|{0:-^30}|{0:-^28}|{0:-^23}|\n", "");
// ready to takeoff
flight_point point = takeoff(t);
flight_point pos = takeoff(start_ts, t);
// estimate aircraft towing
point = tow(point, at);
pos = tow(start_ts, pos, at);
// estimate the altitude needed to reach the finish line from this place
const altitude final_glide_alt = t.finish.alt + height(t.dist.common() / glide_ratio(g.polar[0]));
const altitude final_glide_alt = t.get_finish().alt + height(t.get_length().common() / glide_ratio(g.polar[0]));
// how much height we still need to gain in the thermalls to reach the destination?
height height_to_gain = final_glide_alt - point.alt;
height height_to_gain = final_glide_alt - pos.alt;
do {
// glide to the next thermall
point = glide(point, g, t, s);
pos = glide(start_ts, pos, g, t, s);
// circle in a thermall to gain height
point = circle(point, g, w, t, height_to_gain);
}
while(height_to_gain > height(0 * m));
pos = circle(start_ts, pos, g, w, t, height_to_gain);
} while (height_to_gain > height(0 * m));
// final glide
point = final_glide(point, g, t);
pos = final_glide(start_ts, pos, g, t);
}
} // namespace
// example
namespace {
void example()
{
const auto gliders = get_gliders();
print(gliders);
const auto weather_conditions = get_weather_conditions();
print(weather_conditions);
const task t = {
waypoint{"EPPR", altitude(16_q_ft)},
waypoint{"EPGI", altitude(115_q_ft)},
distance(81.7_q_km)
};
print(t);
const safety s = {height(300 * m)};
print(s);
const aircraft_tow tow = {height(400 * m), rate_of_climb(1.6 * m / ::s)};
print(tow);
for(const auto& g : gliders) {
for(const auto& c : weather_conditions) {
std::string txt = "Scenario: Glider = " + g.name + ", Weather = " + c.first;
std::cout << txt << "\n";
fmt::print("{0:=^{1}}\n\n", "", txt.size());
fmt::print("| {:<12} | {:^28} | {:^26} | {:^21} |\n", "Flight phase", "Duration", "Distance", "Height");
fmt::print("|{0:-^14}|{0:-^30}|{0:-^28}|{0:-^23}|\n", "");
estimate(g, c.second, t, s, tow);
std::cout << "\n\n";
}
}
}
} // namespace
int main()
{
try {
example();
}
catch (const std::exception& ex) {
std::cerr << "Unhandled std exception caught: " << ex.what() << '\n';
}
catch (...) {
std::cerr << "Unhandled unknown exception caught\n";
}
}
} // namespace glide_computer

211
example/glide_computer.h Normal file
View File

@@ -0,0 +1,211 @@
// The MIT License (MIT)
//
// Copyright (c) 2018 Mateusz Pusz
//
// Permission is hereby granted, free of charge, to any person obtaining a copy
// of this software and associated documentation files (the "Software"), to deal
// in the Software without restriction, including without limitation the rights
// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
// copies of the Software, and to permit persons to whom the Software is
// furnished to do so, subject to the following conditions:
//
// The above copyright notice and this permission notice shall be included in all
// copies or substantial portions of the Software.
//
// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
// SOFTWARE.
#pragma once
#include "geographic.h"
#include <units/format.h>
#include <units/math.h>
#include <units/physical/si/derived/speed.h>
#include <units/physical/si/international/base/length.h>
#include <units/quantity_point_kind.h>
// An example of a really simplified tactical glide computer
// Simplifications:
// - glider 100% clean and with full factory performance (brand new painting)
// - no influence of the ballast (pilot weight, water, etc) to glider performance
// - only one point on a glider polar curve
// - no influence of bank angle (during circling) on a glider performance
// - no wind
// - constant thermals strength
// - thermals exactly where and when we need them ;-)
// - no airspaces
// - ground level changes linearly between waypoints
// - no ground obstacles (i.e. mountains) to pass
// - flight path exactly on a shortest possible line to destination
using namespace units;
using namespace units::physical;
template<units::QuantityKind QK>
struct fmt::formatter<QK> : formatter<typename QK::quantity_type> {
template<typename FormatContext>
auto format(const QK& v, FormatContext& ctx)
{
return formatter<typename QK::quantity_type>::format(v.common(), ctx);
}
};
namespace glide_computer {
template<QuantityKind QK1, QuantityKind QK2>
constexpr Dimensionless auto operator/(const QK1& lhs, const QK2& rhs)
requires(!units::QuantityKindRelatedTo<QK1, QK2>) && requires { lhs.common() / rhs.common();}
{
return lhs.common() / rhs.common();
}
// kinds
using horizontal_kind = geographic::horizontal_kind;
struct vertical_kind : kind<vertical_kind, si::dim_length> {};
struct vertical_point_kind : point_kind<vertical_point_kind, vertical_kind> {};
struct velocity_kind : derived_kind<velocity_kind, horizontal_kind, si::dim_speed> {};
struct rate_of_climb_kind : derived_kind<rate_of_climb_kind, vertical_kind, si::dim_speed> {};
// https://en.wikipedia.org/wiki/Flight_planning#Units_of_measurement
// length
using distance = quantity_kind<horizontal_kind, si::kilometre>;
using height = quantity_kind<vertical_kind, si::metre>;
using altitude = quantity_point_kind<vertical_point_kind, si::metre>;
// time
using duration = si::time<si::second>;
using timestamp = quantity_point<si::dim_time, si::second>;
// speed
using velocity = quantity_kind<velocity_kind, si::kilometre_per_hour>;
using rate_of_climb = quantity_kind<rate_of_climb_kind, si::metre_per_second>;
// text output
template<class CharT, class Traits>
std::basic_ostream<CharT, Traits>& operator<<(std::basic_ostream<CharT, Traits>& os, const altitude& a)
{
return os << a.relative().common() << " AMSL";
}
} // namespace glide_computer
template<>
struct fmt::formatter<glide_computer::altitude> : formatter<units::physical::si::length<units::physical::si::metre>> {
template<typename FormatContext>
auto format(glide_computer::altitude a, FormatContext& ctx)
{
formatter<units::physical::si::length<units::physical::si::metre>>::format(a.relative().common(), ctx);
return format_to(ctx.out(), " AMSL");
}
};
// definition of glide computer databases and utilities
namespace glide_computer {
using namespace si::unit_constants;
struct glider {
struct polar_point {
velocity v;
rate_of_climb climb;
};
std::string name;
std::array<polar_point, 1> polar;
};
constexpr Dimensionless auto glide_ratio(const glider::polar_point& polar) { return polar.v / -polar.climb; }
struct weather {
height cloud_base;
rate_of_climb thermal_strength;
};
struct waypoint {
std::string name;
geographic::position pos;
altitude alt;
};
class task {
public:
using waypoints = std::vector<waypoint>;
class leg {
const waypoint* begin_;
const waypoint* end_;
distance length_ = geographic::spherical_distance(begin().pos, end().pos);
public:
leg(const waypoint& b, const waypoint& e) noexcept: begin_(&b), end_(&e) {}
constexpr const waypoint& begin() const { return *begin_; };
constexpr const waypoint& end() const { return *end_; }
constexpr const distance get_length() const { return length_; }
};
using legs = std::vector<leg>;
template<std::ranges::input_range R>
requires std::same_as<std::ranges::range_value_t<R>, waypoint>
explicit task(const R& r) : waypoints_(std::ranges::begin(r), std::ranges::end(r)) {}
task(std::initializer_list<waypoint> wpts) : waypoints_(wpts) {}
const waypoints& get_waypoints() const { return waypoints_; }
const legs& get_legs() const { return legs_; }
const waypoint& get_start() const { return waypoints_.front(); }
const waypoint& get_finish() const { return waypoints_.back(); }
distance get_length() const { return length_; }
distance get_leg_dist_offset(size_t leg_index) const { return leg_index == 0 ? distance(0 * km) : leg_total_distances_[leg_index - 1]; }
size_t get_leg_index(distance dist) const
{
return static_cast<size_t>(std::ranges::distance(leg_total_distances_.cbegin(), std::ranges::lower_bound(leg_total_distances_, dist)));
}
private:
waypoints waypoints_;
legs legs_ = make_legs(waypoints_);
std::vector<distance> leg_total_distances_ = make_leg_total_distances(legs_);
distance length_ = leg_total_distances_.back();
static legs make_legs(const task::waypoints& wpts);
static std::vector<distance> make_leg_total_distances(const legs& legs);
};
struct safety {
height min_agl_height;
};
struct aircraft_tow {
height height_agl;
rate_of_climb performance;
};
struct flight_point {
timestamp ts;
altitude alt;
size_t leg_idx = 0;
distance dist{0 * km};
};
altitude terrain_level_alt(const task& t, const flight_point& pos);
constexpr height agl(altitude glider_alt, altitude terrain_level) { return glider_alt - terrain_level; }
inline si::length<si::kilometre> length_3d(distance dist, height h)
{
// TODO support for hypot(q, q)
return sqrt(pow<2>(dist.common()) + pow<2>(h.common()));
}
distance glide_distance(const flight_point& pos, const glider& g, const task& t, const safety& s, altitude ground_alt);
void estimate(timestamp start_ts, const glider& g, const weather& w, const task& t, const safety& s, const aircraft_tow& at);
} // namespace glide_computer

View File

@@ -0,0 +1,179 @@
// The MIT License (MIT)
//
// Copyright (c) 2018 Mateusz Pusz
//
// Permission is hereby granted, free of charge, to any person obtaining a copy
// of this software and associated documentation files (the "Software"), to deal
// in the Software without restriction, including without limitation the rights
// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
// copies of the Software, and to permit persons to whom the Software is
// furnished to do so, subject to the following conditions:
//
// The above copyright notice and this permission notice shall be included in all
// copies or substantial portions of the Software.
//
// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
// SOFTWARE.
#include "glide_computer.h"
#include <units/chrono.h>
#include <array>
#include <iostream>
namespace {
using namespace glide_computer;
auto get_gliders()
{
static const std::array gliders = {
glider{"SZD-30 Pirat", {velocity(83 * km / h), rate_of_climb(-0.7389 * m / s)}},
glider{"SZD-51 Junior", {velocity(80 * km / h), rate_of_climb(-0.6349 * m / s)}},
glider{"SZD-48 Jantar Std 3", {velocity(110 * km / h), rate_of_climb(-0.77355 * m / s)}},
glider{"SZD-56 Diana", {velocity(110 * km / h), rate_of_climb(-0.63657 * m / s)}}};
return gliders;
}
auto get_weather_conditions()
{
static const std::array weather_conditions = {
std::pair("Good", weather{height(1900 * m), rate_of_climb(4.3 * m / s)}),
std::pair("Medium", weather{height(1550 * m), rate_of_climb(2.8 * m / s)}),
std::pair("Bad", weather{height(850 * m), rate_of_climb(1.8 * m / s)})};
return weather_conditions;
}
auto get_waypoints()
{
using namespace geographic::literals;
using namespace units::physical::si::international::unit_constants;
static const std::array waypoints = {
waypoint{"EPPR", {54.24772_N, 18.6745_E}, altitude(16 * ft)}, // N54°14'51.8" E18°40'28.2"
waypoint{"EPGI", {53.52442_N, 18.84947_E}, altitude(115 * ft)} // N53°31'27.9" E18°50'58.1"
};
return waypoints;
}
template<std::ranges::forward_range R>
requires std::same_as<std::ranges::range_value_t<R>, glider>
void print(const R& gliders)
{
std::cout << "Gliders:\n";
std::cout << "========\n";
for (const auto& g : gliders) {
std::cout << "- Name: " << g.name << "\n";
std::cout << "- Polar:\n";
for (const auto& p : g.polar)
fmt::print(" * {:%.4Q %q} @ {:%.1Q %q} -> {:%.1Q %q}\n", p.climb, p.v, quantity_cast<one>(glide_ratio(g.polar[0])));
std::cout << "\n";
}
}
template<std::ranges::forward_range R>
requires std::same_as<std::ranges::range_value_t<R>, std::pair<const char*, weather>>
void print(const R& conditions)
{
std::cout << "Weather:\n";
std::cout << "========\n";
for (const auto& c : conditions) {
std::cout << "- " << c.first << "\n";
const auto& w = c.second;
std::cout << " * Cloud base: " << fmt::format("{:%.0Q %q}", w.cloud_base) << " AGL\n";
std::cout << " * Thermals strength: " << fmt::format("{:%.1Q %q}", w.thermal_strength) << "\n";
std::cout << "\n";
}
}
template<std::ranges::forward_range R>
requires std::same_as<std::ranges::range_value_t<R>, waypoint>
void print(const R& waypoints)
{
std::cout << "Waypoints:\n";
std::cout << "==========\n";
for (const auto& w : waypoints)
std::cout << fmt::format("- {}: {} {}, {:%.1Q %q}\n", w.name, w.pos.lat, w.pos.lon, w.alt);
std::cout << "\n";
}
void print(const task& t)
{
std::cout << "Task:\n";
std::cout << "=====\n";
std::cout << "- Start: " << t.get_start().name << "\n";
std::cout << "- Finish: " << t.get_finish().name << "\n";
std::cout << "- Length: " << fmt::format("{:%.1Q %q}", t.get_length()) << "\n";
std::cout << "- Legs: " << "\n";
for (const auto& l : t.get_legs())
std::cout << fmt::format(" * {} -> {} ({:%.1Q %q})\n", l.begin().name, l.end().name, l.get_length());
std::cout << "\n";
}
void print(const safety& s)
{
std::cout << "Safety:\n";
std::cout << "=======\n";
std::cout << "- Min AGL separation: " << fmt::format("{:%.0Q %q}", s.min_agl_height) << "\n";
std::cout << "\n";
}
void print(const aircraft_tow& tow)
{
std::cout << "Tow:\n";
std::cout << "====\n";
std::cout << "- Type: aircraft\n";
std::cout << "- Height: " << fmt::format("{:%.0Q %q}", tow.height_agl) << "\n";
std::cout << "- Performance: " << fmt::format("{:%.1Q %q}", tow.performance) << "\n";
std::cout << "\n";
}
void example()
{
const safety s = {height(300 * m)};
const auto gliders = get_gliders();
const auto waypoints = get_waypoints();
const auto weather_conditions = get_weather_conditions();
const task t = {waypoints[0], waypoints[1], waypoints[0]};
const aircraft_tow tow = {height(400 * m), rate_of_climb(1.6 * m / ::s)};
// TODO use C++20 date library when available
// set `start_time` to 11:00 am today
const timestamp start_time(std::chrono::system_clock::now());
print(s);
print(gliders);
print(waypoints);
print(weather_conditions);
print(t);
print(tow);
for (const auto& g : gliders) {
for (const auto& c : weather_conditions) {
std::string txt = "Scenario: Glider = " + g.name + ", Weather = " + c.first;
std::cout << txt << "\n";
fmt::print("{0:=^{1}}\n\n", "", txt.size());
estimate(start_time, g, c.second, t, s, tow);
std::cout << "\n\n";
}
}
}
} // namespace
int main()
{
try {
example();
} catch (const std::exception& ex) {
std::cerr << "Unhandled std exception caught: " << ex.what() << '\n';
} catch (...) {
std::cerr << "Unhandled unknown exception caught\n";
}
}