Public Member Functions | Static Public Member Functions | Protected Attributes | Private Attributes | List of all members
hector_pose_estimation::PoseEstimation Class Reference

#include <pose_estimation.h>

Public Member Functions

template<class InputType >
boost::shared_ptr< InputType > addInput (const std::string &name=std::string())
 
InputPtr addInput (const InputPtr &input, const std::string &name=std::string())
 
InputPtr addInput (Input *input, const std::string &name=std::string())
 
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 Filterfilter () 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 getGlobal (double &latitude, double &longitude, double &altitude)
 
virtual void getGlobal (geographic_msgs::GeoPoint &global)
 
virtual void getGlobal (sensor_msgs::NavSatFix &global)
 
virtual void getGlobal (geographic_msgs::GeoPoint &position, geometry_msgs::Quaternion &quaternion)
 
virtual void getGlobal (geographic_msgs::GeoPose &global)
 
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
 
template<typename MeasurementType >
boost::shared_ptr< MeasurementType > 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
 
template<typename SystemType >
boost::shared_ptr< SystemType > getSystem_ (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 bool getWorldToNavTransform (geometry_msgs::TransformStamped &transform)
 
virtual const GlobalReferencePtrglobalReference ()
 
bool init ()
 
virtual bool inSystemStatus (SystemStatus test_status) const
 
virtual ParameterListparameters ()
 
virtual const ParameterListparameters () const
 
 PoseEstimation (const SystemPtr &system=SystemPtr(), const StatePtr &state=StatePtr())
 
template<typename ConcreteSystemModel >
 PoseEstimation (ConcreteSystemModel *system_model, State *state=0)
 
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_
 
FilterPtr filter_
 
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_
 
StatePtr state_
 
ros::Time timestamp_
 
std::string world_frame_
 
boost::shared_ptr< ZeroRatezerorate_update_
 

Detailed Description

Definition at line 60 of file pose_estimation.h.

Constructor & Destructor Documentation

hector_pose_estimation::PoseEstimation::PoseEstimation ( const SystemPtr system = SystemPtr(),
const StatePtr state = StatePtr() 
)

Definition at line 44 of file pose_estimation.cpp.

template<typename ConcreteSystemModel >
hector_pose_estimation::PoseEstimation::PoseEstimation ( ConcreteSystemModel *  system_model,
State state = 0 
)

Definition at line 195 of file pose_estimation.h.

hector_pose_estimation::PoseEstimation::~PoseEstimation ( )
virtual

Definition at line 78 of file pose_estimation.cpp.

Member Function Documentation

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

Definition at line 223 of file pose_estimation.h.

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

Definition at line 285 of file pose_estimation.cpp.

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

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 304 of file pose_estimation.cpp.

const MeasurementPtr& hector_pose_estimation::PoseEstimation::addMeasurement ( Measurement measurement)
inline

Definition at line 84 of file pose_estimation.h.

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

Definition at line 212 of file pose_estimation.h.

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

Definition at line 279 of file pose_estimation.cpp.

const SystemPtr& hector_pose_estimation::PoseEstimation::addSystem ( System system)
inline

Definition at line 77 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 200 of file pose_estimation.h.

void hector_pose_estimation::PoseEstimation::cleanup ( )

Definition at line 126 of file pose_estimation.cpp.

virtual boost::shared_ptr<Filter> hector_pose_estimation::PoseEstimation::filter ( )
inlinevirtual

Definition at line 160 of file pose_estimation.h.

virtual boost::shared_ptr<const Filter> hector_pose_estimation::PoseEstimation::filter ( ) const
inlinevirtual

Definition at line 161 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 654 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 679 of file pose_estimation.cpp.

const State::Covariance & hector_pose_estimation::PoseEstimation::getCovariance ( )
virtual

Definition at line 318 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getGlobal ( double &  latitude,
double &  longitude,
double &  altitude 
)
virtual

Definition at line 465 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getGlobal ( geographic_msgs::GeoPoint &  global)
virtual

Definition at line 478 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getGlobal ( sensor_msgs::NavSatFix &  global)
virtual

Definition at line 485 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getGlobal ( geographic_msgs::GeoPoint &  position,
geometry_msgs::Quaternion &  quaternion 
)
virtual

Definition at line 512 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getGlobal ( geographic_msgs::GeoPose &  global)
virtual

Definition at line 522 of file pose_estimation.cpp.

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

Definition at line 474 of file pose_estimation.cpp.

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

Definition at line 507 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getHeader ( std_msgs::Header header)
virtual

Definition at line 362 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 561 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 90 of file pose_estimation.h.

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

Definition at line 87 of file pose_estimation.h.

template<typename MeasurementType >
boost::shared_ptr< MeasurementType > hector_pose_estimation::PoseEstimation::getMeasurement_ ( const std::string &  name) const

Definition at line 217 of file pose_estimation.h.

SystemStatus hector_pose_estimation::PoseEstimation::getMeasurementStatus ( ) const
virtual

Definition at line 330 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getOrientation ( tf::Quaternion quaternion)
virtual

Definition at line 527 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getOrientation ( tf::Stamped< tf::Quaternion > &  quaternion)
virtual

Definition at line 532 of file pose_estimation.cpp.

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

Definition at line 538 of file pose_estimation.cpp.

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

Definition at line 546 of file pose_estimation.cpp.

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

Definition at line 551 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getPose ( tf::Pose pose)
virtual

Definition at line 419 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getPose ( tf::Stamped< tf::Pose > &  pose)
virtual

Definition at line 426 of file pose_estimation.cpp.

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

Definition at line 437 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getPosition ( tf::Point point)
virtual

Definition at line 442 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getPosition ( tf::Stamped< tf::Point > &  point)
virtual

Definition at line 447 of file pose_estimation.cpp.

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

Definition at line 460 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getRate ( tf::Vector3 vector)
virtual

Definition at line 607 of file pose_estimation.cpp.

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

Definition at line 613 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getRate ( geometry_msgs::Vector3 vector)
virtual

Definition at line 619 of file pose_estimation.cpp.

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

Definition at line 648 of file pose_estimation.cpp.

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

Definition at line 367 of file pose_estimation.cpp.

const State::Vector & hector_pose_estimation::PoseEstimation::getStateVector ( )
virtual

Definition at line 310 of file pose_estimation.cpp.

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

Definition at line 80 of file pose_estimation.h.

template<typename SystemType >
boost::shared_ptr< SystemType > hector_pose_estimation::PoseEstimation::getSystem_ ( const std::string &  name) const

Definition at line 206 of file pose_estimation.h.

SystemStatus hector_pose_estimation::PoseEstimation::getSystemStatus ( ) const
virtual

Definition at line 326 of file pose_estimation.cpp.

const ros::Time & hector_pose_estimation::PoseEstimation::getTimestamp ( ) const
virtual

Definition at line 354 of file pose_estimation.cpp.

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

Definition at line 687 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getVelocity ( tf::Vector3 vector)
virtual

Definition at line 584 of file pose_estimation.cpp.

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

Definition at line 589 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getVelocity ( geometry_msgs::Vector3 vector)
virtual

Definition at line 595 of file pose_estimation.cpp.

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

Definition at line 602 of file pose_estimation.cpp.

bool hector_pose_estimation::PoseEstimation::getWorldToNavTransform ( geometry_msgs::TransformStamped &  transform)
virtual

Definition at line 767 of file pose_estimation.cpp.

const GlobalReferencePtr & hector_pose_estimation::PoseEstimation::globalReference ( )
virtual

Definition at line 771 of file pose_estimation.cpp.

bool hector_pose_estimation::PoseEstimation::init ( )

Definition at line 88 of file pose_estimation.cpp.

PoseEstimation * hector_pose_estimation::PoseEstimation::Instance ( )
static

Definition at line 83 of file pose_estimation.cpp.

bool hector_pose_estimation::PoseEstimation::inSystemStatus ( SystemStatus  test_status) const
virtual

Definition at line 334 of file pose_estimation.cpp.

virtual ParameterList& hector_pose_estimation::PoseEstimation::parameters ( )
inlinevirtual

Definition at line 157 of file pose_estimation.h.

virtual const ParameterList& hector_pose_estimation::PoseEstimation::parameters ( ) const
inlinevirtual

Definition at line 158 of file pose_estimation.h.

void hector_pose_estimation::PoseEstimation::reset ( )

Definition at line 138 of file pose_estimation.cpp.

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

Definition at line 291 of file pose_estimation.cpp.

bool hector_pose_estimation::PoseEstimation::setMeasurementStatus ( SystemStatus  new_status)
virtual

Definition at line 342 of file pose_estimation.cpp.

bool hector_pose_estimation::PoseEstimation::setSystemStatus ( SystemStatus  new_status)
virtual

Definition at line 338 of file pose_estimation.cpp.

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

Definition at line 358 of file pose_estimation.cpp.

virtual const State& hector_pose_estimation::PoseEstimation::state ( ) const
inlinevirtual

Definition at line 99 of file pose_estimation.h.

virtual State& hector_pose_estimation::PoseEstimation::state ( )
inlinevirtual

Definition at line 100 of file pose_estimation.h.

void hector_pose_estimation::PoseEstimation::update ( ros::Time  timestamp)

Definition at line 165 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::update ( double  dt)

Definition at line 181 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::updated ( )
virtual

Definition at line 273 of file pose_estimation.cpp.

bool hector_pose_estimation::PoseEstimation::updateMeasurementStatus ( SystemStatus  set,
SystemStatus  clear 
)
virtual

Definition at line 350 of file pose_estimation.cpp.

bool hector_pose_estimation::PoseEstimation::updateSystemStatus ( SystemStatus  set,
SystemStatus  clear 
)
virtual

Definition at line 346 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::updateWorldToOtherTransform ( tf::StampedTransform world_to_other_transform)
virtual

Definition at line 755 of file pose_estimation.cpp.

Member Data Documentation

ros::Time hector_pose_estimation::PoseEstimation::alignment_start_
private

Definition at line 184 of file pose_estimation.h.

double hector_pose_estimation::PoseEstimation::alignment_time_
private

Definition at line 185 of file pose_estimation.h.

std::string hector_pose_estimation::PoseEstimation::base_frame_
private

Definition at line 179 of file pose_estimation.h.

FilterPtr hector_pose_estimation::PoseEstimation::filter_
private

Definition at line 172 of file pose_estimation.h.

std::string hector_pose_estimation::PoseEstimation::footprint_frame_
private

Definition at line 181 of file pose_estimation.h.

double hector_pose_estimation::PoseEstimation::gravity_
private

Definition at line 187 of file pose_estimation.h.

boost::shared_ptr<Gravity> hector_pose_estimation::PoseEstimation::gravity_update_
private

Definition at line 190 of file pose_estimation.h.

Inputs hector_pose_estimation::PoseEstimation::inputs_
protected

Definition at line 168 of file pose_estimation.h.

Measurements hector_pose_estimation::PoseEstimation::measurements_
protected

Definition at line 167 of file pose_estimation.h.

std::string hector_pose_estimation::PoseEstimation::nav_frame_
private

Definition at line 178 of file pose_estimation.h.

ParameterList hector_pose_estimation::PoseEstimation::parameters_
private

Definition at line 174 of file pose_estimation.h.

std::string hector_pose_estimation::PoseEstimation::position_frame_
private

Definition at line 182 of file pose_estimation.h.

boost::shared_ptr<Rate> hector_pose_estimation::PoseEstimation::rate_update_
private

Definition at line 189 of file pose_estimation.h.

std::string hector_pose_estimation::PoseEstimation::stabilized_frame_
private

Definition at line 180 of file pose_estimation.h.

StatePtr hector_pose_estimation::PoseEstimation::state_
private

Definition at line 171 of file pose_estimation.h.

Systems hector_pose_estimation::PoseEstimation::systems_
protected

Definition at line 166 of file pose_estimation.h.

ros::Time hector_pose_estimation::PoseEstimation::timestamp_
private

Definition at line 176 of file pose_estimation.h.

std::string hector_pose_estimation::PoseEstimation::world_frame_
private

Definition at line 177 of file pose_estimation.h.

boost::shared_ptr<ZeroRate> hector_pose_estimation::PoseEstimation::zerorate_update_
private

Definition at line 191 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 Thu Feb 18 2021 03:29:31