mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_GPS: added get_type() API
This commit is contained in:
parent
0b2df61114
commit
7efd5248ee
@ -467,6 +467,11 @@ public:
|
||||
// handle possibly fragmented RTCM injection data
|
||||
void handle_gps_rtcm_fragment(uint8_t flags, const uint8_t *data, uint8_t len);
|
||||
|
||||
// get configured type by instance
|
||||
GPS_Type get_type(uint8_t instance) const {
|
||||
return instance>=GPS_MAX_RECEIVERS? GPS_Type::GPS_TYPE_NONE : GPS_Type(_type[instance].get());
|
||||
}
|
||||
|
||||
protected:
|
||||
|
||||
// configuration parameters
|
||||
|
Loading…
Reference in New Issue
Block a user