#include <state_6dof.h>
Classes | |
class | RPYVec |
Public Member Functions | |
bool | isDiff () const |
void | normalize () override |
State6DOF | operator+ (const State6DOF &a) const |
State6DOF | operator- (const State6DOF &a) const |
float & | operator[] (const size_t i) override |
float | operator[] (const size_t i) const |
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 > | |
float | covElement (const T &e, const size_t &j, const size_t &k) |
T | operator+ (const T &a) |
Static Public Member Functions | |
static State6DOF | generateNoise (std::default_random_engine &engine_, const State6DOF &mean, const State6DOF &sigma) |
Static Public Member Functions inherited from mcl_3dl::pf::ParticleBase< float > | |
static T | generateNoise (std::default_random_engine &engine_, T mean, T sigma) |
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 44 of file state_6dof.h.
|
inline |
Definition at line 153 of file state_6dof.h.
|
inline |
Definition at line 160 of file state_6dof.h.
|
inline |
Definition at line 169 of file state_6dof.h.
|
inlinestatic |
Definition at line 194 of file state_6dof.h.
|
inline |
Definition at line 178 of file state_6dof.h.
|
inlineoverridevirtual |
Implements mcl_3dl::pf::ParticleBase< float >.
Definition at line 149 of file state_6dof.h.
Definition at line 217 of file state_6dof.h.
Definition at line 230 of file state_6dof.h.
|
inlineoverridevirtual |
Implements mcl_3dl::pf::ParticleBase< float >.
Definition at line 75 of file state_6dof.h.
|
inline |
Definition at line 110 of file state_6dof.h.
|
inlineoverridevirtual |
Implements mcl_3dl::pf::ParticleBase< float >.
Definition at line 145 of file state_6dof.h.
|
inline |
Definition at line 183 of file state_6dof.h.
bool mcl_3dl::State6DOF::diff_ |
Definition at line 49 of file state_6dof.h.
float mcl_3dl::State6DOF::noise_aa_ |
Definition at line 53 of file state_6dof.h.
float mcl_3dl::State6DOF::noise_al_ |
Definition at line 52 of file state_6dof.h.
float mcl_3dl::State6DOF::noise_la_ |
Definition at line 51 of file state_6dof.h.
float mcl_3dl::State6DOF::noise_ll_ |
Definition at line 50 of file state_6dof.h.
mcl_3dl::Vec3 mcl_3dl::State6DOF::odom_err_integ_ang_ |
Definition at line 55 of file state_6dof.h.
mcl_3dl::Vec3 mcl_3dl::State6DOF::odom_err_integ_lin_ |
Definition at line 54 of file state_6dof.h.
mcl_3dl::Vec3 mcl_3dl::State6DOF::pos_ |
Definition at line 47 of file state_6dof.h.
mcl_3dl::Quat mcl_3dl::State6DOF::rot_ |
Definition at line 48 of file state_6dof.h.
RPYVec mcl_3dl::State6DOF::rpy_ |
Definition at line 74 of file state_6dof.h.