Skip to content

Commit

Permalink
fsfs
Browse files Browse the repository at this point in the history
  • Loading branch information
khancyr committed Nov 21, 2024
1 parent dff0f6f commit b4904b5
Show file tree
Hide file tree
Showing 5 changed files with 108 additions and 0 deletions.
12 changes: 12 additions & 0 deletions libraries/AP_GPS/AP_GPS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,9 @@
#include "AP_GPS_MAV.h"
#include "AP_GPS_MSP.h"
#include "AP_GPS_ExternalAHRS.h"
#if AP_GPS_GPSD_ENABLED
#include "AP_GPS_GPSD.h"
#endif
#include "GPS_Backend.h"
#if HAL_SIM_GPS_ENABLED
#include "AP_GPS_SITL.h"
Expand Down Expand Up @@ -564,6 +567,9 @@ void AP_GPS::send_blob_start(uint8_t instance)
#if HAL_SIM_GPS_ENABLED
case GPS_TYPE_SITL:
#endif // HAL_SIM_GPS_ENABLED
#if AP_GPS_GPSD_ENABLED
case GPS_TYPE_GPSD:
#endif //AP_GPS_GPSD_ENABLED
// none of these GPSs have initialisation blobs
break;
default:
Expand Down Expand Up @@ -673,6 +679,11 @@ AP_GPS_Backend *AP_GPS::_detect_instance(uint8_t instance)
dstate->auto_detected_baud = false; // specified, not detected
return NEW_NOTHROW AP_GPS_GSOF(*this, params[instance], state[instance], _port[instance]);
#endif //AP_GPS_GSOF_ENABLED
#if AP_GPS_GPSD_ENABLED
case GPS_TYPE_GPSD:
dstate->auto_detected_baud = false; // specified, not detected
return NEW_NOTHROW AP_GPS_GPSD(*this, params[instance], state[instance], _port[instance]);
#endif //AP_GPS_GPSD_ENABLED
default:
break;
}
Expand Down Expand Up @@ -895,6 +906,7 @@ void AP_GPS::update_instance(uint8_t instance)
// do not try to detect again if type is MAV or UAVCAN
if (type == GPS_TYPE_MAV ||
type == GPS_TYPE_UAVCAN ||
type == GPS_TYPE_GPSD ||
type == GPS_TYPE_UAVCAN_RTK_BASE ||
type == GPS_TYPE_UAVCAN_RTK_ROVER) {
state[instance].status = NO_FIX;
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_GPS/AP_GPS.h
Original file line number Diff line number Diff line change
Expand Up @@ -112,6 +112,7 @@ class AP_GPS
GPS_TYPE_UNICORE_NMEA = 24,
GPS_TYPE_UNICORE_MOVINGBASE_NMEA = 25,
GPS_TYPE_SBF_DUAL_ANTENNA = 26,
GPS_TYPE_GPSD = 27,
#if HAL_SIM_GPS_ENABLED
GPS_TYPE_SITL = 100,
#endif
Expand Down
38 changes: 38 additions & 0 deletions libraries/AP_GPS/AP_GPSD.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/

//
// GPSD GPS driver
//

#include "AP_GPS_config.h"

#if AP_GPS_GPSD_ENABLED

#include "AP_GPS_GPSD.h"
#include <stdint.h>

#endif //AP_GPS_GPSD_ENABLED


bool AP_GPS_GPSD::read(void)
{
if (_new_data) {
_new_data = false;
return true;
}

return false;
}
53 changes: 53 additions & 0 deletions libraries/AP_GPS/AP_GPSD.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,53 @@
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/

//
// GPSD GPS driver which accepts gps position data from a GPSD deamon
// Initial code by Pierre Kancir
//

#pragma once

#include "AP_GPS_config.h"

#if AP_GPS_GPSD_ENABLED

#include "AP_GPS.h"
#include "GPS_Backend.h"

#include <AP_HAL/AP_HAL.h>

#include <libgpsmm.h>

class AP_GPS_GPSD : public AP_GPS_Backend
{
public:
using AP_GPS_Backend::AP_GPS_Backend;

// Methods
bool read() override;

// driver specific health, returns true if the driver is healthy
bool is_healthy(void) const override;

bool is_configured(void) const override {
return true;
}

private:
gpsmm gps_rec;
struct gps_data_t* newdata;

#endif //AP_GPS_GPSD_ENABLED
4 changes: 4 additions & 0 deletions libraries/AP_GPS/AP_GPS_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -97,6 +97,10 @@
#define AP_GPS_UBLOX_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED
#endif

#ifndef AP_GPS_GPSD_ENABLED
#define AP_GPS_GPSD_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX)
#endif

#ifndef AP_GPS_RTCM_DECODE_ENABLED
#define AP_GPS_RTCM_DECODE_ENABLED BOARD_FLASH_SIZE > 1024
#endif
Expand Down

0 comments on commit b4904b5

Please sign in to comment.