Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Plane: Document setup without GPS or airspeed sensor #6508

Open
wants to merge 1 commit into
base: master
Choose a base branch
from

Conversation

Ryanf55
Copy link
Contributor

@Ryanf55 Ryanf55 commented Jan 4, 2025

Document how to set up ArduPlane to fly in FBWA without GPS or airspeed sensor. Document some known limitations.
This is for a minimal plane build to just use AP as a stabilizer.

Copy link
Contributor

@Hwurzburg Hwurzburg left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

an RC failsafe results in crash or fly-away

put a warning immediately after the header

@Ryanf55
Copy link
Contributor Author

Ryanf55 commented Jan 4, 2025

an RC failsafe results in crash or fly-away

put a warning immediately after the header

What do you think about recommending CIRCLE as a failsafe action. That won't fly away, and over flat area, the vehicle will likely land just fine.

@Hwurzburg
Copy link
Contributor

CIRCLE is not an option...only GLIDE (FBWA no throttle) is useable with no GPS

@Ryanf55
Copy link
Contributor Author

Ryanf55 commented Jan 5, 2025

an RC failsafe results in crash or fly-away

CIRCLE is not an option...only GLIDE (FBWA no throttle) is useable with no GPS

From the wiki: Circle mode is deliberately a very conservative mode, and doesn’t rely on GPS positioning as it is used when GPS fails

And, the code:

#include "mode.h"
#include "Plane.h"

bool ModeCircle::_enter()
{
    // the altitude to circle at is taken from the current altitude
    plane.next_WP_loc.alt = plane.current_loc.alt;

    return true;
}

void ModeCircle::update()
{
    // we have no GPS installed and have lost radio contact
    // or we just want to fly around in a gentle circle w/o GPS,
    // holding altitude at the altitude we set when we
    // switched into the mode
    plane.nav_roll_cd  = plane.roll_limit_cd / 3;
    plane.update_load_factor();
    plane.calc_nav_pitch();
    plane.calc_throttle();
}

The default for FS_SHORT_ACTN is FS_ACTION_SHORT_BESTGUESS, which means circle if I was in FBWA. You can't be in Auto , Guided, or Loiter if you don't have a GPS or airspeed sensor. Users can also select CIRCLE as their FS_SHORT_ACTN.

For FS_LONG_ACTION, we could recommend FS_ACTION_LONG_GLIDE as that is the most likely to not total the aircraft if it doesn't know where it is.

@Hwurzburg
Copy link
Contributor

we should sitl the non gps case with defaults for FS actions (CIRCLE/RTL) with RC failure to be definitive on warning as to what will happen

@Ryanf55 Ryanf55 force-pushed the plane-no-gps-airspeed branch from c9dddbd to 3f68718 Compare January 5, 2025 17:45
@Ryanf55
Copy link
Contributor Author

Ryanf55 commented Jan 5, 2025

./Tools/autotest/sim_vehicle.py -v Plane --console --map -w
param set STALL_PREVENTION 0
param set GPS1_TYPE 0
param set ARSPD_USE 0
param set ARSPD_TYPE 0
param set AHRS_EKF_TYPE 0
param set ARMING_CHECK 0
map set showsimpos 1
# Move the map to follow the sim position.
mode fbwa
rc 2 2000
rc 3 1500
arm throttle

Wait till it gets to ~100m altitude, then trigger a failsafe.

rc 3 900

It performs the short failsafe CIRCLE, then goes to RTL and does a flyaway. Now, repeat the test with param set FS_LONG_ACTN 2 (glide). Likely on a real vehicle it will do super gentle throttle-off circles anyways because FBWA doesn't fly exactly straight.

With graph SERVO_OUTPUT_RAW.servo3_raw you can see that it's commanding no throttle. Eventually it will land.
image

Do you agree that GLIDE is better behavior than a flyaway?

@Hwurzburg
Copy link
Contributor

yes....better

@Ryanf55 Ryanf55 force-pushed the plane-no-gps-airspeed branch from 3f68718 to 05a820e Compare January 5, 2025 19:55
@Ryanf55
Copy link
Contributor Author

Ryanf55 commented Jan 5, 2025

Alright, I added that and an obvious warning about flyaway risk.

Before this wiki goes in, we either need to merge this:
ArduPilot/ardupilot#29012

OR, tell people to use the Set Home in the GCS.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants