Public Member Functions | Static Public Member Functions | Protected Attributes | Private Attributes
hector_pose_estimation::PoseEstimation Class Reference

#include <pose_estimation.h>

List of all members.

Public Member Functions

InputPtr addInput (const InputPtr &input, const std::string &name=std::string())
InputPtr addInput (Input *input)
const MeasurementPtraddMeasurement (const MeasurementPtr &measurement, const std::string &name=std::string())
const MeasurementPtraddMeasurement (Measurement *measurement)
template<class ConcreteMeasurementModel >
const MeasurementPtraddMeasurement (ConcreteMeasurementModel *model, const std::string &name)
const SystemPtraddSystem (const SystemPtr &system, const std::string &name="system")
const SystemPtraddSystem (System *system)
template<typename ConcreteSystemModel >
const SystemPtraddSystem (ConcreteSystemModel *model, const std::string &name="system")
void cleanup ()
virtual boost::shared_ptr< Filterfilter ()
virtual boost::shared_ptr
< const Filter
filter () const
virtual void getBias (geometry_msgs::Vector3 &angular_velocity, geometry_msgs::Vector3 &linear_acceleration)
virtual void getBias (geometry_msgs::Vector3Stamped &angular_velocity, geometry_msgs::Vector3Stamped &linear_acceleration)
virtual const State::CovariancegetCovariance ()
virtual void getGlobalPosition (double &latitude, double &longitude, double &altitude)
virtual void getGlobalPosition (sensor_msgs::NavSatFix &global)
virtual void getHeader (std_msgs::Header &header)
virtual void getImuWithBiases (geometry_msgs::Vector3 &linear_acceleration, geometry_msgs::Vector3 &angular_velocity)
InputPtr getInput (const std::string &name) const
template<class InputType >
boost::shared_ptr< InputType > getInputType (const std::string &name) const
MeasurementPtr getMeasurement (const std::string &name) const
virtual SystemStatus getMeasurementStatus () const
virtual void getOrientation (tf::Quaternion &quaternion)
virtual void getOrientation (tf::Stamped< tf::Quaternion > &quaternion)
virtual void getOrientation (geometry_msgs::Quaternion &pose)
virtual void getOrientation (geometry_msgs::QuaternionStamped &pose)
virtual void getOrientation (double &yaw, double &pitch, double &roll)
virtual void getPose (tf::Pose &pose)
virtual void getPose (tf::Stamped< tf::Pose > &pose)
virtual void getPose (geometry_msgs::Pose &pose)
virtual void getPose (geometry_msgs::PoseStamped &pose)
virtual void getPosition (tf::Point &point)
virtual void getPosition (tf::Stamped< tf::Point > &point)
virtual void getPosition (geometry_msgs::Point &pose)
virtual void getPosition (geometry_msgs::PointStamped &pose)
virtual void getRate (tf::Vector3 &vector)
virtual void getRate (tf::Stamped< tf::Vector3 > &vector)
virtual void getRate (geometry_msgs::Vector3 &vector)
virtual void getRate (geometry_msgs::Vector3Stamped &vector)
virtual void getState (nav_msgs::Odometry &state, bool with_covariances=true)
virtual const State::VectorgetStateVector ()
SystemPtr getSystem (const std::string &name) const
const SystemModelgetSystemModel (const std::string &name) const
virtual SystemStatus getSystemStatus () const
virtual const ros::TimegetTimestamp () const
virtual void getTransforms (std::vector< tf::StampedTransform > &transforms)
virtual void getVelocity (tf::Vector3 &vector)
virtual void getVelocity (tf::Stamped< tf::Vector3 > &vector)
virtual void getVelocity (geometry_msgs::Vector3 &vector)
virtual void getVelocity (geometry_msgs::Vector3Stamped &vector)
virtual const GlobalReferencePtrglobalReference ()
bool init ()
virtual bool inSystemStatus (SystemStatus test_status) const
virtual ParameterListparameters ()
virtual const ParameterListparameters () const
 PoseEstimation (const SystemPtr &system=SystemPtr())
template<typename ConcreteSystemModel >
 PoseEstimation (ConcreteSystemModel *system_model)
template<class InputType >
boost::shared_ptr< InputType > registerInput (const std::string &name=std::string())
void reset ()
InputPtr setInput (const Input &input, std::string name=std::string())
virtual bool setMeasurementStatus (SystemStatus new_status)
virtual bool setSystemStatus (SystemStatus new_status)
virtual void setTimestamp (const ros::Time &timestamp)
virtual const Statestate () const
virtual Statestate ()
void update (ros::Time timestamp)
void update (double dt)
virtual void updated ()
virtual bool updateMeasurementStatus (SystemStatus set, SystemStatus clear)
virtual bool updateSystemStatus (SystemStatus set, SystemStatus clear)
virtual void updateWorldToOtherTransform (tf::StampedTransform &world_to_other_transform)
virtual ~PoseEstimation ()

