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

Add topographic lift library and initial example implementation to SITL #28756

Draft
wants to merge 3 commits into
base: master
Choose a base branch
from

Conversation

Ryanf55
Copy link
Collaborator

@Ryanf55 Ryanf55 commented Nov 27, 2024

Purpose

Demonstrate slope soaring in SITL using a dead-simple lift estimator.

longer term

I want to investigate the idea of feeding in much more complex wind data from CFD models using this interface.
Can ArduPilot be extensible to heavy models that run ONLY on Linux, and perhaps can we feed in data to AP's FDM from another library (python), or can we link in shared libraries that use things like the STL and Boost just to get fancy CDF models?

AP SITL is awesome, but it doesn't have all the capabilities. I don't expect this to run on embedded.

@Ryanf55
Copy link
Collaborator Author

Ryanf55 commented Nov 27, 2024

Check --osd that links to an external library if we want, or use mavproxy for a python implementation.

It will need to be optional if it's not trivial flash. Linking to an external library or mavproxy module to feed in higher fidelity/accuracy wind estimates is totally an option.

It could be a LUA script with TCP/UDP that can interract with AP to feed in the topographic lift estimate, Lua is faster than mavproxy. Longer term, we could have an AP server that can provide soaring estimates directly to the vehicle in flight if we want.

Tridge is keen on improving SITL's capabilities and has other projects such as describing the vehicle in JSON format (wing size, etc).

}

// hXY are the heights of the 4 surrounding grid points
int16_t h00, h01, h10;
Copy link
Contributor

Choose a reason for hiding this comment

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

const these and define as part of declaration

Copy link
Collaborator Author

Choose a reason for hiding this comment

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

Like the PR from yesterday:) #28734

@@ -422,6 +429,7 @@ class AP_Terrain {

// cache the home altitude, as it is needed so often
float home_height;
Vector2f home_gradient;
Copy link
Contributor

Choose a reason for hiding this comment

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

Not needed?

Copy link
Collaborator Author

Choose a reason for hiding this comment

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

Suggested change
Vector2f home_gradient;

Comment on lines +21 to +23


return true;
Copy link
Contributor

Choose a reason for hiding this comment

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

Suggested change
return true;

return false;
}

[[maybe_unused]] const float veh_height_agl = loc.alt * 1E-2 - terrain_height_amsl;
Copy link
Contributor

Choose a reason for hiding this comment

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

We have a define for unused stuff

return terrain->gradient(loc, grad);
}

bool AP_TopoLiftSinglePointEstimate::get_wind_at_current_loc(Vector3f& wind) {
Copy link
Contributor

Choose a reason for hiding this comment

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

Suggested change
bool AP_TopoLiftSinglePointEstimate::get_wind_at_current_loc(Vector3f& wind) {
bool AP_TopoLiftSinglePointEstimate::get_wind_at_current_loc(Vector3f& wind)
{

etc

@@ -0,0 +1,3 @@
#ifndef AP_TOPO_LIFT_ENABLED
Copy link
Contributor

Choose a reason for hiding this comment

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

Suggested change
#ifndef AP_TOPO_LIFT_ENABLED
#include <AP_HAL/AP_HAL_Boards.h>
#ifndef AP_TOPO_LIFT_ENABLED

wind_ef.z += get_local_updraft(position + home.get_distance_NED_double(origin));
auto const curr_pos = position + home.get_distance_NED_double(origin);
wind_ef.z += get_local_updraft(curr_pos);
wind_ef.z += get_topo_lift(location);
Copy link
Contributor

Choose a reason for hiding this comment

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

Definitely want this parameterized; don't want more CPU generally - even in SITL :-)

Copy link
Collaborator Author

Choose a reason for hiding this comment

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

Should I parameterize get_local_updraft to establish the pattern?

// Wind in the topographic frame. X points east, Y points north.
// East wind will be [speed, 0]
// North wind will be [0, speed]
const Vector2f wind_topo(cosf(dir) * speed, sinf(dir) * speed);
Copy link
Contributor

Choose a reason for hiding this comment

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

Suggested change
const Vector2f wind_topo(cosf(dir) * speed, sinf(dir) * speed);
const Vector2f wind_topo{cosf(dir) * speed, sinf(dir) * speed};

Comment on lines +42 to +44
const AP_AHRS &ahrs = AP::ahrs();

return ahrs.wind_estimate(wind);
Copy link
Contributor

Choose a reason for hiding this comment

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

Should we really be using AP::ahrs() here? Your simulation shouldn't really depend on what NavEKF3 is up to - if your fix is wandering your simulation is going to follow that wandering vehicle rather than represent the true lift value the simulated vehicle should be experiencing.

I'm hoping to have a set of AHRS backend results available from the SITL backend which might allow for using the "perfect" AHRS for determining the simulatedwind and a stnadrd backend's results when using on a real vehicle.

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

Successfully merging this pull request may close these issues.

2 participants