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

Baro thrust scaling #28982

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

Conversation

andyp1per
Copy link
Collaborator

This allows a user to apply a linear pressure compensation to a baro based on thrust output. On a small whoop there is a very causal relationship between pressure and throttle:

image

By applying this offset the effect can be normalized:

image

Set by using ```BAROx_THST_SCALE"

@andyp1per andyp1per force-pushed the pr-baro-mot-comp branch 2 times, most recently from 2ea1cf1 to a64c7e9 Compare January 1, 2025 20:56
@@ -103,3 +103,7 @@
// this allows for using the simple model with the --ekf-single configure option
#define AP_BARO_1976_STANDARD_ATMOSPHERE_ENABLED HAL_WITH_EKF_DOUBLE || AP_SIM_ENABLED
#endif

#ifndef HAL_BARO_THST_COMP_ENABLED
#define HAL_BARO_THST_COMP_ENABLED 1
Copy link
Contributor

Choose a reason for hiding this comment

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

Need to know how useful this might be on other vehicles. And flash cost...

Copy link
Collaborator Author

Choose a reason for hiding this comment

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

Cost 160 bytes avg on Durandal

@tpwrules
Copy link
Contributor

The parameter is error at max thrust?

@andyp1per
Copy link
Collaborator Author

The parameter is error at max thrust?

Not sure I follow?

@tpwrules
Copy link
Contributor

Not sure I follow?

The parameter description says "User provided thrust scaling in Pascals. This is used to adjust linearly based on the thrust output for local pressure difference induced by the props.".

If it's a linear scaling, it should be Pascals per something. The code uses the scale as sensors[instance].mot_scale * motors_throttle;, so it's the Pascal scaling to apply when motors_throttle is 1. When is that? Can you clarify the parameter description?

libraries/AP_Baro/AP_Baro.cpp Outdated Show resolved Hide resolved
libraries/AP_Baro/AP_Baro.cpp Show resolved Hide resolved
libraries/AP_Baro/LogStructure.h Show resolved Hide resolved
@Hwurzburg Hwurzburg added the WikiNeeded needs wiki update label Jan 14, 2025
Copy link
Contributor

@tridge tridge left a comment

Choose a reason for hiding this comment

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

I still wonder if this could be a voltage supply, ie motor load drawing down the voltage, impacting the sensor. Could you try props off, but friction load on the motors (eg. your fingers) and see if baro is impacted?

AP_GROUPINFO("1_THST_SCALE", 25, AP_Baro, sensors[0].mot_scale, 0),

#if BARO_MAX_INSTANCES > 1
// @Param: 2_THST_SCALE
Copy link
Contributor

Choose a reason for hiding this comment

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

i think we should only put it on the first baro, I think this issue can only happen on really tiny vehicles, and fixing just one baro should be enough (just to reduce the params). We could keep the variable in the common structure, but it would just be zero

Copy link
Contributor

Choose a reason for hiding this comment

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

@IamPete1 also suggested upside down props for the test, see if the effect is changed

Copy link
Collaborator Author

Choose a reason for hiding this comment

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

I suspect part of the reason is that the props and motors are already on the underside of the vehicle, pushing away from the FC

@rmackay9
Copy link
Contributor

It'd be nice if we could get other devs with whoops to give it a try as well

@@ -103,3 +103,7 @@
// this allows for using the simple model with the --ekf-single configure option
#define AP_BARO_1976_STANDARD_ATMOSPHERE_ENABLED HAL_WITH_EKF_DOUBLE || AP_SIM_ENABLED
#endif

#ifndef AP_BARO_THST_COMP_ENABLED
#define AP_BARO_THST_COMP_ENABLED 1
Copy link
Contributor

Choose a reason for hiding this comment

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

I think it would be good if we only enabled this on the boards/vehicles that really need it. It's just a small part of keeping complexity for the user down

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

Successfully merging this pull request may close these issues.

9 participants