SITL: State constrain rover motor input between 1000 and 2000

This commit is contained in:
Pierre Kancir 2017-03-05 14:20:20 +01:00 committed by Grant Morphett
parent 7f861aafd0
commit f0f7ca2386

View File

@ -379,12 +379,18 @@ void SITL_State::_simulator_servos(SITL::Aircraft::sitl_input &input)
engine_fail = 0; engine_fail = 0;
} }
// apply engine multiplier to motor defined by the SIM_ENGINE_FAIL parameter // apply engine multiplier to motor defined by the SIM_ENGINE_FAIL parameter
input.servos[engine_fail] = ((input.servos[engine_fail]-1000) * engine_mul) + 1000; if (_vehicle != APMrover2) {
input.servos[engine_fail] = ((input.servos[engine_fail]-1000) * engine_mul) + 1000;
} else {
input.servos[engine_fail] = static_cast<uint16_t>(((input.servos[engine_fail] - 1500) * engine_mul) + 1500);
}
if (_vehicle == ArduPlane) { if (_vehicle == ArduPlane) {
motors_on = ((input.servos[2]-1000)/1000.0f) > 0; motors_on = ((input.servos[2] - 1000) / 1000.0f) > 0;
} else if (_vehicle == APMrover2) { } else if (_vehicle == APMrover2) {
motors_on = ((input.servos[2]-1500)/500.0f) != 0; input.servos[2] = static_cast<uint16_t>(constrain_int16(input.servos[2], 1000, 2000));
input.servos[0] = static_cast<uint16_t>(constrain_int16(input.servos[0], 1000, 2000));
motors_on = ((input.servos[2] - 1500) / 500.0f) != 0;
} else { } else {
motors_on = false; motors_on = false;
// run checks on each motor // run checks on each motor