|
|
|
@ -327,29 +327,37 @@ static void NOINLINE send_hwstatus(mavlink_channel_t chan)
@@ -327,29 +327,37 @@ static void NOINLINE send_hwstatus(mavlink_channel_t chan)
|
|
|
|
|
|
|
|
|
|
static void NOINLINE send_rangefinder(mavlink_channel_t chan) |
|
|
|
|
{ |
|
|
|
|
if (!sonar.healthy()) { |
|
|
|
|
if (!sonar.has_data(0) && !sonar.has_data(1)) { |
|
|
|
|
// no sonar to report |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
float distance_cm = 0.0f; |
|
|
|
|
float voltage = 0.0f; |
|
|
|
|
|
|
|
|
|
/* |
|
|
|
|
report smaller distance of two sonars if more than one enabled |
|
|
|
|
report smaller distance of two sonars |
|
|
|
|
*/ |
|
|
|
|
float distance_cm, voltage; |
|
|
|
|
if (!sonar.healthy(1)) { |
|
|
|
|
distance_cm = sonar.distance_cm(0); |
|
|
|
|
voltage = sonar.voltage_mv(0) * 0.001f; |
|
|
|
|
if (sonar.has_data(0) && sonar.has_data(1)) { |
|
|
|
|
if (sonar.distance_cm(0) <= sonar.distance_cm(1)) { |
|
|
|
|
distance_cm = sonar.distance_cm(0); |
|
|
|
|
voltage = sonar.voltage_mv(0); |
|
|
|
|
} else { |
|
|
|
|
distance_cm = sonar.distance_cm(1); |
|
|
|
|
voltage = sonar.voltage_mv(1); |
|
|
|
|
} |
|
|
|
|
} else { |
|
|
|
|
float dist1 = sonar.distance_cm(0); |
|
|
|
|
float dist2 = sonar.distance_cm(1); |
|
|
|
|
if (dist1 <= dist2) { |
|
|
|
|
distance_cm = dist1; |
|
|
|
|
// only sonar 0 or sonar 1 has data |
|
|
|
|
if (sonar.has_data(0)) { |
|
|
|
|
distance_cm = sonar.distance_cm(0); |
|
|
|
|
voltage = sonar.voltage_mv(0) * 0.001f; |
|
|
|
|
} else { |
|
|
|
|
distance_cm = dist2; |
|
|
|
|
} |
|
|
|
|
if (sonar.has_data(1)) { |
|
|
|
|
distance_cm = sonar.distance_cm(1); |
|
|
|
|
voltage = sonar.voltage_mv(1) * 0.001f; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
mavlink_msg_rangefinder_send( |
|
|
|
|
chan, |
|
|
|
|
distance_cm * 0.01f, |
|
|
|
|