Static Public Member Functions

static PoseEstimationInstance ()

Protected Attributes

Inputs inputs_
Measurements measurements_
Systems systems_

Private Attributes

ros::Time alignment_start_
double alignment_time_
std::string base_frame_
boost::shared_ptr< Filterfilter_
std::string footprint_frame_
double gravity_
boost::shared_ptr< Gravitygravity_update_
std::string nav_frame_
ParameterList parameters_
std::string position_frame_
boost::shared_ptr< Raterate_update_
std::string stabilized_frame_
ros::Time timestamp_
std::string world_frame_
boost::shared_ptr< ZeroRatezerorate_update_

Detailed Description

Definition at line 50 of file pose_estimation.h.


Constructor & Destructor Documentation

Definition at line 44 of file pose_estimation.cpp.

template<typename ConcreteSystemModel >
hector_pose_estimation::PoseEstimation::PoseEstimation ( ConcreteSystemModel *  system_model)

Definition at line 189 of file pose_estimation.h.

Definition at line 77 of file pose_estimation.cpp.


Member Function Documentation

InputPtr hector_pose_estimation::PoseEstimation::addInput ( const InputPtr input,
const std::string &  name = std::string() 
)

Definition at line 248 of file pose_estimation.cpp.

Definition at line 94 of file pose_estimation.h.

const MeasurementPtr & hector_pose_estimation::PoseEstimation::addMeasurement ( const MeasurementPtr measurement,
const std::string &  name = std::string() 
)

Definition at line 267 of file pose_estimation.cpp.

Definition at line 85 of file pose_estimation.h.

template<class ConcreteMeasurementModel >
const MeasurementPtr & hector_pose_estimation::PoseEstimation::addMeasurement ( ConcreteMeasurementModel *  model,
const std::string &  name 
)

Definition at line 200 of file pose_estimation.h.

const SystemPtr & hector_pose_estimation::PoseEstimation::addSystem ( const SystemPtr system,
const std::string &  name = "system" 
)

Definition at line 242 of file pose_estimation.cpp.

Definition at line 67 of file pose_estimation.h.

template<typename ConcreteSystemModel >
const SystemPtr & hector_pose_estimation::PoseEstimation::addSystem ( ConcreteSystemModel *  model,
const std::string &  name = "system" 
)

Definition at line 194 of file pose_estimation.h.

Definition at line 121 of file pose_estimation.cpp.

virtual boost::shared_ptr<Filter> hector_pose_estimation::PoseEstimation::filter ( ) [inline, virtual]

Definition at line 154 of file pose_estimation.h.

virtual boost::shared_ptr<const Filter> hector_pose_estimation::PoseEstimation::filter ( ) const [inline, virtual]

Definition at line 155 of file pose_estimation.h.

void hector_pose_estimation::PoseEstimation::getBias ( geometry_msgs::Vector3 &  angular_velocity,
geometry_msgs::Vector3 &  linear_acceleration 
) [virtual]

Definition at line 609 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getBias ( geometry_msgs::Vector3Stamped &  angular_velocity,
geometry_msgs::Vector3Stamped &  linear_acceleration 
) [virtual]

Definition at line 635 of file pose_estimation.cpp.

Definition at line 281 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getGlobalPosition ( double &  latitude,
double &  longitude,
double &  altitude 
) [virtual]

Definition at line 431 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getGlobalPosition ( sensor_msgs::NavSatFix &  global) [virtual]

Definition at line 440 of file pose_estimation.cpp.

Definition at line 325 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getImuWithBiases ( geometry_msgs::Vector3 &  linear_acceleration,
geometry_msgs::Vector3 &  angular_velocity 
) [virtual]

Definition at line 496 of file pose_estimation.cpp.

InputPtr hector_pose_estimation::PoseEstimation::getInput ( const std::string &  name) const [inline]

Definition at line 97 of file pose_estimation.h.

template<class InputType >
boost::shared_ptr<InputType> hector_pose_estimation::PoseEstimation::getInputType ( const std::string &  name) const [inline]

Definition at line 91 of file pose_estimation.h.

MeasurementPtr hector_pose_estimation::PoseEstimation::getMeasurement ( const std::string &  name) const [inline]

Definition at line 88 of file pose_estimation.h.

Definition at line 293 of file pose_estimation.cpp.

Definition at line 462 of file pose_estimation.cpp.

Definition at line 467 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getOrientation ( geometry_msgs::Quaternion &  pose) [virtual]

Definition at line 473 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getOrientation ( geometry_msgs::QuaternionStamped &  pose) [virtual]

Definition at line 481 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getOrientation ( double &  yaw,
double &  pitch,
double &  roll 
) [virtual]

Definition at line 486 of file pose_estimation.cpp.

