Otopilot ile Otonom Uçuş Arasındaki Farklar - Algoritma

Katılım
2 Haziran 2015
Mesajlar
14.290
Makaleler
110
Çözümler
121
Son zamanlarda özellikle İHA'ların yaygınlaşması ile, otonom sistemleri ve akabinde otonom uçuş sistemlerini sıklıkla duyuyoruz. Ne var ki, otonom uçuş sistemleri, uçaklarda bulunan oto pilot sistemleri ile sıklıkla karıştırılmaktadır.

Oto pilot nedir?

Oto pilotlar, günümüz uçaklarında önemli bir yere sahiptir. Aslına bakılırsa ilk oto pilotlu uçaklar, 1912 yılında basit gyroların ve altimetrelerin, hidrolik sistemler yardımıyla uçuş yüzeylerini kontrol etmesi sonucu ortaya çıkmıştır. 1950'li ve 60'lı yıllardan itibaren, özellikle yolcu uçaklarında standart haline gelmiştir. Altın çağına ise FlyByWire sistemlerinin entegrasyonuyla erişmiştir.

(MCAS'ı buradan ayrı bir yere koyuyoruz, onu açıklayacağım)

Otopilot bir otonom sistem mi, değil mi? Neden?

Aslına bakarsak otonom dediğimiz şey, uzun süredir aramızda bulunsa da yeni yeni temellerini bulan ve yeni yeni asıl anlamını kazanan bir kavram. Otopilotlar statik sistemlerdir. Belli başlı parametre ve sensörlere bağlı olarak uçağı pilot gözetiminde yönetirler.

Otonom sistemlerde ise asıl nokta uçağın fiziksel yönetiminden ziyade, uçağın sensörlerini olabildiğince doğru tutmak ve uçağın rotasını tahmin ederek olabilecek en iyi şekilde uçağı uçurmaktır. Bu nedenle otonom sistemlerde sensör verilerinin işlenmesi, bu verilerin çapraz olarak karşılaştırılması ve bir dizi filtreden geçirilmesi, büyük bir önem taşır. Bunun yanında rotanın aktif olarak takip edilmesi ve uçağın belli başlı süreler sonucunda nerelerde olacağının tahmin edilmesi de büyük bir önem taşır.

Otonom uçuş sistemi

Otonom uçuş sistemlerinde sensörlerden gelen verilerin doğruluğu kritiktir. Ancak sensörler, doğaları gereği her zaman doğru veriler üretmez, bunun yanında işleyişleri sırasında kalibrasyonları da bozulabilir (ki bu uçuşlarda sıkça yaşanır). Bu nedenle hem sensörlerden gelen yanlış verileri filtrelemek, hem de sensörlerin olası kalibrasyon bozulmalarını tespit edip kompanse etmek amacıyla bir dizi kontrol algoritması bulunur.

Bu algoritmalardan ilki, EKF'dir.

Tahmin teorisinde, Genişletilmiş Kalman Filtresi (EKF), mevcut ortalama ve kovaryansın (iki değişkenin birlikte ne kadar değiştiklerinin ölçüsü) bir tahminini doğrusallaştıran, Kalman filtresinin doğrusal olmayan versiyonudur. İyi tanımlanmış geçiş modelleri durumunda EKF, doğrusal olmayan durum tahmini, navigasyon sistemleri ve GPS teorisinde fiili standart olarak kabul edilmiştir.

EKF özellikle uçaklar gibi birden fazla sensör girdisine bağlı sistemlerde kilit rol oynar. Bir sensör verisinin diğer sensör verisine göre değişiminden tutun da, sensör verisinin ortama göre mi değiştiğinin yoksa bozuk mu çalıştığının tespitine kadar pek çok kritik görevi yapar. Temelinde ileri düzey matematik denklemlerine dayanan bu algoritmalar, otonom sistemlerdeki sensör verilerinin işlenmesinde ve filtrelenmesinde büyük bir öneme sahiptir.

The-architecture-of-the-integration-system-with-Extended-Kalman-Filter-EKF.png


EKF'nin daha basit filtre algoritmalarına göre avantajı, mevcut tüm ölçümleri birleştirerek, önemli hatalarla yanlış ölçümleri daha iyi tespit edebilmesidir. Bu, aracı tek bir sensörü etkileyen arızalara karşı daha az duyarlı hale getirir.

Mesela EKF'li sistemlerde GPS - IMU - Compass üçlüsü sıkı bir şekilde birbirleri ile karşılaştırılır. EKF sayesinde bu sensörlerden yola çıkarak:

  • Uçağın pusula başı,
  • Uçağın hızı,
  • Hava hızı,
  • Uçağın 3 eksendeki ivmesi,
  • Uçağın hücum açısı,
  • Uçağın tırmanma / düşme oranı
gibi parametreler daha hassas hesaplanır. Ayrıca bir donanım anomalisine karşı bu parametreler, daha doğru çalışmaya devam eder.

Örnek olarak EKF kullanan bir sistem, Compass'taki (pusula başı) ani değişimlerin uçağın hareketinden mi, yoksa donanım arızasından mı kaynaklı olduğunu kolayca anlayabilir. Bunun için Compass verisindeki birim zamanda oluşan değişimi, GPS ve IMU verilerindeki birim zamanda oluşan değişimle karşılaştırması yeterlidir.

EKF bir bakıma uçağın başındaki pilotun yerini alır ve sensör verilerini çapraz karşılaştırarak sensörün doğru ya da yanlış veri üretip üretmediğine karar verir.

showOpenGraphArticleImage.gif


Diğer algoritmalar ise uçağın, navigasyon sistemlerinde sıklıkla kullanılır.

Otonom sistemlerde, araca bir noktadan başka bir noktaya gitmesi söylendiğinde veya bir dizi durak noktası komutu girildiğinde, aracın belli bir düzene göre bu noktalardan geçmesi gerekir.

Uçağı ele aldığımızda; uçak limitleri belli olan, belli bir dönüş yarıçapına ve belli bir maksimum / minimum hıza sahip olan bir araçtır. Birden fazla durak noktasında oluşan rotalarda uçak, direkt olarak noktalarından üstünden geçmeye çalışamaz. Bu noktalara belirli bir algoritma ile yaklaşmalı ve geçmelidir.

Genelde sabit uçuşu ve dönüşleri kontrol eden iki sistem bulunur. Bunlara ek olarak da sadece iniş ve kalkışta, uçağın stabilitesini - hücum açısını - alçalma/yükselme değerini koruyan sistemler bulunur. Özellikle dönüşler, otonom sistemler için önemlidir zira çok noktalı rotalarda bir dönüşün sonraki dönüşe göre hesaplanması, bu hesaba aracın parametrelerinin de dahil olması gerekir.

Waypoint-switching-and-path-tracking-strategy-during-traffic-flow-surveillance-at-highways.png


Uçağın dönüşe nereden başlayacağı, nasıl bir çapta döneceği, nerede bitireceği kritiktir. Kabaca anlatmak gerekirse, grafikteki gibi daireler ile ideal dönüş alanları oluşturulur. Uçak bu alanların içinde bulundukça, dönüşü tamamlamış sayar. Bu alanların kaçırılması ya da çok geniş dönülmesi durumunda, uçak o noktaya tekrardan rota çizer.

EKF ve navigasyon algoritmaları için, açık kaynaklı olan ve sıklıkla kullanılan bir otonom pilot olan, ArduPilot'un Plane kütüphanesinden kodlar bırakmak istiyorum.



[CODE lang="cpp" title="EKF"]#include "Plane.h"

/**
*
* Detects failures of the ekf or inertial nav system triggers an alert
* to the pilot and helps take countermeasures
*
*/

#ifndef EKF_CHECK_ITERATIONS_MAX
# define EKF_CHECK_ITERATIONS_MAX 10 // 1 second (ie. 10 iterations at 10hz) of bad variances signals a failure
#endif

#ifndef EKF_CHECK_WARNING_TIME
# define EKF_CHECK_WARNING_TIME (30*1000) // warning text messages are sent to ground no more than every 30 seconds
#endif

////////////////////////////////////////////////////////////////////////////////
// EKF_check structure
////////////////////////////////////////////////////////////////////////////////
static struct {
uint8_t fail_count; // number of iterations ekf or dcm have been out of tolerances
bool bad_variance; // true if ekf should be considered untrusted (fail_count has exceeded EKF_CHECK_ITERATIONS_MAX)
uint32_t last_warn_time; // system time of last warning in milliseconds. Used to throttle text warnings sent to GCS
bool failsafe_on; // true when the loss of navigation failsafe is on
} ekf_check_state;

// ekf_check - detects if ekf variance are out of tolerance and triggers failsafe
// should be called at 10hz
void Plane::ekf_check()
{
// ensure EKF_CHECK_ITERATIONS_MAX is at least 7
static_assert(EKF_CHECK_ITERATIONS_MAX >= 7, "EKF_CHECK_ITERATIONS_MAX must be at least 7");

// exit immediately if ekf has no origin yet - this assumes the origin can never become unset
Location temp_loc;
if (!ahrs.get_origin(temp_loc)) {
return;
}

// return immediately if motors are not armed, or ekf check is disabled
bool ekf_check_disabled = !plane.arming.is_armed() || (g2.fs_ekf_thresh <= 0.0f);
#if HAL_QUADPLANE_ENABLED
if (!quadplane.in_vtol_posvel_mode()) {
ekf_check_disabled = true;
}
#endif
if (ekf_check_disabled) {
ekf_check_state.fail_count = 0;
ekf_check_state.bad_variance = false;
AP_Notify::flags.ekf_bad = ekf_check_state.bad_variance;
failsafe_ekf_off_event(); // clear failsafe
return;
}

// compare compass and velocity variance vs threshold
if (ekf_over_threshold()) {
// if compass is not yet flagged as bad
if (!ekf_check_state.bad_variance) {
// increase counter
ekf_check_state.fail_count++;
if (ekf_check_state.fail_count == (EKF_CHECK_ITERATIONS_MAX-2)) {
// we are two iterations away from declaring an EKF failsafe, ask the EKF if we can reset
// yaw to resolve the issue
ahrs.request_yaw_reset();
}
if (ekf_check_state.fail_count == (EKF_CHECK_ITERATIONS_MAX-1)) {
// we are just about to declare a EKF failsafe, ask the EKF if we can
// change lanes to resolve the issue
ahrs.check_lane_switch();
}
// if counter above max then trigger failsafe
if (ekf_check_state.fail_count >= EKF_CHECK_ITERATIONS_MAX) {
// limit count from climbing too high
ekf_check_state.fail_count = EKF_CHECK_ITERATIONS_MAX;
ekf_check_state.bad_variance = true;
AP::logger().Write_Error(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_BAD_VARIANCE);
// send message to gcs
if ((AP_HAL::millis() - ekf_check_state.last_warn_time) > EKF_CHECK_WARNING_TIME) {
gcs().send_text(MAV_SEVERITY_CRITICAL,"EKF variance");
ekf_check_state.last_warn_time = AP_HAL::millis();
}
failsafe_ekf_event();
}
}
} else {
// reduce counter
if (ekf_check_state.fail_count > 0) {
ekf_check_state.fail_count--;

// if compass is flagged as bad and the counter reaches zero then clear flag
if (ekf_check_state.bad_variance && ekf_check_state.fail_count == 0) {
ekf_check_state.bad_variance = false;
AP::logger().Write_Error(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_VARIANCE_CLEARED);
// clear failsafe
failsafe_ekf_off_event();
}
}
}

// set AP_Notify flags
AP_Notify::flags.ekf_bad = ekf_check_state.bad_variance;

// To-Do: add ekf variances to extended status
}

// ekf_over_threshold - returns true if the ekf's variance are over the tolerance
bool Plane::ekf_over_threshold()
{
// return false immediately if disabled
if (g2.fs_ekf_thresh <= 0.0f) {
return false;
}

// Get EKF innovations normalised wrt the innovaton test limits.
// A value above 1.0 means the EKF has rejected that sensor data
float position_variance, vel_variance, height_variance, tas_variance;
Vector3f mag_variance;
if (!ahrs.get_variances(vel_variance, position_variance, height_variance, mag_variance, tas_variance)) {
return false;
};

// The EKF rejects all magnetometer axes if any single axis exceeds limits
// so take the maximum of all axes
const float mag_max = fmaxf(fmaxf(mag_variance.x,mag_variance.y),mag_variance.z);

// Assign a score to each over threshold based on severity
uint8_t over_thresh_count = 0;
if (mag_max >= g2.fs_ekf_thresh) {
over_thresh_count++;
}

if (vel_variance >= (2.0f * g2.fs_ekf_thresh)) {
over_thresh_count += 2;
} else if (vel_variance >= g2.fs_ekf_thresh) {
over_thresh_count++;
}

// Position is the most important so accept a lower score from other sensors if position failed
if ((position_variance >= g2.fs_ekf_thresh && over_thresh_count >= 1) || over_thresh_count >= 2) {
return true;
}

return false;
}


// failsafe_ekf_event - perform ekf failsafe
void Plane::failsafe_ekf_event()
{
// return immediately if ekf failsafe already triggered
if (ekf_check_state.failsafe_on) {
return;
}

// EKF failsafe event has occurred
ekf_check_state.failsafe_on = true;
AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_OCCURRED);

// if not in a VTOL mode requring position, then nothing needs to be done
#if HAL_QUADPLANE_ENABLED
if (!quadplane.in_vtol_posvel_mode()) {
return;
}

if (quadplane.in_vtol_auto()) {
// the pilot is not controlling via sticks so switch to QLAND
plane.set_mode(mode_qland, ModeReason::EKF_FAILSAFE);
} else {
// the pilot is controlling via sticks so fallbacl to QHOVER
plane.set_mode(mode_qhover, ModeReason::EKF_FAILSAFE);
}
#endif
}

