GCS_MAVLink: allow more libraries to compile with no HAL_GCS_ENABLED
This commit is contained in:
parent
642d15582a
commit
ed5da4ead2
@ -1,3 +1,7 @@
|
||||
#include "GCS_config.h"
|
||||
|
||||
#if HAL_GCS_ENABLED
|
||||
|
||||
#include "GCS.h"
|
||||
|
||||
#include <AC_Fence/AC_Fence.h>
|
||||
@ -375,3 +379,5 @@ bool GCS_MAVLINK::check_payload_size(uint16_t max_payload_len)
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif // HAL_GCS_ENABLED
|
||||
|
@ -1329,6 +1329,8 @@ void can_printf(const char *fmt, ...);
|
||||
#define GCS_SEND_TEXT(severity, format, args...) (void)severity; can_printf(format, ##args)
|
||||
#endif
|
||||
|
||||
#define GCS_SEND_MESSAGE(msg) gcs().send_message(msg)
|
||||
|
||||
#elif defined(HAL_BUILD_AP_PERIPH) && !defined(STM32F1)
|
||||
|
||||
// map send text to can_printf() on larger AP_Periph boards
|
||||
@ -1336,10 +1338,12 @@ extern "C" {
|
||||
void can_printf(const char *fmt, ...);
|
||||
}
|
||||
#define GCS_SEND_TEXT(severity, format, args...) can_printf(format, ##args)
|
||||
#define GCS_SEND_MESSAGE(msg)
|
||||
|
||||
#else // HAL_GCS_ENABLED
|
||||
// empty send text when we have no GCS
|
||||
#define GCS_SEND_TEXT(severity, format, args...)
|
||||
#define GCS_SEND_MESSAGE(msg)
|
||||
|
||||
#endif // HAL_GCS_ENABLED
|
||||
|
||||
|
@ -14,6 +14,11 @@
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "GCS_config.h"
|
||||
|
||||
#if HAL_GCS_ENABLED
|
||||
|
||||
#include "GCS.h"
|
||||
|
||||
#include <AC_Fence/AC_Fence.h>
|
||||
@ -6709,3 +6714,5 @@ MAV_RESULT GCS_MAVLINK::handle_control_high_latency(const mavlink_command_long_t
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
#endif // HAL_HIGH_LATENCY2_ENABLED
|
||||
|
||||
#endif // HAL_GCS_ENABLED
|
||||
|
@ -1,4 +1,9 @@
|
||||
#include "GCS_config.h"
|
||||
|
||||
#if HAL_GCS_ENABLED
|
||||
|
||||
#include "GCS_Dummy.h"
|
||||
|
||||
#include <stdio.h>
|
||||
|
||||
#define FORCE_VERSION_H_INCLUDE
|
||||
@ -22,3 +27,5 @@ void GCS_Dummy::send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_l
|
||||
::printf("\n");
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif // HAL_GCS_ENABLED
|
||||
|
@ -1,3 +1,7 @@
|
||||
#include "GCS_config.h"
|
||||
|
||||
#if HAL_GCS_ENABLED
|
||||
|
||||
#include "GCS.h"
|
||||
#include <AP_Common/AP_FWVersion.h>
|
||||
|
||||
@ -72,3 +76,5 @@ private:
|
||||
MAV_TYPE frame_type() const override { return MAV_TYPE_FIXED_WING; }
|
||||
uint32_t custom_mode() const override { return 3; } // magic number
|
||||
};
|
||||
|
||||
#endif // HAL_GCS_ENABLED
|
||||
|
@ -14,6 +14,11 @@
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "GCS_config.h"
|
||||
|
||||
#if HAL_GCS_ENABLED
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#include "GCS.h"
|
||||
@ -696,3 +701,5 @@ void GCS_MAVLINK::ftp_list_dir(struct pending_ftp &request, struct pending_ftp &
|
||||
|
||||
AP::FS().closedir(dir);
|
||||
}
|
||||
|
||||
#endif // HAL_GCS_ENABLED
|
||||
|
@ -1,6 +1,7 @@
|
||||
#include "GCS_config.h"
|
||||
#include <AC_Fence/AC_Fence_config.h>
|
||||
|
||||
#if AP_FENCE_ENABLED
|
||||
#if HAL_GCS_ENABLED && AP_FENCE_ENABLED
|
||||
|
||||
#include "GCS.h"
|
||||
|
||||
@ -103,4 +104,4 @@ void GCS_MAVLINK::send_fence_status() const
|
||||
breach_mitigation);
|
||||
}
|
||||
|
||||
#endif
|
||||
#endif // HAL_GCS_ENABLED && AP_FENCE_ENABLED
|
||||
|
@ -19,6 +19,11 @@
|
||||
This provides some support code and variables for MAVLink enabled sketches
|
||||
|
||||
*/
|
||||
|
||||
#include "GCS_config.h"
|
||||
|
||||
#if HAL_GCS_ENABLED
|
||||
|
||||
#include "GCS.h"
|
||||
#include "GCS_MAVLink.h"
|
||||
|
||||
@ -173,3 +178,5 @@ HAL_Semaphore &comm_chan_lock(mavlink_channel_t chan)
|
||||
{
|
||||
return chan_locks[uint8_t(chan)];
|
||||
}
|
||||
|
||||
#endif // HAL_GCS_ENABLED
|
||||
|
@ -14,6 +14,11 @@
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "GCS_config.h"
|
||||
|
||||
#if HAL_GCS_ENABLED
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#include "GCS.h"
|
||||
@ -461,3 +466,5 @@ void GCS_MAVLINK::handle_common_param_message(const mavlink_message_t &msg)
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
#endif // HAL_GCS_ENABLED
|
||||
|
@ -15,6 +15,10 @@
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "GCS_config.h"
|
||||
|
||||
#if HAL_GCS_ENABLED
|
||||
|
||||
#include "GCS.h"
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
@ -259,3 +263,4 @@ uint8_t GCS_MAVLINK::packet_overhead_chan(mavlink_channel_t chan)
|
||||
return MAVLINK_NUM_NON_PAYLOAD_BYTES + reserved_space;
|
||||
}
|
||||
|
||||
#endif // HAL_GCS_ENABLED
|
||||
|
@ -16,6 +16,10 @@
|
||||
/// @file MAVLink_routing.h
|
||||
/// @brief handle routing of MAVLink packets by sysid/componentid
|
||||
|
||||
#include "GCS_config.h"
|
||||
|
||||
#if HAL_GCS_ENABLED
|
||||
|
||||
#include <stdio.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
@ -405,3 +409,4 @@ void MAVLink_routing::get_targets(const mavlink_message_t &msg, int16_t &sysid,
|
||||
}
|
||||
}
|
||||
|
||||
#endif // HAL_GCS_ENABLED
|
||||
|
@ -1,3 +1,7 @@
|
||||
#include "GCS_config.h"
|
||||
|
||||
#if HAL_GCS_ENABLED
|
||||
|
||||
#include "MissionItemProtocol.h"
|
||||
|
||||
#include "GCS.h"
|
||||
@ -380,3 +384,5 @@ void MissionItemProtocol::update()
|
||||
link->send_message(next_item_ap_message_id());
|
||||
}
|
||||
}
|
||||
|
||||
#endif // HAL_GCS_ENABLED
|
||||
|
@ -1,11 +1,14 @@
|
||||
#include "GCS_config.h"
|
||||
#include <AC_Fence/AC_Fence_config.h>
|
||||
|
||||
#if HAL_GCS_ENABLED && AP_FENCE_ENABLED
|
||||
|
||||
#include "MissionItemProtocol_Fence.h"
|
||||
|
||||
#include <AC_Fence/AC_Fence.h>
|
||||
#include <AP_InternalError/AP_InternalError.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
||||
#if AP_FENCE_ENABLED
|
||||
|
||||
/*
|
||||
public function to format mission item as mavlink_mission_item_int_t
|
||||
*/
|
||||
@ -244,4 +247,4 @@ MAV_MISSION_RESULT MissionItemProtocol_Fence::allocate_update_resources()
|
||||
return MAV_MISSION_ACCEPTED;
|
||||
}
|
||||
|
||||
#endif // AP_FENCE_ENABLED
|
||||
#endif // HAL_GCS_ENABLED && AP_FENCE_ENABLED
|
||||
|
@ -16,14 +16,17 @@
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "GCS_config.h"
|
||||
#include <AP_Rally/AP_Rally_config.h>
|
||||
|
||||
#if HAL_GCS_ENABLED && HAL_RALLY_ENABLED
|
||||
|
||||
#include "MissionItemProtocol_Rally.h"
|
||||
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
#include <AP_Rally/AP_Rally.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
||||
#if HAL_RALLY_ENABLED
|
||||
|
||||
MAV_MISSION_RESULT MissionItemProtocol_Rally::append_item(const mavlink_mission_item_int_t &cmd)
|
||||
{
|
||||
RallyLocation rallyloc;
|
||||
@ -139,4 +142,4 @@ void MissionItemProtocol_Rally::truncate(const mavlink_mission_count_t &packet)
|
||||
rally.truncate(packet.count);
|
||||
}
|
||||
|
||||
#endif // HAL_RALLY_ENABLED
|
||||
#endif // HAL_GCS_ENABLED && HAL_RALLY_ENABLED
|
||||
|
@ -16,6 +16,11 @@
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "GCS_config.h"
|
||||
#include <AP_Mission/AP_Mission_config.h>
|
||||
|
||||
#if HAL_GCS_ENABLED && AP_MISSION_ENABLED
|
||||
|
||||
#include "MissionItemProtocol_Waypoints.h"
|
||||
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
@ -139,3 +144,5 @@ void MissionItemProtocol_Waypoints::truncate(const mavlink_mission_count_t &pack
|
||||
// new mission arriving, truncate mission to be the same length
|
||||
mission.truncate(packet.count);
|
||||
}
|
||||
|
||||
#endif // HAL_GCS_ENABLED && AP_MISSION_ENABLED
|
||||
|
Loading…
Reference in New Issue
Block a user