Definition at line 385 of file pose_estimation.cpp.

Definition at line 392 of file pose_estimation.cpp.

Definition at line 398 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getPose ( geometry_msgs::PoseStamped &  pose) [virtual]

Definition at line 403 of file pose_estimation.cpp.

Definition at line 408 of file pose_estimation.cpp.

Definition at line 413 of file pose_estimation.cpp.

Definition at line 419 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getPosition ( geometry_msgs::PointStamped &  pose) [virtual]

Definition at line 426 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getRate ( tf::Vector3 &  vector) [virtual]

Definition at line 549 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getRate ( tf::Stamped< tf::Vector3 > &  vector) [virtual]

Definition at line 555 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getRate ( geometry_msgs::Vector3 &  vector) [virtual]

Definition at line 565 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getRate ( geometry_msgs::Vector3Stamped &  vector) [virtual]

Definition at line 594 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getState ( nav_msgs::Odometry &  state,
bool  with_covariances = true 
) [virtual]

Definition at line 330 of file pose_estimation.cpp.

Definition at line 273 of file pose_estimation.cpp.

SystemPtr hector_pose_estimation::PoseEstimation::getSystem ( const std::string &  name) const [inline]

Definition at line 70 of file pose_estimation.h.

const SystemModel* hector_pose_estimation::PoseEstimation::getSystemModel ( const std::string &  name) const [inline]

Definition at line 78 of file pose_estimation.h.

Definition at line 289 of file pose_estimation.cpp.

Definition at line 317 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getTransforms ( std::vector< tf::StampedTransform > &  transforms) [virtual]

Definition at line 643 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getVelocity ( tf::Vector3 &  vector) [virtual]

Definition at line 519 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getVelocity ( tf::Stamped< tf::Vector3 > &  vector) [virtual]

Definition at line 524 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getVelocity ( geometry_msgs::Vector3 &  vector) [virtual]

Definition at line 534 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getVelocity ( geometry_msgs::Vector3Stamped &  vector) [virtual]

Definition at line 541 of file pose_estimation.cpp.

Definition at line 723 of file pose_estimation.cpp.

Definition at line 87 of file pose_estimation.cpp.

Definition at line 82 of file pose_estimation.cpp.

Definition at line 297 of file pose_estimation.cpp.

Definition at line 151 of file pose_estimation.h.

virtual const ParameterList& hector_pose_estimation::PoseEstimation::parameters ( ) const [inline, virtual]

Definition at line 152 of file pose_estimation.h.

template<class InputType >
boost::shared_ptr< InputType > hector_pose_estimation::PoseEstimation::registerInput ( const std::string &  name = std::string())

Definition at line 205 of file pose_estimation.h.

Definition at line 133 of file pose_estimation.cpp.

InputPtr hector_pose_estimation::PoseEstimation::setInput ( const Input input,
std::string  name = std::string() 
)

Definition at line 254 of file pose_estimation.cpp.

Definition at line 305 of file pose_estimation.cpp.

Definition at line 301 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::setTimestamp ( const ros::Time timestamp) [virtual]

Definition at line 321 of file pose_estimation.cpp.

virtual const State& hector_pose_estimation::PoseEstimation::state ( ) const [inline, virtual]

Definition at line 99 of file pose_estimation.h.

virtual State& hector_pose_estimation::PoseEstimation::state ( ) [inline, virtual]

Definition at line 100 of file pose_estimation.h.

Definition at line 160 of file pose_estimation.cpp.

Definition at line 173 of file pose_estimation.cpp.

Definition at line 236 of file pose_estimation.cpp.

Definition at line 313 of file pose_estimation.cpp.

Definition at line 309 of file pose_estimation.cpp.

Definition at line 711 of file pose_estimation.cpp.


Member Data Documentation

Definition at line 177 of file pose_estimation.h.

Definition at line 178 of file pose_estimation.h.

Definition at line 172 of file pose_estimation.h.

Definition at line 165 of file pose_estimation.h.

Definition at line 174 of file pose_estimation.h.

Definition at line 180 of file pose_estimation.h.

Definition at line 183 of file pose_estimation.h.

Definition at line 162 of file pose_estimation.h.

Definition at line 161 of file pose_estimation.h.

Definition at line 171 of file pose_estimation.h.

Definition at line 167 of file pose_estimation.h.

Definition at line 175 of file pose_estimation.h.

Definition at line 182 of file pose_estimation.h.

Definition at line 173 of file pose_estimation.h.

Definition at line 160 of file pose_estimation.h.

Definition at line 169 of file pose_estimation.h.

Definition at line 170 of file pose_estimation.h.

Definition at line 184 of file pose_estimation.h.


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


hector_pose_estimation_core
Author(s): Johannes Meyer
autogenerated on Mon Oct 6 2014 00:24:16