// failsafe_ekf_off_event - actions to take when EKF failsafe is cleared
void Plane::failsafe_ekf_off_event(void)
{
// return immediately if not in ekf failsafe
if (!ekf_check_state.failsafe_on) {
return;
}

ekf_check_state.failsafe_on = false;
AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_RESOLVED);
}[/CODE]

[CODE lang="cpp" title="Navigation"]#include "Plane.h"

/*
reset the total loiter angle
*/
void Plane::loiter_angle_reset(void)
{
loiter.sum_cd = 0;
loiter.total_cd = 0;
loiter.reached_target_alt = false;
loiter.unable_to_acheive_target_alt = false;
}

/*
update the total angle we have covered in a loiter. Used to support
commands to do N circles of loiter
*/
void Plane::loiter_angle_update(void)
{
static const int32_t lap_check_interval_cd = 3*36000;

const int32_t target_bearing_cd = nav_controller->target_bearing_cd();
int32_t loiter_delta_cd;
const bool reached_target = reached_loiter_target();

if (loiter.sum_cd == 0 && !reached_target) {
// we don't start summing until we are doing the real loiter
loiter_delta_cd = 0;
} else if (loiter.sum_cd == 0) {
// use 1 cd for initial delta
loiter_delta_cd = 1;
loiter.start_lap_alt_cm = current_loc.alt;
loiter.next_sum_lap_cd = lap_check_interval_cd;
} else {
loiter_delta_cd = target_bearing_cd - loiter.old_target_bearing_cd;
}

loiter.old_target_bearing_cd = target_bearing_cd;
loiter_delta_cd = wrap_180_cd(loiter_delta_cd);
loiter.sum_cd += loiter_delta_cd * loiter.direction;

bool reached_target_alt = false;

if (reached_target) {
// once we reach the position target we start checking the
// altitude target
bool terrain_status_ok = false;
#if AP_TERRAIN_AVAILABLE
/*
if doing terrain following then we check against terrain
target, fetch the terrain information
*/
float altitude_agl = 0;
if (target_altitude.terrain_following) {
if (terrain.status() == AP_Terrain::TerrainStatusOK &&
terrain.height_above_terrain(altitude_agl, true)) {
terrain_status_ok = true;
}
}
if (terrain_status_ok &&
fabsf(altitude_agl - target_altitude.terrain_alt_cm*0.01) < 5) {
reached_target_alt = true;
} else
#endif
if (!terrain_status_ok && labs(current_loc.alt - target_altitude.amsl_cm) < 500) {
reached_target_alt = true;
}
}

if (reached_target_alt) {
loiter.reached_target_alt = true;
loiter.unable_to_acheive_target_alt = false;
loiter.next_sum_lap_cd = loiter.sum_cd + lap_check_interval_cd;

} else if (!loiter.reached_target_alt && labs(loiter.sum_cd) >= loiter.next_sum_lap_cd) {
// check every few laps for scenario where up/downdrafts inhibit you from loitering up/down for too long
loiter.unable_to_acheive_target_alt = labs(current_loc.alt - loiter.start_lap_alt_cm) < 500;
loiter.start_lap_alt_cm = current_loc.alt;
loiter.next_sum_lap_cd += lap_check_interval_cd;
}
}

