MAV'RIC
|
Abstract class for magnetometers. More...
#include <magnetometer.hpp>
Public Member Functions | |
virtual bool | init (void)=0 |
Initialise the sensor. | |
virtual bool | update (void)=0 |
Main update function Reads new values from sensor. | |
virtual const float & | last_update_us (void) const =0 |
Get last update time in microseconds. | |
virtual const std::array < float, 3 > & | mag (void) const =0 |
Get X, Y and Z components of magnetic field. | |
virtual const float & | mag_X (void) const =0 |
Get X component of magnetic field. | |
virtual const float & | mag_Y (void) const =0 |
Get Y component of magnetic field. | |
virtual const float & | mag_Z (void) const =0 |
Get Z component of magnetic field. | |
virtual const float & | temperature (void) const =0 |
Get sensor temperature. |
Abstract class for magnetometers.
virtual bool Magnetometer::init | ( | void | ) | [pure virtual] |
virtual const float& Magnetometer::last_update_us | ( | void | ) | const [pure virtual] |
Get last update time in microseconds.
Implemented in Mpu_9250, Hmc5883l, and Magnetometer_sim.
virtual const std::array<float, 3>& Magnetometer::mag | ( | void | ) | const [pure virtual] |
Get X, Y and Z components of magnetic field.
This is raw data, so X, Y and Z components are biased, not scaled, and given in the sensor frame (not in the UAV frame). Use an Imu object to handle bias removal, scaling and axis rotations
Implemented in Mpu_9250, Hmc5883l, and Magnetometer_sim.
virtual const float& Magnetometer::mag_X | ( | void | ) | const [pure virtual] |
Get X component of magnetic field.
This is raw data, so X, Y and Z components are biased, not scaled, and given in the sensor frame (not in the UAV frame). Use an Imu object to handle bias removal, scaling and axis rotations
Implemented in Mpu_9250, Hmc5883l, and Magnetometer_sim.
virtual const float& Magnetometer::mag_Y | ( | void | ) | const [pure virtual] |
Get Y component of magnetic field.
This is raw data, so X, Y and Z components are biased, not scaled, and given in the sensor frame (not in the UAV frame). Use an Imu object to handle bias removal, scaling and axis rotations
Implemented in Mpu_9250, Hmc5883l, and Magnetometer_sim.
virtual const float& Magnetometer::mag_Z | ( | void | ) | const [pure virtual] |
Get Z component of magnetic field.
This is raw data, so X, Y and Z components are biased, not scaled, and given in the sensor frame (not in the UAV frame). Use an Imu object to handle bias removal, scaling and axis rotations
Implemented in Mpu_9250, Hmc5883l, and Magnetometer_sim.
virtual const float& Magnetometer::temperature | ( | void | ) | const [pure virtual] |
virtual bool Magnetometer::update | ( | void | ) | [pure virtual] |
Main update function Reads new values from sensor.
Implemented in Mpu_9250_mag, Hmc5883l, and Magnetometer_sim.