$search

hector_pose_estimation::PoseEstimation Class Reference

#include <pose_estimation.h>

List of all members.

Public Types

typedef boost::function< bool(SystemStatus &)> SystemStatusCallback

Public Member Functions

template<class ConcreteMeasurementModel >
const MeasurementPtraddMeasurement (const std::string &name, ConcreteMeasurementModel *model)
virtual const MeasurementPtraddMeasurement (const std::string &name, const MeasurementPtr &measurement)
virtual const MeasurementPtraddMeasurement (Measurement *measurement)
virtual const MeasurementPtraddMeasurement (const MeasurementPtr &measurement)
virtual void cleanup ()
virtual const BFL::KalmanFilter * filter () const
virtual BFL::KalmanFilter * filter ()
virtual void getBias (geometry_msgs::Vector3Stamped &angular_velocity, geometry_msgs::Vector3Stamped &linear_acceleration)
virtual void getBias (geometry_msgs::Vector3 &angular_velocity, geometry_msgs::Vector3 &linear_acceleration)
virtual void getBias (tf::Stamped< tf::Vector3 > &angular_velocity, tf::Stamped< tf::Vector3 > &linear_acceleration)
virtual void getBias (tf::Vector3 &angular_velocity, tf::Vector3 &linear_acceleration)
virtual const StateCovariancegetCovariance ()
virtual void getGlobalPosition (sensor_msgs::NavSatFix &global)
virtual void getGlobalPosition (double &latitude, double &longitude, double &altitude)
virtual void getHeader (std_msgs::Header &header)
virtual void getImuWithBiases (geometry_msgs::Vector3 &linear_acceleration, geometry_msgs::Vector3 &angular_velocity)
virtual MeasurementPtr getMeasurement (const std::string &name) const
virtual SystemStatus getMeasurementStatus () const
virtual void getOrientation (double &yaw, double &pitch, double &roll)
virtual void getOrientation (geometry_msgs::QuaternionStamped &pose)
virtual void getOrientation (geometry_msgs::Quaternion &pose)
virtual void getOrientation (tf::Stamped< tf::Quaternion > &quaternion)
virtual void getOrientation (tf::Quaternion &quaternion)
virtual ParameterList getParameters () const
virtual void getPose (geometry_msgs::PoseStamped &pose)
virtual void getPose (geometry_msgs::Pose &pose)
virtual void getPose (tf::Stamped< tf::Pose > &pose)
virtual void getPose (tf::Pose &pose)
virtual void getPosition (geometry_msgs::PointStamped &pose)
virtual void getPosition (geometry_msgs::Point &pose)
virtual void getPosition (tf::Stamped< tf::Point > &point)
virtual void getPosition (tf::Point &point)
virtual void getRate (geometry_msgs::Vector3Stamped &vector)
virtual void getRate (geometry_msgs::Vector3 &vector)
virtual void getRate (tf::Stamped< tf::Vector3 > &vector)
virtual void getRate (tf::Vector3 &vector)
virtual void getState (nav_msgs::Odometry &state, bool with_covariances=true)
virtual const StateVectorgetState ()
virtual const SystemPtrgetSystem () const
virtual const SystemModelgetSystemModel () const
virtual SystemStatus getSystemStatus () const
virtual ros::Time getTimestamp () const
virtual void getTransforms (std::vector< tf::StampedTransform > &transforms)
virtual void getVelocity (geometry_msgs::Vector3Stamped &vector)
virtual void getVelocity (geometry_msgs::Vector3 &vector)
virtual void getVelocity (tf::Stamped< tf::Vector3 > &vector)
virtual void getVelocity (tf::Vector3 &vector)
virtual GlobalReferenceglobalReference ()
virtual bool init ()
virtual bool inSystemStatus (SystemStatus test_status) const
virtual const ParameterListparameters () const
virtual ParameterListparameters ()
template<typename ConcreteSystemModel >
 PoseEstimation (ConcreteSystemModel *system_model)
 PoseEstimation (const SystemPtr &system=SystemPtr())
virtual void reset ()
virtual void setCovariance (const StateCovariance &covariance)
virtual bool setMeasurementStatus (SystemStatus new_status)
virtual void setState (const StateVector &state)
virtual const SystemPtrsetSystem (System *system)
virtual const SystemPtrsetSystem (const SystemPtr &system)
template<typename ConcreteSystemModel >
const SystemPtrsetSystemModel (ConcreteSystemModel *system_model, const std::string &name="system")
virtual bool setSystemStatus (SystemStatus new_status)
virtual void setSystemStatusCallback (SystemStatusCallback callback)
virtual void setTimestamp (ros::Time timestamp)
virtual void update (double dt)
virtual void update (const SystemInput &input, ros::Time timestamp)
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 Types