//****************************************************************
// Function that will calculate the desired direction to fly and distance
//****************************************************************
void Plane::navigate()
{
// do not navigate with corrupt data
// ---------------------------------
if (!have_position) {
return;
}

if (next_WP_loc.lat == 0 && next_WP_loc.lng == 0) {
return;
}

// waypoint distance from plane
// ----------------------------
auto_state.wp_distance = current_loc.get_distance(next_WP_loc);
auto_state.wp_proportion = current_loc.line_path_proportion(prev_WP_loc, next_WP_loc);
SpdHgt_Controller->set_path_proportion(auto_state.wp_proportion);

// update total loiter angle
loiter_angle_update();

// control mode specific updates to navigation demands
// ---------------------------------------------------
control_mode->navigate();
}

// method intended for use in calc_airspeed_errors only
float Plane::mode_auto_target_airspeed_cm()
{
#if HAL_QUADPLANE_ENABLED
if ((quadplane.options & QuadPlane::OPTION_MISSION_LAND_FW_APPROACH) &&
((vtol_approach_s.approach_stage == Landing_ApproachStage::APPROACH_LINE) ||
(vtol_approach_s.approach_stage == Landing_ApproachStage::VTOL_LANDING))) {
const float land_airspeed = SpdHgt_Controller->get_land_airspeed();
if (is_positive(land_airspeed)) {
return land_airspeed * 100;
}
// fallover to normal airspeed
return aparm.airspeed_cruise_cm;
}
if (quadplane.in_vtol_land_approach()) {
return quadplane.get_land_airspeed() * 100;
}
#endif

// normal AUTO mode and new_airspeed variable was set by
// DO_CHANGE_SPEED command while in AUTO mode
if (new_airspeed_cm > 0) {
return new_airspeed_cm;
}

// fallover to normal airspeed
return aparm.airspeed_cruise_cm;
}

