diff --git a/libraries/AP_AccelCal/AP_AccelCal.cpp b/libraries/AP_AccelCal/AP_AccelCal.cpp index d4fa4cba030b4b..5c2fc07e00fa17 100644 --- a/libraries/AP_AccelCal/AP_AccelCal.cpp +++ b/libraries/AP_AccelCal/AP_AccelCal.cpp @@ -362,7 +362,7 @@ bool AP_AccelCal::client_active(uint8_t client_num) return (bool)_clients[client_num]->_acal_get_calibrator(0); } -#if HAL_GCS_ENABLED +#if HAL_GCS_ENABLED || defined(GCS_MAVLINK) void AP_AccelCal::handle_command_ack(const mavlink_command_ack_t &packet) { if (!_waiting_for_mavlink_ack) { diff --git a/libraries/AP_AccelCal/AP_AccelCal.h b/libraries/AP_AccelCal/AP_AccelCal.h index de6168ce62e042..cecac1029bd8a2 100644 --- a/libraries/AP_AccelCal/AP_AccelCal.h +++ b/libraries/AP_AccelCal/AP_AccelCal.h @@ -12,7 +12,9 @@ #endif #endif +#include #include + #include "AccelCalibrator.h" #define AP_ACCELCAL_MAX_NUM_CLIENTS 4 @@ -45,7 +47,7 @@ class AP_AccelCal { // interface to the clients for registration static void register_client(AP_AccelCal_Client* client); -#if HAL_GCS_ENABLED +#if HAL_GCS_ENABLED || defined(GCS_MAVLINK) void handle_command_ack(const mavlink_command_ack_t &packet); #endif diff --git a/libraries/AP_Compass/AP_Compass.cpp b/libraries/AP_Compass/AP_Compass.cpp index 039ade2d5a70e2..a47b65ef0f164b 100644 --- a/libraries/AP_Compass/AP_Compass.cpp +++ b/libraries/AP_Compass/AP_Compass.cpp @@ -71,7 +71,7 @@ extern const AP_HAL::HAL& hal; const AP_Param::GroupInfo Compass::var_info[] = { // index 0 was used for the old orientation matrix -#ifndef HAL_BUILD_AP_PERIPH +#if !defined(HAL_BUILD_AP_PERIPH) && !COMPASS_CAL_ENABLED // @Param: OFS_X // @DisplayName: Compass offsets in milligauss on the X axis // @Description: Offset to be added to the compass x-axis values to compensate for metal in the frame diff --git a/libraries/AP_Compass/AP_Compass.h b/libraries/AP_Compass/AP_Compass.h index f08a63e81c96b6..21f26bc40fe94f 100644 --- a/libraries/AP_Compass/AP_Compass.h +++ b/libraries/AP_Compass/AP_Compass.h @@ -10,6 +10,7 @@ #include #include #include +#include #include #include diff --git a/libraries/AP_Compass/AP_Compass_Calibration.cpp b/libraries/AP_Compass/AP_Compass_Calibration.cpp index 809ca03c0e931d..500dc1e6213017 100644 --- a/libraries/AP_Compass/AP_Compass_Calibration.cpp +++ b/libraries/AP_Compass/AP_Compass_Calibration.cpp @@ -240,7 +240,7 @@ bool Compass::_accept_calibration_mask(uint8_t mask) return success; } -#if HAL_GCS_ENABLED +#if HAL_GCS_ENABLED || defined(GCS_MAVLINK) bool Compass::send_mag_cal_progress(const GCS_MAVLINK& link) { const mavlink_channel_t chan = link.get_chan(); diff --git a/libraries/AP_DAL/AP_DAL.cpp b/libraries/AP_DAL/AP_DAL.cpp index 986fe66bcf0251..abe872a63a4cd5 100644 --- a/libraries/AP_DAL/AP_DAL.cpp +++ b/libraries/AP_DAL/AP_DAL.cpp @@ -76,7 +76,9 @@ void AP_DAL::start_frame(AP_DAL::FrameType frametype) #if AP_OPTICALFLOW_ENABLED _RFRN.opticalflow_enabled = AP::opticalflow() && AP::opticalflow()->enabled(); #endif +#if AP_WHEELENCODER_ENABLED _RFRN.wheelencoder_enabled = AP::wheelencoder() && (AP::wheelencoder()->num_sensors() > 0); +#endif _RFRN.ekf_type = ahrs.get_ekf_type(); WRITE_REPLAY_BLOCK_IFCHANGED(RFRN, _RFRN, old); diff --git a/libraries/AP_HAL/AP_HAL_Boards.h b/libraries/AP_HAL/AP_HAL_Boards.h index 5ba862d7ef177f..cef4e94d5440be 100644 --- a/libraries/AP_HAL/AP_HAL_Boards.h +++ b/libraries/AP_HAL/AP_HAL_Boards.h @@ -373,3 +373,7 @@ #endif #define HAL_GPIO_LED_OFF (!HAL_GPIO_LED_ON) + +#ifndef HAL_MAVLINK_ENABLED +#define HAL_MAVLINK_ENABLED 0 +#endif diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index b2a76a1f266b28..b5f63843233ec0 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -2482,7 +2482,7 @@ bool AP_InertialSensor::get_primary_accel_cal_sample_avg(uint8_t sample_num, Vec return true; } -#if HAL_GCS_ENABLED +#if HAL_GCS_ENABLED || defined(GCS_MAVLINK) bool AP_InertialSensor::calibrate_gyros() { init_gyro(); diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.h b/libraries/AP_InertialSensor/AP_InertialSensor.h index 9bce50d4ac57dc..e1ec785e4423b3 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor.h @@ -289,7 +289,7 @@ class AP_InertialSensor : AP_AccelCal_Client void acal_update(); #endif -#if HAL_GCS_ENABLED +#if HAL_GCS_ENABLED || defined(GCS_MAVLINK) bool calibrate_gyros(); MAV_RESULT calibrate_trim(); diff --git a/libraries/AP_WheelEncoder/AP_WheelEncoder.cpp b/libraries/AP_WheelEncoder/AP_WheelEncoder.cpp index 610a7cd8e2bd7e..167e70d5bce661 100644 --- a/libraries/AP_WheelEncoder/AP_WheelEncoder.cpp +++ b/libraries/AP_WheelEncoder/AP_WheelEncoder.cpp @@ -14,6 +14,7 @@ */ #include "AP_WheelEncoder.h" +#if AP_WHEELENCODER_ENABLED #include "WheelEncoder_Quadrature.h" #include "WheelEncoder_SITL_Quadrature.h" #include @@ -363,3 +364,4 @@ AP_WheelEncoder *wheelencoder() } } +#endif // AP_WHEELENCODER_ENABLED diff --git a/libraries/AP_WheelEncoder/AP_WheelEncoder.h b/libraries/AP_WheelEncoder/AP_WheelEncoder.h index 4c92c911479d75..fc0b21874e4cb5 100644 --- a/libraries/AP_WheelEncoder/AP_WheelEncoder.h +++ b/libraries/AP_WheelEncoder/AP_WheelEncoder.h @@ -14,6 +14,9 @@ */ #pragma once +#include "AP_WheelEncoder_config.h" + +#if AP_WHEELENCODER_ENABLED #include #include #include @@ -133,3 +136,4 @@ class AP_WheelEncoder namespace AP { AP_WheelEncoder *wheelencoder(); } +#endif // AP_WHEELENCODER_ENABLED diff --git a/libraries/AP_WheelEncoder/AP_WheelRateControl.cpp b/libraries/AP_WheelEncoder/AP_WheelRateControl.cpp index 97c9a1e19c5e16..ee9f626a565209 100644 --- a/libraries/AP_WheelEncoder/AP_WheelRateControl.cpp +++ b/libraries/AP_WheelEncoder/AP_WheelRateControl.cpp @@ -1,4 +1,5 @@ #include +#if AP_WHEELENCODER_ENABLED extern const AP_HAL::HAL& hal; @@ -281,3 +282,5 @@ void AP_WheelRateControl::set_notch_sample_rate(float sample_rate) _rate_pid1.set_notch_sample_rate(sample_rate); #endif } + +#endif // AP_WHEELENCODER_ENABLED diff --git a/libraries/AP_WheelEncoder/AP_WheelRateControl.h b/libraries/AP_WheelEncoder/AP_WheelRateControl.h index f62d981bfb6863..a099fb1a83cda9 100644 --- a/libraries/AP_WheelEncoder/AP_WheelRateControl.h +++ b/libraries/AP_WheelEncoder/AP_WheelRateControl.h @@ -15,6 +15,10 @@ #pragma once +#include "AP_WheelEncoder_config.h" + +#if AP_WHEELENCODER_ENABLED + #include #include #include @@ -74,3 +78,4 @@ class AP_WheelRateControl { const AP_WheelEncoder& _wheel_encoder; // pointer to accompanying wheel encoder uint32_t _last_update_ms; // system time of last call to get_rate_controlled_throttle }; +#endif // AP_WHEELENCODER_ENABLED diff --git a/libraries/AP_WheelEncoder/WheelEncoder_Backend.cpp b/libraries/AP_WheelEncoder/WheelEncoder_Backend.cpp index 4742dcfa1f2199..4906426c9b3204 100644 --- a/libraries/AP_WheelEncoder/WheelEncoder_Backend.cpp +++ b/libraries/AP_WheelEncoder/WheelEncoder_Backend.cpp @@ -13,8 +13,10 @@ along with this program. If not, see . */ -#include #include "AP_WheelEncoder.h" + +#if AP_WHEELENCODER_ENABLED +#include #include "WheelEncoder_Backend.h" // base class constructor. @@ -56,3 +58,4 @@ void AP_WheelEncoder_Backend::copy_state_to_frontend(int32_t distance_count, uin _state.error_count = error_count; _state.last_reading_ms = last_reading_ms; } +#endif // AP_WHEELENCODER_ENABLED diff --git a/libraries/AP_WheelEncoder/WheelEncoder_Backend.h b/libraries/AP_WheelEncoder/WheelEncoder_Backend.h index 382c911ff76f94..757c2e4a3cfc54 100644 --- a/libraries/AP_WheelEncoder/WheelEncoder_Backend.h +++ b/libraries/AP_WheelEncoder/WheelEncoder_Backend.h @@ -14,9 +14,11 @@ */ #pragma once -#include #include "AP_WheelEncoder.h" +#if AP_WHEELENCODER_ENABLED +#include + class AP_WheelEncoder_Backend { public: @@ -42,3 +44,4 @@ class AP_WheelEncoder_Backend AP_WheelEncoder &_frontend; AP_WheelEncoder::WheelEncoder_State &_state; }; +#endif // AP_WHEELENCODER_ENABLED diff --git a/libraries/AP_WheelEncoder/WheelEncoder_Quadrature.cpp b/libraries/AP_WheelEncoder/WheelEncoder_Quadrature.cpp index cb82bef21bca85..a078c59d1941d9 100644 --- a/libraries/AP_WheelEncoder/WheelEncoder_Quadrature.cpp +++ b/libraries/AP_WheelEncoder/WheelEncoder_Quadrature.cpp @@ -13,10 +13,10 @@ along with this program. If not, see . */ -#include - #include "WheelEncoder_Quadrature.h" +#if AP_WHEELENCODER_ENABLED +#include #include extern const AP_HAL::HAL& hal; @@ -140,3 +140,4 @@ void AP_WheelEncoder_Quadrature::irq_handler(uint8_t pin, // record update time irq_state.last_reading_ms = timestamp * 1e-3f; } +#endif // AP_WHEELENCODER_ENABLED diff --git a/libraries/AP_WheelEncoder/WheelEncoder_Quadrature.h b/libraries/AP_WheelEncoder/WheelEncoder_Quadrature.h index 9693ba9a124f6c..c2725b8905b937 100644 --- a/libraries/AP_WheelEncoder/WheelEncoder_Quadrature.h +++ b/libraries/AP_WheelEncoder/WheelEncoder_Quadrature.h @@ -15,6 +15,8 @@ #pragma once #include "AP_WheelEncoder.h" + +#if AP_WHEELENCODER_ENABLED #include "WheelEncoder_Backend.h" #include #include @@ -57,3 +59,4 @@ class AP_WheelEncoder_Quadrature : public AP_WheelEncoder_Backend uint8_t last_pin_a_value; uint8_t last_pin_b_value; }; +#endif // AP_WHEELENCODER_ENABLED diff --git a/libraries/AP_WheelEncoder/WheelEncoder_SITL_Quadrature.cpp b/libraries/AP_WheelEncoder/WheelEncoder_SITL_Quadrature.cpp index 9fc073d545d0d5..dafc2ca491d549 100644 --- a/libraries/AP_WheelEncoder/WheelEncoder_SITL_Quadrature.cpp +++ b/libraries/AP_WheelEncoder/WheelEncoder_SITL_Quadrature.cpp @@ -18,6 +18,7 @@ #if CONFIG_HAL_BOARD == HAL_BOARD_SITL #include "WheelEncoder_SITL_Quadrature.h" +#if AP_WHEELENCODER_ENABLED #include extern const AP_HAL::HAL& hal; @@ -86,4 +87,5 @@ void AP_WheelEncoder_SITL_Quadrature::update(void) copy_state_to_frontend(_distance_count, _total_count, 0, time_now); } -#endif +#endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL +#endif // AP_WHEELENCODER_ENABLED diff --git a/libraries/AP_WheelEncoder/WheelEncoder_SITL_Quadrature.h b/libraries/AP_WheelEncoder/WheelEncoder_SITL_Quadrature.h index 006d9700ca1cae..4a55fb8c238256 100644 --- a/libraries/AP_WheelEncoder/WheelEncoder_SITL_Quadrature.h +++ b/libraries/AP_WheelEncoder/WheelEncoder_SITL_Quadrature.h @@ -14,9 +14,9 @@ */ #pragma once -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#include "WheelEncoder_Quadrature.h" +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && AP_WHEELENCODER_ENABLED -#include "WheelEncoder_Backend.h" #include #include @@ -34,4 +34,4 @@ class AP_WheelEncoder_SITL_Quadrature : public AP_WheelEncoder_Backend uint32_t _total_count; // total number of encoder ticks }; -#endif // CONFIG_HAL_BOARD \ No newline at end of file +#endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL && AP_WHEELENCODER_ENABLED \ No newline at end of file diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index bd26264667b566..c9248f53743ba6 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -1372,6 +1372,10 @@ extern "C" { #define GCS_SEND_MESSAGE(msg) #define AP_HAVE_GCS_SEND_TEXT 1 +#include "../../../AP_Periph/MAVLink.h" +#define GCS_MAVLINK MAVLink_Periph +#define HAVE_PAYLOAD_SPACE(_chan, id) true + /* we need a severity enum for the can_printf_severity function with no GCS present */