Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Remove GCS includes from headers #22185

Merged
merged 15 commits into from Nov 16, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
1 change: 1 addition & 0 deletions libraries/AC_AutoTune/AC_AutoTune_Heli.h
Expand Up @@ -20,6 +20,7 @@

#include "AC_AutoTune.h"
#include <AP_Math/chirp.h>
#include <GCS_MAVLink/GCS.h>

#include <AP_Scheduler/AP_Scheduler.h>

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_CANManager/AP_CANManager.cpp
Expand Up @@ -30,7 +30,7 @@
#include <AP_PiccoloCAN/AP_PiccoloCAN.h>
#include <AP_EFI/AP_EFI_NWPMU.h>
#include "AP_CANTester.h"
#include <GCS_MAVLink/GCS_MAVLink.h>
#include <GCS_MAVLink/GCS.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
#include <AP_HAL_Linux/CANSocketIface.h>
#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
Expand Down
5 changes: 4 additions & 1 deletion libraries/AP_CANManager/AP_CANManager.h
Expand Up @@ -24,7 +24,10 @@
#include <AP_Param/AP_Param.h>
#include "AP_SLCANIface.h"
#include "AP_CANDriver.h"
#include <GCS_MAVLink/GCS.h>
#include <GCS_MAVLink/GCS_config.h>
#if HAL_GCS_ENABLED
#include <GCS_MAVLink/GCS_MAVLink.h>
#endif

