mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Periph: fixed ESC output
should be range, not angle
This commit is contained in:
parent
dda69bfcb0
commit
50d5fced54
@ -45,7 +45,7 @@ void AP_Periph_FW::rcout_init()
|
||||
|
||||
uint16_t esc_mask = 0;
|
||||
for (uint8_t i=0; i<SERVO_OUT_MOTOR_MAX; i++) {
|
||||
SRV_Channels::set_angle(SRV_Channels::get_motor_function(i), UAVCAN_ESC_MAX_VALUE);
|
||||
SRV_Channels::set_range(SRV_Channels::get_motor_function(i), UAVCAN_ESC_MAX_VALUE);
|
||||
uint8_t chan;
|
||||
if (SRV_Channels::find_channel(SRV_Channels::get_motor_function(i), chan)) {
|
||||
esc_mask |= 1U << chan;
|
||||
@ -77,7 +77,8 @@ void AP_Periph_FW::rcout_esc(int16_t *rc, uint8_t num_channels)
|
||||
|
||||
const uint8_t channel_count = MIN(num_channels, SERVO_OUT_MOTOR_MAX);
|
||||
for (uint8_t i=0; i<channel_count; i++) {
|
||||
SRV_Channels::set_output_scaled(SRV_Channels::get_motor_function(i), rc[i]);
|
||||
// we don't support motor reversal yet on ESCs in AP_Periph
|
||||
SRV_Channels::set_output_scaled(SRV_Channels::get_motor_function(i), MAX(0,rc[i]));
|
||||
}
|
||||
|
||||
rcout_has_new_data_to_update = true;
|
||||
|
Loading…
Reference in New Issue
Block a user