mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Tools: move from HAL_NO_GCS to HAL_GCS_ENABLED
This commit is contained in:
parent
9f6b9c7519
commit
76e2db952b
@ -92,7 +92,7 @@ void AP_Periph_FW::init()
|
||||
|
||||
stm32_watchdog_pat();
|
||||
|
||||
#ifdef HAL_NO_GCS
|
||||
#if !HAL_GCS_ENABLED
|
||||
hal.serial(0)->begin(AP_SERIALMANAGER_CONSOLE_BAUD, 32, 32);
|
||||
#endif
|
||||
hal.serial(3)->begin(115200, 128, 256);
|
||||
@ -103,13 +103,13 @@ void AP_Periph_FW::init()
|
||||
|
||||
can_start();
|
||||
|
||||
#ifndef HAL_NO_GCS
|
||||
#if HAL_GCS_ENABLED
|
||||
stm32_watchdog_pat();
|
||||
gcs().init();
|
||||
#endif
|
||||
serial_manager.init();
|
||||
|
||||
#ifndef HAL_NO_GCS
|
||||
#if HAL_GCS_ENABLED
|
||||
gcs().setup_console();
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "AP_Periph GCS Initialised!");
|
||||
#endif
|
||||
@ -347,7 +347,7 @@ void AP_Periph_FW::update()
|
||||
rcout_init_1Hz();
|
||||
#endif
|
||||
|
||||
#ifndef HAL_NO_GCS
|
||||
#if HAL_GCS_ENABLED
|
||||
gcs().send_message(MSG_HEARTBEAT);
|
||||
gcs().send_message(MSG_SYS_STATUS);
|
||||
#endif
|
||||
@ -384,7 +384,7 @@ void AP_Periph_FW::update()
|
||||
#ifdef HAL_PERIPH_ENABLE_NOTIFY
|
||||
notify.update();
|
||||
#endif
|
||||
#ifndef HAL_NO_GCS
|
||||
#if HAL_GCS_ENABLED
|
||||
gcs().update_receive();
|
||||
gcs().update_send();
|
||||
#endif
|
||||
|
@ -23,7 +23,7 @@
|
||||
#include <AP_HAL_SITL/CANSocketIface.h>
|
||||
#endif
|
||||
|
||||
#ifndef HAL_NO_GCS
|
||||
#if HAL_GCS_ENABLED
|
||||
#include "GCS_MAVLink.h"
|
||||
#endif
|
||||
|
||||
@ -219,7 +219,7 @@ public:
|
||||
AP_Logger logger;
|
||||
#endif
|
||||
|
||||
#ifndef HAL_NO_GCS
|
||||
#if HAL_GCS_ENABLED
|
||||
GCS_Periph _gcs;
|
||||
#endif
|
||||
// setup the var_info table
|
||||
|
@ -16,7 +16,7 @@
|
||||
#include "GCS_MAVLink.h"
|
||||
#include "AP_Periph.h"
|
||||
|
||||
#ifndef HAL_NO_GCS
|
||||
#if HAL_GCS_ENABLED
|
||||
|
||||
static const ap_message STREAM_RAW_SENSORS_msgs[] = {
|
||||
MSG_RAW_IMU
|
||||
@ -75,4 +75,4 @@ MAV_RESULT GCS_MAVLINK_Periph::handle_preflight_reboot(const mavlink_command_lon
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif // #ifndef HAL_NO_GCS
|
||||
#endif // #if HAL_GCS_ENABLED
|
||||
|
@ -15,7 +15,7 @@
|
||||
#pragma once
|
||||
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
#ifndef HAL_NO_GCS
|
||||
#if HAL_GCS_ENABLED
|
||||
|
||||
/*
|
||||
* GCS backend used for many examples and tools
|
||||
@ -89,4 +89,4 @@ private:
|
||||
MAV_TYPE frame_type() const override { return MAV_TYPE_GENERIC; }
|
||||
uint32_t custom_mode() const override { return 3; } // magic number
|
||||
};
|
||||
#endif // HAL_NO_GCS
|
||||
#endif // HAL_GCS_ENABLED
|
||||
|
@ -334,7 +334,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
|
||||
GSCALAR(log_bitmask, "LOG_BITMASK", 4),
|
||||
#endif
|
||||
|
||||
#ifndef HAL_NO_GCS
|
||||
#if HAL_GCS_ENABLED
|
||||
// @Param: SYSID_THISMAV
|
||||
// @DisplayName: MAVLink system ID of this vehicle
|
||||
// @Description: Allows setting an individual system id for this vehicle to distinguish it from others on the same network
|
||||
|
@ -114,7 +114,7 @@ public:
|
||||
AP_Int32 log_bitmask;
|
||||
#endif
|
||||
|
||||
#ifndef HAL_NO_GCS
|
||||
#if HAL_GCS_ENABLED
|
||||
AP_Int16 sysid_this_mav;
|
||||
#endif
|
||||
|
||||
|
@ -70,7 +70,7 @@ class Board:
|
||||
|
||||
# allow GCS disable for AP_DAL example
|
||||
if cfg.options.no_gcs:
|
||||
env.CXXFLAGS += ['-DHAL_NO_GCS=1']
|
||||
env.CXXFLAGS += ['-DHAL_GCS_ENABLED=0']
|
||||
|
||||
# setup for supporting onvif cam control
|
||||
if cfg.options.enable_onvif:
|
||||
@ -626,7 +626,7 @@ class sitl_periph_gps(sitl):
|
||||
HAL_CAN_DEFAULT_NODE_ID = 0,
|
||||
HAL_RAM_RESERVE_START = 0,
|
||||
APJ_BOARD_ID = 100,
|
||||
HAL_NO_GCS = 1,
|
||||
HAL_GCS_ENABLED = 0,
|
||||
HAL_LOGGING_ENABLED = 0,
|
||||
HAL_LOGGING_MAVLINK_ENABLED = 0,
|
||||
HAL_MISSION_ENABLED = 0,
|
||||
|
Loading…
Reference in New Issue
Block a user