RC_Channel: added set_esc_scaling() to SRV_Channels
This commit is contained in:
parent
fcd98e2c44
commit
2ec439d7e3
@ -22,6 +22,8 @@
|
||||
#include "SRV_Channel.h"
|
||||
#include "RC_Channel.h"
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
const AP_Param::GroupInfo SRV_Channels::var_info[] = {
|
||||
// @Param: RNG_ENABLE
|
||||
// @DisplayName: Enable servo output ranges
|
||||
@ -248,3 +250,13 @@ void SRV_Channels::set_trim(void)
|
||||
servo_trim[i].set_and_save(new_trim);
|
||||
}
|
||||
}
|
||||
|
||||
void SRV_Channels::set_esc_scaling(uint8_t chnum)
|
||||
{
|
||||
if (!enable || chnum >= NUM_SERVO_RANGE_CHANNELS) {
|
||||
const RC_Channel *ch = RC_Channel::rc_channel(chnum);
|
||||
hal.rcout->set_esc_scaling(ch->get_radio_min(), ch->get_radio_max());
|
||||
} else {
|
||||
hal.rcout->set_esc_scaling(servo_min[chnum], servo_max[chnum]);
|
||||
}
|
||||
}
|
||||
|
@ -36,6 +36,9 @@ public:
|
||||
|
||||
// set and save trim values from current RC input trim
|
||||
void set_trim(void);
|
||||
|
||||
// setup output ESC scaling for a channel
|
||||
void set_esc_scaling(uint8_t chnum);
|
||||
|
||||
private:
|
||||
AP_Int8 enable;
|
||||
|
Loading…
Reference in New Issue
Block a user