mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
Make the GPS ctor protected so that it can't be accidentally constructed or copied.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1353 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
b006aa6179
commit
02d6b6414f
@ -15,15 +15,6 @@ class GPS
|
|||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
|
|
||||||
/// Constructor
|
|
||||||
///
|
|
||||||
/// @note The stream is expected to be set up and configured for the
|
|
||||||
/// correct bitrate before ::init is called.
|
|
||||||
///
|
|
||||||
/// @param s Stream connected to the GPS module.
|
|
||||||
///
|
|
||||||
GPS(Stream *s) : _port(s) {};
|
|
||||||
|
|
||||||
/// Update GPS state based on possible bytes received from the module.
|
/// Update GPS state based on possible bytes received from the module.
|
||||||
///
|
///
|
||||||
/// This routine must be called periodically to process incoming data.
|
/// This routine must be called periodically to process incoming data.
|
||||||
@ -87,6 +78,15 @@ public:
|
|||||||
protected:
|
protected:
|
||||||
Stream *_port; ///< port the GPS is attached to
|
Stream *_port; ///< port the GPS is attached to
|
||||||
|
|
||||||
|
/// Constructor
|
||||||
|
///
|
||||||
|
/// @note The stream is expected to be set up and configured for the
|
||||||
|
/// correct bitrate before ::init is called.
|
||||||
|
///
|
||||||
|
/// @param s Stream connected to the GPS module.
|
||||||
|
///
|
||||||
|
GPS(Stream *s) : _port(s) {};
|
||||||
|
|
||||||
/// read from the GPS stream and update properties
|
/// read from the GPS stream and update properties
|
||||||
///
|
///
|
||||||
/// Must be implemented by the GPS driver.
|
/// Must be implemented by the GPS driver.
|
||||||
|
Loading…
Reference in New Issue
Block a user