Class MagnetometerCompass
Defined in File magnetometer_compass.hpp
Class Documentation
-
class MagnetometerCompass
Convert magnetometer and IMU measurements to azimuth.
Public Types
-
using NodeClockInterface = rclcpp::node_interfaces::NodeClockInterface
-
using NodeLoggingInterface = rclcpp::node_interfaces::NodeLoggingInterface
-
using NodeParametersInterface = rclcpp::node_interfaces::NodeParametersInterface
-
using RequiredInterfaces = rclcpp::node_interfaces::NodeInterfaces<NodeClockInterface, NodeLoggingInterface, NodeParametersInterface>
Public Functions
Create the compass.
- Parameters:
node – [in] The node to use.
frame – [in] 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.
tf – [in] 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.
-
virtual ~MagnetometerCompass()
-
virtual void configFromParams()
Configure the bias remover from ROS 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).
-
geometry_msgs::msg::Quaternion getRotationBetweenFrames(const sensor_msgs::msg::Imu &imu_msg)
-
virtual void setLowPassRatio(double ratio)
The azimuth is filtered with a low-pass filter. This sets its aggressivity.
- Parameters:
ratio – [in] The ratio (0 means raw measurements, 1 means no updates).
-
virtual cras::expected<compass_interfaces::msg::Azimuth, std::string> computeAzimuth(const sensor_msgs::msg::Imu &imu, const sensor_msgs::msg::MagneticField &magUnbiased)
Compute azimuth from the provided IMU and magnetometer measurements.
Note
The function does not check time synchronization of the two inputs.
Note
Both inputs have to be transformable to the configured target frame.
- Parameters:
imu – [in] IMU tied to the magnetometer. It has to contain valid orientation.
magUnbiased – [in] Magnetometer measurement with removed bias.
- Returns:
The computed azimuth, or an error message. The azimuth will be in radians and NED frame.
-
virtual void reset()
Reset the computation (i.e. the low-pass filter and estimated variance).
Protected Functions
-
virtual void updateVariance()
Re-estimate variance after adding a new measurement.
Note
This is not yet implemented.
-
using NodeClockInterface = rclcpp::node_interfaces::NodeClockInterface