diff --git a/libraries/AP_GPS/AP_GPS_ERB.cpp b/libraries/AP_GPS/AP_GPS_ERB.cpp index 80ba47de97..ff9750f19d 100644 --- a/libraries/AP_GPS/AP_GPS_ERB.cpp +++ b/libraries/AP_GPS/AP_GPS_ERB.cpp @@ -225,7 +225,7 @@ AP_GPS_ERB::_parse_gps(void) } void -AP_GPS_ERB::inject_data(uint8_t *data, uint8_t len) +AP_GPS_ERB::inject_data(const uint8_t *data, uint16_t len) { if (port->txspace() > len) { diff --git a/libraries/AP_GPS/AP_GPS_GSOF.cpp b/libraries/AP_GPS/AP_GPS_GSOF.cpp index 609205a3f6..d622256561 100644 --- a/libraries/AP_GPS/AP_GPS_GSOF.cpp +++ b/libraries/AP_GPS/AP_GPS_GSOF.cpp @@ -345,7 +345,7 @@ AP_GPS_GSOF::process_message(void) } void -AP_GPS_GSOF::inject_data(uint8_t *data, uint8_t len) +AP_GPS_GSOF::inject_data(const uint8_t *data, uint16_t len) { if (port->txspace() > len) { diff --git a/libraries/AP_GPS/AP_GPS_GSOF.h b/libraries/AP_GPS/AP_GPS_GSOF.h index e5ba6536a3..843c026435 100644 --- a/libraries/AP_GPS/AP_GPS_GSOF.h +++ b/libraries/AP_GPS/AP_GPS_GSOF.h @@ -35,7 +35,7 @@ public: // Methods bool read(); - void inject_data(uint8_t *data, uint8_t len); + void inject_data(const uint8_t *data, uint16_t len) override; private: diff --git a/libraries/AP_GPS/AP_GPS_MAV.cpp b/libraries/AP_GPS/AP_GPS_MAV.cpp index 11ec17ff3d..ef05b1d3bd 100644 --- a/libraries/AP_GPS/AP_GPS_MAV.cpp +++ b/libraries/AP_GPS/AP_GPS_MAV.cpp @@ -41,7 +41,7 @@ bool AP_GPS_MAV::read(void) // handles an incoming mavlink message (HIL_GPS) and sets // corresponding gps data appropriately; -void AP_GPS_MAV::handle_msg(mavlink_message_t *msg) +void AP_GPS_MAV::handle_msg(const mavlink_message_t *msg) { mavlink_gps_input_t packet; mavlink_msg_gps_input_decode(msg, &packet); diff --git a/libraries/AP_GPS/AP_GPS_MAV.h b/libraries/AP_GPS/AP_GPS_MAV.h index eb632313dc..66f2f0d60a 100644 --- a/libraries/AP_GPS/AP_GPS_MAV.h +++ b/libraries/AP_GPS/AP_GPS_MAV.h @@ -34,7 +34,7 @@ public: static bool _detect(struct MAV_detect_state &state, uint8_t data); - void handle_msg(mavlink_message_t *msg); + void handle_msg(const mavlink_message_t *msg); private: bool _new_data; diff --git a/libraries/AP_GPS/AP_GPS_NOVA.cpp b/libraries/AP_GPS/AP_GPS_NOVA.cpp index 303ad56ff0..d948c04f59 100644 --- a/libraries/AP_GPS/AP_GPS_NOVA.cpp +++ b/libraries/AP_GPS/AP_GPS_NOVA.cpp @@ -279,7 +279,7 @@ AP_GPS_NOVA::process_message(void) } void -AP_GPS_NOVA::inject_data(uint8_t *data, uint8_t len) +AP_GPS_NOVA::inject_data(const uint8_t *data, uint16_t len) { if (port->txspace() > len) { last_injected_data_ms = AP_HAL::millis(); diff --git a/libraries/AP_GPS/AP_GPS_NOVA.h b/libraries/AP_GPS/AP_GPS_NOVA.h index 72054e1b70..cc4d1d967b 100644 --- a/libraries/AP_GPS/AP_GPS_NOVA.h +++ b/libraries/AP_GPS/AP_GPS_NOVA.h @@ -33,7 +33,7 @@ public: // Methods bool read(); - void inject_data(uint8_t *data, uint8_t len); + void inject_data(const uint8_t *data, uint16_t len) override; private: diff --git a/libraries/AP_GPS/AP_GPS_SBF.cpp b/libraries/AP_GPS/AP_GPS_SBF.cpp index ea967471c9..58bdeab34b 100644 --- a/libraries/AP_GPS/AP_GPS_SBF.cpp +++ b/libraries/AP_GPS/AP_GPS_SBF.cpp @@ -296,7 +296,7 @@ AP_GPS_SBF::process_message(void) } void -AP_GPS_SBF::inject_data(uint8_t *data, uint8_t len) +AP_GPS_SBF::inject_data(const uint8_t *data, uint16_t len) { if (port->txspace() > len) { diff --git a/libraries/AP_GPS/AP_GPS_SBF.h b/libraries/AP_GPS/AP_GPS_SBF.h index eb2a4a441b..ce185effe8 100644 --- a/libraries/AP_GPS/AP_GPS_SBF.h +++ b/libraries/AP_GPS/AP_GPS_SBF.h @@ -35,7 +35,7 @@ public: // Methods bool read(); - void inject_data(uint8_t *data, uint8_t len); + void inject_data(const uint8_t *data, uint16_t len) override; private: diff --git a/libraries/AP_GPS/AP_GPS_SBP.cpp b/libraries/AP_GPS/AP_GPS_SBP.cpp index 376fa26939..e4707860ed 100644 --- a/libraries/AP_GPS/AP_GPS_SBP.cpp +++ b/libraries/AP_GPS/AP_GPS_SBP.cpp @@ -85,7 +85,7 @@ AP_GPS_SBP::read(void) } void -AP_GPS_SBP::inject_data(uint8_t *data, uint8_t len) +AP_GPS_SBP::inject_data(const uint8_t *data, uint16_t len) { if (port->txspace() > len) { diff --git a/libraries/AP_GPS/AP_GPS_SBP.h b/libraries/AP_GPS/AP_GPS_SBP.h index cb279e797b..00b5b20bf4 100644 --- a/libraries/AP_GPS/AP_GPS_SBP.h +++ b/libraries/AP_GPS/AP_GPS_SBP.h @@ -35,7 +35,7 @@ public: // Methods bool read(); - void inject_data(uint8_t *data, uint8_t len); + void inject_data(const uint8_t *data, uint16_t len) override; static bool _detect(struct SBP_detect_state &state, uint8_t data); diff --git a/libraries/AP_GPS/AP_GPS_UBLOX.cpp b/libraries/AP_GPS/AP_GPS_UBLOX.cpp index 56f7d77a17..3dc9dbf529 100644 --- a/libraries/AP_GPS/AP_GPS_UBLOX.cpp +++ b/libraries/AP_GPS/AP_GPS_UBLOX.cpp @@ -1154,7 +1154,7 @@ AP_GPS_UBLOX::_configure_rate(void) } void -AP_GPS_UBLOX::inject_data(uint8_t *data, uint8_t len) +AP_GPS_UBLOX::inject_data(const uint8_t *data, uint16_t len) { if (port->txspace() > len) { port->write(data, len); diff --git a/libraries/AP_GPS/AP_GPS_UBLOX.h b/libraries/AP_GPS/AP_GPS_UBLOX.h index f676754ca3..b380a21df7 100644 --- a/libraries/AP_GPS/AP_GPS_UBLOX.h +++ b/libraries/AP_GPS/AP_GPS_UBLOX.h @@ -99,7 +99,7 @@ public: static bool _detect(struct UBLOX_detect_state &state, uint8_t data); - void inject_data(uint8_t *data, uint8_t len); + void inject_data(const uint8_t *data, uint16_t len) override; bool is_configured(void) { if (!gps._auto_config) {