PX4 Firmware
PX4 Autopilot Software http://px4.io
ak09916.hpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2019 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 #pragma once
35 
36 
37 #include <px4_platform_common/px4_config.h>
38 #include <lib/perf/perf_counter.h>
39 #include <systemlib/conversions.h>
40 #include <drivers/drv_hrt.h>
41 #include <drivers/device/i2c.h>
42 #include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
44 
45 static constexpr auto AK09916_DEVICE_PATH_MAG = "/dev/ak09916_i2c_int";
46 static constexpr auto AK09916_DEVICE_PATH_MAG_EXT = "/dev/ak09916_i2c_ext";
47 
48 // in 16-bit sampling mode the mag resolution is 1.5 milli Gauss per bit.
49 static constexpr float AK09916_MAG_RANGE_GA = 1.5e-3f;
50 
51 static constexpr uint8_t AK09916_I2C_ADDR = 0x0C;
52 
53 static constexpr uint8_t AK09916_DEVICE_ID_A = 0x48;
54 static constexpr uint8_t AK09916REG_WIA = 0x00;
55 
56 static constexpr uint8_t AK09916REG_ST1 = 0x10;
57 static constexpr uint8_t AK09916REG_HXL = 0x11;
58 static constexpr uint8_t AK09916REG_CNTL2 = 0x31;
59 static constexpr uint8_t AK09916REG_CNTL3 = 0x32;
60 
61 static constexpr uint8_t AK09916_RESET = 0x01;
62 static constexpr uint8_t AK09916_CNTL2_CONTINOUS_MODE_100HZ = 0x08;
63 
64 static constexpr uint8_t AK09916_ST1_DRDY = 0x01;
65 static constexpr uint8_t AK09916_ST1_DOR = 0x02;
66 
67 static constexpr uint8_t AK09916_ST2_HOFL = 0x08;
68 
69 // Run at 100 Hz.
70 static constexpr unsigned AK09916_CONVERSION_INTERVAL_us = 1000000 / 100;
71 
72 #pragma pack(push, 1)
73 struct ak09916_regs {
74  int16_t x;
75  int16_t y;
76  int16_t z;
77  uint8_t tmps;
78  uint8_t st2;
79 };
80 #pragma pack(pop)
81 
82 
83 class AK09916 : public device::I2C, px4::ScheduledWorkItem
84 {
85 public:
86  AK09916(int bus, const char *path, enum Rotation rotation);
87  ~AK09916();
88 
89  virtual int init() override;
90  void start();
91  void stop();
92  void print_info();
93  int probe();
94 
95 protected:
96  int setup();
97  int setup_master_i2c();
98  bool check_id();
99  void Run();
100  void try_measure();
101  bool is_ready();
102  void measure();
103  int reset();
104 
105  uint8_t read_reg(uint8_t reg);
106  void read_block(uint8_t reg, uint8_t *val, uint8_t count);
107  void write_reg(uint8_t reg, uint8_t value);
108 
109 private:
110 
112 
113  uint32_t _cycle_interval{0};
114 
119 
120  AK09916(const AK09916 &) = delete;
121  AK09916 operator=(const AK09916 &) = delete;
122 };
static constexpr uint8_t AK09916_RESET
Definition: ak09916.hpp:61
static constexpr unsigned AK09916_CONVERSION_INTERVAL_us
Definition: ak09916.hpp:70
static constexpr uint8_t AK09916REG_CNTL2
Definition: ak09916.hpp:58
static constexpr uint8_t AK09916_ST2_HOFL
Definition: ak09916.hpp:67
static constexpr uint8_t AK09916REG_ST1
Definition: ak09916.hpp:56
static constexpr uint8_t AK09916_ST1_DOR
Definition: ak09916.hpp:65
int reset(enum LPS22HB_BUS busid)
Reset the driver.
static void stop()
Definition: dataman.cpp:1491
static constexpr uint8_t AK09916_I2C_ADDR
Definition: ak09916.hpp:51
High-resolution timer with callouts and timekeeping.
uint8_t tmps
Definition: ICM20948_mag.h:99
perf_counter_t _mag_reads
Definition: ak09916.hpp:115
perf_counter_t _mag_overruns
Definition: ak09916.hpp:117
Header common to all counters.
void init()
Activates/configures the hardware registers.
static constexpr uint8_t AK09916_ST1_DRDY
Definition: ak09916.hpp:64
Definition of commonly used conversions.
Rotation
Enum for board and external compass rotations.
Definition: rotation.h:51
perf_counter_t _mag_errors
Definition: ak09916.hpp:116
Vector< float, 6 > f(float t, const Matrix< float, 6, 1 > &, const Matrix< float, 3, 1 > &)
Definition: integration.cpp:8
static constexpr uint8_t AK09916REG_CNTL3
Definition: ak09916.hpp:59
static int start()
Definition: dataman.cpp:1452
static constexpr uint8_t AK09916_CNTL2_CONTINOUS_MODE_100HZ
Definition: ak09916.hpp:62
perf_counter_t _mag_overflows
Definition: ak09916.hpp:118
static constexpr auto AK09916_DEVICE_PATH_MAG_EXT
Definition: ak09916.hpp:46
static constexpr uint8_t AK09916REG_HXL
Definition: ak09916.hpp:57
static constexpr uint8_t AK09916REG_WIA
Definition: ak09916.hpp:54
PX4Magnetometer _px4_mag
Definition: ak09916.hpp:111
static constexpr float AK09916_MAG_RANGE_GA
Definition: ak09916.hpp:49
Performance measuring tools.
static constexpr uint8_t AK09916_DEVICE_ID_A
Definition: ak09916.hpp:53
static constexpr auto AK09916_DEVICE_PATH_MAG
Definition: ak09916.hpp:45
Base class for devices connected via I2C.