PX4 Firmware
PX4 Autopilot Software http://px4.io
I2C.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2012-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 i2c.cpp
36  *
37  * Base class for devices attached via the I2C bus.
38  *
39  * @todo Bus frequency changes; currently we do nothing with the value
40  * that is supplied. Should we just depend on the bus knowing?
41  */
42 
43 #include "I2C.hpp"
44 
45 #include "dev_fs_lib_i2c.h"
46 
47 namespace device
48 {
49 
50 I2C::I2C(const char *name, const char *devname, const int bus, const uint16_t address, const uint32_t frequency) :
51  CDev(name, devname)
52 {
53  DEVICE_DEBUG("I2C::I2C name = %s devname = %s", name, devname);
54  // fill in _device_id fields for a I2C device
55  _device_id.devid_s.bus_type = DeviceBusType_I2C;
56  _device_id.devid_s.bus = bus;
57  _device_id.devid_s.address = address;
58  // devtype needs to be filled in by the driver
59  _device_id.devid_s.devtype = 0;
60 }
61 
62 I2C::~I2C()
63 {
64  if (_fd >= 0) {
65  ::close(_fd);
66  _fd = -1;
67  }
68 }
69 
70 int
71 I2C::init()
72 {
73  // Assume the driver set the desired bus frequency. There is no standard
74  // way to set it from user space.
75 
76  // do base class init, which will create device node, etc
77  int ret = CDev::init();
78 
79  if (ret != PX4_OK) {
80  DEVICE_DEBUG("CDev::init failed");
81  return ret;
82  }
83 
84  // Open the actual I2C device
85  char dev_path[16];
86  snprintf(dev_path, sizeof(dev_path), "/dev/iic-%i", get_device_bus());
87  _fd = ::open(dev_path, O_RDWR);
88 
89  if (_fd < 0) {
90  PX4_ERR("could not open %s", dev_path);
91  px4_errno = errno;
92  return PX4_ERROR;
93  }
94 
95  return ret;
96 }
97 
98 int
99 I2C::transfer(const uint8_t *send, const unsigned send_len, uint8_t *recv, const unsigned recv_len)
100 {
101  dspal_i2c_ioctl_combined_write_read ioctl_write_read{};
102 
103  ioctl_write_read.write_buf = (uint8_t *)send;
104  ioctl_write_read.write_buf_len = send_len;
105  ioctl_write_read.read_buf = recv;
106  ioctl_write_read.read_buf_len = recv_len;
107 
108  int bytes_read = ::ioctl(_fd, I2C_IOCTL_RDWR, &ioctl_write_read);
109 
110  if (bytes_read != (ssize_t)recv_len) {
111  PX4_ERR("read register reports a read of %d bytes, but attempted to read %d bytes", bytes_read, recv_len);
112  return -1;
113  }
114 
115  return 0;
116 }
117 
118 } // namespace device
int transfer(const uint8_t *send, const unsigned send_len, uint8_t *recv, const unsigned recv_len)
Perform an I2C transaction to the device.
void * send(void *data)
Namespace encapsulating all device framework classes, functions and data.
Definition: CDev.cpp:47
virtual ~I2C()
void init()
Activates/configures the hardware registers.
int px4_errno
const char * name
Definition: tests_main.c:58
virtual int init() override
#define DEVICE_DEBUG(FMT,...)
Definition: Device.hpp:52