Browse Source

MAVLink app: Use proper C99 NaN define

sbg
Lorenz Meier 9 years ago
parent
commit
165f75589b
  1. 14
      src/modules/mavlink/mavlink_messages.cpp

14
src/modules/mavlink/mavlink_messages.cpp

@ -2890,19 +2890,17 @@ protected: @@ -2890,19 +2890,17 @@ protected:
msg.time_usec = hrt_absolute_time();
static constexpr float NAN_VAL = 0.0f / 0.0f;
msg.altitude_monotonic = (_sensor_time > 0) ? sensor.baro_alt_meter[0] : NAN_VAL;
msg.altitude_amsl = (_global_pos_time > 0) ? global_pos.alt : NAN_VAL;
msg.altitude_local = (_local_pos_time > 0) ? -local_pos.z : NAN_VAL;
msg.altitude_relative = (_home_time > 0) ? (global_pos.alt - home.alt) : NAN_VAL;
msg.altitude_monotonic = (_sensor_time > 0) ? sensor.baro_alt_meter[0] : NAN;
msg.altitude_amsl = (_global_pos_time > 0) ? global_pos.alt : NAN;
msg.altitude_local = (_local_pos_time > 0) ? -local_pos.z : NAN;
msg.altitude_relative = (_home_time > 0) ? (global_pos.alt - home.alt) : NAN;
if (global_pos.terrain_alt_valid) {
msg.altitude_terrain = global_pos.terrain_alt;
msg.bottom_clearance = global_pos.alt - global_pos.terrain_alt;
} else {
msg.altitude_terrain = NAN_VAL;
msg.bottom_clearance = NAN_VAL;
msg.altitude_terrain = NAN;
msg.bottom_clearance = NAN;
}
_mavlink->send_message(MAVLINK_MSG_ID_ALTITUDE, &msg);

Loading…
Cancel
Save