mirror of https://github.com/ArduPilot/ardupilot
AP_RPM: fixed SITL RPM backend for new motor mask
This commit is contained in:
parent
e4a747c247
commit
220fd7caa1
|
@ -34,10 +34,17 @@ void AP_RPM_SITL::update(void)
|
||||||
if (sitl == nullptr) {
|
if (sitl == nullptr) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
if (instance == 0) {
|
const uint32_t motor_mask = sitl->state.motor_mask;
|
||||||
state.rate_rpm = sitl->state.rpm[0];
|
uint8_t count = 0;
|
||||||
} else {
|
// find the motor with the corresponding index
|
||||||
state.rate_rpm = sitl->state.rpm[1];
|
for (uint8_t i=0; i<32; i++) {
|
||||||
|
if (motor_mask & (1U<<i)) {
|
||||||
|
if (count == instance) {
|
||||||
|
state.rate_rpm = sitl->state.rpm[i];
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
count++;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
state.rate_rpm *= ap_rpm._params[state.instance].scaling;
|
state.rate_rpm *= ap_rpm._params[state.instance].scaling;
|
||||||
state.signal_quality = 0.5f;
|
state.signal_quality = 0.5f;
|
||||||
|
|
Loading…
Reference in New Issue