Browse Source

GCS_MAVLink: omit code that breaks build for herepro

gps-1.3.1
Siddharth Purohit 4 years ago committed by Andrew Tridgell
parent
commit
9a19a86a81
  1. 4
      libraries/GCS_MAVLink/GCS_Common.cpp
  2. 3
      libraries/GCS_MAVLink/GCS_Rally.cpp

4
libraries/GCS_MAVLink/GCS_Common.cpp

@ -3470,7 +3470,9 @@ void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg) @@ -3470,7 +3470,9 @@ void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg)
case MAVLINK_MSG_ID_RALLY_POINT:
case MAVLINK_MSG_ID_RALLY_FETCH_POINT:
#if HAL_RALLY_ENABLED
handle_common_rally_message(msg);
#endif
break;
case MAVLINK_MSG_ID_REQUEST_DATA_STREAM:
@ -5375,9 +5377,11 @@ uint64_t GCS_MAVLINK::capabilities() const @@ -5375,9 +5377,11 @@ uint64_t GCS_MAVLINK::capabilities() const
ret |= MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION;
}
#if HAL_RALLY_ENABLED
if (AP::rally()) {
ret |= MAV_PROTOCOL_CAPABILITY_MISSION_RALLY;
}
#endif
if (AP::fence()) {
ret |= MAV_PROTOCOL_CAPABILITY_MISSION_FENCE;

3
libraries/GCS_MAVLink/GCS_Rally.cpp

@ -21,6 +21,8 @@ @@ -21,6 +21,8 @@
#include <AP_Rally/AP_Rally.h>
#include <AP_Logger/AP_Logger.h>
#if HAL_RALLY_ENABLED
void GCS_MAVLINK::handle_rally_point(const mavlink_message_t &msg) const
{
AP_Rally *r = AP::rally();
@ -103,3 +105,4 @@ void GCS_MAVLINK::handle_common_rally_message(const mavlink_message_t &msg) @@ -103,3 +105,4 @@ void GCS_MAVLINK::handle_common_rally_message(const mavlink_message_t &msg)
break;
}
}
#endif //#if HAL_RALLY_ENABLED

Loading…
Cancel
Save