Browse Source

Rover: send_wheel_encoder_distance uses definition for array size

master
Randy Mackay 6 years ago
parent
commit
ce3de6b047
  1. 2
      APMrover2/GCS_Mavlink.cpp

2
APMrover2/GCS_Mavlink.cpp

@ -291,7 +291,7 @@ void Rover::send_wheel_encoder_distance(mavlink_channel_t chan)
{ {
// send wheel encoder data using wheel_distance message // send wheel encoder data using wheel_distance message
if (g2.wheel_encoder.num_sensors() > 0) { if (g2.wheel_encoder.num_sensors() > 0) {
double distances[16] {}; double distances[MAVLINK_MSG_WHEEL_DISTANCE_FIELD_DISTANCE_LEN] {};
for (uint8_t i = 0; i < g2.wheel_encoder.num_sensors(); i++) { for (uint8_t i = 0; i < g2.wheel_encoder.num_sensors(); i++) {
distances[i] = wheel_encoder_last_distance_m[i]; distances[i] = wheel_encoder_last_distance_m[i];
} }

Loading…
Cancel
Save