PCA9685 library
Dependents: s-rov-firmware DISCO-F746NG_rtos_test
pca9685.h@0:c6fb5a9a8f91, 2017-01-16 (annotated)
- Committer:
- YJ_Kim
- Date:
- Mon Jan 16 04:54:27 2017 +0000
- Revision:
- 0:c6fb5a9a8f91
- Child:
- 1:7e071acc57b1
first commit
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
YJ_Kim | 0:c6fb5a9a8f91 | 1 | #ifndef _PCA9685_H_ |
YJ_Kim | 0:c6fb5a9a8f91 | 2 | #define _PCA9685_H_ |
YJ_Kim | 0:c6fb5a9a8f91 | 3 | |
YJ_Kim | 0:c6fb5a9a8f91 | 4 | #include "mbed.h" |
YJ_Kim | 0:c6fb5a9a8f91 | 5 | |
YJ_Kim | 0:c6fb5a9a8f91 | 6 | #define PCA9685_MODE1 0x00 |
YJ_Kim | 0:c6fb5a9a8f91 | 7 | #define PCA9685_MODE2 0x01 |
YJ_Kim | 0:c6fb5a9a8f91 | 8 | #define PCA9685_PRESCALE 0xFE |
YJ_Kim | 0:c6fb5a9a8f91 | 9 | #define PCA9685_LED0_ON_L 0x06 |
YJ_Kim | 0:c6fb5a9a8f91 | 10 | #define PCA9685_CLOCK 25000000 |
YJ_Kim | 0:c6fb5a9a8f91 | 11 | |
YJ_Kim | 0:c6fb5a9a8f91 | 12 | #define CH_LED1 2 |
YJ_Kim | 0:c6fb5a9a8f91 | 13 | #define CH_LED2 3 |
YJ_Kim | 0:c6fb5a9a8f91 | 14 | #define CH_ESC1 4 |
YJ_Kim | 0:c6fb5a9a8f91 | 15 | #define CH_ESC2 5 |
YJ_Kim | 0:c6fb5a9a8f91 | 16 | #define CH_ESC3 6 |
YJ_Kim | 0:c6fb5a9a8f91 | 17 | #define CH_ESC4 7 |
YJ_Kim | 0:c6fb5a9a8f91 | 18 | #define CH_1 11 |
YJ_Kim | 0:c6fb5a9a8f91 | 19 | #define CH_2 10 |
YJ_Kim | 0:c6fb5a9a8f91 | 20 | #define CH_3 9 |
YJ_Kim | 0:c6fb5a9a8f91 | 21 | #define CH_4 8 |
YJ_Kim | 0:c6fb5a9a8f91 | 22 | #define CH_5 0 |
YJ_Kim | 0:c6fb5a9a8f91 | 23 | #define CH_6 1 |
YJ_Kim | 0:c6fb5a9a8f91 | 24 | |
YJ_Kim | 0:c6fb5a9a8f91 | 25 | |
YJ_Kim | 0:c6fb5a9a8f91 | 26 | class PCA9685{ |
YJ_Kim | 0:c6fb5a9a8f91 | 27 | public: |
YJ_Kim | 0:c6fb5a9a8f91 | 28 | PCA9685(uint8_t i2c_addr, I2C i2c_object, float freq); |
YJ_Kim | 0:c6fb5a9a8f91 | 29 | void reset(void); |
YJ_Kim | 0:c6fb5a9a8f91 | 30 | void init(void); |
YJ_Kim | 0:c6fb5a9a8f91 | 31 | void set_pwm_frequency(float freq); |
YJ_Kim | 0:c6fb5a9a8f91 | 32 | void set_pwm_output(uint8_t num, uint16_t on, uint16_t off); |
YJ_Kim | 0:c6fb5a9a8f91 | 33 | void set_pwm_duty(uint8_t num, float duty); |
YJ_Kim | 0:c6fb5a9a8f91 | 34 | void set_servo_angle(uint8_t num, float angle); |
YJ_Kim | 0:c6fb5a9a8f91 | 35 | void write_8(uint8_t reg, uint8_t msg); |
YJ_Kim | 0:c6fb5a9a8f91 | 36 | char read_8(uint8_t reg); |
YJ_Kim | 0:c6fb5a9a8f91 | 37 | |
YJ_Kim | 0:c6fb5a9a8f91 | 38 | private: |
YJ_Kim | 0:c6fb5a9a8f91 | 39 | uint8_t PCA9685_ADDR; |
YJ_Kim | 0:c6fb5a9a8f91 | 40 | float frequency; |
YJ_Kim | 0:c6fb5a9a8f91 | 41 | I2C i2c; |
YJ_Kim | 0:c6fb5a9a8f91 | 42 | |
YJ_Kim | 0:c6fb5a9a8f91 | 43 | }; |
YJ_Kim | 0:c6fb5a9a8f91 | 44 | |
YJ_Kim | 0:c6fb5a9a8f91 | 45 | #endif |