mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
RC_Channel: added support for LimitValue settings
this allows you to set a channel failsafe or radio_out to a limit value
This commit is contained in:
parent
a1edf347bf
commit
0d4985079e
@ -127,10 +127,12 @@ RC_Channel::set_reverse(bool reverse)
|
||||
}
|
||||
|
||||
bool
|
||||
RC_Channel::get_reverse(void)
|
||||
RC_Channel::get_reverse(void) const
|
||||
{
|
||||
if (_reverse==-1) return 1;
|
||||
else return 0;
|
||||
if (_reverse == -1) {
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
void
|
||||
@ -453,3 +455,18 @@ RC_Channel *RC_Channel::rc_channel(uint8_t i)
|
||||
}
|
||||
return rc_ch[i];
|
||||
}
|
||||
|
||||
// return a limit PWM value
|
||||
uint16_t RC_Channel::get_limit_pwm(LimitValue limit) const
|
||||
{
|
||||
switch (limit) {
|
||||
case RC_CHANNEL_LIMIT_TRIM:
|
||||
return radio_trim;
|
||||
case RC_CHANNEL_LIMIT_MAX:
|
||||
return get_reverse() ? radio_min : radio_max;
|
||||
case RC_CHANNEL_LIMIT_MIN:
|
||||
return get_reverse() ? radio_max : radio_min;
|
||||
}
|
||||
// invalid limit value, return trim
|
||||
return radio_trim;
|
||||
}
|
||||
|
@ -33,6 +33,13 @@ public:
|
||||
}
|
||||
}
|
||||
|
||||
// used to get min/max/trim limit value based on _reverse
|
||||
enum LimitValue {
|
||||
RC_CHANNEL_LIMIT_TRIM,
|
||||
RC_CHANNEL_LIMIT_MIN,
|
||||
RC_CHANNEL_LIMIT_MAX
|
||||
};
|
||||
|
||||
// setup min and max radio values in CLI
|
||||
void update_min_max();
|
||||
void zero_min_max();
|
||||
@ -48,14 +55,20 @@ public:
|
||||
void set_range_out(int16_t low, int16_t high);
|
||||
void set_angle(int16_t angle);
|
||||
void set_reverse(bool reverse);
|
||||
bool get_reverse(void);
|
||||
bool get_reverse(void) const;
|
||||
void set_default_dead_zone(int16_t dzone);
|
||||
|
||||
// get the channel number
|
||||
uint8_t get_ch_out(void) const { return _ch_out; };
|
||||
|
||||
// read input from APM_RC - create a control_in value
|
||||
void set_pwm(int16_t pwm);
|
||||
static void set_pwm_all(void);
|
||||
void set_pwm_no_deadzone(int16_t pwm);
|
||||
|
||||
// return a limit PWM value
|
||||
uint16_t get_limit_pwm(LimitValue limit) const;
|
||||
|
||||
// pwm is stored here
|
||||
int16_t radio_in;
|
||||
|
||||
|
@ -260,6 +260,42 @@ RC_Channel_aux::set_servo_out(RC_Channel_aux::Aux_servo_function_t function, int
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
setup failsafe value for an auxiliary function type to a LimitValue
|
||||
*/
|
||||
void
|
||||
RC_Channel_aux::set_servo_failsafe(RC_Channel_aux::Aux_servo_function_t function, RC_Channel::LimitValue limit)
|
||||
{
|
||||
if (!function_assigned(function)) {
|
||||
return;
|
||||
}
|
||||
for (uint8_t i = 0; i < RC_AUX_MAX_CHANNELS; i++) {
|
||||
const RC_Channel_aux *ch = _aux_channels[i];
|
||||
if (ch && ch->function.get() == function) {
|
||||
uint16_t pwm = ch->get_limit_pwm(limit);
|
||||
hal.rcout->set_failsafe_pwm(1U<<ch->get_ch_out(), pwm);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
set radio output value for an auxiliary function type to a LimitValue
|
||||
*/
|
||||
void
|
||||
RC_Channel_aux::set_servo_limit(RC_Channel_aux::Aux_servo_function_t function, RC_Channel::LimitValue limit)
|
||||
{
|
||||
if (!function_assigned(function)) {
|
||||
return;
|
||||
}
|
||||
for (uint8_t i = 0; i < RC_AUX_MAX_CHANNELS; i++) {
|
||||
RC_Channel_aux *ch = _aux_channels[i];
|
||||
if (ch && ch->function.get() == function) {
|
||||
uint16_t pwm = ch->get_limit_pwm(limit);
|
||||
ch->radio_out = pwm;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
return true if a particular function is assigned to at least one RC channel
|
||||
*/
|
||||
|
@ -99,6 +99,12 @@ public:
|
||||
// set servo_out
|
||||
static void set_servo_out(Aux_servo_function_t function, int16_t value);
|
||||
|
||||
// setup failsafe for an auxillary channel function
|
||||
static void set_servo_failsafe(Aux_servo_function_t function, RC_Channel::LimitValue limit);
|
||||
|
||||
// set servo to a LimitValue
|
||||
static void set_servo_limit(Aux_servo_function_t function, RC_Channel::LimitValue limit);
|
||||
|
||||
// return true if a function is assigned to a channel
|
||||
static bool function_assigned(Aux_servo_function_t function);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user