typedef std::vector
< MeasurementPtr
Measurements

Protected Attributes

Measurements measurements_
SystemPtr system_

Private Attributes

ros::Time alignment_start_
double alignment_time_
std::string base_frame_
StateCovariance covariance_
bool covariance_is_dirty_
boost::shared_ptr
< BFL::ExtendedKalmanFilter > 
filter_
std::string footprint_frame_
GlobalReference global_reference_
boost::shared_ptr< Gravitygravity_
SystemStatus measurement_status_
std::string nav_frame_
ParameterList parameters_
std::string position_frame_
boost::shared_ptr< Raterate_
std::string stabilized_frame_
StateVector state_
bool state_is_dirty_
SystemStatus status_
SystemStatusCallback status_callback_
ros::Time timestamp_
std::string world_frame_
boost::shared_ptr< ZeroRatezerorate_

Detailed Description

Definition at line 59 of file pose_estimation.h.


Member Typedef Documentation

Definition at line 154 of file pose_estimation.h.

Definition at line 101 of file pose_estimation.h.


Constructor & Destructor Documentation

hector_pose_estimation::PoseEstimation::PoseEstimation ( const SystemPtr system = SystemPtr()  ) 

Definition at line 38 of file pose_estimation.cpp.

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

Definition at line 201 of file pose_estimation.h.

hector_pose_estimation::PoseEstimation::~PoseEstimation (  )  [virtual]

Definition at line 75 of file pose_estimation.cpp.


Member Function Documentation

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

Definition at line 84 of file pose_estimation.h.

const MeasurementPtr & hector_pose_estimation::PoseEstimation::addMeasurement ( const std::string &  name,
const MeasurementPtr measurement 
) [virtual]

Definition at line 295 of file pose_estimation.cpp.

const MeasurementPtr & hector_pose_estimation::PoseEstimation::addMeasurement ( Measurement measurement  )  [virtual]

Definition at line 300 of file pose_estimation.cpp.

const MeasurementPtr & hector_pose_estimation::PoseEstimation::addMeasurement ( const MeasurementPtr measurement  )  [virtual]

Definition at line 290 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::cleanup (  )  [virtual]

Definition at line 106 of file pose_estimation.cpp.

virtual const BFL::KalmanFilter* hector_pose_estimation::PoseEstimation::filter (  )  const [inline, virtual]

Definition at line 148 of file pose_estimation.h.

virtual BFL::KalmanFilter* hector_pose_estimation::PoseEstimation::filter (  )  [inline, virtual]

Definition at line 147 of file pose_estimation.h.

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

Definition at line 696 of file pose_estimation.cpp.

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

Definition at line 686 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getBias ( tf::Stamped< tf::Vector3 > &  angular_velocity,
tf::Stamped< tf::Vector3 > &  linear_acceleration 
) [virtual]

Definition at line 678 of file pose_estimation.cpp.

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

Definition at line 668 of file pose_estimation.cpp.

const StateCovariance & hector_pose_estimation::PoseEstimation::getCovariance (  )  [virtual]

Definition at line 319 of file pose_estimation.cpp.

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

Definition at line 525 of file pose_estimation.cpp.

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

Definition at line 516 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::getHeader ( std_msgs::Header &  header  )  [virtual]

Definition at line 393 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 569 of file pose_estimation.cpp.

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

Definition at line 304 of file pose_estimation.cpp.

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

Definition at line 343 of file pose_estimation.cpp.

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

Definition at line 559 of file pose_estimation.cpp.

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

Definition at line 554 of file pose_estimation.cpp.

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

Definition at line 546 of file pose_estimation.cpp.

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

Definition at line 540 of file pose_estimation.cpp.

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

Definition at line 535 of file pose_estimation.cpp.

ParameterList hector_pose_estimation::PoseEstimation::getParameters (  )  const [virtual]

Definition at line 784 of file pose_estimation.cpp.

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

Definition at line 488 of file pose_estimation.cpp.

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

Definition at line 483 of file pose_estimation.cpp.

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

Definition at line 477 of file pose_estimation.cpp.

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

Definition at line 470 of file pose_estimation.cpp.

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

Definition at line 511 of file pose_estimation.cpp.

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

Definition at line 504 of file pose_estimation.cpp.

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

Definition at line 498 of file pose_estimation.cpp.

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

Definition at line 493 of file pose_estimation.cpp.

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

Definition at line 663 of file pose_estimation.cpp.

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

Definition at line 643 of file pose_estimation.cpp.

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

Definition at line 637 of file pose_estimation.cpp.

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

Definition at line 623 of file pose_estimation.cpp.

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

Definition at line 398 of file pose_estimation.cpp.

