AP_GPS: Expose COM port and Output Rate in header

* This removes magic numbers of hard coding the hardware port and output
  rate
* This also fixes configuring the incorrect hardware port
* Now, COM2 (TTL) is configured for GSOF output
* The data rate remains the same as before

Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
This commit is contained in:
Ryan Friedman 2023-11-03 22:22:27 -06:00 committed by Andrew Tridgell
parent 9285188d85
commit 9445cb2672
2 changed files with 33 additions and 6 deletions

View File

@ -17,6 +17,11 @@
// Trimble GPS driver for ArduPilot. // Trimble GPS driver for ArduPilot.
// Code by Michael Oborne // Code by Michael Oborne
// //
// Usage in SITL with hardware for debugging:
// sim_vehicle.py -v Plane -A "--serial3=uart:/dev/ttyUSB0" --console --map -DG
// param set GPS_TYPE 11 // GSOF
// param set SERIAL3_PROTOCOL 5 // GPS
//
#define ALLOW_DOUBLE_MATH_FUNCTIONS #define ALLOW_DOUBLE_MATH_FUNCTIONS
@ -70,8 +75,7 @@ AP_GPS_GSOF::read(void)
if (gsofmsgreq_index < (sizeof(gsofmsgreq))) { if (gsofmsgreq_index < (sizeof(gsofmsgreq))) {
if (now > gsofmsg_time) { if (now > gsofmsg_time) {
requestGSOF(gsofmsgreq[gsofmsgreq_index], 0); requestGSOF(gsofmsgreq[gsofmsgreq_index], HW_Port::COM2, Output_Rate::FREQ_10_HZ);
requestGSOF(gsofmsgreq[gsofmsgreq_index], 3);
gsofmsg_time = now + 110; gsofmsg_time = now + 110;
gsofmsgreq_index++; gsofmsgreq_index++;
} }
@ -167,16 +171,15 @@ AP_GPS_GSOF::requestBaud(const uint8_t portindex)
} }
void void
AP_GPS_GSOF::requestGSOF(const uint8_t messagetype, const uint8_t portindex) AP_GPS_GSOF::requestGSOF(const uint8_t messageType, const HW_Port portIndex, const Output_Rate rateHz)
{ {
uint8_t buffer[21] = {0x02,0x00,0x64,0x0f,0x00,0x00,0x00, // application file record uint8_t buffer[21] = {0x02,0x00,0x64,0x0f,0x00,0x00,0x00, // application file record
0x03,0x00,0x01,0x00, // file control information block 0x03,0x00,0x01,0x00, // file control information block
0x07,0x06,0x0a,portindex,0x01,0x00,0x01,0x00, // output message record 0x07,0x06,0x0a,static_cast<uint8_t>(portIndex),static_cast<uint8_t>(rateHz),0x00,messageType,0x00, // output message record
0x00,0x03 0x00,0x03
}; // checksum }; // checksum
buffer[4] = packetcount++; buffer[4] = packetcount++;
buffer[17] = messagetype;
uint8_t checksum = 0; uint8_t checksum = 0;
for (uint8_t a = 1; a < (sizeof(buffer) - 1); a++) { for (uint8_t a = 1; a < (sizeof(buffer) - 1); a++) {

View File

@ -40,15 +40,39 @@ public:
private: private:
// A subset of the port identifiers in the GSOF protocol that are used for serial.
// Ethernet, USB, etc are not supported by the GPS driver at this time so they are omitted.
// These values are not documented in the API.
enum class HW_Port {
COM1 = 3, // RS232 serial
COM2 = 1, // TTL serial
};
// A subset of the data frequencies in the GSOF protocol that are used for serial.
// These values are not documented in the API.
enum class Output_Rate {
FREQ_10_HZ = 1,
FREQ_50_HZ = 15,
FREQ_100_HZ = 16,
};
bool parse(const uint8_t temp) WARN_IF_UNUSED; bool parse(const uint8_t temp) WARN_IF_UNUSED;
bool process_message() WARN_IF_UNUSED; bool process_message() WARN_IF_UNUSED;
void requestBaud(const uint8_t portindex); void requestBaud(const uint8_t portindex);
void requestGSOF(const uint8_t messagetype, const uint8_t portindex);
// Send a request to the GPS to enable a message type on the port at the specified rate.
// Note - these request functions currently ignore the ACK from the device.
// If the device is already sending serial traffic, there is no mechanism to prevent conflict.
// According to the manufacturer, the best approach is to switch to ethernet.
void requestGSOF(const uint8_t messageType, const HW_Port portIndex, const Output_Rate rateHz);
double SwapDouble(const uint8_t* src, const uint32_t pos) const WARN_IF_UNUSED; double SwapDouble(const uint8_t* src, const uint32_t pos) const WARN_IF_UNUSED;
float SwapFloat(const uint8_t* src, const uint32_t pos) const WARN_IF_UNUSED; float SwapFloat(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; 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;
bool validate_baud(const uint8_t baud) const WARN_IF_UNUSED;
struct Msg_Parser struct Msg_Parser
{ {