Classes | Public Types | Public Member Functions | Static Public Member Functions | Private Member Functions | Private Attributes | List of all members
hector_pose_estimation::GlobalReference Class Reference

#include <global_reference.h>

Classes

struct  Heading
 
struct  Position
 
struct  Radius
 

Public Types

typedef boost::function< void()> UpdateCallback
 

Public Member Functions

void addUpdateCallback (const UpdateCallback &)
 
void fromAltitude (double altitude, double &z)
 
void fromNorthEast (double north, double east, double &x, double &y)
 
void fromWGS84 (double latitude, double longitude, double &x, double &y)
 
void getGeoPose (geographic_msgs::GeoPose &geopose) const
 
bool getWorldToNavTransform (geometry_msgs::TransformStamped &transform, const std::string &world_frame, const std::string &nav_frame, const ros::Time &stamp=ros::Time()) const
 
bool hasAltitude () const
 
bool hasHeading () const
 
bool hasPosition () const
 
const Headingheading () const
 
ParameterListparameters ()
 
const Positionposition () const
 
const Radiusradius () const
 
void reset ()
 
GlobalReferencesetAltitude (double altitude, bool intermediate=false)
 
GlobalReferencesetCurrentAltitude (const State &state, double altitude)
 
GlobalReferencesetCurrentHeading (const State &state, double heading)
 
GlobalReferencesetCurrentPosition (const State &state, double latitude, double longitude)
 
GlobalReferencesetHeading (double heading, bool intermediate=false)
 
GlobalReferencesetPosition (double latitude, double longitude, bool intermediate=false)
 
void toAltitude (double z, double &altitude)
 
void toNorthEast (double x, double y, double &north, double &east)
 
void toWGS84 (double x, double y, double &latitude, double &longitude)
 
void updated (bool intermediate=false)
 

Static Public Member Functions

static const GlobalReferencePtrInstance ()
 

Private Member Functions

 GlobalReference ()
 

Private Attributes

Heading heading_
 
ParameterList parameters_
 
Position position_
 
Radius radius_
 
double reference_altitude_
 
double reference_heading_
 
double reference_latitude_
 
double reference_longitude_
 
std::list< UpdateCallbackupdate_callbacks_
 

Detailed Description

Definition at line 45 of file global_reference.h.

Member Typedef Documentation

Definition at line 104 of file global_reference.h.

Constructor & Destructor Documentation

hector_pose_estimation::GlobalReference::GlobalReference ( )
private

Definition at line 39 of file global_reference.cpp.

Member Function Documentation

void hector_pose_estimation::GlobalReference::addUpdateCallback ( const UpdateCallback cb)

Definition at line 269 of file global_reference.cpp.

void hector_pose_estimation::GlobalReference::fromAltitude ( double  altitude,
double &  z 
)
void hector_pose_estimation::GlobalReference::fromNorthEast ( double  north,
double  east,
double &  x,
double &  y 
)

Definition at line 141 of file global_reference.cpp.

void hector_pose_estimation::GlobalReference::fromWGS84 ( double  latitude,
double  longitude,
double &  x,
double &  y 
)

Definition at line 117 of file global_reference.cpp.

void hector_pose_estimation::GlobalReference::getGeoPose ( geographic_msgs::GeoPose &  geopose) const

Definition at line 226 of file global_reference.cpp.

bool hector_pose_estimation::GlobalReference::getWorldToNavTransform ( geometry_msgs::TransformStamped &  transform,
const std::string &  world_frame,
const std::string &  nav_frame,
const ros::Time stamp = ros::Time() 
) const

Definition at line 238 of file global_reference.cpp.

bool hector_pose_estimation::GlobalReference::hasAltitude ( ) const
inline

Definition at line 88 of file global_reference.h.

bool hector_pose_estimation::GlobalReference::hasHeading ( ) const
inline

Definition at line 87 of file global_reference.h.

bool hector_pose_estimation::GlobalReference::hasPosition ( ) const
inline

Definition at line 86 of file global_reference.h.

const Heading& hector_pose_estimation::GlobalReference::heading ( ) const
inline

Definition at line 72 of file global_reference.h.

const GlobalReferencePtr & hector_pose_estimation::GlobalReference::Instance ( )
static

Definition at line 49 of file global_reference.cpp.

ParameterList & hector_pose_estimation::GlobalReference::parameters ( )

Definition at line 71 of file global_reference.cpp.

const Position& hector_pose_estimation::GlobalReference::position ( ) const
inline

Definition at line 71 of file global_reference.h.

const Radius& hector_pose_estimation::GlobalReference::radius ( ) const
inline

Definition at line 73 of file global_reference.h.

void hector_pose_estimation::GlobalReference::reset ( )

Definition at line 56 of file global_reference.cpp.

GlobalReference & hector_pose_estimation::GlobalReference::setAltitude ( double  altitude,
bool  intermediate = false 
)

Definition at line 176 of file global_reference.cpp.

GlobalReference & hector_pose_estimation::GlobalReference::setCurrentAltitude ( const State state,
double  altitude 
)

Definition at line 220 of file global_reference.cpp.

GlobalReference & hector_pose_estimation::GlobalReference::setCurrentHeading ( const State state,
double  heading 
)

Definition at line 198 of file global_reference.cpp.

GlobalReference & hector_pose_estimation::GlobalReference::setCurrentPosition ( const State state,
double  latitude,
double  longitude 
)

Definition at line 183 of file global_reference.cpp.

GlobalReference & hector_pose_estimation::GlobalReference::setHeading ( double  heading,
bool  intermediate = false 
)

Definition at line 169 of file global_reference.cpp.

GlobalReference & hector_pose_estimation::GlobalReference::setPosition ( double  latitude,
double  longitude,
bool  intermediate = false 
)

Definition at line 161 of file global_reference.cpp.

void hector_pose_estimation::GlobalReference::toAltitude ( double  z,
double &  altitude 
)
void hector_pose_estimation::GlobalReference::toNorthEast ( double  x,
double  y,
double &  north,
double &  east 
)

Definition at line 151 of file global_reference.cpp.

void hector_pose_estimation::GlobalReference::toWGS84 ( double  x,
double  y,
double &  latitude,
double &  longitude 
)

Definition at line 128 of file global_reference.cpp.

void hector_pose_estimation::GlobalReference::updated ( bool  intermediate = false)

Definition at line 75 of file global_reference.cpp.

Member Data Documentation

Heading hector_pose_estimation::GlobalReference::heading_
private

Definition at line 111 of file global_reference.h.

ParameterList hector_pose_estimation::GlobalReference::parameters_
private

Definition at line 114 of file global_reference.h.

Position hector_pose_estimation::GlobalReference::position_
private

Definition at line 110 of file global_reference.h.

Radius hector_pose_estimation::GlobalReference::radius_
private

Definition at line 112 of file global_reference.h.

double hector_pose_estimation::GlobalReference::reference_altitude_
private

Definition at line 117 of file global_reference.h.

double hector_pose_estimation::GlobalReference::reference_heading_
private

Definition at line 118 of file global_reference.h.

double hector_pose_estimation::GlobalReference::reference_latitude_
private

Definition at line 115 of file global_reference.h.

double hector_pose_estimation::GlobalReference::reference_longitude_
private

Definition at line 116 of file global_reference.h.

std::list<UpdateCallback> hector_pose_estimation::GlobalReference::update_callbacks_
private

Definition at line 120 of file global_reference.h.


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


hector_pose_estimation_core
Author(s): Johannes Meyer
autogenerated on Thu Feb 18 2021 03:29:31