mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-04 23:18:28 -04:00
AP_MotorsUGV: consolidate parameter sanity checks
This commit is contained in:
parent
dcce9dffba
commit
34e5f521ad
@ -106,9 +106,6 @@ void AP_MotorsUGV::init()
|
||||
|
||||
// set safety output
|
||||
setup_safety_output();
|
||||
|
||||
// sanity check parameters
|
||||
_vector_throttle_base = constrain_float(_vector_throttle_base, 0.0f, 100.0f);
|
||||
}
|
||||
|
||||
// setup output in case of main CPU failure
|
||||
@ -162,9 +159,6 @@ void AP_MotorsUGV::set_steering(float steering)
|
||||
// set throttle as a value from -100 to 100
|
||||
void AP_MotorsUGV::set_throttle(float throttle)
|
||||
{
|
||||
// sanity check throttle min and max
|
||||
_throttle_min = constrain_int16(_throttle_min, 0, 20);
|
||||
_throttle_max = constrain_int16(_throttle_max, 30, 100);
|
||||
|
||||
// check throttle is between -_throttle_max ~ +_throttle_max but outside -throttle_min ~ +throttle_min
|
||||
_throttle = constrain_float(throttle, -_throttle_max, _throttle_max);
|
||||
@ -189,6 +183,9 @@ void AP_MotorsUGV::output(bool armed, float dt)
|
||||
armed = false;
|
||||
}
|
||||
|
||||
// sanity check parameters
|
||||
sanity_check_parameters();
|
||||
|
||||
// clear and set limits based on input (limit flags may be set again by output_regular or output_skid_steering methods)
|
||||
set_limits_from_input(armed, _steering, _throttle);
|
||||
|
||||
@ -333,6 +330,14 @@ bool AP_MotorsUGV::pre_arm_check(bool report) const
|
||||
return true;
|
||||
}
|
||||
|
||||
// sanity check parameters
|
||||
void AP_MotorsUGV::sanity_check_parameters()
|
||||
{
|
||||
_throttle_min = constrain_int16(_throttle_min, 0, 20);
|
||||
_throttle_max = constrain_int16(_throttle_max, 30, 100);
|
||||
_vector_throttle_base = constrain_float(_vector_throttle_base, 0.0f, 100.0f);
|
||||
}
|
||||
|
||||
// setup pwm output type
|
||||
void AP_MotorsUGV::setup_pwm_type()
|
||||
{
|
||||
|
@ -74,6 +74,9 @@ public:
|
||||
|
||||
protected:
|
||||
|
||||
// sanity check parameters
|
||||
void sanity_check_parameters();
|
||||
|
||||
// setup pwm output type
|
||||
void setup_pwm_type();
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user