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

AP_Baro: Allow setting field elevation to 0 #28605

Closed
wants to merge 1 commit into from

Conversation

stephendade
Copy link
Contributor

@stephendade stephendade commented Nov 13, 2024

This came up when using a vision-based vehicle (no GPS).

When using set_gps_global_origin_send to set the GPS origin of a vehicle, if the set altitude is exactly 0 then AP_Baro will continually keep resetting the field elevation.

This patch will warn the user if they try to do this.

This patch will allow setting the altitude to 0, but only once per boot.

Example pymavlink code to demonstrate issue:

#!/usr/bin/env python3
'''
Quick test script to send origin

'''
import argparse
import time
from pymavlink import mavutil


if __name__ == '__main__':
    parser = argparse.ArgumentParser()
    parser.add_argument(
        "--device", type=str, default="udpin:127.0.0.1:14550", help="MAVLink connection string")
    parser.add_argument("--baud", type=int, default=115200,
                        help="MAVLink baud rate, if using serial")
    parser.add_argument("--source-system", type=int,
                        default=1, help="MAVLink Source system")
    args = parser.parse_args()

    # Start mavlink connection
    try:
        conn = mavutil.mavlink_connection(args.device, autoreconnect=True, source_system=args.source_system,
                                          baud=args.baud, force_connected=False,
                                          source_component=mavutil.mavlink.MAV_COMP_ID_VISUAL_INERTIAL_ODOMETRY)
    except Exception as msg:
        print("Failed to start mavlink connection on %s: %s" %
              (args.device, msg,))
        raise

    # wait for the heartbeat msg to find the system ID. Need to exit from here too
    # We are sending a heartbeat signal too, to allow ardupilot to init the comms channel
    while True:
        conn.mav.heartbeat_send(mavutil.mavlink.MAV_TYPE_ONBOARD_CONTROLLER,
                                mavutil.mavlink.MAV_AUTOPILOT_GENERIC,
                                0,
                                0,
                                0)
        if conn.wait_heartbeat(timeout=0.5) is not None:
            # Got a hearbeart, go to next loop
            break

    print("Got Heartbeat from APM (system %u component %u)" %
          (conn.target_system, conn.target_component))

    time.sleep(0.05)
    print("Setting EKF origin")
    current_time_us = int(round(time.time() * 1000000))
    conn.mav.set_gps_global_origin_send(conn.target_system,
                                        int(-35.363261*1.0e7),
                                        int(149.165230*1.0e7),
                                        int(0*1.0e3),
                                        current_time_us)

@tpwrules
Copy link
Contributor

tpwrules commented Nov 13, 2024

Some slightly ignorant questions: Would it be a better experience to just convert it to 0.01? Could drifting back down to 0 cause the Baro reset to happen again?

@stephendade
Copy link
Contributor Author

Would it be a better experience to just convert it to 0.01

That would work too. My only concern would be it's different to what the user specified, which may lead to confusion in later data analysis if they don't know about the 0 -> 0.01 change.

_field_elevation_active = origin.alt * 0.01;
new_field_elev = true;
} else if (!armed && AP::ahrs().get_origin(origin) && origin.alt == 0) {
GCS_SEND_TEXT(MAV_SEVERITY_ALERT, "Origin altitude cannot be 0");
Copy link
Contributor

Choose a reason for hiding this comment

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

Wouldn't it make sense to name the parameter here?

@@ -961,9 +961,11 @@ void AP_Baro::update_field_elevation(void)
is_zero(_field_elevation)) {
// auto-set based on origin
Location origin;
if (!armed && AP::ahrs().get_origin(origin)) {
if (!armed && AP::ahrs().get_origin(origin) && origin.alt != 0) {
_field_elevation_active = origin.alt * 0.01;
new_field_elev = true;
Copy link
Contributor

Choose a reason for hiding this comment

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

The issue is that new_field_elev can be set true even is the value hasn't changed. Probably should be something like:

            Location origin;
            if (!armed && AP::ahrs().get_origin(origin)) {
                new_field_elev = !is_equal(_field_elevation_active, origin.alt * 0.01f);
                _field_elevation_active = origin.alt * 0.01;
            }

@stephendade
Copy link
Contributor Author

stephendade commented Nov 15, 2024

I've changed this to @nexton-winjeel's suggestion - we can now set the field elevation to 0.

However the field elevation can now only be set once per boot. Not sure if this conflicts with any other assumptions in the codebase?

@stephendade stephendade changed the title AP_Baro: Warn user if they set field elevation to 0 AP_Baro: Allow setting field elevation to 0 Nov 15, 2024
@Ryanf55
Copy link
Collaborator

Ryanf55 commented Nov 17, 2024

I've changed this to @nexton-winjeel's suggestion - we can now set the field elevation to 0.

However the field elevation can now only be set once per boot. Not sure if this conflicts with any other assumptions in the codebase?

How does this handle moving the home location from a GCS?

@stephendade
Copy link
Contributor Author

How does this handle moving the home location from a GCS?

Just tested this with copter SITL. No issues with: a) taking off, b) setting home to a different location (and altitude), c) setting RTL. Copter landed fine in the new home location.

@rbeall
Copy link
Contributor

rbeall commented Dec 9, 2024

I think this will solve the "now" problem, but might create "future" problems. Could there be a situation where you'd want to update the pressure datum more than once? Maybe an auto take off to auto land an hr away and then disarm... relaunch back home without rebooting? I feel like there should be a method for pushing EKF origin without having it impact auto datum and/or the ability to trigger an auto Baro datum on secondary arming at some later time in the flight. As stated, I think this "could" be fine as is. I just think it's elucidating a broader problem that maybe should be looked at.

@stephendade
Copy link
Contributor Author

Closing this one, as it appears there's a requirement to update the baro in-flight.

Will ponder a different solution...

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.

6 participants