PX4 Firmware
PX4 Autopilot Software http://px4.io
PCA9685.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2017 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  * Original Author : Georgi Todorov
34  * Edited by : Tord Wessman
35  * Created on : Nov 22, 2013
36  * Rewrite : Fan.zhang 421395590@qq.com
37  * Updated on : Mar 2, 2017
38  ****************************************************************************/
39 
40 #include <sys/stat.h>
41 #include <sys/ioctl.h>
42 #include <unistd.h>
43 #include <linux/i2c-dev.h>
44 #include <stdio.h> /* Standard I/O functions */
45 #include <fcntl.h>
46 #include <inttypes.h>
47 #include <errno.h>
48 #include <math.h>
49 #include <stdio.h>
50 #include <unistd.h>
51 
52 #include "PCA9685.h"
53 
54 #include <px4_platform_common/log.h>
55 
56 using namespace linux_pwm_out;
57 
58 int PCA9685::init(int bus, int address)
59 {
60  _fd = open_fd(bus, address);
61  reset();
62 
63  usleep(1000 * 100);
64  /* 12BIT 精度输出下,好赢电调可以到200HZ刷新 */
65  /* 200HZ for 12bit Resolution, supported by most of the esc's */
66  setPWMFreq(200);
67  usleep(1000 * 1000);
68  return 0;
69 }
70 
71 int PCA9685::send_output_pwm(const uint16_t *pwm, int num_outputs)
72 {
73  if (num_outputs > 16) {
74  num_outputs = 16;
75  }
76 
77  for (int i = 0; i < num_outputs; ++i) {
78  setPWM(i, pwm[i]);
79  }
80 
81  return 0;
82 }
83 
85 {
87 }
88 
89 PCA9685::PCA9685(int bus, int address)
90 {
91  init(bus, address);
92 }
93 
95 {
96  reset();
97 
98  if (_fd >= 0) {
99  close(_fd);
100  }
101 }
102 
104 {
105  if (_fd != -1) {
106  write_byte(_fd, MODE1, 0x00); //Normal mode
107  write_byte(_fd, MODE2, 0x04); //Normal mode
108  }
109 }
110 
111 void PCA9685::setPWMFreq(int freq)
112 {
113  if (_fd != -1) {
114  uint8_t prescale = (CLOCK_FREQ / MAX_PWM_RES / freq) - 1;
115  //printf ("Setting prescale value to: %d\n", prescale);
116  //printf ("Using Frequency: %d\n", freq);
117 
118  uint8_t oldmode = read_byte(_fd, MODE1);
119  uint8_t newmode = (oldmode & 0x7F) | 0x10; //sleep
120  write_byte(_fd, MODE1, newmode); // go to sleep
121  write_byte(_fd, PRE_SCALE, prescale);
122  write_byte(_fd, MODE1, oldmode);
123  usleep(10 * 1000);
124  write_byte(_fd, MODE1, oldmode | 0x80);
125  }
126 }
127 
128 
129 void PCA9685::setPWM(uint8_t led, int value)
130 {
131  setPWM(led, 0, value);
132 }
133 
134 void PCA9685::setPWM(uint8_t led, int on_value, int off_value)
135 {
136  if (_fd != -1) {
137  write_byte(_fd, LED0_ON_L + LED_MULTIPLYER * led, on_value & 0xFF);
138 
139  write_byte(_fd, LED0_ON_H + LED_MULTIPLYER * led, on_value >> 8);
140 
141  write_byte(_fd, LED0_OFF_L + LED_MULTIPLYER * led, off_value & 0xFF);
142 
143  write_byte(_fd, LED0_OFF_H + LED_MULTIPLYER * led, off_value >> 8);
144  }
145 
146 }
147 
148 uint8_t PCA9685::read_byte(int fd, uint8_t address)
149 {
150 
151  uint8_t buf[1];
152  buf[0] = address;
153 
154  if (write(fd, buf, 1) != 1) {
155  return -1;
156  }
157 
158  if (read(fd, buf, 1) != 1) {
159  return -1;
160  }
161 
162  return buf[0];
163 }
164 
165 void PCA9685::write_byte(int fd, uint8_t address, uint8_t data)
166 {
167  uint8_t buf[2];
168  buf[0] = address;
169  buf[1] = data;
170 
171  if (write(fd, buf, sizeof(buf)) != sizeof(buf)) {
172  PX4_ERR("Write failed (%i)", errno);
173  }
174 }
175 
176 int PCA9685::open_fd(int bus, int address)
177 {
178  int fd;
179  char bus_file[64];
180  snprintf(bus_file, sizeof(bus_file), "/dev/i2c-%d", bus);
181 
182  if ((fd = open(bus_file, O_RDWR)) < 0) {
183  PX4_ERR("Couldn't open I2C Bus %d [open_fd():open %d]", bus, errno);
184  return -1;
185  }
186 
187  if (ioctl(fd, I2C_SLAVE, address) < 0) {
188  PX4_ERR("I2C slave %d failed [open_fd():ioctl %d]", address, errno);
189  return -1;
190  }
191 
192  return fd;
193 }
#define LED_MULTIPLYER
Definition: PCA9685.h:60
void reset()
Sets PCA9685 mode to 00.
Definition: PCA9685.cpp:103
#define LED0_OFF_L
Definition: PCA9685.h:58
#define PCA9685_DEFAULT_I2C_BUS
Definition: PCA9685.h:69
#define PRE_SCALE
Definition: PCA9685.h:65
uint8_t read_byte(int fd, uint8_t address)
Read a single byte from PCA9685.
Definition: PCA9685.cpp:148
void setPWMFreq(int freq)
Set the frequency of PWM.
Definition: PCA9685.cpp:111
void write_byte(int fd, uint8_t address, uint8_t data)
Write a single byte to PCA9685.
Definition: PCA9685.cpp:165
int init() override
Definition: PCA9685.h:85
#define LED0_OFF_H
Definition: PCA9685.h:59
int _fd
I2C device file descriptor.
Definition: PCA9685.h:118
static void read(bootloader_app_shared_t *pshared)
uint8_t * data
Definition: dataman.cpp:149
#define MAX_PWM_RES
Definition: PCA9685.h:66
#define CLOCK_FREQ
Definition: PCA9685.h:67
int fd
Definition: dataman.cpp:146
#define LED0_ON_L
Definition: PCA9685.h:56
#define MODE2
Definition: PCA9685.h:50
#define MODE1
Definition: PCA9685.h:49
static void write(bootloader_app_shared_t *pshared)
#define LED0_ON_H
Definition: PCA9685.h:57
#define PCA9685_DEFAULT_I2C_ADDR
Definition: PCA9685.h:68
int send_output_pwm(const uint16_t *pwm, int num_outputs) override
Definition: PCA9685.cpp:71
int open_fd(int bus, int address)
Open device file for PCA9685 I2C bus.
Definition: PCA9685.cpp:176
void setPWM(uint8_t channel, int on_value, int off_value)
PWM a single channel with custom on time.
Definition: PCA9685.cpp:134