void Plane::calc_airspeed_errors()
{
float airspeed_measured = 0;

// we use the airspeed estimate function not direct sensor as TECS
// may be using synthetic airspeed
ahrs.airspeed_estimate(airspeed_measured);

// FBW_B/cruise airspeed target
if (!failsafe.rc_failsafe && (control_mode == &mode_fbwb || control_mode == &mode_cruise)) {
if (g2.flight_options & FlightOptions::CRUISE_TRIM_AIRSPEED) {
target_airspeed_cm = aparm.airspeed_cruise_cm;
} else if (g2.flight_options & FlightOptions::CRUISE_TRIM_THROTTLE) {
float control_min = 0.0f;
float control_mid = 0.0f;
const float control_max = channel_throttle->get_range();
const float control_in = get_throttle_input();
switch (channel_throttle->get_type()) {
case RC_Channel::RC_CHANNEL_TYPE_ANGLE:
control_min = -control_max;
break;
case RC_Channel::RC_CHANNEL_TYPE_RANGE:
control_mid = channel_throttle->get_control_mid();
break;
}
if (control_in <= control_mid) {
target_airspeed_cm = linear_interpolate(aparm.airspeed_min * 100, aparm.airspeed_cruise_cm,
control_in,
control_min, control_mid);
} else {
target_airspeed_cm = linear_interpolate(aparm.airspeed_cruise_cm, aparm.airspeed_max * 100,
control_in,
control_mid, control_max);
}
} else {
target_airspeed_cm = ((int32_t)(aparm.airspeed_max - aparm.airspeed_min) *
get_throttle_input()) + ((int32_t)aparm.airspeed_min * 100);
}
#if OFFBOARD_GUIDED == ENABLED
} else if (control_mode == &mode_guided && guided_state.target_airspeed_cm > 0.0) { // if offbd guided speed change cmd not set, then this section is skipped
// offboard airspeed demanded
uint32_t now = AP_HAL::millis();
float delta = 1e-3f * (now - guided_state.target_airspeed_time_ms);
guided_state.target_airspeed_time_ms = now;
float delta_amt = 100 * delta * guided_state.target_airspeed_accel;
target_airspeed_cm += delta_amt;

//target_airspeed_cm recalculated then clamped to between MIN airspeed and MAX airspeed by constrain_float
if (is_positive(guided_state.target_airspeed_accel)) {
target_airspeed_cm = constrain_float(MIN(guided_state.target_airspeed_cm, target_airspeed_cm), aparm.airspeed_min *100, aparm.airspeed_max *100);
} else {
target_airspeed_cm = constrain_float(MAX(guided_state.target_airspeed_cm, target_airspeed_cm), aparm.airspeed_min *100, aparm.airspeed_max *100);
}

#endif // OFFBOARD_GUIDED == ENABLED

} else if (flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND) {
// Landing airspeed target
target_airspeed_cm = landing.get_target_airspeed_cm();
} else if (control_mode == &mode_guided && new_airspeed_cm > 0) { //DO_CHANGE_SPEED overrides onboard guided speed commands, user would have re-enter guided mode to revert
target_airspeed_cm = new_airspeed_cm;
} else if (control_mode == &mode_auto) {
target_airspeed_cm = mode_auto_target_airspeed_cm();
#if HAL_QUADPLANE_ENABLED
} else if (control_mode == &mode_qrtl && quadplane.in_vtol_land_approach()) {
target_airspeed_cm = quadplane.get_land_airspeed() * 100;
#endif
} else {
// Normal airspeed target for all other cases
target_airspeed_cm = aparm.airspeed_cruise_cm;
}

// Set target to current airspeed + ground speed undershoot,
// but only when this is faster than the target airspeed commanded
// above.
if (control_mode->does_auto_throttle() &&
aparm.min_gndspeed_cm > 0 &&
control_mode != &mode_circle) {
int32_t min_gnd_target_airspeed = airspeed_measured*100 + groundspeed_undershoot;
if (min_gnd_target_airspeed > target_airspeed_cm) {
target_airspeed_cm = min_gnd_target_airspeed;
}
}

// when using the special GUIDED mode features for slew control, don't allow airspeed nudging as it doesn't play nicely.
#if OFFBOARD_GUIDED == ENABLED
if (control_mode == &mode_guided && !is_zero(guided_state.target_airspeed_cm) && (airspeed_nudge_cm != 0)) {
airspeed_nudge_cm = 0; //airspeed_nudge_cm forced to zero
}
#endif

// Bump up the target airspeed based on throttle nudging
if (control_mode->allows_throttle_nudging() && airspeed_nudge_cm > 0) {
target_airspeed_cm += airspeed_nudge_cm;
}

// Apply airspeed limit
target_airspeed_cm = constrain_int32(target_airspeed_cm, aparm.airspeed_min*100, aparm.airspeed_max*100);

// use the TECS view of the target airspeed for reporting, to take
// account of the landing speed
airspeed_error = SpdHgt_Controller->get_target_airspeed() - airspeed_measured;
}

