Browse Source

SITL: correct max_distance in simulated mavlink rangefinder

zr-v5.1
Peter Barker 4 years ago committed by Peter Barker
parent
commit
81ab322daa
  1. 2
      libraries/SITL/SIM_RF_MAVLink.cpp

2
libraries/SITL/SIM_RF_MAVLink.cpp

@ -42,7 +42,7 @@ uint32_t RF_MAVLink::packet_for_alt(uint16_t alt_cm, uint8_t *buffer, uint8_t bu @@ -42,7 +42,7 @@ uint32_t RF_MAVLink::packet_for_alt(uint16_t alt_cm, uint8_t *buffer, uint8_t bu
const mavlink_distance_sensor_t distance_sensor{
time_boot_ms: AP_HAL::millis(),
min_distance: 10, // cm
max_distance: 10, // cm
max_distance: 1000, // cm
current_distance: alt_cm,
type: 0,
id: 72, // ID

Loading…
Cancel
Save