mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_GPS: added get_semaphore()
This commit is contained in:
parent
dc3e345a05
commit
f0d1d3fa90
@ -772,6 +772,8 @@ void AP_GPS::update_instance(uint8_t instance)
|
||||
*/
|
||||
void AP_GPS::update(void)
|
||||
{
|
||||
WITH_SEMAPHORE(rsem);
|
||||
|
||||
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
|
||||
update_instance(i);
|
||||
}
|
||||
|
@ -74,6 +74,11 @@ public:
|
||||
return _singleton;
|
||||
}
|
||||
|
||||
// allow threads to lock against GPS update
|
||||
HAL_Semaphore &get_semaphore(void) {
|
||||
return rsem;
|
||||
}
|
||||
|
||||
// GPS driver types
|
||||
enum GPS_Type {
|
||||
GPS_TYPE_NONE = 0,
|
||||
@ -488,6 +493,7 @@ protected:
|
||||
|
||||
private:
|
||||
static AP_GPS *_singleton;
|
||||
HAL_Semaphore_Recursive rsem;
|
||||
|
||||
// returns the desired gps update rate in milliseconds
|
||||
// this does not provide any guarantee that the GPS is updating at the requested
|
||||
|
Loading…
Reference in New Issue
Block a user