mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
RC_Channel: added static functions to simplify operations on all channels
this avoids vehicle code having to loop over all channels for common operations
This commit is contained in:
parent
21c205a57e
commit
11f196318e
@ -160,6 +160,19 @@ RC_Channel::set_pwm(int16_t pwm)
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
call read() and set_pwm() on all channels
|
||||
*/
|
||||
void
|
||||
RC_Channel::set_pwm_all(void)
|
||||
{
|
||||
for (uint8_t i=0; i<RC_MAX_CHANNELS; i++) {
|
||||
if (rc_ch[i] != NULL) {
|
||||
rc_ch[i]->set_pwm(rc_ch[i]->read());
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// read input from APM_RC - create a control_in value, but use a
|
||||
// zero value for the dead zone. When done this way the control_in
|
||||
// value can be used as servo_out to give the same output as input
|
||||
@ -388,6 +401,15 @@ void RC_Channel::output_trim() const
|
||||
hal.rcout->write(_ch_out, radio_trim);
|
||||
}
|
||||
|
||||
void RC_Channel::output_trim_all()
|
||||
{
|
||||
for (uint8_t i=0; i<RC_MAX_CHANNELS; i++) {
|
||||
if (rc_ch[i] != NULL) {
|
||||
rc_ch[i]->output_trim();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
RC_Channel::input()
|
||||
{
|
||||
|
@ -53,6 +53,7 @@ public:
|
||||
|
||||
// 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);
|
||||
|
||||
// pwm is stored here
|
||||
@ -98,6 +99,7 @@ public:
|
||||
|
||||
void output() const;
|
||||
void output_trim() const;
|
||||
static void output_trim_all();
|
||||
uint16_t read() const;
|
||||
void input();
|
||||
void enable_out();
|
||||
|
@ -24,7 +24,7 @@ uint32_t RC_Channel_aux::_function_mask;
|
||||
|
||||
/// map a function to a servo channel and output it
|
||||
void
|
||||
RC_Channel_aux::output_ch(unsigned char ch_nr)
|
||||
RC_Channel_aux::output_ch(void)
|
||||
{
|
||||
// take care of two corner cases
|
||||
switch(function)
|
||||
@ -35,7 +35,20 @@ RC_Channel_aux::output_ch(unsigned char ch_nr)
|
||||
radio_out = radio_in;
|
||||
break;
|
||||
}
|
||||
hal.rcout->write(ch_nr, radio_out);
|
||||
hal.rcout->write(_ch_out, radio_out);
|
||||
}
|
||||
|
||||
/*
|
||||
call output_ch() on all auxillary channels
|
||||
*/
|
||||
void
|
||||
RC_Channel_aux::output_ch_all(void)
|
||||
{
|
||||
for (uint8_t i = 0; i < RC_AUX_MAX_CHANNELS; i++) {
|
||||
if (_aux_channels[i]) {
|
||||
_aux_channels[i]->output_ch();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -71,7 +71,11 @@ public:
|
||||
|
||||
AP_Int8 function; ///< see Aux_servo_function_t enum
|
||||
|
||||
void output_ch(unsigned char ch_nr);
|
||||
// output one auxillary channel
|
||||
void output_ch(void);
|
||||
|
||||
// output all auxillary channels
|
||||
static void output_ch_all(void);
|
||||
|
||||
// set radio_out for a function channel
|
||||
static void set_radio(Aux_servo_function_t function, int16_t value);
|
||||
|
Loading…
Reference in New Issue
Block a user