mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_GPS: pass mavlink_message_t by const reference
This commit is contained in:
parent
09f0f34fe5
commit
13ac187fd8
@ -781,10 +781,10 @@ void AP_GPS::update(void)
|
|||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_GPS::handle_gps_inject(const mavlink_message_t *msg)
|
void AP_GPS::handle_gps_inject(const mavlink_message_t &msg)
|
||||||
{
|
{
|
||||||
mavlink_gps_inject_data_t packet;
|
mavlink_gps_inject_data_t packet;
|
||||||
mavlink_msg_gps_inject_data_decode(msg, &packet);
|
mavlink_msg_gps_inject_data_decode(&msg, &packet);
|
||||||
//TODO: check target
|
//TODO: check target
|
||||||
|
|
||||||
inject_data(packet.data, packet.len);
|
inject_data(packet.data, packet.len);
|
||||||
@ -793,9 +793,9 @@ void AP_GPS::handle_gps_inject(const mavlink_message_t *msg)
|
|||||||
/*
|
/*
|
||||||
pass along a mavlink message (for MAV type)
|
pass along a mavlink message (for MAV type)
|
||||||
*/
|
*/
|
||||||
void AP_GPS::handle_msg(const mavlink_message_t *msg)
|
void AP_GPS::handle_msg(const mavlink_message_t &msg)
|
||||||
{
|
{
|
||||||
switch (msg->msgid) {
|
switch (msg.msgid) {
|
||||||
case MAVLINK_MSG_ID_GPS_RTCM_DATA:
|
case MAVLINK_MSG_ID_GPS_RTCM_DATA:
|
||||||
// pass data to de-fragmenter
|
// pass data to de-fragmenter
|
||||||
handle_gps_rtcm_data(msg);
|
handle_gps_rtcm_data(msg);
|
||||||
@ -1029,10 +1029,10 @@ bool AP_GPS::blend_health_check() const
|
|||||||
/*
|
/*
|
||||||
re-assemble GPS_RTCM_DATA message
|
re-assemble GPS_RTCM_DATA message
|
||||||
*/
|
*/
|
||||||
void AP_GPS::handle_gps_rtcm_data(const mavlink_message_t *msg)
|
void AP_GPS::handle_gps_rtcm_data(const mavlink_message_t &msg)
|
||||||
{
|
{
|
||||||
mavlink_gps_rtcm_data_t packet;
|
mavlink_gps_rtcm_data_t packet;
|
||||||
mavlink_msg_gps_rtcm_data_decode(msg, &packet);
|
mavlink_msg_gps_rtcm_data_decode(&msg, &packet);
|
||||||
|
|
||||||
if (packet.len > MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN) {
|
if (packet.len > MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN) {
|
||||||
// invalid packet
|
// invalid packet
|
||||||
|
@ -169,7 +169,7 @@ public:
|
|||||||
void update(void);
|
void update(void);
|
||||||
|
|
||||||
// Pass mavlink data to message handlers (for MAV type)
|
// Pass mavlink data to message handlers (for MAV type)
|
||||||
void handle_msg(const mavlink_message_t *msg);
|
void handle_msg(const mavlink_message_t &msg);
|
||||||
|
|
||||||
// Accessor functions
|
// Accessor functions
|
||||||
|
|
||||||
@ -538,8 +538,8 @@ private:
|
|||||||
} *rtcm_buffer;
|
} *rtcm_buffer;
|
||||||
|
|
||||||
// re-assemble GPS_RTCM_DATA message
|
// re-assemble GPS_RTCM_DATA message
|
||||||
void handle_gps_rtcm_data(const mavlink_message_t *msg);
|
void handle_gps_rtcm_data(const mavlink_message_t &msg);
|
||||||
void handle_gps_inject(const mavlink_message_t *msg);
|
void handle_gps_inject(const mavlink_message_t &msg);
|
||||||
|
|
||||||
//Inject a packet of raw binary to a GPS
|
//Inject a packet of raw binary to a GPS
|
||||||
void inject_data(uint8_t *data, uint16_t len);
|
void inject_data(uint8_t *data, uint16_t len);
|
||||||
|
@ -39,13 +39,13 @@ bool AP_GPS_MAV::read(void)
|
|||||||
|
|
||||||
// handles an incoming mavlink message (HIL_GPS) and sets
|
// handles an incoming mavlink message (HIL_GPS) and sets
|
||||||
// corresponding gps data appropriately;
|
// corresponding gps data appropriately;
|
||||||
void AP_GPS_MAV::handle_msg(const mavlink_message_t *msg)
|
void AP_GPS_MAV::handle_msg(const mavlink_message_t &msg)
|
||||||
{
|
{
|
||||||
switch (msg->msgid) {
|
switch (msg.msgid) {
|
||||||
|
|
||||||
case MAVLINK_MSG_ID_GPS_INPUT: {
|
case MAVLINK_MSG_ID_GPS_INPUT: {
|
||||||
mavlink_gps_input_t packet;
|
mavlink_gps_input_t packet;
|
||||||
mavlink_msg_gps_input_decode(msg, &packet);
|
mavlink_msg_gps_input_decode(&msg, &packet);
|
||||||
|
|
||||||
bool have_alt = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_ALT) == 0);
|
bool have_alt = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_ALT) == 0);
|
||||||
bool have_hdop = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_HDOP) == 0);
|
bool have_hdop = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_HDOP) == 0);
|
||||||
@ -111,7 +111,7 @@ void AP_GPS_MAV::handle_msg(const mavlink_message_t *msg)
|
|||||||
|
|
||||||
case MAVLINK_MSG_ID_HIL_GPS: {
|
case MAVLINK_MSG_ID_HIL_GPS: {
|
||||||
mavlink_hil_gps_t packet;
|
mavlink_hil_gps_t packet;
|
||||||
mavlink_msg_hil_gps_decode(msg, &packet);
|
mavlink_msg_hil_gps_decode(&msg, &packet);
|
||||||
|
|
||||||
state.time_week = 0;
|
state.time_week = 0;
|
||||||
state.time_week_ms = packet.time_usec/1000;
|
state.time_week_ms = packet.time_usec/1000;
|
||||||
|
@ -33,7 +33,7 @@ public:
|
|||||||
|
|
||||||
static bool _detect(struct MAV_detect_state &state, uint8_t data);
|
static bool _detect(struct MAV_detect_state &state, uint8_t data);
|
||||||
|
|
||||||
void handle_msg(const mavlink_message_t *msg) override;
|
void handle_msg(const mavlink_message_t &msg) override;
|
||||||
|
|
||||||
const char *name() const override { return "MAV"; }
|
const char *name() const override { return "MAV"; }
|
||||||
|
|
||||||
|
@ -50,7 +50,7 @@ public:
|
|||||||
|
|
||||||
virtual void broadcast_configuration_failure_reason(void) const { return ; }
|
virtual void broadcast_configuration_failure_reason(void) const { return ; }
|
||||||
|
|
||||||
virtual void handle_msg(const mavlink_message_t *msg) { return ; }
|
virtual void handle_msg(const mavlink_message_t &msg) { return ; }
|
||||||
|
|
||||||
// driver specific lag, returns true if the driver is confident in the provided lag
|
// driver specific lag, returns true if the driver is confident in the provided lag
|
||||||
virtual bool get_lag(float &lag) const { lag = 0.2f; return true; }
|
virtual bool get_lag(float &lag) const { lag = 0.2f; return true; }
|
||||||
|
Loading…
Reference in New Issue
Block a user