class AP_CANManager
{
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_CANManager/AP_CANTester_KDECAN.cpp
Expand Up @@ -25,6 +25,7 @@
#include <AP_Math/AP_Math.h>
#include <AP_HAL/utility/sparse-endian.h>
#include <AP_Vehicle/AP_Vehicle_Type.h>
#include <GCS_MAVLink/GCS.h>

#define debug_can(level_debug, fmt, args...) do { AP::can().log_text(level_debug, "TestKDECAN", fmt, ##args); } while (0)
extern const AP_HAL::HAL& hal;
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_CANManager/AP_SLCANIface.cpp
Expand Up @@ -28,6 +28,7 @@
#include <AP_SerialManager/AP_SerialManager.h>
#include <stdio.h>
#include <AP_Vehicle/AP_Vehicle_Type.h>
#include <GCS_MAVLink/GCS.h>

#define LOG_TAG "SLCAN"

Expand Down
5 changes: 3 additions & 2 deletions libraries/AP_CheckFirmware/AP_CheckFirmware.h
Expand Up @@ -6,8 +6,9 @@
#include <AP_HAL/AP_HAL_Boards.h>
#include <AP_OpenDroneID/AP_OpenDroneID_config.h>
#include <AP_HAL/AP_HAL.h>
#ifndef HAL_BOOTLOADER_BUILD
#include <GCS_MAVLink/GCS.h>
#include <GCS_MAVLink/GCS_config.h>
#if HAL_GCS_ENABLED
#include <GCS_MAVLink/GCS_MAVLink.h>
#endif

#ifndef AP_CHECK_FIRMWARE_ENABLED
Expand Down
Expand Up @@ -7,7 +7,11 @@
#if AP_CHECK_FIRMWARE_ENABLED && AP_SIGNED_FIRMWARE && !defined(HAL_BOOTLOADER_BUILD)

#include "monocypher.h"
#include <AP_Math/crc.h>
#include <AP_Math/AP_Math.h>

#if HAL_GCS_ENABLED
#include <GCS_MAVLink/GCS.h>
#endif

extern const AP_HAL::HAL &hal;

Expand Down
1 change: 1 addition & 0 deletions libraries/AP_EFI/AP_EFI_NWPMU.cpp
Expand Up @@ -18,6 +18,7 @@
#include <AP_Common/AP_Common.h>
#include <AP_HAL/utility/sparse-endian.h>
#include <AP_Math/AP_Math.h>
#include <GCS_MAVLink/GCS.h>

#include "AP_EFI_NWPMU.h"

Expand Down
3 changes: 2 additions & 1 deletion libraries/AP_Frsky_Telem/AP_Frsky_MAVliteMsgHandler.cpp
Expand Up @@ -2,6 +2,7 @@

#include <AC_Fence/AC_Fence.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include <GCS_MAVLink/GCS.h>

extern const AP_HAL::HAL& hal;

Expand Down Expand Up @@ -291,4 +292,4 @@ bool AP_Frsky_MAVliteMsgHandler::send_message(AP_Frsky_MAVlite_Message &txmsg)
{
return _send_fn(txmsg);
}
#endif
#endif
1 change: 1 addition & 0 deletions libraries/AP_Generator/AP_Generator_RichenPower.cpp
Expand Up @@ -20,6 +20,7 @@
#include <AP_Logger/AP_Logger.h>
#include <AP_SerialManager/AP_SerialManager.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include <GCS_MAVLink/GCS.h>

#include <AP_HAL/utility/sparse-endian.h>

Expand Down
3 changes: 0 additions & 3 deletions libraries/AP_HAL_ChibiOS/Util.h
Expand Up @@ -20,9 +20,6 @@
#include "AP_HAL_ChibiOS_Namespace.h"
#include "AP_HAL_ChibiOS.h"
#include <ch.h>
#if !defined(HAL_BOOTLOADER_BUILD)
#include <GCS_MAVLink/GCS.h>
#endif

class ExpandingString;

Expand Down
5 changes: 5 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py
Expand Up @@ -2960,6 +2960,11 @@ def add_bootloader_defaults(f):
#define HAL_GYROFFT_ENABLED 0
#endif

// bootloaders don't talk to the GCS:
#ifndef HAL_GCS_ENABLED
#define HAL_GCS_ENABLED 0
#endif

#define HAL_MAX_CAN_PROTOCOL_DRIVERS 0
''')

Expand Down
1 change: 1 addition & 0 deletions libraries/AP_Motors/AP_MotorsMatrix_6DoF_Scripting.cpp
Expand Up @@ -19,6 +19,7 @@
#include "AP_MotorsMatrix_6DoF_Scripting.h"
#include <GCS_MAVLink/GCS.h>
#include <SRV_Channel/SRV_Channel.h>
#include <GCS_MAVLink/GCS.h>

extern const AP_HAL::HAL& hal;

Expand Down
1 change: 1 addition & 0 deletions libraries/AP_OSD/AP_OSD.cpp
Expand Up @@ -36,6 +36,7 @@
#include <AP_Notify/AP_Notify.h>
#include <AP_Terrain/AP_Terrain.h>
#include <AP_RSSI/AP_RSSI.h>
#include <GCS_MAVLink/GCS.h>

// macro for easy use of var_info2
#define AP_SUBGROUPINFO2(element, name, idx, thisclazz, elclazz) { AP_PARAM_GROUP, idx, name, AP_VAROFFSET(thisclazz, element), { group_info : elclazz::var_info2 }, AP_PARAM_FLAG_NESTED_OFFSET }
Expand Down
12 changes: 8 additions & 4 deletions libraries/AP_OSD/AP_OSD.h
Expand Up @@ -22,11 +22,13 @@
#include <AP_Math/AP_Math.h>
#include <AP_ESC_Telem/AP_ESC_Telem.h>
#include <RC_Channel/RC_Channel.h>
#include <GCS_MAVLink/GCS.h>
#include <GCS_MAVLink/GCS_config.h>
#include <AP_OLC/AP_OLC.h>
#include <AP_MSP/msp.h>
#include <AP_Baro/AP_Baro.h>
#if HAL_GCS_ENABLED
#include <GCS_MAVLink/GCS_MAVLink.h>
#endif
#include <AC_Fence/AC_Fence_config.h>

#ifndef OSD_ENABLED
Expand Down Expand Up @@ -349,8 +351,10 @@ class AP_OSD_ParamSetting : public AP_OSD_Setting

static const ParamMetadata _param_metadata[];

#if HAL_GCS_ENABLED
AP_OSD_ParamSetting(uint8_t param_number, bool enabled, uint8_t x, uint8_t y, int16_t key, int8_t idx, int32_t group,
int8_t type = OSD_PARAM_NONE, float min = 0.0f, float max = 1.0f, float incr = 0.001f);
#endif
AP_OSD_ParamSetting(uint8_t param_number);
AP_OSD_ParamSetting(const Initializer& initializer);

Expand Down Expand Up @@ -408,8 +412,8 @@ class AP_OSD_ParamScreen : public AP_OSD_AbstractScreen
void draw(void) override;
#endif
#if HAL_GCS_ENABLED
void handle_write_msg(const mavlink_osd_param_config_t& packet, const GCS_MAVLINK& link);
void handle_read_msg(const mavlink_osd_param_show_config_t& packet, const GCS_MAVLINK& link);
void handle_write_msg(const mavlink_osd_param_config_t& packet, const class GCS_MAVLINK& link);
void handle_read_msg(const mavlink_osd_param_show_config_t& packet, const class GCS_MAVLINK& link);
#endif
// get a setting and associated metadata
AP_OSD_ParamSetting* get_setting(uint8_t param_idx);
Expand Down Expand Up @@ -593,7 +597,7 @@ class AP_OSD
#endif
// handle OSD parameter configuration
#if HAL_GCS_ENABLED
void handle_msg(const mavlink_message_t &msg, const GCS_MAVLINK& link);
void handle_msg(const mavlink_message_t &msg, const class GCS_MAVLINK& link);
#endif

// allow threads to lock against OSD update
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_OSD/AP_OSD_Backend.cpp
Expand Up @@ -16,6 +16,7 @@

#include <AP_OSD/AP_OSD_Backend.h>
#include <AP_HAL/Util.h>
#include <GCS_MAVLink/GCS.h>
#include <ctype.h>

extern const AP_HAL::HAL& hal;
Expand Down
4 changes: 3 additions & 1 deletion libraries/AP_OSD/AP_OSD_MSP_DisplayPort.cpp
Expand Up @@ -22,6 +22,8 @@

#if HAL_WITH_MSP_DISPLAYPORT

#include <GCS_MAVLink/GCS.h>

static const struct AP_Param::defaults_table_struct defaults_table[] = {
/*
{ "PARAM_NAME", value_float }
Expand Down Expand Up @@ -131,4 +133,4 @@ AP_OSD_Backend *AP_OSD_MSP_DisplayPort::probe(AP_OSD &osd)
}
return backend;
}
#endif
#endif
1 change: 1 addition & 0 deletions libraries/AP_OSD/AP_OSD_ParamScreen.cpp
Expand Up @@ -30,6 +30,7 @@
#include <AP_Vehicle/AP_Vehicle_Type.h>
#include <AP_Arming/AP_Arming.h>
#include <AP_Vehicle/AP_Vehicle_Type.h>
#include <GCS_MAVLink/GCS.h>

extern const AP_HAL::HAL& hal;

Expand Down
1 change: 1 addition & 0 deletions libraries/AP_OSD/AP_OSD_ParamSetting.cpp
Expand Up @@ -23,6 +23,7 @@

#include "AP_OSD.h"
#include <AP_Vehicle/AP_Vehicle_Type.h>
#include <GCS_MAVLink/GCS.h>
#include <SRV_Channel/SRV_Channel.h>
#include <ctype.h>

Expand Down
2 changes: 0 additions & 2 deletions libraries/AP_OpenDroneID/AP_OpenDroneID.cpp
Expand Up @@ -33,8 +33,6 @@

#include <AP_HAL/AP_HAL.h>
#include <GCS_MAVLink/GCS.h>
#include <GCS_MAVLink/GCS_MAVLink.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_GPS/AP_GPS.h>
#include <AP_Baro/AP_Baro.h>
#include <AP_AHRS/AP_AHRS.h>
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_OpenDroneID/AP_OpenDroneID_DroneCAN.cpp
Expand Up @@ -30,7 +30,7 @@
#include <dronecan/remoteid/System.hpp>
#include <dronecan/remoteid/ArmStatus.hpp>

#include <GCS_MAVLink/GCS_MAVLink.h>
#include <GCS_MAVLink/GCS.h>

static uavcan::Publisher<dronecan::remoteid::Location>* dc_location[HAL_MAX_CAN_PROTOCOL_DRIVERS];
static uavcan::Publisher<dronecan::remoteid::BasicID>* dc_basic_id[HAL_MAX_CAN_PROTOCOL_DRIVERS];
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.cpp
Expand Up @@ -5,6 +5,7 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_CANManager/AP_CANManager.h>
#include <AP_UAVCAN/AP_UAVCAN.h>
#include <GCS_MAVLink/GCS.h>

#include <uavcan/equipment/range_sensor/Measurement.hpp>

Expand Down
1 change: 1 addition & 0 deletions libraries/AP_Vehicle/AP_Vehicle.cpp
Expand Up @@ -12,6 +12,7 @@
#include <AP_Motors/AP_Motors.h>
#include <AR_Motors/AP_MotorsUGV.h>
#include <AP_CheckFirmware/AP_CheckFirmware.h>
#include <GCS_MAVLink/GCS.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
#include <AP_HAL_ChibiOS/sdcard.h>
#include <AP_HAL_ChibiOS/hwdef/common/stm32_util.h>
Expand Down