AP_GPS: update drivers for changed inject_data() API

need 16 bit length
This commit is contained in:
Andrew Tridgell 2016-10-04 18:37:52 +11:00
parent 500df1edf2
commit 9caf44b494
13 changed files with 13 additions and 13 deletions

View File

@ -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) {

View File

@ -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) {

View File

@ -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:

View File

@ -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);

View File

@ -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;

View File

@ -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();

View File

@ -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:

View File

@ -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) {

View File

@ -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:

View File

@ -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) {

View File

@ -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);

View File

@ -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);

View File

@ -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) {