#include <gps.h>
Public Member Functions | |
void | close () |
bool | configure () |
template<typename ConfigT > | |
bool | configure (const ConfigT &message, bool wait=true) |
bool | enableSBAS (bool onoff) |
Gps () | |
template<typename StreamT > | |
void | initialize (StreamT &stream, boost::asio::io_service &io_service) |
void | initialize (const boost::shared_ptr< Worker > &worker) |
template<> | |
void | initialize (boost::asio::serial_port &serial_port, boost::asio::io_service &io_service) |
bool | isConfigured () const |
bool | isInitialized () const |
template<typename ConfigT > | |
bool | poll (ConfigT &message, const boost::posix_time::time_duration &timeout=default_timeout_) |
bool | poll (uint8_t class_id, uint8_t message_id, const std::vector< uint8_t > &payload=std::vector< uint8_t >()) |
template<typename T > | |
bool | read (T &message, const boost::posix_time::time_duration &timeout=default_timeout_) |
bool | setBaudrate (unsigned int baudrate) |
bool | setRate (uint8_t class_id, uint8_t message_id, unsigned int rate) |
template<typename T > | |
Callbacks::iterator | subscribe (typename CallbackHandler_< T >::Callback callback, unsigned int rate) |
template<typename T > | |
Callbacks::iterator | subscribe (typename CallbackHandler_< T >::Callback callback) |
void | waitForAcknowledge (const boost::posix_time::time_duration &timeout) |
virtual | ~Gps () |
Private Types | |
enum | { WAIT, ACK, NACK } |
Private Member Functions | |
void | readCallback (unsigned char *data, std::size_t &size) |
Private Attributes | |
enum ublox_gps::Gps:: { ... } | acknowledge_ |
unsigned int | baudrate_ |
boost::mutex | callback_mutex_ |
Callbacks | callbacks_ |
bool | configured_ |
boost::shared_ptr< Worker > | worker_ |
Static Private Attributes | |
static boost::posix_time::time_duration | default_timeout_ |
ublox_gps::Gps::~Gps | ( | ) | [virtual] |
void ublox_gps::Gps::close | ( | ) |
bool ublox_gps::Gps::configure | ( | ) |
bool ublox_gps::Gps::configure | ( | const ConfigT & | message, |
bool | wait = true |
||
) |
bool ublox_gps::Gps::enableSBAS | ( | bool | onoff | ) |
void ublox_gps::Gps::initialize | ( | StreamT & | stream, |
boost::asio::io_service & | io_service | ||
) |
void ublox_gps::Gps::initialize | ( | const boost::shared_ptr< Worker > & | worker | ) |
void ublox_gps::Gps::initialize | ( | boost::asio::serial_port & | serial_port, |
boost::asio::io_service & | io_service | ||
) |
bool ublox_gps::Gps::isConfigured | ( | ) | const [inline] |
bool ublox_gps::Gps::isInitialized | ( | ) | const [inline] |
bool ublox_gps::Gps::poll | ( | ConfigT & | message, |
const boost::posix_time::time_duration & | timeout = default_timeout_ |
||
) |
bool ublox_gps::Gps::poll | ( | uint8_t | class_id, |
uint8_t | message_id, | ||
const std::vector< uint8_t > & | payload = std::vector<uint8_t>() |
||
) |
bool ublox_gps::Gps::read | ( | T & | message, |
const boost::posix_time::time_duration & | timeout = default_timeout_ |
||
) |
void ublox_gps::Gps::readCallback | ( | unsigned char * | data, |
std::size_t & | size | ||
) | [private] |
bool ublox_gps::Gps::setBaudrate | ( | unsigned int | baudrate | ) |
bool ublox_gps::Gps::setRate | ( | uint8_t | class_id, |
uint8_t | message_id, | ||
unsigned int | rate | ||
) |
Callbacks::iterator ublox_gps::Gps::subscribe | ( | typename CallbackHandler_< T >::Callback | callback, |
unsigned int | rate | ||
) |
Callbacks::iterator ublox_gps::Gps::subscribe | ( | typename CallbackHandler_< T >::Callback | callback | ) |
void ublox_gps::Gps::waitForAcknowledge | ( | const boost::posix_time::time_duration & | timeout | ) |
enum { ... } ublox_gps::Gps::acknowledge_ [private] |
unsigned int ublox_gps::Gps::baudrate_ [private] |
boost::mutex ublox_gps::Gps::callback_mutex_ [private] |
Callbacks ublox_gps::Gps::callbacks_ [private] |
bool ublox_gps::Gps::configured_ [private] |
boost::posix_time::time_duration ublox_gps::Gps::default_timeout_ [static, private] |
boost::shared_ptr<Worker> ublox_gps::Gps::worker_ [private] |