Class Magnetometer
Defined in File magnetometer.hpp
Class Documentation
-
class Magnetometer
Public Functions
-
explicit Magnetometer(int32_t serial_number, int hub_port, bool is_hub_port_device, std::function<void(const double[3], double)> data_handler)
-
~Magnetometer()
-
int32_t getSerialNumber() const noexcept
-
void setCompassCorrectionParameters(double cc_mag_field, double cc_offset0, double cc_offset1, double cc_offset2, double cc_gain0, double cc_gain1, double cc_gain2, double cc_T0, double cc_T1, double cc_T2, double cc_T3, double cc_T4, double cc_T5)
-
void getMagneticField(double &x, double &y, double &z, double ×tamp) const
-
void setDataInterval(uint32_t interval_ms) const
-
void dataHandler(const double magnetic_field[3], double timestamp) const
-
explicit Magnetometer(int32_t serial_number, int hub_port, bool is_hub_port_device, std::function<void(const double[3], double)> data_handler)