Skip to content

Commit

Permalink
RSC_Autorotation: fixup: Add pre-arm
Browse files Browse the repository at this point in the history
  • Loading branch information
MattKear committed Sep 23, 2024
1 parent 4d7dae1 commit 6e22ddc
Show file tree
Hide file tree
Showing 2 changed files with 17 additions and 0 deletions.
14 changes: 14 additions & 0 deletions libraries/AC_Autorotation/RSC_Autorotation.cpp
Original file line number Diff line number Diff line change
@@ -1,8 +1,11 @@
#include "RSC_Autorotation.h"
#include <GCS_MAVLink/GCS.h>
#include <AP_HAL/AP_HAL.h>

#define RSC_AROT_RAMP_TIME_DEFAULT 2 // time in seconds to ramp motors when bailing out of autorotation

extern const AP_HAL::HAL& hal;

// RSC autorotation state specific parameters
const AP_Param::GroupInfo RSC_Autorotation::var_info[] = {

Expand Down Expand Up @@ -137,3 +140,14 @@ float RSC_Autorotation::get_runup_time(void) const
// Never let the runup timer be less than the throttle ramp time
return (float) MAX(bailout_throttle_time.get() + 1, bailout_runup_time.get());
}

// sanity check of parameters, should be called only whilst disarmed
bool RSC_Autorotation::arming_checks(size_t buflen, char *buffer) const
{
// throttle runup must be larger than ramp, keep the params up to date to not confuse users
if (bailout_throttle_time.get() + 1 > bailout_runup_time.get()) {
hal.util->snprintf(buffer, buflen, "H_RSC_AROT_RUNUP must be > H_RSC_AROT_RAMP");
return false;
}
return true;
}
3 changes: 3 additions & 0 deletions libraries/AC_Autorotation/RSC_Autorotation.h
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,9 @@ class RSC_Autorotation
// request changes in autorotation state
void set_active(bool active, bool force_state);

// sanity check of parameters, should be called only whilst disarmed
bool arming_checks(size_t buflen, char *buffer) const;

// var_info for holding Parameter information
static const struct AP_Param::GroupInfo var_info[];

Expand Down

0 comments on commit 6e22ddc

Please sign in to comment.