diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index a6231ed988..148757e0b4 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -522,12 +522,14 @@ protected: void handle_set_mode(const mavlink_message_t &msg); void handle_command_int(const mavlink_message_t &msg); - MAV_RESULT handle_command_do_set_home(const mavlink_command_int_t &packet); virtual MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg); MAV_RESULT handle_command_int_external_position_estimate(const mavlink_command_int_t &packet); +#if AP_HOME_ENABLED + MAV_RESULT handle_command_do_set_home(const mavlink_command_int_t &packet); bool set_home_to_current_location(bool lock); bool set_home(const Location& loc, bool lock); +#endif #if AP_ARMING_ENABLED virtual MAV_RESULT handle_command_component_arm_disarm(const mavlink_command_int_t &packet); diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 3b81e551ad..207143d08a 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -5066,6 +5066,7 @@ void GCS_MAVLINK::handle_landing_target(const mavlink_message_t &msg) } +#if AP_HOME_ENABLED bool GCS_MAVLINK::set_home_to_current_location(bool _lock) { #if AP_VEHICLE_ENABLED @@ -5082,7 +5083,9 @@ bool GCS_MAVLINK::set_home(const Location& loc, bool _lock) { return false; #endif } +#endif // AP_HOME_ENABLED +#if AP_HOME_ENABLED MAV_RESULT GCS_MAVLINK::handle_command_do_set_home(const mavlink_command_int_t &packet) { if (is_equal(packet.param1, 1.0f) || (packet.x == 0 && packet.y == 0)) { @@ -5105,6 +5108,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_set_home(const mavlink_command_int_t & } return MAV_RESULT_ACCEPTED; } +#endif // AP_HOME_ENABLED #if AP_AHRS_POSITION_RESET_ENABLED MAV_RESULT GCS_MAVLINK::handle_command_int_external_position_estimate(const mavlink_command_int_t &packet) @@ -5309,8 +5313,11 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p send_banner(); return MAV_RESULT_ACCEPTED; +#if AP_HOME_ENABLED case MAV_CMD_DO_SET_HOME: return handle_command_do_set_home(packet); +#endif + #if AP_AHRS_POSITION_RESET_ENABLED case MAV_CMD_EXTERNAL_POSITION_ESTIMATE: return handle_command_int_external_position_estimate(packet);