Go to the documentation of this file.
13 #include <compass_msgs/Azimuth.h>
18 #include <sensor_msgs/Imu.h>
19 #include <sensor_msgs/MagneticField.h>
25 struct MagnetometerCompassPrivate;
42 const std::shared_ptr<tf2::BufferCore>&
tf);
53 const std::shared_ptr<cras::InterruptibleTFBuffer>&
tf);
82 virtual cras::expected<compass_msgs::Azimuth, std::string>
computeAzimuth(
83 const sensor_msgs::Imu& imu,
const sensor_msgs::MagneticField& magUnbiased);
98 std::unique_ptr<MagnetometerCompassPrivate>
data;
MagnetometerCompass(const cras::LogHelperPtr &log, const std::string &frame, const std::shared_ptr< tf2::BufferCore > &tf)
Create the compass.
virtual void configFromParams(const cras::BoundParamHelper ¶ms)
Configure the bias remover from ROS parameters.
virtual void updateVariance()
Re-estimate variance after adding a new measurement.
virtual void reset()
Reset the computation (i.e. the low-pass filter and estimated variance).
virtual cras::expected< compass_msgs::Azimuth, std::string > computeAzimuth(const sensor_msgs::Imu &imu, const sensor_msgs::MagneticField &magUnbiased)
Compute azimuth from the provided IMU and magnetometer measurements.
virtual ~MagnetometerCompass()
Convert magnetometer and IMU measurements to azimuth.
::cras::LogHelper::Ptr LogHelperPtr
virtual void setLowPassRatio(double ratio)
The azimuth is filtered with a low-pass filter. This sets its aggressivity.
std::unique_ptr< MagnetometerCompassPrivate > data
PIMPL.