PX4 Firmware
PX4 Autopilot Software http://px4.io
hmc5883_i2c.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2013-2015 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 /**
35  * @file HMC5883_I2C.cpp
36  *
37  * I2C interface for HMC5883 / HMC 5983
38  */
39 
40 #include <px4_platform_common/px4_config.h>
41 #include <drivers/device/i2c.h>
42 #include <drivers/drv_mag.h>
43 #include <drivers/drv_device.h>
44 
45 #include "hmc5883.h"
46 
47 #define HMC5883L_ADDRESS 0x1E
48 
50 
51 class HMC5883_I2C : public device::I2C
52 {
53 public:
54  HMC5883_I2C(int bus);
55  virtual ~HMC5883_I2C() = default;
56 
57  virtual int read(unsigned address, void *data, unsigned count);
58  virtual int write(unsigned address, void *data, unsigned count);
59 
60  virtual int ioctl(unsigned operation, unsigned &arg);
61 
62 protected:
63  virtual int probe();
64 
65 };
66 
69 {
70  return new HMC5883_I2C(bus);
71 }
72 
74  I2C("HMC5883_I2C", nullptr, bus, HMC5883L_ADDRESS, 400000)
75 {
76  _device_id.devid_s.devtype = DRV_MAG_DEVTYPE_HMC5883;
77 }
78 
79 int
80 HMC5883_I2C::ioctl(unsigned operation, unsigned &arg)
81 {
82  int ret;
83 
84  switch (operation) {
85 
86  case MAGIOCGEXTERNAL:
87  return external();
88 
89  case DEVIOCGDEVICEID:
90  return CDev::ioctl(nullptr, operation, arg);
91 
92  default:
93  ret = -EINVAL;
94  }
95 
96  return ret;
97 }
98 
99 int
101 {
102  uint8_t data[3] = {0, 0, 0};
103 
104  _retries = 10;
105 
106  if (read(ADDR_ID_A, &data[0], 1) ||
107  read(ADDR_ID_B, &data[1], 1) ||
108  read(ADDR_ID_C, &data[2], 1)) {
109  DEVICE_DEBUG("read_reg fail");
110  return -EIO;
111  }
112 
113  _retries = 2;
114 
115  if ((data[0] != ID_A_WHO_AM_I) ||
116  (data[1] != ID_B_WHO_AM_I) ||
117  (data[2] != ID_C_WHO_AM_I)) {
118  DEVICE_DEBUG("ID byte mismatch (%02x,%02x,%02x)", data[0], data[1], data[2]);
119  return -EIO;
120  }
121 
122  return OK;
123 }
124 
125 int
126 HMC5883_I2C::write(unsigned address, void *data, unsigned count)
127 {
128  uint8_t buf[32];
129 
130  if (sizeof(buf) < (count + 1)) {
131  return -EIO;
132  }
133 
134  buf[0] = address;
135  memcpy(&buf[1], data, count);
136 
137  return transfer(&buf[0], count + 1, nullptr, 0);
138 }
139 
140 int
141 HMC5883_I2C::read(unsigned address, void *data, unsigned count)
142 {
143  uint8_t cmd = address;
144  return transfer(&cmd, 1, (uint8_t *)data, count);
145 }
#define MAGIOCGEXTERNAL
determine if mag is external or onboard
Definition: drv_mag.h:88
#define ADDR_ID_B
Definition: hmc5883.h:45
virtual ~HMC5883_I2C()=default
#define ID_C_WHO_AM_I
Definition: hmc5883.h:50
#define ADDR_ID_A
Definition: hmc5883.h:44
#define DRV_MAG_DEVTYPE_HMC5883
Sensor type definitions.
Definition: drv_sensor.h:55
virtual int read(unsigned address, void *data, unsigned count)
device::Device * HMC5883_I2C_interface(int bus)
Definition: hmc5883_i2c.cpp:68
#define ID_B_WHO_AM_I
Definition: hmc5883.h:49
Generic device / sensor interface.
#define ADDR_ID_C
Definition: hmc5883.h:46
uint8_t * data
Definition: dataman.cpp:149
HMC5883_I2C(int bus)
Definition: hmc5883_i2c.cpp:73
virtual int write(unsigned address, void *data, unsigned count)
#define ID_A_WHO_AM_I
Definition: hmc5883.h:48
virtual int probe()
Shared defines for the hmc5883 driver.
Fundamental base class for all physical drivers (I2C, SPI).
Definition: Device.hpp:65
virtual int ioctl(unsigned operation, unsigned &arg)
Definition: hmc5883_i2c.cpp:80
#define OK
Definition: uavcan_main.cpp:71
#define HMC5883L_ADDRESS
Definition: hmc5883_i2c.cpp:47
#define DEVICE_DEBUG(FMT,...)
Definition: Device.hpp:52
Base class for devices connected via I2C.