mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 23:18:29 -04:00
AP_GPS: added lock_port() interface
used by SERIAL_CONTROL message
This commit is contained in:
parent
b8675b9abc
commit
67ed5b73ef
@ -207,6 +207,11 @@ AP_GPS::update_instance(uint8_t instance)
|
||||
state[instance].status = NO_GPS;
|
||||
return;
|
||||
}
|
||||
if (locked_ports & (1U<<instance)) {
|
||||
// the port is locked by another driver
|
||||
return;
|
||||
}
|
||||
|
||||
if (drivers[instance] == NULL || state[instance].status == NO_GPS) {
|
||||
// we don't yet know the GPS type of this one, or it has timed
|
||||
// out and needs to be re-initialised
|
||||
@ -311,3 +316,21 @@ AP_GPS::setHIL(uint8_t instance, GPS_Status _status, uint64_t time_epoch_ms,
|
||||
timing[instance].last_fix_time_ms = tnow;
|
||||
_type[instance].set(GPS_TYPE_HIL);
|
||||
}
|
||||
|
||||
/**
|
||||
Lock a GPS port, prevening the GPS driver from using it. This can
|
||||
be used to allow a user to control a GPS port via the
|
||||
SERIAL_CONTROL protocol
|
||||
*/
|
||||
void
|
||||
AP_GPS::lock_port(uint8_t instance, bool lock)
|
||||
{
|
||||
if (instance >= GPS_MAX_INSTANCES) {
|
||||
return;
|
||||
}
|
||||
if (lock) {
|
||||
locked_ports |= (1U<<instance);
|
||||
} else {
|
||||
locked_ports &= ~(1U<<instance);
|
||||
}
|
||||
}
|
||||
|
@ -258,6 +258,9 @@ public:
|
||||
void send_blob_start(uint8_t instance, const prog_char *_blob, uint16_t size);
|
||||
void send_blob_update(uint8_t instance);
|
||||
|
||||
// lock out a GPS port, allowing another application to use the port
|
||||
void lock_port(uint8_t instance, bool locked);
|
||||
|
||||
private:
|
||||
struct GPS_timing {
|
||||
// the time we got our last fix in system milliseconds
|
||||
@ -276,6 +279,9 @@ private:
|
||||
/// number of GPS instances present
|
||||
uint8_t num_instances:2;
|
||||
|
||||
// which ports are locked
|
||||
uint8_t locked_ports:2;
|
||||
|
||||
// state of auto-detection process, per instance
|
||||
struct detect_state {
|
||||
uint32_t detect_started_ms;
|
||||
|
Loading…
Reference in New Issue
Block a user