mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_GPS: fixed build without logging
This commit is contained in:
parent
2c962e46c1
commit
6832eab8a5
@ -30,7 +30,7 @@
|
|||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
#define SBP_DEBUGGING 1
|
#define SBP_DEBUGGING 1
|
||||||
#define SBP_HW_LOGGING 1
|
#define SBP_HW_LOGGING HAL_LOGGING_ENABLED
|
||||||
|
|
||||||
#define SBP_TIMEOUT_HEATBEAT 4000
|
#define SBP_TIMEOUT_HEATBEAT 4000
|
||||||
#define SBP_TIMEOUT_PVT 500
|
#define SBP_TIMEOUT_PVT 500
|
||||||
@ -228,7 +228,9 @@ AP_GPS_SBP::_sbp_process_message() {
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if SBP_HW_LOGGING
|
||||||
logging_log_raw_sbp(parser_state.msg_type, parser_state.sender_id, parser_state.msg_len, parser_state.msg_buff);
|
logging_log_raw_sbp(parser_state.msg_type, parser_state.sender_id, parser_state.msg_len, parser_state.msg_buff);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
bool
|
bool
|
||||||
@ -292,7 +294,9 @@ AP_GPS_SBP::_attempt_state_update()
|
|||||||
last_full_update_cpu_ms = now;
|
last_full_update_cpu_ms = now;
|
||||||
state.rtk_iar_num_hypotheses = last_iar_num_hypotheses;
|
state.rtk_iar_num_hypotheses = last_iar_num_hypotheses;
|
||||||
|
|
||||||
|
#if SBP_HW_LOGGING
|
||||||
logging_log_full_update();
|
logging_log_full_update();
|
||||||
|
#endif
|
||||||
ret = true;
|
ret = true;
|
||||||
|
|
||||||
} else if (now - last_full_update_cpu_ms > SBP_TIMEOUT_PVT) {
|
} else if (now - last_full_update_cpu_ms > SBP_TIMEOUT_PVT) {
|
||||||
|
@ -208,17 +208,21 @@ AP_GPS_SBP2::_sbp_process_message() {
|
|||||||
case SBP_EXT_EVENT_MSGTYPE:
|
case SBP_EXT_EVENT_MSGTYPE:
|
||||||
memcpy(&last_event, parser_state.msg_buff, sizeof(struct sbp_ext_event_t));
|
memcpy(&last_event, parser_state.msg_buff, sizeof(struct sbp_ext_event_t));
|
||||||
check_new_itow(last_event.tow, parser_state.msg_len);
|
check_new_itow(last_event.tow, parser_state.msg_len);
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
logging_ext_event();
|
logging_ext_event();
|
||||||
|
#endif
|
||||||
break;
|
break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
// send all messages we receive to log, even if it's an unsupported message,
|
// send all messages we receive to log, even if it's an unsupported message,
|
||||||
// so we can do additional post-processing from logs.
|
// so we can do additional post-processing from logs.
|
||||||
// The log mask will be used to adjust or suppress logging
|
// The log mask will be used to adjust or suppress logging
|
||||||
logging_log_raw_sbp(parser_state.msg_type, parser_state.sender_id, parser_state.msg_len, parser_state.msg_buff);
|
logging_log_raw_sbp(parser_state.msg_type, parser_state.sender_id, parser_state.msg_len, parser_state.msg_buff);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
int32_t
|
int32_t
|
||||||
@ -440,6 +444,7 @@ AP_GPS_SBP2::_detect(struct SBP2_detect_state &state, uint8_t data)
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
void
|
void
|
||||||
AP_GPS_SBP2::logging_log_full_update()
|
AP_GPS_SBP2::logging_log_full_update()
|
||||||
{
|
{
|
||||||
@ -525,4 +530,5 @@ AP_GPS_SBP2::logging_ext_event() {
|
|||||||
};
|
};
|
||||||
AP::logger().WriteBlock(&pkt, sizeof(pkt));
|
AP::logger().WriteBlock(&pkt, sizeof(pkt));
|
||||||
};
|
};
|
||||||
|
#endif // HAL_LOGGING_ENABLED
|
||||||
#endif //AP_GPS_SBP2_ENABLED
|
#endif //AP_GPS_SBP2_ENABLED
|
||||||
|
Loading…
Reference in New Issue
Block a user