mirror of https://github.com/ArduPilot/ardupilot
AP_MotorsUGV: Fix Riscv64 compiler error issue #25974
This commit is contained in:
parent
bddb9aaac7
commit
0151dabf52
|
@ -925,7 +925,7 @@ void AP_MotorsUGV::output_omni(bool armed, float steering, float throttle, float
|
||||||
const float scaled_steering = steering / 4500.0f;
|
const float scaled_steering = steering / 4500.0f;
|
||||||
const float scaled_lateral = lateral * 0.01f;
|
const float scaled_lateral = lateral * 0.01f;
|
||||||
|
|
||||||
float thr_str_ltr_out[AP_MOTORS_NUM_MOTORS_MAX];
|
float thr_str_ltr_out[_motors_num];
|
||||||
float thr_str_ltr_max = 1;
|
float thr_str_ltr_max = 1;
|
||||||
for (uint8_t i=0; i<_motors_num; i++) {
|
for (uint8_t i=0; i<_motors_num; i++) {
|
||||||
// Each motor outputs throttle + steering + lateral
|
// Each motor outputs throttle + steering + lateral
|
||||||
|
|
Loading…
Reference in New Issue