void Plane::calc_gndspeed_undershoot()
{
// Use the component of ground speed in the forward direction
// This prevents flyaway if wind takes plane backwards
if (gps.status() >= AP_GPS::GPS_OK_FIX_2D) {
Vector2f gndVel = ahrs.groundspeed_vector();
const Matrix3f &rotMat = ahrs.get_rotation_body_to_ned();
Vector2f yawVect = Vector2f(rotMat.a.x,rotMat.b.x);
if (!yawVect.is_zero()) {
yawVect.normalize();
float gndSpdFwd = yawVect * gndVel;
groundspeed_undershoot = (aparm.min_gndspeed_cm > 0) ? (aparm.min_gndspeed_cm - gndSpdFwd*100) : 0;
}
} else {
groundspeed_undershoot = 0;
}
}

// method intended to be used by update_loiter
void Plane::update_loiter_update_nav(uint16_t radius)
{
#if HAL_QUADPLANE_ENABLED
if (loiter.start_time_ms != 0 &&
quadplane.guided_mode_enabled()) {
if (!auto_state.vtol_loiter) {
auto_state.vtol_loiter = true;
// reset loiter start time, so we don't consider the point
// reached till we get much closer
loiter.start_time_ms = 0;
quadplane.guided_start();
}
return;
}
#endif

#if HAL_QUADPLANE_ENABLED
const bool quadplane_qrtl_switch = (control_mode == &mode_rtl && quadplane.available() && quadplane.rtl_mode == QuadPlane::RTL_MODE::SWITCH_QRTL);
#else
const bool quadplane_qrtl_switch = false;
#endif

if ((loiter.start_time_ms == 0 &&
(control_mode == &mode_auto || control_mode == &mode_guided) &&
auto_state.crosstrack &&
current_loc.get_distance(next_WP_loc) > radius*3) ||
quadplane_qrtl_switch) {
/*
if never reached loiter point and using crosstrack and somewhat far away from loiter point
navigate to it like in auto-mode for normal crosstrack behavior

we also use direct waypoint navigation if we are a quadplane
that is going to be switching to QRTL when it gets within
RTL_RADIUS
*/
nav_controller->update_waypoint(prev_WP_loc, next_WP_loc);
return;
}
nav_controller->update_loiter(next_WP_loc, radius, loiter.direction);
}

