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

Airspeed selector follow-up #12887

Merged
merged 6 commits into from
Nov 21, 2019
Merged

Airspeed selector follow-up #12887

merged 6 commits into from
Nov 21, 2019

Conversation

sfuhrer
Copy link
Contributor

@sfuhrer sfuhrer commented Sep 3, 2019

This PR enables the airspeed validation & selection module (#12353) by making the controllers listen to the airspeed_validated topic and no longer to the airspeed topic.

Changes:

  • VTOL_att_controller, FW_att_controller, FW_pos_controller subscribe to airspeed_validated topic
  • add ability to completely switch off airspeed failure detection (parameter ASPD_DO_CHECKS)
  • add ability to fallback to groundspeed-windspeed if airspeed sensor is declared invalid (param ASPD_FALLBACK)
  • remove airspeed checks from commander (since Airspeed validation & selection module #12353 was merged it was implemented also in this new module)
  • remove airspeed failsafe actions in commander (COM_ASPD_FS_ACT)
  • remove status.aspd_use_inhibit (the airspeed_validated topic airspeeds are set to NAN if not valid
  • rename all the params for the airspeed validation and move them from the COM to the ASPD section

After this gets merged, we should think about this stuff:

  • make it easy to switch between non-airspeed and normal flight (can we remove the CBRK_AIRSPD_CHECK? Rename/remove FW_ARSP_MODE?)
  • think about which airspeed should be fused into EKF (currently is still the "raw" airspeed from the first airspeed sensor)
  • improve wind estimator (tuning, resets) to get less false positives for the failure detection

Fixes: #13144.

@sfuhrer sfuhrer requested a review from RomanBapst September 3, 2019 13:13
@sfuhrer sfuhrer self-assigned this Sep 3, 2019
@sfuhrer sfuhrer force-pushed the pr-AirspeedSelector_followup branch from f7c0748 to 9ba7418 Compare September 16, 2019 12:51
@julianoes julianoes changed the title [WIP] Pr airspeed selector followup [WIP] Airspeed selector follow-up Sep 25, 2019
@sfuhrer sfuhrer force-pushed the pr-AirspeedSelector_followup branch from 9ba7418 to a1cd0e5 Compare October 8, 2019 08:57
@sfuhrer
Copy link
Contributor Author

sfuhrer commented Oct 8, 2019

so far only sitl and bench tested, will go testflying soon

@sfuhrer sfuhrer marked this pull request as ready for review October 8, 2019 09:09
@sfuhrer sfuhrer changed the title [WIP] Airspeed selector follow-up Airspeed selector follow-up Oct 8, 2019
@sfuhrer sfuhrer force-pushed the pr-AirspeedSelector_followup branch 2 times, most recently from 7a8cb3c to 08647c9 Compare October 8, 2019 14:29
@sfuhrer
Copy link
Contributor Author

sfuhrer commented Oct 8, 2019

Flight tested on standard VTOL: https://review.px4.io/plot_app?log=efbe527d-cb51-46e7-9264-ee0c0450494f

I set:
ASPD_PRIMARY = 1 (the airspeed sensor that's mounted)
ASPD_DO_CHECKS = 1 (enabling airspeed validity checks)
ASPD_FALLBACK = 1 (to use ground-windspeed as fallback if failure is detected)

At 3.30min I set the stallspeed to 100, thus triggering a failure detection. The selector then switched automatically to the groundspeed minus windspeed airspeed estimate (as defined in ASPD_FALLBACK = 1). No change change in behavior noticeable to the pilot, it kept flying in position control mode with airspeed and altitude controllable separately.
Note: very calm conditions, almost no wind.

msg/airspeed_validated.msg Outdated Show resolved Hide resolved
src/lib/AirspeedValidator/AirspeedValidator.cpp Outdated Show resolved Hide resolved
src/modules/airspeed_selector/airspeed_selector_main.cpp Outdated Show resolved Hide resolved
src/modules/airspeed_selector/airspeed_selector_main.cpp Outdated Show resolved Hide resolved
src/modules/airspeed_selector/airspeed_selector_main.cpp Outdated Show resolved Hide resolved
@@ -182,7 +182,7 @@ void Standard::update_vtol_state()
} else if (_vtol_schedule.flight_mode == vtol_mode::TRANSITION_TO_FW) {
// continue the transition to fw mode while monitoring airspeed for a final switch to fw mode
if (((_params->airspeed_disabled ||
_airspeed->indicated_airspeed_m_s >= _params->transition_airspeed) &&
Copy link
Contributor

Choose a reason for hiding this comment

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

@sfuhrer I think we need to check for airspeed validity here as well. I assume we can just remove the check on "_params->airspeed_disabled" and check if airspeed is finite, correct?

Copy link
Contributor

Choose a reason for hiding this comment

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

Same holds for everywhere else in the vtol code.

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've added a PX4_ISFINITE(airpseed) everywhere airspeed is used, and if it's invalid it does the same as when "_params->airspeed_disabled". I've not yet removed the parameter, not 100% if we should do so with this PR, or if that's fuel for another PR (I was also thinking about removing the CBRK_AIRSPD_CHECK, but this then needs some further thoughts.

@RomanBapst
Copy link
Contributor

@sfuhrer Please have a look at my last three commits. I cleaned up the airspeed usage for all three vtol types for the transition.
I had a lot of trouble reading what was there before (not your fault btw) and decided to change it.
I think previously it was also the case the even if the airspeed was NAN further down it was checked if airspeed was greater than the transition threshold.

@RomanBapst RomanBapst force-pushed the pr-AirspeedSelector_followup branch from 910e7dd to b1fb8a7 Compare October 17, 2019 05:30
@RomanBapst
Copy link
Contributor

@sfuhrer I also rebased on master btw.

@sfuhrer sfuhrer force-pushed the pr-AirspeedSelector_followup branch 7 times, most recently from a8a61a6 to 63de4a0 Compare November 14, 2019 11:11
- FW attitude controller, FW position controller and VTOL attitude controller subscribe to airspeed_validated topic
- add possibility to switch off the airspeed valid checks
- remove airspeed valid checks from commander
- clean up of VTOL transition logic

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
…depending on number of connected sensors) but do it statically for the maximum number allowed. Check for number of connected sensors not only during start up, but always when vehicle is disarmed.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
@sfuhrer sfuhrer force-pushed the pr-AirspeedSelector_followup branch from 63de4a0 to 8e4992d Compare November 14, 2019 13:56
* @reboot_required true
* @group Airspeed Validator
*/
PARAM_DEFINE_INT32(ASPD_PRIMARY, 1);
Copy link
Member

Choose a reason for hiding this comment

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

We'll probably need to find a better way to do this later. We can't rely on the ordering being maintained in all cases.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Agree. As we currently though anyway just support 1 sensor it's not yet that critical.

@@ -578,7 +578,7 @@ Commander::Commander() :

Commander::~Commander()
{
delete[] _airspeed_fault_type;

Copy link
Member

Choose a reason for hiding this comment

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

You can delete this entirely, then in the header set the destructor to = default.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

done

&& PX4_ISFINITE(as.true_airspeed_m_s)
&& (as.indicated_airspeed_m_s > 0.0f)
&& !_vehicle_status.aspd_use_inhibit) {
if (PX4_ISFINITE(airspeed_validated.equivalent_airspeed_m_s)
Copy link
Member

Choose a reason for hiding this comment

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

I think we should be able to drop these checks and trust our "validated airspeed".

Copy link
Contributor Author

Choose a reason for hiding this comment

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

The way it works currently is that the airspeed validated is set to NAN inside the airspeed module if it is detected to be invalid (or user has disabled it by setting PRIMARY to -1). As I see it we either keep it this way and check for the finiteness of the airspeed_validated where it's used, or build in some logic in commander that sets a "airspeed_inhibited" flag in vehicle_status, or make this flag part of the airpseed_validated message (as it was at some point, but was removed because it then contains redundant information (setting it to NAN should be equal to "don't use airspeed)".
I'd vote for bringing it in as it is now.

Copy link
Member

Choose a reason for hiding this comment

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

That's fine as long as every consumer ends up with the same notion of airspeed validity.

@dagar
Copy link
Member

dagar commented Nov 14, 2019

I would change the work queue thread if this is now flight critical.

px4::wq_configurations::lp_default -> px4::wq_configurations::att_pos_ctrl

This is where the controllers and estimator run.

@sfuhrer sfuhrer force-pushed the pr-AirspeedSelector_followup branch from 4b0cdae to 9794449 Compare November 14, 2019 15:35
@sfuhrer
Copy link
Contributor Author

sfuhrer commented Nov 14, 2019

I would change the work queue thread if this is now flight critical.

px4::wq_configurations::lp_default -> px4::wq_configurations::att_pos_ctrl

This is where the controllers and estimator run.

Sounds reasonable, changed it.

@dagar
Copy link
Member

dagar commented Nov 15, 2019

This needs to be included in px4_fmu-v2_default.

Note for later, we should probably do something to require the airspeed selector is active and healthy at arming for FW and VTOL (preflight check).

@@ -285,6 +270,7 @@ class Commander : public ModuleBase<Commander>, public ModuleParams
uORB::Subscription _vehicle_acceleration_sub{ORB_ID(vehicle_acceleration)};

uORB::SubscriptionData<airspeed_s> _airspeed_sub{ORB_ID(airspeed)};
uORB::SubscriptionData<airspeed_validated_s> _airspeed_validated_sub{ORB_ID(airspeed_validated)};
Copy link
Member

Choose a reason for hiding this comment

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

Is any of this still being used in commander?

_airspeed_sub, _airspeed_validated_sub, _airspeed_fault_declared, _time_airspeed_fault_declared

…module is safety-critical

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
…peed_validated subscription

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
@sfuhrer sfuhrer force-pushed the pr-AirspeedSelector_followup branch from b8cd03d to f327c9b Compare November 15, 2019 16:38
@sfuhrer
Copy link
Contributor Author

sfuhrer commented Nov 15, 2019

This needs to be included in px4_fmu-v2_default.

Good point. v2 doesn't have enough flash (see CI failure). I had hoped that v2 would be sunset anyway soon (#13428), but as it seems this won't happen now. So how can we solve it, do you have open PRs that will free up flash @dagar ?

@dagar dagar merged commit ebdc29b into master Nov 21, 2019
@dagar dagar deleted the pr-AirspeedSelector_followup branch November 21, 2019 19:17
@mrpollo mrpollo mentioned this pull request Mar 16, 2020
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
None yet
Development

Successfully merging this pull request may close these issues.

Aispeed sensor switching on SITL plane landings
5 participants