Namespaces | |
| EstimatorResults | |
| FilterTypes | |
| FilterUtilities | |
| NavsatConversions | |
| RosFilterUtilities | |
Classes | |
| struct | CallbackData |
| class | Ekf |
| Extended Kalman filter class. More... | |
| class | EkfNodelet |
| struct | EstimatorState |
| Robot Localization Estimator State. More... | |
| class | FilterBase |
| struct | FilterState |
| Structure used for storing and comparing filter states. More... | |
| struct | Measurement |
| Structure used for storing and comparing measurements (for priority queues) More... | |
| class | NavSatTransform |
| class | NavSatTransformNodelet |
| class | RobotLocalizationEstimator |
| Robot Localization Listener class. More... | |
| class | RobotLocalizationListenerNode |
| class | RosFilter |
| class | RosRobotLocalizationListener |
| RosRobotLocalizationListener class. More... | |
| struct | Twist |
| class | Ukf |
| Unscented Kalman filter class. More... | |
| class | UkfNodelet |
Typedefs | |
| typedef EstimatorResults::EstimatorResult | EstimatorResult |
| typedef std::deque< FilterStatePtr > | FilterStateHistoryDeque |
| typedef boost::shared_ptr< FilterState > | FilterStatePtr |
| typedef FilterTypes::FilterType | FilterType |
| typedef std::deque< MeasurementPtr > | MeasurementHistoryDeque |
| typedef boost::shared_ptr< Measurement > | MeasurementPtr |
| typedef std::priority_queue< MeasurementPtr, std::vector< MeasurementPtr >, Measurement > | MeasurementQueue |
| typedef RosFilter< Ekf > | RosEkf |
| typedef RosFilter< Ukf > | RosUkf |
Enumerations | |
| enum | ControlMembers { ControlMemberVx, ControlMemberVy, ControlMemberVz, ControlMemberVroll, ControlMemberVpitch, ControlMemberVyaw } |
| Enumeration that defines the control vector. More... | |
| enum | StateMembers { StateMemberX = 0, StateMemberY, StateMemberZ, StateMemberRoll, StateMemberPitch, StateMemberYaw, StateMemberVx, StateMemberVy, StateMemberVz, StateMemberVroll, StateMemberVpitch, StateMemberVyaw, StateMemberAx, StateMemberAy, StateMemberAz } |
| Enumeration that defines the state vector. More... | |
Functions | |
| FilterType | filterTypeFromString (const std::string &filter_type_str) |
| bool | findAncestor (const tf2_ros::Buffer &buffer, const std::string &source_frame, const std::string &target_frame) |
| bool | findAncestorRecursiveYAML (YAML::Node &tree, const std::string &source_frame, const std::string &target_frame) |
Variables | |
| const int | ACCELERATION_SIZE = 3 |
| static std::map< std::string, std::vector< std::string > > | ancestor_map |
| static std::map< std::string, std::vector< std::string > > | descendant_map |
| const int | LINEAR_VELOCITY_SIZE = 3 |
| const int | ORIENTATION_OFFSET = StateMemberRoll |
| const int | ORIENTATION_SIZE = 3 |
| const int | ORIENTATION_V_OFFSET = StateMemberVroll |
| const double | PI = 3.141592653589793 |
| Common variables. More... | |
| const int | POSE_SIZE = 6 |
| Pose and twist messages each contain six variables. More... | |
| const int | POSITION_A_OFFSET = StateMemberAx |
| const int | POSITION_OFFSET = StateMemberX |
| const int | POSITION_SIZE = 3 |
| const int | POSITION_V_OFFSET = StateMemberVx |
| const int | STATE_SIZE = 15 |
| Global constants that define our state vector size and offsets to groups of values within that state. More... | |
| const double | TAU = 6.283185307179587 |
| const int | TWIST_SIZE = 6 |
Definition at line 98 of file robot_localization_estimator.h.
| typedef std::deque<FilterStatePtr> RobotLocalization::FilterStateHistoryDeque |
Definition at line 108 of file ros_filter.h.
Definition at line 145 of file filter_base.h.
Definition at line 109 of file robot_localization_estimator.h.
| typedef std::deque<MeasurementPtr> RobotLocalization::MeasurementHistoryDeque |
Definition at line 107 of file ros_filter.h.
Definition at line 109 of file filter_base.h.
| typedef std::priority_queue<MeasurementPtr, std::vector<MeasurementPtr>, Measurement> RobotLocalization::MeasurementQueue |
Definition at line 106 of file ros_filter.h.
| typedef RosFilter<Ekf> RobotLocalization::RosEkf |
Definition at line 43 of file ros_filter_types.h.
| typedef RosFilter<Ukf> RobotLocalization::RosUkf |
Definition at line 44 of file ros_filter_types.h.
Enumeration that defines the control vector.
| Enumerator | |
|---|---|
| ControlMemberVx | |
| ControlMemberVy | |
| ControlMemberVz | |
| ControlMemberVroll | |
| ControlMemberVpitch | |
| ControlMemberVyaw | |
Definition at line 62 of file filter_common.h.
Enumeration that defines the state vector.
Definition at line 41 of file filter_common.h.
| FilterType RobotLocalization::filterTypeFromString | ( | const std::string & | filter_type_str | ) |
Definition at line 52 of file ros_robot_localization_listener.cpp.
| bool RobotLocalization::findAncestor | ( | const tf2_ros::Buffer & | buffer, |
| const std::string & | source_frame, | ||
| const std::string & | target_frame | ||
| ) |
Definition at line 279 of file ros_robot_localization_listener.cpp.
| bool RobotLocalization::findAncestorRecursiveYAML | ( | YAML::Node & | tree, |
| const std::string & | source_frame, | ||
| const std::string & | target_frame | ||
| ) |
Definition at line 259 of file ros_robot_localization_listener.cpp.
| const int RobotLocalization::ACCELERATION_SIZE = 3 |
Definition at line 89 of file filter_common.h.
|
static |
Definition at line 277 of file ros_robot_localization_listener.cpp.
|
static |
Definition at line 278 of file ros_robot_localization_listener.cpp.
| const int RobotLocalization::LINEAR_VELOCITY_SIZE = 3 |
Definition at line 88 of file filter_common.h.
| const int RobotLocalization::ORIENTATION_OFFSET = StateMemberRoll |
Definition at line 77 of file filter_common.h.
| const int RobotLocalization::ORIENTATION_SIZE = 3 |
Definition at line 87 of file filter_common.h.
| const int RobotLocalization::ORIENTATION_V_OFFSET = StateMemberVroll |
Definition at line 79 of file filter_common.h.
| const double RobotLocalization::PI = 3.141592653589793 |
Common variables.
Definition at line 92 of file filter_common.h.
| const int RobotLocalization::POSE_SIZE = 6 |
Pose and twist messages each contain six variables.
Definition at line 84 of file filter_common.h.
| const int RobotLocalization::POSITION_A_OFFSET = StateMemberAx |
Definition at line 80 of file filter_common.h.
| const int RobotLocalization::POSITION_OFFSET = StateMemberX |
Definition at line 76 of file filter_common.h.
| const int RobotLocalization::POSITION_SIZE = 3 |
Definition at line 86 of file filter_common.h.
| const int RobotLocalization::POSITION_V_OFFSET = StateMemberVx |
Definition at line 78 of file filter_common.h.
| const int RobotLocalization::STATE_SIZE = 15 |
Global constants that define our state vector size and offsets to groups of values within that state.
Definition at line 75 of file filter_common.h.
| const double RobotLocalization::TAU = 6.283185307179587 |
Definition at line 93 of file filter_common.h.
| const int RobotLocalization::TWIST_SIZE = 6 |
Definition at line 85 of file filter_common.h.