mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
Rover: solve servo reverse in brushed configuration
This commit is contained in:
parent
b0c7766197
commit
46e6057493
@ -300,18 +300,25 @@ void AP_MotorsUGV::output_throttle(SRV_Channel::Aux_servo_function_t function, f
|
|||||||
|
|
||||||
// set relay if necessary
|
// set relay if necessary
|
||||||
if (_pwm_type == PWM_TYPE_BRUSHED) {
|
if (_pwm_type == PWM_TYPE_BRUSHED) {
|
||||||
|
// find the output channel, if not found return
|
||||||
|
const SRV_Channel *out_chan = SRV_Channels::get_channel_for(function);
|
||||||
|
if (out_chan == nullptr) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
bool relay_high = out_chan->get_reversed() ? !is_negative(throttle) : is_negative(throttle);
|
||||||
switch (function) {
|
switch (function) {
|
||||||
case SRV_Channel::k_throttle:
|
case SRV_Channel::k_throttle:
|
||||||
case SRV_Channel::k_throttleLeft:
|
case SRV_Channel::k_throttleLeft:
|
||||||
_relayEvents.do_set_relay(0, is_negative(throttle));
|
_relayEvents.do_set_relay(0, relay_high);
|
||||||
break;
|
break;
|
||||||
case SRV_Channel::k_throttleRight:
|
case SRV_Channel::k_throttleRight:
|
||||||
_relayEvents.do_set_relay(1, is_negative(throttle));
|
_relayEvents.do_set_relay(1, relay_high);
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
// do nothing
|
// do nothing
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
// brushed-with-relay motors should receive positive values
|
||||||
throttle = fabsf(throttle);
|
throttle = fabsf(throttle);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user