26 #ifdef HAL_COMPASS_HMC5843_I2C_ADDR 46 #define HMC5843_REG_CONFIG_A 0x00 48 #define HMC5843_SAMPLE_AVERAGING_1 (0x00 << 5) 49 #define HMC5843_SAMPLE_AVERAGING_2 (0x01 << 5) 50 #define HMC5843_SAMPLE_AVERAGING_4 (0x02 << 5) 51 #define HMC5843_SAMPLE_AVERAGING_8 (0x03 << 5) 53 #define HMC5843_CONF_TEMP_ENABLE (0x80) 56 #define HMC5843_OSR_0_75HZ (0x00 << 2) 57 #define HMC5843_OSR_1_5HZ (0x01 << 2) 58 #define HMC5843_OSR_3HZ (0x02 << 2) 59 #define HMC5843_OSR_7_5HZ (0x03 << 2) 60 #define HMC5843_OSR_15HZ (0x04 << 2) 61 #define HMC5843_OSR_30HZ (0x05 << 2) 62 #define HMC5843_OSR_75HZ (0x06 << 2) 64 #define HMC5843_OPMODE_NORMAL 0x00 65 #define HMC5843_OPMODE_POSITIVE_BIAS 0x01 66 #define HMC5843_OPMODE_NEGATIVE_BIAS 0x02 67 #define HMC5843_OPMODE_MASK 0x03 69 #define HMC5843_REG_CONFIG_B 0x01 70 #define HMC5883L_GAIN_0_88_GA (0x00 << 5) 71 #define HMC5883L_GAIN_1_30_GA (0x01 << 5) 72 #define HMC5883L_GAIN_1_90_GA (0x02 << 5) 73 #define HMC5883L_GAIN_2_50_GA (0x03 << 5) 74 #define HMC5883L_GAIN_4_00_GA (0x04 << 5) 75 #define HMC5883L_GAIN_4_70_GA (0x05 << 5) 76 #define HMC5883L_GAIN_5_60_GA (0x06 << 5) 77 #define HMC5883L_GAIN_8_10_GA (0x07 << 5) 79 #define HMC5843_GAIN_0_70_GA (0x00 << 5) 80 #define HMC5843_GAIN_1_00_GA (0x01 << 5) 81 #define HMC5843_GAIN_1_50_GA (0x02 << 5) 82 #define HMC5843_GAIN_2_00_GA (0x03 << 5) 83 #define HMC5843_GAIN_3_20_GA (0x04 << 5) 84 #define HMC5843_GAIN_3_80_GA (0x05 << 5) 85 #define HMC5843_GAIN_4_50_GA (0x06 << 5) 86 #define HMC5843_GAIN_6_50_GA (0x07 << 5) 88 #define HMC5843_REG_MODE 0x02 89 #define HMC5843_MODE_CONTINUOUS 0x00 90 #define HMC5843_MODE_SINGLE 0x01 92 #define HMC5843_REG_DATA_OUTPUT_X_MSB 0x03 94 #define HMC5843_REG_ID_A 0x0A 98 bool force_external,
enum Rotation rotation)
101 , _rotation(rotation)
102 , _force_external(force_external)
125 if (!sensor || !sensor->
init()) {
145 if (!sensor || !sensor->
init()) {
158 hal.
console->
printf(
"HMC5843: Unable to get bus semaphore\n");
163 _bus->set_retries(10);
165 if (!_bus->configure()) {
166 hal.
console->
printf(
"HMC5843: Could not configure the bus\n");
170 if (!_check_whoami()) {
176 hal.
console->
printf(
"HMC5843: Could not calibrate sensor\n");
180 if (!_setup_sampling_mode()) {
184 if (!_bus->start_measurements()) {
185 hal.
console->
printf(
"HMC5843: Could not start measurements on bus\n");
192 _bus->set_retries(3);
206 if (_force_external) {
211 _bus->register_periodic_callback(13333,
214 hal.
console->
printf(
"HMC5843 found on bus 0x%x\n", (
unsigned)_bus->get_bus_id());
230 bool result = _read_sample();
246 raw_field *= _gain_scale;
269 _mag_x_accum += raw_field.
x;
270 _mag_y_accum += raw_field.
y;
271 _mag_z_accum += raw_field.
z;
273 if (_accum_count == 14) {
301 if (_accum_count == 0) {
306 Vector3f field(_mag_x_accum * _scaling[0],
307 _mag_y_accum * _scaling[1],
308 _mag_z_accum * _scaling[2]);
309 field /= _accum_count;
312 _mag_x_accum = _mag_y_accum = _mag_z_accum = 0;
321 _gain_scale = (1.0f / 1090) * 1000;
322 if (!_bus->register_write(HMC5843_REG_CONFIG_A,
323 HMC5843_CONF_TEMP_ENABLE |
325 HMC5843_SAMPLE_AVERAGING_1) ||
326 !_bus->register_write(HMC5843_REG_CONFIG_B,
327 HMC5883L_GAIN_1_30_GA) ||
328 !_bus->register_write(HMC5843_REG_MODE,
329 HMC5843_MODE_SINGLE)) {
347 if (!_bus->block_read(HMC5843_REG_DATA_OUTPUT_X_MSB, (uint8_t *) &val,
sizeof(val))){
355 if (rx == -4096 || ry == -4096 || rz == -4096) {
373 _bus->register_write(HMC5843_REG_MODE,
374 HMC5843_MODE_SINGLE);
380 if (!_bus->block_read(HMC5843_REG_ID_A,
id, 3)) {
396 uint8_t calibration_gain;
397 int numAttempts = 0, good_count = 0;
398 bool success =
false;
400 calibration_gain = HMC5883L_GAIN_2_50_GA;
405 float expected[3] = { 1.16*600, 1.08*600, 1.16*600 };
407 uint8_t base_config = HMC5843_OSR_15HZ;
408 uint8_t num_samples = 0;
410 while (success == 0 && numAttempts < 25 && good_count < 5) {
414 if (!_bus->register_write(HMC5843_REG_CONFIG_A,
415 base_config | HMC5843_OPMODE_POSITIVE_BIAS)) {
423 if (!_bus->register_write(HMC5843_REG_CONFIG_B, calibration_gain) ||
424 !_bus->register_write(HMC5843_REG_MODE, HMC5843_MODE_SINGLE)) {
430 if (!_read_sample()) {
441 cal[0] = fabsf(expected[0] / _mag_x);
442 cal[1] = fabsf(expected[1] / _mag_y);
443 cal[2] = fabsf(expected[2] / _mag_z);
451 if (numAttempts <= 2) {
455 #define IS_CALIBRATION_VALUE_VALID(val) (val > 0.7f && val < 1.35f) 457 if (IS_CALIBRATION_VALUE_VALID(cal[0]) &&
458 IS_CALIBRATION_VALUE_VALID(cal[1]) &&
459 IS_CALIBRATION_VALUE_VALID(cal[2])) {
463 _scaling[0] += cal[0];
464 _scaling[1] += cal[1];
465 _scaling[2] += cal[2];
468 #undef IS_CALIBRATION_VALUE_VALID 472 hal.
console->
printf(
"MagX: %d MagY: %d MagZ: %d\n", (
int)_mag_x, (
int)_mag_y, (
int)_mag_z);
473 hal.
console->
printf(
"CalX: %.2f CalY: %.2f CalZ: %.2f\n", cal[0], cal[1], cal[2]);
477 _bus->register_write(HMC5843_REG_CONFIG_A, base_config);
479 if (good_count >= 5) {
480 _scaling[0] = _scaling[0] / good_count;
481 _scaling[1] = _scaling[1] / good_count;
482 _scaling[2] = _scaling[2] / good_count;
489 if (num_samples > 5) {
497 printf(
"scaling: %.2f %.2f %.2f\n",
498 _scaling[0], _scaling[1], _scaling[2]);
506 : _dev(
std::move(dev))
510 _dev->set_read_flag(0xC0);
516 return _dev->read_registers(reg, buf, size);
521 return _dev->read_registers(reg, val, 1);
526 return _dev->write_register(reg, val);
531 return _dev->get_semaphore();
536 return _dev->register_periodic_callback(period_usec, cb);
571 assert(reg == HMC5843_REG_DATA_OUTPUT_X_MSB);
573 int n = _slave->read(buf);
574 return n ==
static_cast<int>(size);
577 int r = _slave->passthrough_read(reg, buf, size);
579 return r > 0 &&
static_cast<uint32_t
>(r) == size;
584 return _slave->passthrough_read(reg, val, 1) == 1;
589 return _slave->passthrough_write(reg, val) == 1;
594 return _bus->get_semaphore();
600 if (!_bus || !_slave) {
608 if (_bus->register_periodic_read(_slave, HMC5843_REG_DATA_OUTPUT_X_MSB, 6) < 0) {
619 return _bus->register_periodic_callback(period_usec, cb);
625 _bus->set_device_type(devtype);
631 return _bus->get_bus_id();
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override
int printf(const char *fmt,...)
#define HAL_INS_MPU60XX_SPI
AP_HAL::Semaphore * get_semaphore() override
bool register_write(uint8_t reg, uint8_t val) override
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override
AP_Compass_HMC5843(Compass &compass, AP_HMC5843_BusDriver *bus, bool force_external, enum Rotation rotation)
void set_device_type(uint8_t devtype) override
Vector3< float > Vector3f
bool configure() override
bool register_read(uint8_t reg, uint8_t *val) override
void set_external(uint8_t instance, bool external)
AP_HAL::UARTDriver * console
#define HAL_COMPASS_HMC5843_I2C_ADDR
void rotate_field(Vector3f &mag, uint8_t instance)
bool register_read(uint8_t reg, uint8_t *val) override
void publish_filtered_field(const Vector3f &mag, uint8_t instance)
void correct_field(Vector3f &mag, uint8_t i)
bool field_ok(const Vector3f &field)
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev, bool force_external=false, enum Rotation rotation=ROTATION_NONE)
#define HAL_SEMAPHORE_BLOCK_FOREVER
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
void set_dev_id(uint8_t instance, uint32_t dev_id)
static AP_InertialSensor ins
virtual void delay(uint16_t ms)=0
virtual void printf(const char *,...) FMT_PRINTF(2
virtual bool take_nonblocking() WARN_IF_UNUSED=0
bool register_write(uint8_t reg, uint8_t val) override
static uint16_t be16toh(be16_t value)
static AP_HAL::OwnPtr< AP_HAL::Device > dev
uint8_t register_compass(void) const
AuxiliaryBusSlave * request_next_slave(uint8_t addr)
virtual ~AP_HMC5843_BusDriver_Auxiliary()
AP_HAL::Semaphore * get_semaphore() override
uint32_t get_bus_id(void) const override
bool _setup_sampling_mode()
AP_HMC5843_BusDriver_Auxiliary(AP_InertialSensor &ins, uint8_t backend_id, uint8_t addr)
virtual ~AP_Compass_HMC5843()
void rotate(enum Rotation rotation)
uint8_t _compass_instance[HIL_NUM_COMPASSES]
bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) override
void set_rotation(uint8_t instance, enum Rotation rotation)
AuxiliaryBus * get_auxiliary_bus(int16_t backend_id)
static AP_Compass_Backend * probe_mpu6000(Compass &compass, enum Rotation rotation=ROTATION_NONE)
bool is_external(uint8_t instance)
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) override
void publish_raw_field(const Vector3f &mag, uint8_t instance)
AP_HMC5843_BusDriver_HALDevice(AP_HAL::OwnPtr< AP_HAL::Device > dev)
bool start_measurements() override
static AP_InertialSensor * get_instance()
AP_HAL::Scheduler * scheduler
uint16_t __ap_bitwise be16_t