const StateVector & hector_pose_estimation::PoseEstimation::getState (  )  [virtual]

Definition at line 311 of file pose_estimation.cpp.

const SystemPtr & hector_pose_estimation::PoseEstimation::getSystem (  )  const [virtual]

Definition at line 286 of file pose_estimation.cpp.

const SystemModel * hector_pose_estimation::PoseEstimation::getSystemModel (  )  const [virtual]

Definition at line 281 of file pose_estimation.cpp.

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

Definition at line 339 of file pose_estimation.cpp.

ros::Time hector_pose_estimation::PoseEstimation::getTimestamp (  )  const [virtual]

Definition at line 385 of file pose_estimation.cpp.

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

Definition at line 704 of file pose_estimation.cpp.

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

Definition at line 618 of file pose_estimation.cpp.

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

Definition at line 611 of file pose_estimation.cpp.

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

Definition at line 605 of file pose_estimation.cpp.

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

Definition at line 600 of file pose_estimation.cpp.

GlobalReference * hector_pose_estimation::PoseEstimation::globalReference (  )  [virtual]

Definition at line 798 of file pose_estimation.cpp.

bool hector_pose_estimation::PoseEstimation::init (  )  [virtual]

Definition at line 85 of file pose_estimation.cpp.

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

Definition at line 80 of file pose_estimation.cpp.

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

Definition at line 347 of file pose_estimation.cpp.

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

Definition at line 145 of file pose_estimation.h.

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

Definition at line 144 of file pose_estimation.h.

void hector_pose_estimation::PoseEstimation::reset (  )  [virtual]

Definition at line 118 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::setCovariance ( const StateCovariance covariance  )  [virtual]

Definition at line 333 of file pose_estimation.cpp.

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

Definition at line 363 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::setState ( const StateVector state  )  [virtual]

Definition at line 327 of file pose_estimation.cpp.

const SystemPtr & hector_pose_estimation::PoseEstimation::setSystem ( System system  )  [virtual]

Definition at line 277 of file pose_estimation.cpp.

const SystemPtr & hector_pose_estimation::PoseEstimation::setSystem ( const SystemPtr system  )  [virtual]

Definition at line 267 of file pose_estimation.cpp.

template<typename ConcreteSystemModel >
const SystemPtr & hector_pose_estimation::PoseEstimation::setSystemModel ( ConcreteSystemModel *  system_model,
const std::string &  name = "system" 
) [inline]

Definition at line 194 of file pose_estimation.h.

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

Definition at line 351 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::setSystemStatusCallback ( SystemStatusCallback  callback  )  [virtual]

Definition at line 381 of file pose_estimation.cpp.

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

Definition at line 389 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::update ( double  dt  )  [virtual]

Definition at line 160 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::update ( const SystemInput input,
ros::Time  timestamp 
) [virtual]

Definition at line 144 of file pose_estimation.cpp.

void hector_pose_estimation::PoseEstimation::updated (  )  [virtual]

Definition at line 262 of file pose_estimation.cpp.

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

Definition at line 377 of file pose_estimation.cpp.

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

Definition at line 373 of file pose_estimation.cpp.

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

Definition at line 772 of file pose_estimation.cpp.


Member Data Documentation

Definition at line 179 of file pose_estimation.h.

Definition at line 180 of file pose_estimation.h.

Definition at line 174 of file pose_estimation.h.

Definition at line 161 of file pose_estimation.h.

Definition at line 163 of file pose_estimation.h.

boost::shared_ptr<BFL::ExtendedKalmanFilter> hector_pose_estimation::PoseEstimation::filter_ [private]

Definition at line 158 of file pose_estimation.h.

Definition at line 176 of file pose_estimation.h.

Definition at line 169 of file pose_estimation.h.

Definition at line 185 of file pose_estimation.h.

Definition at line 166 of file pose_estimation.h.

Definition at line 155 of file pose_estimation.h.

Definition at line 173 of file pose_estimation.h.

Definition at line 167 of file pose_estimation.h.

Definition at line 177 of file pose_estimation.h.

Definition at line 184 of file pose_estimation.h.

Definition at line 175 of file pose_estimation.h.

Definition at line 160 of file pose_estimation.h.

Definition at line 162 of file pose_estimation.h.

Definition at line 165 of file pose_estimation.h.

Definition at line 182 of file pose_estimation.h.

Definition at line 153 of file pose_estimation.h.

Definition at line 171 of file pose_estimation.h.

Definition at line 172 of file pose_estimation.h.

Definition at line 186 of file pose_estimation.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends


hector_pose_estimation_core
Author(s): Johannes Meyer
autogenerated on Tue Mar 5 12:32:36 2013