Go to the documentation of this file.
29 #ifndef HECTOR_POSE_ESTIMATION_POSEUPDATE_H
30 #define HECTOR_POSE_ESTIMATION_POSEUPDATE_H
33 #include <geometry_msgs/PoseWithCovarianceStamped.h>
34 #include <geometry_msgs/TwistWithCovarianceStamped.h>
36 #include <boost/function.hpp>
85 PoseUpdate(
const std::string& name =
"poseupdate");
97 geometry_msgs::PoseWithCovarianceStampedConstPtr
pose;
98 geometry_msgs::TwistWithCovarianceStampedConstPtr
twist;
136 template <
typename MeasurementVector,
typename MeasurementMatrix,
typename NoiseVariance>
137 double updateInternal(
State &state,
const NoiseVariance &Iy,
const MeasurementVector &error,
const MeasurementMatrix &H,
const std::string& text,
const double max_error = 0.0,
JumpFunction jump_function =
JumpFunction());
146 #endif // HECTOR_POSE_ESTIMATION_POSEUPDATE_H
virtual bool update(const MeasurementUpdate &update)
virtual void getExpectedValue(MeasurementVector &y_pred, const State &state)
double fixed_angular_rate_z_stddev_
geometry_msgs::PoseWithCovarianceStampedConstPtr pose
Update(const geometry_msgs::PoseWithCovarianceStamped &pose)
PositionZModel position_z_model_
double max_velocity_z_error_
double calculateOmega(const SymmetricMatrix &Ix, const SymmetricMatrix &Iy)
virtual void getStateJacobian(MeasurementMatrix &C, const State &state, bool init)
virtual void getStateJacobian(MeasurementMatrix &C, const State &state, bool init)
ColumnVector_< Dynamic >::type ColumnVector
void updateState(State &state, const ColumnVector &diff) const
SymmetricMatrix_< Dynamic >::type SymmetricMatrix
Update(const geometry_msgs::TwistWithCovarianceStamped &twist)
double max_time_difference_
Update(const geometry_msgs::PoseWithCovarianceStampedConstPtr &pose)
double max_angular_rate_z_error_
PoseUpdate(const std::string &name="poseupdate")
Update(const geometry_msgs::PoseWithCovarianceStamped &pose, const geometry_msgs::TwistWithCovarianceStamped &twist)
Update(const geometry_msgs::TwistWithCovarianceStampedConstPtr &twist)
double updateInternal(State &state, const NoiseVariance &Iy, const MeasurementVector &error, const MeasurementMatrix &H, const std::string &text, const double max_error=0.0, JumpFunction jump_function=JumpFunction())
geometry_msgs::TwistWithCovarianceStampedConstPtr twist
double fixed_position_xy_stddev_
double fixed_angular_rate_xy_stddev_
Update(const geometry_msgs::PoseWithCovarianceStampedConstPtr &pose, const geometry_msgs::TwistWithCovarianceStampedConstPtr &twist)
virtual void getStateJacobian(MeasurementMatrix &C, const State &state, bool init)
virtual ~PositionXYModel()
bool interpret_covariance_as_information_matrix_
boost::function< void(State &state, const ColumnVector &diff)> JumpFunction
virtual void getExpectedValue(MeasurementVector &y_pred, const State &state)
virtual void getExpectedValue(MeasurementVector &y_pred, const State &state)
double max_position_xy_error_
void updateState(State &state, const ColumnVector &diff) const
virtual void getStateJacobian(MeasurementMatrix &C, const State &state, bool init)
void updateState(State &state, const ColumnVector &diff) const
double fixed_velocity_xy_stddev_
double max_angular_rate_xy_error_
double fixed_velocity_z_stddev_
double max_velocity_xy_error_
virtual ~PositionZModel()
double max_position_z_error_
double fixed_position_z_stddev_
virtual void getExpectedValue(MeasurementVector &y_pred, const State &state)
virtual bool updateImpl(const MeasurementUpdate &update)
PositionXYModel position_xy_model_