magnetometer_compass.h
Go to the documentation of this file.
1 // SPDX-License-Identifier: BSD-3-Clause
2 // SPDX-FileCopyrightText: Czech Technical University in Prague
3 
10 #include <memory>
11 #include <string>
12 
13 #include <compass_msgs/Azimuth.h>
18 #include <sensor_msgs/Imu.h>
19 #include <sensor_msgs/MagneticField.h>
20 #include <tf2/buffer_core.h>
21 
23 {
24 
25 struct MagnetometerCompassPrivate;
26 
31 {
32 public:
41  MagnetometerCompass(const cras::LogHelperPtr& log, const std::string& frame,
42  const std::shared_ptr<tf2::BufferCore>& tf);
43 
52  MagnetometerCompass(const cras::LogHelperPtr& log, const std::string& frame,
53  const std::shared_ptr<cras::InterruptibleTFBuffer>& tf);
54 
55  virtual ~MagnetometerCompass();
56 
66  virtual void configFromParams(const cras::BoundParamHelper& params);
67 
72  virtual void setLowPassRatio(double ratio);
73 
82  virtual cras::expected<compass_msgs::Azimuth, std::string> computeAzimuth(
83  const sensor_msgs::Imu& imu, const sensor_msgs::MagneticField& magUnbiased);
84 
88  virtual void reset();
89 
90 protected:
95  virtual void updateVariance();
96 
97 private:
98  std::unique_ptr<MagnetometerCompassPrivate> data;
99 };
100 }
magnetometer_compass::MagnetometerCompass::MagnetometerCompass
MagnetometerCompass(const cras::LogHelperPtr &log, const std::string &frame, const std::shared_ptr< tf2::BufferCore > &tf)
Create the compass.
magnetometer_compass::MagnetometerCompass::configFromParams
virtual void configFromParams(const cras::BoundParamHelper &params)
Configure the bias remover from ROS parameters.
cras::HasLogger
magnetometer_compass::MagnetometerCompass::updateVariance
virtual void updateVariance()
Re-estimate variance after adding a new measurement.
cras::BoundParamHelper
log_utils.h
magnetometer_compass
Definition: magnetometer_compass.h:22
magnetometer_compass::MagnetometerCompass::reset
virtual void reset()
Reset the computation (i.e. the low-pass filter and estimated variance).
magnetometer_compass::MagnetometerCompass::computeAzimuth
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.
magnetometer_compass::MagnetometerCompass::~MagnetometerCompass
virtual ~MagnetometerCompass()
buffer_core.h
bound_param_helper.hpp
magnetometer_compass::MagnetometerCompass
Convert magnetometer and IMU measurements to azimuth.
Definition: magnetometer_compass.h:30
expected.hpp
cras::LogHelperPtr
::cras::LogHelper::Ptr LogHelperPtr
cras::HasLogger::log
::cras::LogHelperPtr log
interruptible_buffer.h
tf
magnetometer_compass::MagnetometerCompass::setLowPassRatio
virtual void setLowPassRatio(double ratio)
The azimuth is filtered with a low-pass filter. This sets its aggressivity.
magnetometer_compass::MagnetometerCompass::data
std::unique_ptr< MagnetometerCompassPrivate > data
PIMPL.
Definition: magnetometer_compass.h:98


magnetometer_compass
Author(s): Martin Pecka
autogenerated on Wed Jan 8 2025 04:03:16