#include <state_6dof.h>

Classes | |
| class | RPYVec |
Public Member Functions | |
| size_t | covDimension () const override |
| float | covElement (const State6DOF &e, const size_t &j, const size_t &k) |
| bool | isDiff () const |
| void | normalize () override |
| State6DOF | operator+ (const State6DOF &a) const |
| State6DOF | operator- (const State6DOF &a) const |
| float | operator[] (const size_t i) const |
| float & | operator[] (const size_t i) override |
| size_t | size () const override |
| State6DOF () | |
| State6DOF (const mcl_3dl::Vec3 pos, const mcl_3dl::Quat rot) | |
| State6DOF (const mcl_3dl::Vec3 pos, const mcl_3dl::Vec3 rpy) | |
| template<typename PointType > | |
| void | transform (pcl::PointCloud< PointType > &pc) const |
Public Member Functions inherited from mcl_3dl::pf::ParticleBase< float > | |
| virtual size_t | covDimension () const |
| float | covElement (const T &e, const size_t &j, const size_t &k) |
| T | operator+ (const T &a) |
| virtual size_t | size () const=0 |
Static Public Member Functions | |
| template<typename T , typename RANDOM_ENGINE , typename NOISE_GEN > | |
| static State6DOF | generateNoise (RANDOM_ENGINE &engine, const NOISE_GEN &gen) |
Static Public Member Functions inherited from mcl_3dl::pf::ParticleBase< float > | |
| static T | generateNoise (RANDOM_ENGINE &engine, const NOISE_GEN &gen) |
Public Attributes | |
| bool | diff_ |
| float | noise_aa_ |
| float | noise_al_ |
| float | noise_la_ |
| float | noise_ll_ |
| mcl_3dl::Vec3 | odom_err_integ_ang_ |
| mcl_3dl::Vec3 | odom_err_integ_lin_ |
| mcl_3dl::Vec3 | pos_ |
| mcl_3dl::Quat | rot_ |
| RPYVec | rpy_ |
Definition at line 49 of file state_6dof.h.
|
inline |
Definition at line 185 of file state_6dof.h.
|
inline |
Definition at line 192 of file state_6dof.h.
|
inline |
Definition at line 201 of file state_6dof.h.
|
inlineoverride |
Definition at line 158 of file state_6dof.h.
|
inline |
Definition at line 162 of file state_6dof.h.
|
inlinestatic |
Definition at line 227 of file state_6dof.h.
|
inline |
Definition at line 210 of file state_6dof.h.
|
inlineoverridevirtual |
Implements mcl_3dl::pf::ParticleBase< float >.
Definition at line 154 of file state_6dof.h.
Definition at line 249 of file state_6dof.h.
Definition at line 262 of file state_6dof.h.
|
inline |
Definition at line 115 of file state_6dof.h.
|
inlineoverridevirtual |
Implements mcl_3dl::pf::ParticleBase< float >.
Definition at line 80 of file state_6dof.h.
|
inlineoverride |
Definition at line 150 of file state_6dof.h.
|
inline |
Definition at line 215 of file state_6dof.h.
| bool mcl_3dl::State6DOF::diff_ |
Definition at line 54 of file state_6dof.h.
| float mcl_3dl::State6DOF::noise_aa_ |
Definition at line 58 of file state_6dof.h.
| float mcl_3dl::State6DOF::noise_al_ |
Definition at line 57 of file state_6dof.h.
| float mcl_3dl::State6DOF::noise_la_ |
Definition at line 56 of file state_6dof.h.
| float mcl_3dl::State6DOF::noise_ll_ |
Definition at line 55 of file state_6dof.h.
| mcl_3dl::Vec3 mcl_3dl::State6DOF::odom_err_integ_ang_ |
Definition at line 60 of file state_6dof.h.
| mcl_3dl::Vec3 mcl_3dl::State6DOF::odom_err_integ_lin_ |
Definition at line 59 of file state_6dof.h.
| mcl_3dl::Vec3 mcl_3dl::State6DOF::pos_ |
Definition at line 52 of file state_6dof.h.
| mcl_3dl::Quat mcl_3dl::State6DOF::rot_ |
Definition at line 53 of file state_6dof.h.
| RPYVec mcl_3dl::State6DOF::rpy_ |
Definition at line 79 of file state_6dof.h.