mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_GPS: Use enum classes in GSOF
Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
This commit is contained in:
parent
c41d5f4ff6
commit
2f5f77712f
@ -46,7 +46,7 @@ AP_GPS_GSOF::AP_GPS_GSOF(AP_GPS &_gps, AP_GPS::GPS_State &_state,
|
|||||||
AP_HAL::UARTDriver *_port) :
|
AP_HAL::UARTDriver *_port) :
|
||||||
AP_GPS_Backend(_gps, _state, _port)
|
AP_GPS_Backend(_gps, _state, _port)
|
||||||
{
|
{
|
||||||
gsof_msg.gsof_state = gsof_msg_parser_t::STARTTX;
|
gsof_msg.gsof_state = gsof_msg_parser_t::gsof_states::STARTTX;
|
||||||
|
|
||||||
// baud request for port 0
|
// baud request for port 0
|
||||||
requestBaud(0);
|
requestBaud(0);
|
||||||
@ -91,49 +91,49 @@ AP_GPS_GSOF::parse(const uint8_t temp)
|
|||||||
switch (gsof_msg.gsof_state)
|
switch (gsof_msg.gsof_state)
|
||||||
{
|
{
|
||||||
default:
|
default:
|
||||||
case gsof_msg_parser_t::STARTTX:
|
case gsof_msg_parser_t::gsof_states::STARTTX:
|
||||||
if (temp == GSOF_STX)
|
if (temp == GSOF_STX)
|
||||||
{
|
{
|
||||||
gsof_msg.gsof_state = gsof_msg_parser_t::STATUS;
|
gsof_msg.gsof_state = gsof_msg_parser_t::gsof_states::STATUS;
|
||||||
gsof_msg.read = 0;
|
gsof_msg.read = 0;
|
||||||
gsof_msg.checksumcalc = 0;
|
gsof_msg.checksumcalc = 0;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case gsof_msg_parser_t::STATUS:
|
case gsof_msg_parser_t::gsof_states::STATUS:
|
||||||
gsof_msg.status = temp;
|
gsof_msg.status = temp;
|
||||||
gsof_msg.gsof_state = gsof_msg_parser_t::PACKETTYPE;
|
gsof_msg.gsof_state = gsof_msg_parser_t::gsof_states::PACKETTYPE;
|
||||||
gsof_msg.checksumcalc += temp;
|
gsof_msg.checksumcalc += temp;
|
||||||
break;
|
break;
|
||||||
case gsof_msg_parser_t::PACKETTYPE:
|
case gsof_msg_parser_t::gsof_states::PACKETTYPE:
|
||||||
gsof_msg.packettype = temp;
|
gsof_msg.packettype = temp;
|
||||||
gsof_msg.gsof_state = gsof_msg_parser_t::LENGTH;
|
gsof_msg.gsof_state = gsof_msg_parser_t::gsof_states::LENGTH;
|
||||||
gsof_msg.checksumcalc += temp;
|
gsof_msg.checksumcalc += temp;
|
||||||
break;
|
break;
|
||||||
case gsof_msg_parser_t::LENGTH:
|
case gsof_msg_parser_t::gsof_states::LENGTH:
|
||||||
gsof_msg.length = temp;
|
gsof_msg.length = temp;
|
||||||
gsof_msg.gsof_state = gsof_msg_parser_t::DATA;
|
gsof_msg.gsof_state = gsof_msg_parser_t::gsof_states::DATA;
|
||||||
gsof_msg.checksumcalc += temp;
|
gsof_msg.checksumcalc += temp;
|
||||||
break;
|
break;
|
||||||
case gsof_msg_parser_t::DATA:
|
case gsof_msg_parser_t::gsof_states::DATA:
|
||||||
gsof_msg.data[gsof_msg.read] = temp;
|
gsof_msg.data[gsof_msg.read] = temp;
|
||||||
gsof_msg.read++;
|
gsof_msg.read++;
|
||||||
gsof_msg.checksumcalc += temp;
|
gsof_msg.checksumcalc += temp;
|
||||||
if (gsof_msg.read >= gsof_msg.length)
|
if (gsof_msg.read >= gsof_msg.length)
|
||||||
{
|
{
|
||||||
gsof_msg.gsof_state = gsof_msg_parser_t::CHECKSUM;
|
gsof_msg.gsof_state = gsof_msg_parser_t::gsof_states::CHECKSUM;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case gsof_msg_parser_t::CHECKSUM:
|
case gsof_msg_parser_t::gsof_states::CHECKSUM:
|
||||||
gsof_msg.checksum = temp;
|
gsof_msg.checksum = temp;
|
||||||
gsof_msg.gsof_state = gsof_msg_parser_t::ENDTX;
|
gsof_msg.gsof_state = gsof_msg_parser_t::gsof_states::ENDTX;
|
||||||
if (gsof_msg.checksum == gsof_msg.checksumcalc)
|
if (gsof_msg.checksum == gsof_msg.checksumcalc)
|
||||||
{
|
{
|
||||||
return process_message();
|
return process_message();
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case gsof_msg_parser_t::ENDTX:
|
case gsof_msg_parser_t::gsof_states::ENDTX:
|
||||||
gsof_msg.endtx = temp;
|
gsof_msg.endtx = temp;
|
||||||
gsof_msg.gsof_state = gsof_msg_parser_t::STARTTX;
|
gsof_msg.gsof_state = gsof_msg_parser_t::gsof_states::STARTTX;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -48,10 +48,10 @@ private:
|
|||||||
uint32_t SwapUint32(const uint8_t* src, const uint32_t pos) const WARN_IF_UNUSED;
|
uint32_t SwapUint32(const uint8_t* src, const uint32_t pos) const WARN_IF_UNUSED;
|
||||||
uint16_t SwapUint16(const uint8_t* src, const uint32_t pos) const WARN_IF_UNUSED;
|
uint16_t SwapUint16(const uint8_t* src, const uint32_t pos) const WARN_IF_UNUSED;
|
||||||
|
|
||||||
|
|
||||||
struct gsof_msg_parser_t
|
struct gsof_msg_parser_t
|
||||||
{
|
{
|
||||||
enum
|
|
||||||
|
enum class gsof_states
|
||||||
{
|
{
|
||||||
STARTTX = 0,
|
STARTTX = 0,
|
||||||
STATUS,
|
STATUS,
|
||||||
@ -60,7 +60,9 @@ private:
|
|||||||
DATA,
|
DATA,
|
||||||
CHECKSUM,
|
CHECKSUM,
|
||||||
ENDTX
|
ENDTX
|
||||||
} gsof_state;
|
};
|
||||||
|
|
||||||
|
gsof_states gsof_state;
|
||||||
|
|
||||||
uint8_t status;
|
uint8_t status;
|
||||||
uint8_t packettype;
|
uint8_t packettype;
|
||||||
|
Loading…
Reference in New Issue
Block a user