Skip to content

Commit

Permalink
AP_GPS: Use GPS_COM_PORT param
Browse files Browse the repository at this point in the history
* Instead of hard coding to COM2, allow users to set it
* The enum is confusing, so this needs a wiki entry

Signed-off-by: Ryan Friedman <[email protected]>
  • Loading branch information
Ryanf55 committed Nov 7, 2023
1 parent bbfc949 commit dfb91ad
Show file tree
Hide file tree
Showing 2 changed files with 19 additions and 1 deletion.
19 changes: 18 additions & 1 deletion libraries/AP_GPS/AP_GPS_GSOF.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,8 +74,13 @@ AP_GPS_GSOF::read(void)
const uint32_t now = AP_HAL::millis();

if (gsofmsgreq_index < (sizeof(gsofmsgreq))) {
const auto com_port = gps._com_port[state.instance].get();
if (!validate_com_port(com_port)) {
// The user parameter for COM port is not a valid GSOF port
return false;
}
if (now > gsofmsg_time) {
requestGSOF(gsofmsgreq[gsofmsgreq_index], HW_Port::COM2, Output_Rate::FREQ_10_HZ);
requestGSOF(gsofmsgreq[gsofmsgreq_index], static_cast<HW_Port>(com_port), Output_Rate::FREQ_10_HZ);
gsofmsg_time = now + 110;
gsofmsgreq_index++;
}
Expand Down Expand Up @@ -347,4 +352,16 @@ AP_GPS_GSOF::process_message(void)

return false;
}

bool
AP_GPS_GSOF::validate_com_port(const uint8_t com_port) const {
switch(com_port) {
case static_cast<uint8_t>(HW_Port::COM1):
case static_cast<uint8_t>(HW_Port::COM2):
return true;
default:
return false;
}
}

#endif
1 change: 1 addition & 0 deletions libraries/AP_GPS/AP_GPS_GSOF.h
Original file line number Diff line number Diff line change
Expand Up @@ -72,6 +72,7 @@ class AP_GPS_GSOF : public AP_GPS_Backend
uint16_t SwapUint16(const uint8_t* src, const uint32_t pos) const WARN_IF_UNUSED;

bool validate_baud(const uint8_t baud) const WARN_IF_UNUSED;
bool validate_com_port(const uint8_t com_port) const WARN_IF_UNUSED;

struct Msg_Parser
{
Expand Down

0 comments on commit dfb91ad

Please sign in to comment.