void Plane::update_loiter(uint16_t radius)
{
if (radius <= 1) {
// if radius is <=1 then use the general loiter radius. if it's small, use default
radius = (abs(aparm.loiter_radius) <= 1) ? LOITER_RADIUS_DEFAULT : abs(aparm.loiter_radius);
if (next_WP_loc.loiter_ccw == 1) {
loiter.direction = -1;
} else {
loiter.direction = (aparm.loiter_radius < 0) ? -1 : 1;
}
}

update_loiter_update_nav(radius);

if (loiter.start_time_ms == 0) {
if (reached_loiter_target() ||
auto_state.wp_proportion > 1) {
// we've reached the target, start the timer
loiter.start_time_ms = millis();
if (control_mode->is_guided_mode()) {
// starting a loiter in GUIDED means we just reached the target point
gcs().send_mission_item_reached_message(0);
}
#if HAL_QUADPLANE_ENABLED
if (quadplane.guided_mode_enabled()) {
quadplane.guided_start();
}
#endif
}
}
}

/*
handle speed and height control in FBWB or CRUISE mode.
In this mode the elevator is used to change target altitude. The
throttle is used to change target airspeed or throttle
*/
void Plane::update_fbwb_speed_height(void)
{
uint32_t now = micros();
if (now - target_altitude.last_elev_check_us >= 100000) {
// we don't run this on every loop as it would give too small granularity on quadplanes at 300Hz, and
// give below 1cm altitude change, which would result in no climb or descent
float dt = (now - target_altitude.last_elev_check_us) * 1.0e-6;
dt = constrain_float(dt, 0.1, 0.15);

target_altitude.last_elev_check_us = now;

float elevator_input = channel_pitch->get_control_in() / 4500.0f;

if (g.flybywire_elev_reverse) {
elevator_input = -elevator_input;
}

int32_t alt_change_cm = g.flybywire_climb_rate * elevator_input * dt * 100;
change_target_altitude(alt_change_cm);

if (is_zero(elevator_input) && !is_zero(target_altitude.last_elevator_input)) {
// the user has just released the elevator, lock in
// the current altitude
set_target_altitude_current();
}

#if HAL_SOARING_ENABLED
if (g2.soaring_controller.is_active()) {
if (g2.soaring_controller.get_throttle_suppressed()) {
// we're in soaring mode with throttle suppressed
set_target_altitude_current();
} else {
// we're in soaring mode climbing back to altitude. Set target to SOAR_ALT_CUTOFF plus 10m to ensure we positively climb
// through SOAR_ALT_CUTOFF, thus triggering throttle suppression and return to glide.
target_altitude.amsl_cm = 100*plane.g2.soaring_controller.get_alt_cutoff() + 1000 + AP::ahrs().get_home().alt;
}
}
#endif

target_altitude.last_elevator_input = elevator_input;
}

check_fbwb_minimum_altitude();

altitude_error_cm = calc_altitude_error_cm();

calc_throttle();
calc_nav_pitch();
}

