24 #ifndef HUMANOID_LOCALIZATION_MOTIONMODEL_H_ 25 #define HUMANOID_LOCALIZATION_MOTIONMODEL_H_ 30 #include <eigen3/Eigen/Cholesky> 71 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
void storeOdomPose(const tf::Stamped< tf::Pose > &odomPose)
store odomPose as m_lastOdomPose to compute future odom transforms
tf::Transform odomTransformNoise(const tf::Transform &odomTransform)
double m_odomNoisePitch
std.dev param of noise in pitch (depending on distance traveled)
bool lookupLocalTransform(const std::string &targetFrame, const ros::Time &t, tf::StampedTransform &localTransform) const
lookup the local target frame in the base frame (local transform)
boost::variate_generator< EngineT &, NormalDistributionT > NormalGeneratorT
standard normal-distributed noise
boost::mt19937 EngineT
Boost RNG engine:
tf::TransformListener * m_tfListener
Eigen::Matrix3d m_odomCalibration2D
systematic calibration parameters for odometry drift
NormalGeneratorT m_rngNormal
double m_odomNoiseZ
std.dev param of noise in Z (depending on distance traveled)
bool m_firstOdometryReceived
MotionModel(ros::NodeHandle *nh, EngineT *rngEngine, tf::TransformListener *tf, const std::string &odomFrameId, const std::string &baseFrameId)
bool getLastOdomPose(tf::Stamped< tf::Pose > &lastOdomPose) const
bool lookupOdomPose(const ros::Time &t, tf::Stamped< tf::Pose > &odomPose) const
look up the odom pose at a certain time through tf
void transformPose(tf::Pose &particlePose, const tf::Transform &odomTransform)
Transform a particle's pose with the relative odomTransform with added random noise.
std::string m_footprintFrameId
UniformGeneratorT m_rngUniform
Eigen::Matrix3d m_odomNoise2D
variance parameters for calibrated odometry noise
tf::Transform computeOdomTransform(const tf::Transform currentPose) const
boost::variate_generator< EngineT &, UniformDistributionT > UniformGeneratorT
uniform noise in range [0,1)
tf::Transform calibrateOdometry(const tf::Transform &odomTransform) const
std::string m_baseFrameId
bool lookupOdomTransform(const ros::Time &t, tf::Transform &odomTransform) const
looks up the odometry pose at time t and then calls computeOdomTransform()
bool applyOdomTransformTemporal(Particles &particles, const ros::Time &t, double dt)
std::string m_odomFrameId
std::vector< Particle > Particles
double m_odomNoiseRoll
std.dev param of noise in roll (depending on distance traveled)
bool lookupPoseHeight(const ros::Time &t, double &poseHeight) const
lookup the height of the torso, based on tf between the base and footprint frames ...
void applyOdomTransform(Particles &particles, const tf::Transform &odomTransform)
apply odomTransform to all particles (with random noise and calibration)
tf::Stamped< tf::Pose > m_lastOdomPose