mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
SRV_Channel: use enum-class for SRV_CHANNEL_LIMIT_TRIM and friends
This commit is contained in:
parent
3521117817
commit
f1c2e55f68
@ -172,16 +172,16 @@ float SRV_Channel::get_output_norm(void)
|
|||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint16_t SRV_Channel::get_limit_pwm(LimitValue limit) const
|
uint16_t SRV_Channel::get_limit_pwm(Limit limit) const
|
||||||
{
|
{
|
||||||
switch (limit) {
|
switch (limit) {
|
||||||
case SRV_CHANNEL_LIMIT_TRIM:
|
case Limit::TRIM:
|
||||||
return servo_trim;
|
return servo_trim;
|
||||||
case SRV_CHANNEL_LIMIT_MIN:
|
case Limit::MIN:
|
||||||
return reversed?servo_max:servo_min;
|
return reversed?servo_max:servo_min;
|
||||||
case SRV_CHANNEL_LIMIT_MAX:
|
case Limit::MAX:
|
||||||
return reversed?servo_min:servo_max;
|
return reversed?servo_min:servo_max;
|
||||||
case SRV_CHANNEL_LIMIT_ZERO_PWM:
|
case Limit::ZERO_PWM:
|
||||||
default:
|
default:
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
@ -155,11 +155,11 @@ public:
|
|||||||
} Aux_servo_function_t;
|
} Aux_servo_function_t;
|
||||||
|
|
||||||
// used to get min/max/trim limit value based on reverse
|
// used to get min/max/trim limit value based on reverse
|
||||||
enum LimitValue {
|
enum class Limit {
|
||||||
SRV_CHANNEL_LIMIT_TRIM,
|
TRIM,
|
||||||
SRV_CHANNEL_LIMIT_MIN,
|
MIN,
|
||||||
SRV_CHANNEL_LIMIT_MAX,
|
MAX,
|
||||||
SRV_CHANNEL_LIMIT_ZERO_PWM
|
ZERO_PWM
|
||||||
};
|
};
|
||||||
|
|
||||||
// set the output value as a pwm value
|
// set the output value as a pwm value
|
||||||
@ -269,7 +269,7 @@ private:
|
|||||||
void aux_servo_function_setup(void);
|
void aux_servo_function_setup(void);
|
||||||
|
|
||||||
// return PWM for a given limit value
|
// return PWM for a given limit value
|
||||||
uint16_t get_limit_pwm(LimitValue limit) const;
|
uint16_t get_limit_pwm(Limit limit) const;
|
||||||
|
|
||||||
// get normalised output from -1 to 1
|
// get normalised output from -1 to 1
|
||||||
float get_output_norm(void);
|
float get_output_norm(void);
|
||||||
@ -385,13 +385,13 @@ public:
|
|||||||
static void set_failsafe_pwm(SRV_Channel::Aux_servo_function_t function, uint16_t pwm);
|
static void set_failsafe_pwm(SRV_Channel::Aux_servo_function_t function, uint16_t pwm);
|
||||||
|
|
||||||
// setup failsafe for an auxiliary channel function
|
// setup failsafe for an auxiliary channel function
|
||||||
static void set_failsafe_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::LimitValue limit);
|
static void set_failsafe_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::Limit limit);
|
||||||
|
|
||||||
// setup safety for an auxiliary channel function (used when disarmed)
|
// setup safety for an auxiliary channel function (used when disarmed)
|
||||||
static void set_safety_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::LimitValue limit);
|
static void set_safety_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::Limit limit);
|
||||||
|
|
||||||
// set servo to a LimitValue
|
// set servo to a Limit
|
||||||
static void set_output_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::LimitValue limit);
|
static void set_output_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::Limit limit);
|
||||||
|
|
||||||
// return true if a function is assigned to a channel
|
// return true if a function is assigned to a channel
|
||||||
static bool function_assigned(SRV_Channel::Aux_servo_function_t function);
|
static bool function_assigned(SRV_Channel::Aux_servo_function_t function);
|
||||||
|
@ -317,7 +317,7 @@ SRV_Channels::copy_radio_in_out_mask(uint16_t mask)
|
|||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
setup failsafe value for an auxiliary function type to a LimitValue
|
setup failsafe value for an auxiliary function type to a Limit
|
||||||
*/
|
*/
|
||||||
void
|
void
|
||||||
SRV_Channels::set_failsafe_pwm(SRV_Channel::Aux_servo_function_t function, uint16_t pwm)
|
SRV_Channels::set_failsafe_pwm(SRV_Channel::Aux_servo_function_t function, uint16_t pwm)
|
||||||
@ -334,10 +334,10 @@ SRV_Channels::set_failsafe_pwm(SRV_Channel::Aux_servo_function_t function, uint1
|
|||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
setup failsafe value for an auxiliary function type to a LimitValue
|
setup failsafe value for an auxiliary function type to a Limit
|
||||||
*/
|
*/
|
||||||
void
|
void
|
||||||
SRV_Channels::set_failsafe_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::LimitValue limit)
|
SRV_Channels::set_failsafe_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::Limit limit)
|
||||||
{
|
{
|
||||||
if (!function_assigned(function)) {
|
if (!function_assigned(function)) {
|
||||||
return;
|
return;
|
||||||
@ -352,10 +352,10 @@ SRV_Channels::set_failsafe_limit(SRV_Channel::Aux_servo_function_t function, SRV
|
|||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
setup safety value for an auxiliary function type to a LimitValue
|
setup safety value for an auxiliary function type to a Limit
|
||||||
*/
|
*/
|
||||||
void
|
void
|
||||||
SRV_Channels::set_safety_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::LimitValue limit)
|
SRV_Channels::set_safety_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::Limit limit)
|
||||||
{
|
{
|
||||||
if (!function_assigned(function)) {
|
if (!function_assigned(function)) {
|
||||||
return;
|
return;
|
||||||
@ -370,10 +370,10 @@ SRV_Channels::set_safety_limit(SRV_Channel::Aux_servo_function_t function, SRV_C
|
|||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
set radio output value for an auxiliary function type to a LimitValue
|
set radio output value for an auxiliary function type to a Limit
|
||||||
*/
|
*/
|
||||||
void
|
void
|
||||||
SRV_Channels::set_output_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::LimitValue limit)
|
SRV_Channels::set_output_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::Limit limit)
|
||||||
{
|
{
|
||||||
if (!function_assigned(function)) {
|
if (!function_assigned(function)) {
|
||||||
return;
|
return;
|
||||||
|
Loading…
Reference in New Issue
Block a user