/*
calculate the turn angle for the next leg of the mission
*/
void Plane::setup_turn_angle(void)
{
int32_t next_ground_course_cd = mission.get_next_ground_course_cd(-1);
if (next_ground_course_cd == -1) {
// the mission library can't determine a turn angle, assume 90 degrees
auto_state.next_turn_angle = 90.0f;
} else {
// get the heading of the current leg
int32_t ground_course_cd = prev_WP_loc.get_bearing_to(next_WP_loc);

// work out the angle we need to turn through
auto_state.next_turn_angle = wrap_180_cd(next_ground_course_cd - ground_course_cd) * 0.01f;
}
}

/*
see if we have reached our loiter target
*/
bool Plane::reached_loiter_target(void)
{
#if HAL_QUADPLANE_ENABLED
if (quadplane.in_vtol_auto()) {
return auto_state.wp_distance < 3;
}
#endif
return nav_controller->reached_loiter_target();
}[/CODE]

Regular-waypoint-tracking.png


Peki İbrahim; MCAS nerede, yapay zeka nerede?

Aslında bu son dönemlerde sıkça karşımıza çıkan bir durum. Gördüğünüz üzre, sistemlerde bir yapay zeka yok. Sadece kompleks matematik denklemlerinden oluşan algoritmalar var. Ancak özellikle uçağın karakteristiklerini öğrenme ve sensörlerin doğasını öğrenme noktasında, yapay zeka ve makine öğrenmesi, yeni bir basamak.

Normalde bu sistemlerde, sensörlerin hata aralıklarını öğrenen algoritmalar vardır ancak bunlar, EKF'den gelen çıktıya göre şekillenir. Yani bir bakıma uçuştan uçuşa değişirler.

Ancak MCAS tipi sistemler, direkt olarak uçağın ya da pilotun hareketlerinden yola çıkarak, duruma müdahele ederler. MCAS da temelinde sensörden gelen veriye göre hareket eden bir sistem. Ama Boeing'in hatası, kabaca sensöerden yanlış bir veri geldiğinde, bunu kompanse edecek ya da saf dışı bırakacak bir sistemi entegre etmemiş olmasıydı.

AOA-sensor-works-W-780x520.jpg


Uzun zamandır yazmak istediğim bir konuyu, bulduğum kısa zamanda yazmaya çalıştım. Konu hakkında detaylı bilgiye sahip kişiler için basit ya da çok yüzeysel gelecektir, ancak ilgi duyan ve başlamak isteyenler için güzel bir örnek olduğunu düşünüyorum.

Okuduğunuz için teşekkürler, sağlıcakla kalın. :)
 
Son düzenleyen: Moderatör:
Elinize sağlık, bu işleri cidden güzel şekilde yapıyorsunuz. Başarılarınız daim olsun, kolay gelsin.
 
Normalde yazmayacaktım :)

