AP_GPS: remove SBP raw logging

takes up flash for everyone

packet definitions are invalid

newer features in ArduPilot which work for all GPS (including replay capability) are better
This commit is contained in:
Peter Barker 2025-03-09 12:47:48 +11:00 committed by Andrew Tridgell
parent 74d8bf0694
commit 434c2b3efa
5 changed files with 3 additions and 158 deletions

View File

@ -30,7 +30,6 @@
extern const AP_HAL::HAL& hal;
#define SBP_DEBUGGING 1
#define SBP_HW_LOGGING HAL_LOGGING_ENABLED
#define SBP_TIMEOUT_HEATBEAT 4000
#define SBP_TIMEOUT_PVT 500
@ -232,10 +231,6 @@ AP_GPS_SBP::_sbp_process_message() {
// The log mask will be used to adjust or suppress logging
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);
#endif
}
bool
@ -296,7 +291,7 @@ AP_GPS_SBP::_attempt_state_update()
last_full_update_cpu_ms = now;
state.rtk_iar_num_hypotheses = last_iar_num_hypotheses;
#if SBP_HW_LOGGING
#if HAL_LOGGING_ENABLED
logging_log_full_update();
#endif
ret = true;
@ -395,8 +390,7 @@ AP_GPS_SBP::_detect(struct SBP_detect_state &state, uint8_t data)
return false;
}
#if SBP_HW_LOGGING
#if HAL_LOGGING_ENABLED
void
AP_GPS_SBP::logging_log_full_update()
{
@ -415,54 +409,6 @@ AP_GPS_SBP::logging_log_full_update()
AP::logger().WriteBlock(&pkt, sizeof(pkt));
};
#endif // HAL_LOGGING_ENABLED
void
AP_GPS_SBP::logging_log_raw_sbp(uint16_t msg_type,
uint16_t sender_id,
uint8_t msg_len,
uint8_t *msg_buff) {
if (!should_log()) {
return;
}
//MASK OUT MESSAGES WE DON'T WANT TO LOG
if (( ((uint16_t) gps._sbp_logmask) & msg_type) == 0) {
return;
}
uint64_t time_us = AP_HAL::micros64();
uint8_t pages = 1;
if (msg_len > 48) {
pages += (msg_len - 48) / 104 + 1;
}
struct log_SbpRAWH pkt = {
LOG_PACKET_HEADER_INIT(LOG_MSG_SBPRAWH),
time_us : time_us,
msg_type : msg_type,
sender_id : sender_id,
index : 1,
pages : pages,
msg_len : msg_len,
};
memcpy(pkt.data, msg_buff, MIN(msg_len, 48));
AP::logger().WriteBlock(&pkt, sizeof(pkt));
for (uint8_t i = 0; i < pages - 1; i++) {
struct log_SbpRAWM pkt2 = {
LOG_PACKET_HEADER_INIT(LOG_MSG_SBPRAWM),
time_us : time_us,
msg_type : msg_type,
sender_id : sender_id,
index : uint8_t(i + 2),
pages : pages,
msg_len : msg_len,
};
memcpy(pkt2.data, &msg_buff[48 + i * 104], MIN(msg_len - (48 + i * 104), 104));
AP::logger().WriteBlock(&pkt2, sizeof(pkt2));
}
};
#endif // SBP_HW_LOGGING
#endif // AP_GPS_SBP_ENABLED

View File

@ -184,8 +184,5 @@ private:
// ************************************************************************
void logging_log_full_update();
void logging_log_raw_sbp(uint16_t msg_type, uint16_t sender_id, uint8_t msg_len, uint8_t *msg_buff);
};
#endif

View File

