PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <stdint.h>
#include <sys/ioctl.h>
#include "drv_sensor.h"
#include "drv_orb_dev.h"
#include <uORB/topics/sensor_mag.h>
Go to the source code of this file.
Classes | |
struct | mag_calibration_s |
mag scaling factors; Vout = (Vin * Vscale) + Voffset More... | |
Macros | |
#define | MAG_BASE_DEVICE_PATH "/dev/mag" |
#define | MAG0_DEVICE_PATH "/dev/mag0" |
#define | MAG1_DEVICE_PATH "/dev/mag1" |
#define | MAG2_DEVICE_PATH "/dev/mag2" |
#define | mag_report sensor_mag_s |
#define | _MAGIOCBASE (0x2400) |
#define | _MAGIOC(_n) (_PX4_IOC(_MAGIOCBASE, _n)) |
#define | MAGIOCSSCALE _MAGIOC(4) |
set the mag scaling constants to the structure pointed to by (arg) More... | |
#define | MAGIOCGSCALE _MAGIOC(5) |
copy the mag scaling constants to the structure pointed to by (arg) More... | |
#define | MAGIOCSRANGE _MAGIOC(6) |
set the measurement range to handle (at least) arg Gauss More... | |
#define | MAGIOCCALIBRATE _MAGIOC(8) |
perform self-calibration, update scale factors to canonical units More... | |
#define | MAGIOCEXSTRAP _MAGIOC(9) |
excite strap More... | |
#define | MAGIOCGEXTERNAL _MAGIOC(11) |
determine if mag is external or onboard More... | |
#define | MAGIOCSTEMPCOMP _MAGIOC(12) |
enable/disable temperature compensation More... | |
#define _MAGIOC | ( | _n | ) | (_PX4_IOC(_MAGIOCBASE, _n)) |
#define MAG_BASE_DEVICE_PATH "/dev/mag" |
Definition at line 47 of file drv_mag.h.
Referenced by do_mag_calibration(), LSM303AGR::init(), LIS3MDL::init(), HMC5883::init(), RM3100::init(), QMC5883::init(), IST8310::init(), BMM150::init(), mag_calibrate_all(), sensors::VotedSensorsUpdate::parametersUpdate(), PX4Magnetometer::print_status(), PX4Magnetometer::PX4Magnetometer(), BMM150::~BMM150(), HMC5883::~HMC5883(), IST8310::~IST8310(), LIS3MDL::~LIS3MDL(), LSM303AGR::~LSM303AGR(), PX4Magnetometer::~PX4Magnetometer(), QMC5883::~QMC5883(), and RM3100::~RM3100().
#define mag_report sensor_mag_s |
Definition at line 53 of file drv_mag.h.
Referenced by DfAK8963Wrapper::_publish(), DfHmc5883Wrapper::_publish(), DfLsm9ds1Wrapper::_publish(), DfMpu9250Wrapper::_publish(), LIS3MDL::calibrate(), IST8310::calibrate(), LSM303AGR::collect(), RM3100::collect(), LIS3MDL::collect(), QMC5883::collect(), HMC5883::collect(), BMM150::collect(), IST8310::collect(), mpu9x50::create_pubs(), LIS3MDL::init(), HMC5883::init(), RM3100::init(), QMC5883::init(), IST8310::init(), BMM150::init(), mag_calibrate_all(), mag_calibration_worker(), sensors::VotedSensorsUpdate::magPoll(), sensors::VotedSensorsUpdate::parametersUpdate(), HMC5883::read(), LIS3MDL::read(), RM3100::read(), QMC5883::read(), IST8310::read(), BMM150::read(), DfLsm9ds1Wrapper::start(), bmm150::test(), rm3100::test(), lis3mdl::test(), qmc5883::test(), and ist8310::test().
#define MAGIOCCALIBRATE _MAGIOC(8) |
perform self-calibration, update scale factors to canonical units
Definition at line 82 of file drv_mag.h.
Referenced by lis3mdl::calibrate(), hmc5883::calibrate(), ist8310::calibrate(), do_mag_calibration(), UavcanMagnetometerBridge::ioctl(), LIS3MDL::ioctl(), HMC5883::ioctl(), RM3100::ioctl(), IST8310::ioctl(), and BMM150::ioctl().
#define MAGIOCEXSTRAP _MAGIOC(9) |
excite strap
Definition at line 85 of file drv_mag.h.
Referenced by HMC5883::calibrate(), LIS3MDL::calibrate(), IST8310::calibrate(), UavcanMagnetometerBridge::ioctl(), LIS3MDL::ioctl(), HMC5883::ioctl(), IST8310::ioctl(), and BMM150::ioctl().
#define MAGIOCGEXTERNAL _MAGIOC(11) |
determine if mag is external or onboard
Definition at line 88 of file drv_mag.h.
Referenced by RM3100::collect(), LIS3MDL::collect(), QMC5883::collect(), HMC5883::collect(), do_mag_calibration(), UavcanMagnetometerBridge::ioctl(), HMC5883_I2C::ioctl(), QMC5883_I2C::ioctl(), LSM303AGR::ioctl(), LIS3MDL::ioctl(), HMC5883::ioctl(), RM3100::ioctl(), QMC5883::ioctl(), IST8310::ioctl(), rm3100::test(), lis3mdl::test(), qmc5883::test(), and ist8310::test().
#define MAGIOCGSCALE _MAGIOC(5) |
copy the mag scaling constants to the structure pointed to by (arg)
Definition at line 76 of file drv_mag.h.
Referenced by HMC5883::calibrate(), IST8310::calibrate(), PX4Magnetometer::ioctl(), UavcanMagnetometerBridge::ioctl(), LSM303AGR::ioctl(), LIS3MDL::ioctl(), HMC5883::ioctl(), RM3100::ioctl(), QMC5883::ioctl(), IST8310::ioctl(), BMM150::ioctl(), and mag_calibrate_all().
#define MAGIOCSRANGE _MAGIOC(6) |
set the measurement range to handle (at least) arg Gauss
Definition at line 79 of file drv_mag.h.
Referenced by HMC5883::calibrate(), LIS3MDL::calibrate(), do_mag(), UavcanMagnetometerBridge::ioctl(), LIS3MDL::ioctl(), HMC5883::ioctl(), RM3100::ioctl(), and QMC5883::ioctl().
#define MAGIOCSSCALE _MAGIOC(4) |
set the mag scaling constants to the structure pointed to by (arg)
Definition at line 73 of file drv_mag.h.
Referenced by sensors::VotedSensorsUpdate::applyMagCalibration(), HMC5883::calibrate(), IST8310::calibrate(), do_mag_calibration(), PX4Magnetometer::ioctl(), UavcanMagnetometerBridge::ioctl(), LSM303AGR::ioctl(), LIS3MDL::ioctl(), HMC5883::ioctl(), RM3100::ioctl(), QMC5883::ioctl(), IST8310::ioctl(), BMM150::ioctl(), and mag_calibrate_all().
#define MAGIOCSTEMPCOMP _MAGIOC(12) |
enable/disable temperature compensation
Definition at line 91 of file drv_mag.h.
Referenced by HMC5883::ioctl(), and hmc5883::temp_enable().