Convert magnetometer and IMU measurements to azimuth.
More...
#include <magnetometer_compass.h>
|
| std::unique_ptr< MagnetometerCompassPrivate > | data |
| | PIMPL. More...
|
| |
Convert magnetometer and IMU measurements to azimuth.
Definition at line 30 of file magnetometer_compass.h.
◆ MagnetometerCompass() [1/2]
| magnetometer_compass::MagnetometerCompass::MagnetometerCompass |
( |
const cras::LogHelperPtr & |
log, |
|
|
const std::string & |
frame, |
|
|
const std::shared_ptr< tf2::BufferCore > & |
tf |
|
) |
| |
Create the compass.
- Parameters
-
| [in] | log | Logger. |
| [in] | frame | The target frame in which the azimuth is expressed. Its Z axis should approx. point upwards. Azimuth is the angle between magnetic North and this frame's X axis. |
| [in] | tf | TF buffer for transforming incoming data to frame. If you are sure data are already in the target frame, you can pass an empty buffer. |
◆ MagnetometerCompass() [2/2]
Create the compass.
- Parameters
-
| [in] | log | Logger. |
| [in] | frame | The target frame in which the azimuth is expressed. Its Z axis should approx. point upwards. Azimuth is the angle between magnetic North and this frame's X axis. |
| [in] | tf | TF buffer for transforming incoming data to frame. If you are sure data are already in the target frame, you can pass an empty buffer. |
◆ ~MagnetometerCompass()
| virtual magnetometer_compass::MagnetometerCompass::~MagnetometerCompass |
( |
| ) |
|
|
virtual |
◆ computeAzimuth()
| virtual cras::expected<compass_msgs::Azimuth, std::string> magnetometer_compass::MagnetometerCompass::computeAzimuth |
( |
const sensor_msgs::Imu & |
imu, |
|
|
const sensor_msgs::MagneticField & |
magUnbiased |
|
) |
| |
|
virtual |
Compute azimuth from the provided IMU and magnetometer measurements.
- Parameters
-
| [in] | imu | IMU tied to the magnetometer. It has to contain valid orientation. |
| [in] | magUnbiased | Magnetometer measurement with removed bias. |
- Returns
- The computed azimuth, or an error message. The azimuth will be in radians and NED frame.
- Note
- The function does not check time synchronization of the two inputs.
-
Both inputs have to be transformable to the configured target frame.
◆ configFromParams()
| virtual void magnetometer_compass::MagnetometerCompass::configFromParams |
( |
const cras::BoundParamHelper & |
params | ) |
|
|
virtual |
Configure the bias remover from ROS parameters.
- Parameters
-
| [in] | params | The parameters. |
The following parameters are read:
~initial_variance (double, default 0): Variance of the measurement used at startup (in rad^2).
~low_pass_ratio (double, default 0.95): The azimuth is filtered with a low-pass filter. This sets its aggressivity (0 means raw measurements, 1 means no updates).
◆ reset()
| virtual void magnetometer_compass::MagnetometerCompass::reset |
( |
| ) |
|
|
virtual |
Reset the computation (i.e. the low-pass filter and estimated variance).
◆ setLowPassRatio()
| virtual void magnetometer_compass::MagnetometerCompass::setLowPassRatio |
( |
double |
ratio | ) |
|
|
virtual |
The azimuth is filtered with a low-pass filter. This sets its aggressivity.
- Parameters
-
| [in] | ratio | The ratio (0 means raw measurements, 1 means no updates). |
◆ updateVariance()
| virtual void magnetometer_compass::MagnetometerCompass::updateVariance |
( |
| ) |
|
|
protectedvirtual |
Re-estimate variance after adding a new measurement.
- Note
- This is not yet implemented.
◆ data
| std::unique_ptr<MagnetometerCompassPrivate> magnetometer_compass::MagnetometerCompass::data |
|
private |
The documentation for this class was generated from the following file: