|
|
|
@ -219,7 +219,7 @@ NOINLINE void Copter::send_extended_status1(mavlink_channel_t chan)
@@ -219,7 +219,7 @@ NOINLINE void Copter::send_extended_status1(mavlink_channel_t chan)
|
|
|
|
|
battery_current = battery.current_amps() * 100; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
#if AP_TERRAIN_AVAILABLE |
|
|
|
|
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN |
|
|
|
|
switch (terrain.status()) { |
|
|
|
|
case AP_Terrain::TerrainStatusDisabled: |
|
|
|
|
break; |
|
|
|
@ -642,7 +642,7 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id)
@@ -642,7 +642,7 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id)
|
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case MSG_TERRAIN: |
|
|
|
|
#if AP_TERRAIN_AVAILABLE |
|
|
|
|
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN |
|
|
|
|
CHECK_PAYLOAD_SIZE(TERRAIN_REQUEST); |
|
|
|
|
copter.terrain.send_request(chan); |
|
|
|
|
#endif |
|
|
|
@ -961,7 +961,7 @@ GCS_MAVLINK::data_stream_send(void)
@@ -961,7 +961,7 @@ GCS_MAVLINK::data_stream_send(void)
|
|
|
|
|
send_message(MSG_HWSTATUS); |
|
|
|
|
send_message(MSG_SYSTEM_TIME); |
|
|
|
|
send_message(MSG_RANGEFINDER); |
|
|
|
|
#if AP_TERRAIN_AVAILABLE |
|
|
|
|
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN |
|
|
|
|
send_message(MSG_TERRAIN); |
|
|
|
|
#endif |
|
|
|
|
send_message(MSG_BATTERY2); |
|
|
|
@ -1828,7 +1828,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
@@ -1828,7 +1828,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|
|
|
|
|
|
|
|
|
case MAVLINK_MSG_ID_TERRAIN_DATA: |
|
|
|
|
case MAVLINK_MSG_ID_TERRAIN_CHECK: |
|
|
|
|
#if AP_TERRAIN_AVAILABLE |
|
|
|
|
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN |
|
|
|
|
copter.terrain.handle_data(chan, msg); |
|
|
|
|
#endif |
|
|
|
|
break; |
|
|
|
|