Skip to content

Commit

Permalink
AP_GSOF: refactor GSOF to expect packets by ID
Browse files Browse the repository at this point in the history
Signed-off-by: Ryan Friedman <25047695+Ryanf55@users.noreply.github.com>
  • Loading branch information
Ryanf55 committed Jan 7, 2025
1 parent 9d11115 commit 01614e8
Show file tree
Hide file tree
Showing 3 changed files with 31 additions and 27 deletions.
27 changes: 9 additions & 18 deletions libraries/AP_GSOF/AP_GSOF.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ do { \
#endif

int
AP_GSOF::parse(const uint8_t temp, const uint8_t n_expected)
AP_GSOF::parse(const uint8_t temp, MsgTypes& parsed_msgs)
{
// https://receiverhelp.trimble.com/oem-gnss/index.html#API_DataCollectorFormatPacketStructure.html
switch (msg.state) {
Expand Down Expand Up @@ -67,11 +67,10 @@ AP_GSOF::parse(const uint8_t temp, const uint8_t n_expected)
msg.checksum = temp;
msg.state = Msg_Parser::State::ENDTX;
if (msg.checksum == msg.checksumcalc) {
const auto n_processed = process_message();
if (n_processed != n_expected ) {
return UNEXPECTED_NUM_GSOF_PACKETS;
if (!process_message(parsed_msgs)) {
return NO_GSOF_DATA;
}
return n_processed;
return PARSED_GSOF_DATA;
}
break;
case Msg_Parser::State::ENDTX:
Expand All @@ -83,8 +82,8 @@ AP_GSOF::parse(const uint8_t temp, const uint8_t n_expected)
return NO_GSOF_DATA;
}

int
AP_GSOF::process_message(void)
bool
AP_GSOF::process_message(MsgTypes& parsed_msgs)
{
if (msg.packettype == 0x40) { // GSOF
// https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_TIME.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257C_____25
Expand All @@ -97,12 +96,9 @@ AP_GSOF::process_message(void)
pageidx, maxpageidx, trans_number);
#endif

// This counts up the number of received packets.
int valid = 0;

// want 1 2 8 9 12
for (uint32_t a = 3; a < msg.length; a++) {
const uint8_t output_type = msg.data[a];
parsed_msgs.set(output_type);
a++;
const uint8_t output_length = msg.data[a];
a++;
Expand All @@ -111,23 +107,18 @@ AP_GSOF::process_message(void)
switch (output_type) {
case POS_TIME:
parse_pos_time(a);
valid++;
break;
case POS:
parse_pos(a);
valid++;
break;
case VEL:
parse_vel(a);
valid++;
break;
case DOP:
parse_dop(a);
valid++;
break;
case POS_SIGMA:
parse_pos_sigma(a);
valid++;
break;
default:
break;
Expand All @@ -136,11 +127,11 @@ AP_GSOF::process_message(void)
a += output_length - 1u;
}

return valid;
return true;
}

// No GSOF packets.
return NO_GSOF_DATA;
return false;
}

void AP_GSOF::parse_pos_time(uint32_t a)
Expand Down
18 changes: 11 additions & 7 deletions libraries/AP_GSOF/AP_GSOF.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
#pragma once

#include "AP_GSOF_config.h"
#include <AP_Common/Bitmask.h>

#if AP_GSOF_ENABLED

Expand All @@ -11,14 +12,15 @@ class AP_GSOF
public:

static constexpr int NO_GSOF_DATA = 0;
static constexpr int UNEXPECTED_NUM_GSOF_PACKETS = -1;
static constexpr int PARSED_GSOF_DATA = 1;

// A type alias for which packets have been parsed.
using MsgTypes = Bitmask<71>;

// Parse a single byte into the buffer.
// When enough data has arrived, it returns the number of GSOF packets parsed in the GENOUT packet.
// If an unexpected number of GSOF packets were parsed, returns UNEXPECTED_NUM_GSOF_PACKETS.
// This means there is no fix.
// When enough data has arrived, it populates a bitmask of which GSOF packets were parsed in the GENOUT packet and returns PARSED_GSOF_DATA.
// If it returns NO_GSOF_DATA, the parser just needs more data.
int parse(const uint8_t temp, const uint8_t n_expected) WARN_IF_UNUSED;
int parse(const uint8_t temp, MsgTypes& parsed_msgs) WARN_IF_UNUSED;

// GSOF packet numbers.
enum msg_idx_t {
Expand Down Expand Up @@ -91,8 +93,10 @@ class AP_GSOF

private:

// Parses current data and returns the number of parsed GSOF messages.
int process_message() WARN_IF_UNUSED;
// Parses current data.
// Returns true if, and only if, the expected packets were parsed.
// Unexpected/unparsed data will make this return false.
bool process_message(MsgTypes& parsed_msgs) WARN_IF_UNUSED;

void parse_pos_time(uint32_t a);
void parse_pos(uint32_t a);
Expand Down
13 changes: 11 additions & 2 deletions libraries/AP_GSOF/tests/test_gsof.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,8 @@ const AP_HAL::HAL &hal = AP_HAL::get_HAL();
TEST(AP_GSOF, incomplete_packet)
{
AP_GSOF gsof;
EXPECT_FALSE(gsof.parse(0, 5));
AP_GSOF::MsgTypes expected;
EXPECT_FALSE(gsof.parse(0, expected));
}

TEST(AP_GSOF, packet1)
Expand All @@ -27,9 +28,17 @@ TEST(AP_GSOF, packet1)
AP_GSOF gsof;
char c = 0;
bool parsed = false;

AP_GSOF::MsgTypes expected;
expected.set(1);
expected.set(2);
expected.set(8);
expected.set(9);
expected.set(12);

while (c != EOF) {
c = fgetc (fp);
parsed |= gsof.parse((uint8_t)c, 5);
parsed |= gsof.parse((uint8_t)c, expected);
}

EXPECT_TRUE(parsed);
Expand Down

0 comments on commit 01614e8

Please sign in to comment.