Matematiğin, fiziğin, yazılımın, mühendislik alanlarının birleşiminin sanat eseri...
İşin içinde aerodinamik var, direnç var. Elinize sağlık hocam, keyifle okudum. Sayenizde fikir edindim.

Mühendislik ve matematik iç içe. Otonom sistemler gibi ekstrem alanlarda bu daha da iyi fark ediliyor.

Öyle hayati ki %20 ila % 60 oranında hata düzeltme yapabiliyor bu algoritmalar. Kendi sistemlerimizde de pusula bozulmasına karşın sağlıklı uçuşlar gerçekleştirebildik, zira bu algoritmalar sayesinde pusuladan gelen pusula başı bilgisi bozuk olsa bile, uçak IMU ve GPS verilerini kullanarak yönünü bulabiliyor.
 
Mühendislik ve matematik iç içe. Otonom sistemler gibi ekstrem alanlarda bu daha da iyi fark ediliyor.

Öyle hayati ki %20 ila % 60 oranında hata düzeltme yapabiliyor bu algoritmalar. Kendi sistemlerimizde de pusula bozulmasına karşın sağlıklı uçuşlar gerçekleştirebildik, zira bu algoritmalar sayesinde pusuladan gelen pusula başı bilgisi bozuk olsa bile, uçak ımu ve GPS verilerini kullanarak yönünü bulabiliyor.

Tam olarak emin değilim ancak yapay zeka ile otonom işlem karışımı gibi bir şeye benziyor bu olay.

Anladığım kadarıyla her türlü koşulda amacına ulaşmayı sağlıyor algoritmalar.
 
Yapay zeka yok aslında.

Dediğim gibi ilk başta Kalman filtresini ve hata düzeltme - filtreleme - sonraki veriyi tahmin etme mantığını kavramak gerek.

Ama yapay zeka, daha doğrusu makine öğrenmesi tabii ki entegre edilebilir ki büyük ve özellikle savunma odaklı otonom sistemlerde, bu algoritmalar yapay zekalar ile iç içedir.
 
Bu yazdığınız konuyu kendim için son derecede aydınlatıcı buldum. Elinize sağlık. Uzun zamandır STM32 ile kendi uçuş kontrol kartımı tasarlamayı planlıyorum ve bunun için çalışıyorum. Bu tip uçuş algoritmalarını anlatan Türkçe kaynaklar olması benim için büyük bir nimet. Tekrardan teşekkür ediyorum.
 
Bu yazdığınız konuyu kendim için son derecede aydınlatıcı buldum. Elinize sağlık. Uzun zamandır STM32 ile kendi uçuş kontrol kartımı tasarlamayı planlıyorum ve bunun için çalışıyorum. Bu tip uçuş algoritmalarını anlatan Türkçe kaynaklar olması benim için büyük bir nimet. Tekrardan teşekkür ediyorum.

Rica ederim. :)

Ben de yaklaşık 1 senedir STM32H7 tabanlı kartlar üzerinde çalışıyorum. Bu Mart gibi de bir uçuş kontrol kartı tasarımına başladım. Aslında kartı tasarlamak bir noktada kolay (yazılım tarafına göre tabii ki :D ) zira belirli sınırları var. Kullanılacak sensörler, protokoller, gerekli yalıtımlar, RF izolasyonu ve empedanslara dikkat etmek, sinyal kirliliğini önlemek.

Ama işin yazılım ve özellikle algoritma tarafında benzer sınırlar yok, çok açık. STM32'nin en büyük nimetleri HAL kütüphaneleri ve geniş dökümantasyonları ancak bunlar bile yetmiyor.

Bir uçuş algoritmasını entegre etmek, bunun doğru çalışmasını sağlamak ve o sistemlerle onlarca uçuş yapmak... Büyük ve tek başına yapılamayacak işler... :)
 
Büyük ve tek başına yapılamayacak işle
Tek başına çalışmaya baya alışmış biriyim. Uçağımı kendim Solidworks ile çizdim, simulasyonlarını yaptım. Kaba taslak PCB tasarımı yapabiliyorum (Bu tasarım yüzünden her yer parazit olacak ;) ).
STM32'nin en büyük nimetleri HAL kütüphaneleri ve geniş dökümantasyonları ancak bunlar bile yetmiyor.
Hocam STM32 ile bir şeyler yazarken register seviyesinden yukarı çıkmamaya özen gösteriyorum. HAL kütüphanelerinin CPU'yu çok fazla meşgul ettiğini düşünüyorum. Ama geliştirme süresini çok kısalttıklarını inkar edemem.
 

Technopat Haberler

Yeni konular

Geri
Yukarı