Public Member Functions | Private Member Functions | Private Attributes
labust::navigation::GPSHandler Class Reference

#include <SensorHandlers.hpp>

Inheritance diagram for labust::navigation::GPSHandler:
Inheritance graph
[legend]

List of all members.

Public Member Functions

void configure (ros::NodeHandle &nh)
 GPSHandler ()
const std::pair< double, double > & latlon () const
const std::pair< double, double > & origin () const
const std::pair< double, double > & position () const
void setRotation (const Eigen::Quaternion< double > &quat)

Private Member Functions

void onGps (const sensor_msgs::NavSatFix::ConstPtr &data)

Private Attributes

tf2_ros::Buffer buffer
ros::Subscriber gps
tf2_ros::TransformListener listener
std::pair< double, double > originLL
std::pair< double, double > posLL
std::pair< double, double > posxy
Eigen::Quaternion< double > rot

Detailed Description

The GPS handler.

Definition at line 74 of file SensorHandlers.hpp.


Constructor & Destructor Documentation

Definition at line 77 of file SensorHandlers.hpp.


Member Function Documentation

Definition at line 44 of file SensorHandlers.cpp.

const std::pair<double, double>& labust::navigation::GPSHandler::latlon ( ) const [inline]

Definition at line 87 of file SensorHandlers.hpp.

void GPSHandler::onGps ( const sensor_msgs::NavSatFix::ConstPtr &  data) [private]

Definition at line 50 of file SensorHandlers.cpp.

const std::pair<double, double>& labust::navigation::GPSHandler::origin ( ) const [inline]

Definition at line 84 of file SensorHandlers.hpp.

const std::pair<double, double>& labust::navigation::GPSHandler::position ( ) const [inline]

Definition at line 81 of file SensorHandlers.hpp.

void labust::navigation::GPSHandler::setRotation ( const Eigen::Quaternion< double > &  quat) [inline]

Definition at line 89 of file SensorHandlers.hpp.


Member Data Documentation

Definition at line 94 of file SensorHandlers.hpp.

Definition at line 96 of file SensorHandlers.hpp.

Definition at line 95 of file SensorHandlers.hpp.

std::pair<double, double> labust::navigation::GPSHandler::originLL [private]

Definition at line 93 of file SensorHandlers.hpp.

std::pair<double, double> labust::navigation::GPSHandler::posLL [private]

Definition at line 93 of file SensorHandlers.hpp.

std::pair<double, double> labust::navigation::GPSHandler::posxy [private]

Definition at line 93 of file SensorHandlers.hpp.

Eigen::Quaternion<double> labust::navigation::GPSHandler::rot [private]

Definition at line 97 of file SensorHandlers.hpp.


The documentation for this class was generated from the following files:


labust_navigation
Author(s): Gyula Nagy
autogenerated on Fri Aug 28 2015 11:23:33