ArduPlane: change LIM_ROLL_CD to ROLL_LIMIT_DEG

This commit is contained in:
Andrew Tridgell 2024-01-19 12:58:28 +11:00
parent cfc30fac44
commit 89a947cdca
6 changed files with 13 additions and 13 deletions

View File

@ -76,8 +76,8 @@ bool AP_Arming_Plane::pre_arm_checks(bool display_failure)
ret = false;
}
if (plane.aparm.roll_limit_cd < 300) {
check_failed(display_failure, "LIM_ROLL_CD too small (%u)", (unsigned)plane.aparm.roll_limit_cd);
if (plane.aparm.roll_limit < 3) {
check_failed(display_failure, "LIM_ROLL_DEG too small (%.1f)", plane.aparm.roll_limit.get());
ret = false;
}

View File

@ -172,7 +172,7 @@ void Plane::ahrs_update()
#endif
// calculate a scaled roll limit based on current pitch
roll_limit_cd = aparm.roll_limit_cd;
roll_limit_cd = aparm.roll_limit*100;
pitch_limit_min = aparm.pitch_limit_min;
bool rotate_limits = true;

View File

@ -512,14 +512,14 @@ const AP_Param::Info Plane::var_info[] = {
// @User: Advanced
GSCALAR(initial_mode, "INITIAL_MODE", Mode::Number::MANUAL),
// @Param: LIM_ROLL_CD
// @Param: ROLL_LIMIT_DEG
// @DisplayName: Maximum Bank Angle
// @Description: Maximum bank angle commanded in modes with stabilized limits. Increase this value for sharper turns, but decrease to prevent accelerated stalls.
// @Units: cdeg
// @Range: 0 9000
// @Increment: 10
// @Units: deg
// @Range: 0 90
// @Increment: 0.1
// @User: Standard
ASCALAR(roll_limit_cd, "LIM_ROLL_CD", HEAD_MAX_CENTIDEGREE),
ASCALAR(roll_limit, "ROLL_LIMIT_DEG", ROLL_LIMIT_DEG),
// @Param: PTCH_LIM_MAX_DEG
// @DisplayName: Maximum Pitch Angle
@ -1554,6 +1554,7 @@ void Plane::load_parameters(void)
g.cruise_alt_floor.convert_centi_parameter(AP_PARAM_INT16);
aparm.pitch_limit_max.convert_centi_parameter(AP_PARAM_INT16);
aparm.pitch_limit_min.convert_centi_parameter(AP_PARAM_INT16);
aparm.roll_limit.convert_centi_parameter(AP_PARAM_INT16);
hal.console->printf("load_all took %uus\n", (unsigned)(micros() - before));
}

View File

@ -213,7 +213,7 @@ public:
//
k_param_crosstrack_gain = 150, // unused
k_param_crosstrack_entry_angle, // unused
k_param_roll_limit_cd,
k_param_roll_limit,
k_param_pitch_limit_max,
k_param_pitch_limit_min,
k_param_airspeed_cruise,

View File

@ -156,8 +156,8 @@
//////////////////////////////////////////////////////////////////////////////
// Autopilot control limits
//
#ifndef HEAD_MAX
# define HEAD_MAX 45
#ifndef ROLL_LIMIT_DEG
# define ROLL_LIMIT_DEG 45
#endif
#ifndef PITCH_MAX
# define PITCH_MAX 20
@ -165,7 +165,6 @@
#ifndef PITCH_MIN
# define PITCH_MIN -25
#endif
#define HEAD_MAX_CENTIDEGREE HEAD_MAX * 100
#ifndef RUDDER_MIX
# define RUDDER_MIX 0.5f

View File

@ -1517,7 +1517,7 @@ bool QuadPlane::should_assist(float aspeed, bool have_airspeed)
*/
const uint16_t allowed_envelope_error_cd = 500U;
if (labs(ahrs.roll_sensor) <= plane.aparm.roll_limit_cd+allowed_envelope_error_cd &&
if (labs(ahrs.roll_sensor) <= plane.aparm.roll_limit*100 + allowed_envelope_error_cd &&
ahrs.pitch_sensor < plane.aparm.pitch_limit_max*100+allowed_envelope_error_cd &&
ahrs.pitch_sensor > -(allowed_envelope_error_cd-plane.aparm.pitch_limit_min*100)) {
// we are inside allowed attitude envelope