mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_GPS: update drivers for changed inject_data() API
need 16 bit length
This commit is contained in:
parent
500df1edf2
commit
9caf44b494
@ -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) {
|
||||
|
@ -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) {
|
||||
|
@ -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:
|
||||
|
||||
|
@ -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);
|
||||
|
@ -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;
|
||||
|
@ -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();
|
||||
|
@ -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:
|
||||
|
||||
|
@ -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) {
|
||||
|
@ -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:
|
||||
|
||||
|
@ -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) {
|
||||
|
@ -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);
|
||||
|
||||
|
@ -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);
|
||||
|
@ -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) {
|
||||
|
Loading…
Reference in New Issue
Block a user