Skip to content

Conversation

@Ryanf55
Copy link
Contributor

@Ryanf55 Ryanf55 commented Jan 9, 2025

Purpose

Add an initial soaring module, which displays the location and estimated radius of the thermal from AP's thermal soaring estimator.
image

Once we have a mavlink packet definition for the thermal estimator, we can move to that from NAMED_VALUE_FLOAT.

Demo

Enable the NVT for the EKF and run the soaring autotest without speedup.

Terminal 1:

./Tools/autotest/autotest.py build.Plane test.Plane.Soaring --map --speedup=1 --waf-configure-args "--define HAL_SOARING_NVF_EKF_ENABLED=1"

Terminal 2:

mavproxy.py --console --master tcp:127.0.0.1:5763 --map
module load soar

Once the vehicle hits the thermal southwest of home, it will show up on the map. You can see the estimator converge on the thermal.

@Ryanf55 Ryanf55 force-pushed the soar-module branch 2 times, most recently from 73a4b5a to 0238a68 Compare January 14, 2025 05:06
print("No y")
return

home = self.module('wp').get_home()
Copy link
Contributor

Choose a reason for hiding this comment

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

This module might not be loaded.

Copy link
Contributor

Choose a reason for hiding this comment

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

.... also, are these thermals really home-relative or are they navigation-origin-relative?

Copy link
Contributor Author

@Ryanf55 Ryanf55 Jan 14, 2025

Choose a reason for hiding this comment

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

I added a module check for wp, good idea.

.... also, are these thermals really home-relative or are they navigation-origin-relative?

Per SoaringController::update_thermalling:

    const AP_AHRS &_ahrs = AP::ahrs();
    if (!_ahrs.get_relative_position_NED_home(current_position)) {
        return;
    }
    ...
    
    // update the filter
    _ekf.update(_vario.reading, current_position.x, current_position.y, wind_drift.x, wind_drift.y);

Based on that, I take it as home-relative. Not great, but that's how it is today. Seems like moving home would break stuff. Anyways, yea, I currently draw them relative to home to match.

@Ryanf55
Copy link
Contributor Author

Ryanf55 commented Jan 14, 2025

Added the clearing stale thermals! Here's a brief recording of it working.
MavproxySoarThermalClear01-13-2025 10:56:47 PM.webm

(0, 255, 255),
linewidth=2)
for mp in self.module_matching('map*'):
self._last_draw_time = time.time()
Copy link
Contributor

Choose a reason for hiding this comment

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

I was thinking timeout might be based on message retrieval time rather than draw time.

That way when the vehicle loses the thermal the GCS gets updated to remove the thermal hint

Copy link
Contributor Author

Choose a reason for hiding this comment

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

I was thinking timeout might be based on message retrieval time rather than draw time.

That way when the vehicle loses the thermal the GCS gets updated to remove the thermal hint

The estimator stops running once you exit thermal mode when you lose the thermal - you stop getting packets. Functionally, message receipt calls draw, so it's the same time anyways.

Signed-off-by: Ryan Friedman <25047695+Ryanf55@users.noreply.github.com>
Copy link
Contributor

@peterbarker peterbarker left a comment

Choose a reason for hiding this comment

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

LGTM

@peterbarker peterbarker merged commit 2b1803c into ArduPilot:master Jan 16, 2025
2 checks passed
@Ryanf55 Ryanf55 deleted the soar-module branch January 16, 2025 05:19
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