@ -221,13 +221,6 @@ AP_GPS_SBP2::_sbp_process_message() {
default:
break;
}
#if HAL_LOGGING_ENABLED
// send all messages we receive to log, even if it's an unsupported message,
// so we can do additional post-processing from logs.
// 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);
#endif
}
int32_t
@ -466,55 +459,6 @@ AP_GPS_SBP2::logging_log_full_update()
};
AP::logger().WriteBlock(&pkt, sizeof(pkt));
};
void
AP_GPS_SBP2::logging_log_raw_sbp(uint16_t msg_type,
uint16_t sender_id,
uint8_t msg_len,
uint8_t *msg_buff) {
if (!should_log()) {
return;
}
//MASK OUT MESSAGES WE DON'T WANT TO LOG
if (( ((uint16_t) gps._sbp_logmask) & msg_type) == 0) {
return;
}
uint64_t time_us = AP_HAL::micros64();
uint8_t pages = 1;
if (msg_len > 48) {
pages += (msg_len - 48) / 104 + 1;
}
struct log_SbpRAWH pkt = {
LOG_PACKET_HEADER_INIT(LOG_MSG_SBPRAWH),
time_us : time_us,
msg_type : msg_type,
sender_id : sender_id,
index : 1,
pages : pages,
msg_len : msg_len,
};
memcpy(pkt.data, msg_buff, MIN(msg_len, 48));
AP::logger().WriteBlock(&pkt, sizeof(pkt));
for (uint8_t i = 0; i < pages - 1; i++) {
struct log_SbpRAWM pkt2 = {
LOG_PACKET_HEADER_INIT(LOG_MSG_SBPRAWM),
time_us : time_us,
msg_type : msg_type,
sender_id : sender_id,
index : uint8_t(i + 2),
pages : pages,
msg_len : msg_len,
};
memcpy(pkt2.data, &msg_buff[48 + i * 104], MIN(msg_len - (48 + i * 104), 104));
AP::logger().WriteBlock(&pkt2, sizeof(pkt2));
}
};
void
AP_GPS_SBP2::logging_ext_event() {
if (!should_log()) {

View File

@ -197,7 +197,6 @@ private:
void logging_log_full_update();
void logging_ext_event();
void logging_log_raw_sbp(uint16_t msg_type, uint16_t sender_id, uint8_t msg_len, uint8_t *msg_buff);
int32_t distMod(int32_t tow1_ms, int32_t tow2_ms, int32_t mod);

View File

@ -5,8 +5,6 @@
#define LOG_IDS_FROM_GPS_SBP \
LOG_MSG_SBPHEALTH, \
LOG_MSG_SBPRAWH, \
LOG_MSG_SBPRAWM, \
LOG_MSG_SBPEVENT
// @LoggerMessage: SBPH
@ -24,41 +22,6 @@ struct PACKED log_SbpHealth {
uint32_t last_iar_num_hypotheses;
};
// @LoggerMessage: SBRH
// @Description: Swift Raw Message Data
// @Field: TimeUS: Time since system startup
// @Field: msg_flag: Swift message type
// @Field: 1: Sender ID
// @Field: 2: index; always 1
// @Field: 3: pages; number of pages received
// @Field: 4: msg length; number of bytes received
// @Field: 5: unused; always zero
// @Field: 6: data received from device
struct PACKED log_SbpRAWH {
LOG_PACKET_HEADER;
uint64_t time_us;
uint16_t msg_type;
uint16_t sender_id;
uint8_t index;
uint8_t pages;
uint8_t msg_len;
uint8_t res;
uint8_t data[48];
};
struct PACKED log_SbpRAWM {
LOG_PACKET_HEADER;
uint64_t time_us;
uint16_t msg_type;
uint16_t sender_id;
uint8_t index;
uint8_t pages;
uint8_t msg_len;
uint8_t res;
uint8_t data[104];
};
struct PACKED log_SbpEvent {
LOG_PACKET_HEADER;
uint64_t time_us;
@ -73,10 +36,6 @@ struct PACKED log_SbpEvent {
#define LOG_STRUCTURE_FROM_GPS_SBP \
{ LOG_MSG_SBPHEALTH, sizeof(log_SbpHealth), \
"SBPH", "QIII", "TimeUS,CrcError,LastInject,IARhyp", "s---", "F---" , true }, \
{ LOG_MSG_SBPRAWH, sizeof(log_SbpRAWH), \
"SBRH", "QQQQQQQQ", "TimeUS,msg_flag,1,2,3,4,5,6", "s-------", "F-------" , true }, \
{ LOG_MSG_SBPRAWM, sizeof(log_SbpRAWM), \
"SBRM", "QQQQQQQQQQQQQQQ", "TimeUS,msg_flag,1,2,3,4,5,6,7,8,9,10,11,12,13", "s??????????????", "F??????????????" , true }, \
{ LOG_MSG_SBPEVENT, sizeof(log_SbpEvent), \
"SBRE", "QHIiBB", "TimeUS,GWk,GMS,ns_residual,level,quality", "s?????", "F?????" },
#else