seeed unified library interface

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers suli2.h Source File

suli2.h

00001 /*
00002   suli2.h
00003   Seeed Unified Library Interface v2.0
00004   2015 Copyright (c) Seeed Technology Inc.  All right reserved.
00005 
00006   Author:Jack Shao, Loovee
00007   Change Logs:
00008   2015-4-17: initial version for v2
00009 
00010   suli is designed for the purpose of reusing the high level implementation
00011   of each libraries for different platforms out of the hardware layer.
00012   suli2 is the new reversion of original suli. There're lot of improvements upon
00013   the previous version. Currently, it can be treated as the internal strategy for
00014   quick library development of seeed. But always welcome the community to
00015   follow the basis of suli to contribute grove libraries.
00016 
00017   The MIT License (MIT)
00018 
00019   Permission is hereby granted, free of charge, to any person obtaining a copy
00020   of this software and associated documentation files (the "Software"), to deal
00021   in the Software without restriction, including without limitation the rights
00022   to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
00023   copies of the Software, and to permit persons to whom the Software is
00024   furnished to do so, subject to the following conditions:
00025 
00026   The above copyright notice and this permission notice shall be included in
00027   all copies or substantial portions of the Software.
00028 
00029   THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
00030   IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
00031   FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
00032   AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
00033   LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
00034   OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
00035   THE SOFTWARE.
00036 */
00037 
00038 #ifndef __SULI2_H__
00039 #define __SULI2_H__
00040 
00041 
00042 #if defined(__MBED__)
00043 #include "mbed.h"
00044 #elif defined(ARDUINO)
00045 #include "Arduino.h"
00046 #endif
00047 
00048 
00049 /***************************************************************************
00050  * IO related APIs
00051  ***************************************************************************/
00052 //-------------- mbed ---------------
00053 #if defined(__MBED__)
00054 
00055 typedef gpio_t IO_T;
00056 #define SULI_INPUT    PIN_INPUT
00057 #define SULI_OUTPUT   PIN_OUTPUT
00058 #define SULI_HIGH     0x01
00059 #define SULI_LOW      0x00
00060 
00061 /**
00062  * void suli_pin_init(IO_T *, PIN_T, PIN_DIR )
00063  */
00064 #define suli_pin_init(pio,pin,dir) {gpio_set((PinName)pin); gpio_init(pio, (PinName)pin); gpio_dir(pio, dir);}
00065 
00066 /**
00067  * void suli_pin_dir(IO_T *, PIN_DIR )
00068  */
00069 #define suli_pin_dir(pio,dir) { gpio_dir(pio, dir); }
00070 
00071 /**
00072  * void suli_pin_write(IO_T *, PIN_HIGH_LOW)
00073  */
00074 #define suli_pin_write(pio,state) {gpio_write(pio, state);}
00075 
00076 /**
00077  * int suli_pin_read(IO_T *)
00078  */
00079 #define suli_pin_read(pio) gpio_read(pio)
00080 
00081 /**
00082  * uint32_t suli_pin_pulse_in(IO_T *, what_state, timeout)
00083  */
00084 uint32_t suli_pin_pulse_in(IO_T *pio, int state, uint32_t timeout);
00085 
00086 #define suli_pin_attach_interrupt_handler(pio, func, mode)
00087 
00088 
00089 //-------------- arduino ---------------
00090 #elif defined(ARDUINO)
00091 
00092 typedef int IO_T;
00093 #define SULI_INPUT    INPUT
00094 #define SULI_OUTPUT   OUTPUT
00095 #define SULI_HIGH     0x01
00096 #define SULI_LOW      0x00
00097 
00098 /**
00099  * void suli_pin_init(IO_T *, PIN_T, PIN_DIR )
00100  */
00101 #define suli_pin_init(pio, pin, dir) {*(pio) = pin; pinMode(pin, dir);}
00102 
00103 /**
00104  * void suli_pin_dir(IO_T *, PIN_DIR )
00105  */
00106 #define suli_pin_dir(pio,dir) pinMode(*(pio), dir)
00107 
00108 /**
00109  * void suli_pin_write(IO_T *, PIN_HIGH_LOW)
00110  */
00111 #define suli_pin_write(pio,state)  digitalWrite(*(pio), state)
00112 
00113 /**
00114  * int suli_pin_read(IO_T *)
00115  */
00116 #define suli_pin_read(pio)  digitalRead(*(pio))
00117 
00118 /**
00119  * uint32_t suli_pin_pulse_in(IO_T *, what_state, timeout)
00120  */
00121 #define suli_pin_pulse_in(pio,state,timeout)  pulseIn(*(pio), state, timeout)
00122 
00123 #define suli_pin_attach_interrupt_handler(pio, func, mode) attachInterrupt(*pio, func, mode)
00124 
00125 #endif
00126 
00127 
00128 /***************************************************************************
00129  * Analog related APIs
00130  ***************************************************************************/
00131 //-------------- mbed ---------------
00132 #if defined(__MBED__)
00133 
00134 typedef analogin_t ANALOG_T;
00135 
00136 /**
00137  * NOTE:
00138  * To make the higher level driver compatible with each other
00139  * among several platforms, we unify the resolution of ADC to
00140  * 10bits. We think 10bits is enough for analog reading. So if
00141  * your ADC is 12bit, you need to >>2, or your ADC is 8Bit, you
00142  * need to <<2
00143  */
00144 
00145 /**
00146  * void suli_analog_init(ANALOG_T *aio, int pin);
00147  */
00148 #define suli_analog_init(aio, pin)    analogin_init(aio, (PinName)pin)
00149 
00150 /**
00151  * uint16_t suli_analog_read(ANALOG_T *)
00152  */
00153 #define suli_analog_read(aio)    ((uint16_t)(analogin_read_u16(aio)>>6))
00154 
00155 
00156 //-------------- Arduino ---------------
00157 #elif defined(ARDUINO)
00158 
00159 typedef int ANALOG_T;
00160 /**
00161  * void suli_analog_init(ANALOG_T *aio, int pin);
00162  */
00163 #define suli_analog_init(aio, pin)    {*aio = pin; pinMode(pin, INPUT);}
00164 
00165 /**
00166  * uint16_t suli_analog_read(ANALOG_T *)
00167  */
00168 #define suli_analog_read(aio)    analogRead(*aio)
00169 
00170 
00171 #endif
00172 
00173 
00174 /***************************************************************************
00175  * PWM related APIs
00176  ***************************************************************************/
00177 //-------------- mbed ---------------
00178 #if defined(__MBED__)
00179 
00180 typedef pwmout_t PWM_T;
00181 
00182 /**
00183  * void suli_pwm_init(PWM_T *, int pin)
00184  */
00185 inline void suli_pwm_init(PWM_T *pwm, int pin)
00186 {
00187     pwmout_init(pwm, (PinName)pin);
00188 }
00189 
00190 /**
00191  * void suli_pwm_frequency(PWM_T *, uint32_t Hz)
00192  */
00193 inline void suli_pwm_frequency(PWM_T *pwm, uint32_t hz)
00194 {
00195     int us = 1000000 / hz;
00196     pwmout_period_us(pwm, us);
00197 }
00198 
00199 /**
00200  * void suli_pwm_output(PWM_T *, float percent)
00201  */
00202 inline void suli_pwm_output(PWM_T *pwm, float percent)
00203 {
00204     pwmout_write(pwm, percent);
00205 }
00206 
00207 
00208 //-------------- Arduino ---------------
00209 #elif defined(ARDUINO)
00210 
00211 typedef int PWM_T;
00212 
00213 /**
00214  * void suli_pwm_init(PWM_T *, int pin)
00215  */
00216 inline void suli_pwm_init(PWM_T *pwm, int pin)
00217 {
00218     *pwm = pin;
00219     pinMode(pin, OUTPUT);
00220 }
00221 
00222 /**
00223  * void suli_pwm_frequency(PWM_T *, uint32_t Hz)
00224  * This method is not implemented for Arduino because changing
00225  * the PWM frequency will also change the timer related API.
00226  * So the default frequencies are:
00227  * Arduino Pins 5 and 6: 1kHz
00228  * Arduino Pins 9, 10, 11, and 3: 500Hz
00229  */
00230 inline void suli_pwm_frequency(PWM_T *pwm, uint32_t hz)
00231 {
00232 #ifdef ESP8266
00233     analogWriteFreq(hz);
00234 #endif
00235 }
00236 
00237 /**
00238  * void suli_pwm_output(PWM_T *, float percent)
00239  */
00240 inline void suli_pwm_output(PWM_T *pwm, float percent)
00241 {
00242 #ifdef ESP8266
00243     int duty = constrain((int)(1023 * percent), 0, 1023);
00244 #else
00245     uint8_t duty = constrain((int)(255.0 * percent), 0, 255);
00246 #endif
00247     analogWrite(*pwm, duty);
00248 }
00249 
00250 
00251 #endif
00252 
00253 
00254 /***************************************************************************
00255  * Time related APIs
00256  ***************************************************************************/
00257 //-------------- mbed ---------------
00258 #if defined(__MBED__)
00259 
00260 /*
00261  * delay
00262  */
00263 #define suli_delay_us(us)   wait_us(us)
00264 #define suli_delay_ms(ms)   wait_ms(ms)
00265 
00266 
00267 /*
00268  * Returns the number of milliseconds since your board began running the current program.
00269  * This number will overflow (go back to zero), after approximately 50 days.
00270 */
00271 #define suli_millis()   (us_ticker_read()/1000)
00272 
00273 
00274 /*
00275  * Returns the number of microseconds since your board began running the current program.
00276  * This number will overflow (go back to zero), after approximately 70 minutes.
00277  * Note: there are 1,000 microseconds in a millisecond and 1,000,000 microseconds in a second.
00278  */
00279 #define suli_micros()   us_ticker_read()
00280 
00281 
00282 //-------------- Arduino ---------------
00283 #elif defined(ARDUINO)
00284 
00285 #define suli_delay_us(us)  delayMicroseconds(us)
00286 #define suli_delay_ms(ms)  delay(ms)
00287 #define suli_millis()      millis()
00288 #define suli_micros()      micros()
00289 
00290 #endif
00291 
00292 
00293 /***************************************************************************
00294  * I2C related APIs
00295  ***************************************************************************/
00296 //-------------- mbed ---------------
00297 #if defined(__MBED__)
00298 
00299 typedef i2c_t I2C_T;
00300 
00301 /**
00302  * I2C interface initialize.
00303  */
00304 inline void suli_i2c_init(I2C_T *i2c_device, int pin_sda, int pin_clk)
00305 {
00306     i2c_init(i2c_device, (PinName)pin_sda, (PinName)pin_clk);
00307     i2c_frequency(i2c_device, 100000);
00308 }
00309 
00310 /**
00311  * write a buff to I2C
00312  * dev_addr: 8bits address
00313  */
00314 inline uint8_t suli_i2c_write(I2C_T *i2c_device, uint8_t dev_addr, uint8_t *data, int len)
00315 {
00316     return i2c_write(i2c_device, (int)dev_addr, (const char *)data, len, 1);
00317 }
00318 
00319 /**
00320  * read data from I2C
00321  * dev_addr: 8bits address
00322  */
00323 inline uint8_t suli_i2c_read(I2C_T *i2c_device, uint8_t dev_addr, uint8_t *buff, int len)
00324 {
00325     return i2c_read(i2c_device, (int)dev_addr, (char *)buff, len, 1);
00326 }
00327 
00328 
00329 //-------------- Arduino ---------------
00330 #elif defined(ARDUINO) && (defined (ARDUINO_USE_I2C) || defined(ESP8266))
00331 
00332 #include <Wire.h>
00333 
00334 typedef TwoWire *I2C_T;
00335 /**
00336  * I2C interface initialize.
00337  * ignore pin definations for Arduino
00338  */
00339 void suli_i2c_init(I2C_T *i2c_device, int pin_sda=0, int pin_clk=0);
00340 
00341 
00342 /**
00343  * write a buff to I2C
00344  * dev_addr: 8bits address
00345  */
00346 uint8_t suli_i2c_write(I2C_T *i2c_device, uint8_t dev_addr, uint8_t *data, int len);
00347 
00348 /**
00349  * read data from I2C
00350  * dev_addr: 8bits address
00351  */
00352 uint8_t suli_i2c_read(I2C_T *i2c_device, uint8_t dev_addr, uint8_t *buff, int len);
00353 
00354 
00355 #endif
00356 
00357 
00358 /***************************************************************************
00359  * UART related APIs
00360  ***************************************************************************/
00361 //-------------- mbed ---------------
00362 #if defined(__MBED__)
00363 
00364 typedef serial_t UART_T;
00365 typedef void (*cb_fun_ptr)(void);//jacly add
00366 
00367 /**
00368  * void suli_uart_init(UART_T *, int pin_tx, int pin_rx, uint32_t baud)
00369  */
00370 inline void suli_uart_init(UART_T *uart, int pin_tx, int pin_rx, uint32_t baud)
00371 {
00372     serial_init(uart, (PinName)pin_tx, (PinName)pin_rx);
00373     serial_baud(uart, (int)baud);
00374 }
00375 
00376 /**
00377 jacly add
00378  * void suli_uart_attach(UART_T *uart, SerialIrq irq, uint32_t enable)
00379  */
00380 inline void suli_uart_rx_event_attach(UART_T *uart, cb_fun_ptr irq)
00381 {
00382     serial_irq_handler(uart, (uart_irq_handler)irq, 1);
00383     serial_irq_set(uart, RxIrq, 1);
00384 }
00385 
00386 /**
00387  * send a byte to uart
00388  * void suli_uart_write(UART_T *, uint8_t)
00389  */
00390 inline void suli_uart_write(UART_T *uart, uint8_t data)
00391 {
00392     serial_putc(uart, (int)data);
00393 }
00394 
00395 /**
00396  * send bytes to uart
00397  * int suli_uart_write_bytes(UART_T *, uint8_t *, int)
00398  */
00399 int suli_uart_write_bytes(UART_T *uart, uint8_t *data, int len);
00400 
00401 /**
00402  * write a float
00403  * num - number to write
00404  * decimal - x decimal point
00405  */
00406 void suli_uart_write_float(UART_T *uart, float float_num, int decimal=2);
00407 
00408 /**
00409  * write an integer
00410  * num - number to write
00411  */
00412 void suli_uart_write_int(UART_T *uart, int32_t num);
00413 
00414 
00415 /**
00416  * read a byte from uart
00417  */
00418 inline uint8_t suli_uart_read(UART_T *uart)
00419 {
00420     return (uint8_t)serial_getc(uart);
00421 }
00422 
00423 /**
00424  * read bytes from uart
00425  */
00426 int suli_uart_read_bytes(UART_T *uart, uint8_t *buff, int len);
00427 
00428 /**
00429  * read bytes from uart with timeout ms
00430  */
00431 int suli_uart_read_bytes_timeout(UART_T *uart, uint8_t *buff, int len, int timeout_ms=1000);
00432 
00433 /**
00434  * if uart get data, return 1-readable, 0-unreadable
00435  */
00436 inline int suli_uart_readable(UART_T *uart)
00437 {
00438     return serial_readable(uart);
00439 }
00440 
00441 
00442 
00443 
00444 
00445 //-------------- Arduino ---------------
00446 #elif defined(ARDUINO)
00447 
00448 typedef Stream* UART_T;
00449 
00450 /**
00451  * void suli_uart_init(UART_T *, int pin_tx, int pin_rx, uint32_t baud)
00452  * if you want to use softwareSerial, you need to include
00453  * "SoftwareSerial.h" in sketchbook, and #define ARDUINO_SOFTWARE_SERIAL
00454  */
00455 void suli_uart_init(UART_T *uart, int pin_tx, int pin_rx, uint32_t baud);
00456 
00457 /**
00458  * send a byte to uart
00459  * void suli_uart_write(UART_T *, uint8_t)
00460  */
00461 inline void suli_uart_write(UART_T *uart, uint8_t data)
00462 {
00463     (*uart)->write(data);
00464 }
00465 
00466 /**
00467  * send bytes to uart
00468  * int suli_uart_write_bytes(UART_T *, uint8_t *, int)
00469  */
00470 int suli_uart_write_bytes(UART_T *uart, uint8_t *data, int len);
00471 
00472 /**
00473  * write a float
00474  * num - number to write
00475  * decimal - x decimal point
00476  */
00477 inline void suli_uart_write_float(UART_T *uart, float float_num, int decimal = 2)
00478 {
00479     (*uart)->print(float_num, decimal);
00480 }
00481 /**
00482  * write an integer
00483  * num - number to write
00484  */
00485 inline void suli_uart_write_int(UART_T *uart, int32_t num)
00486 {
00487     (*uart)->print(num);
00488 }
00489 
00490 /**
00491  * read a byte from uart
00492  */
00493 inline uint8_t suli_uart_read(UART_T *uart)
00494 {
00495     return (uint8_t)(*uart)->read();
00496 }
00497 
00498 /**
00499  * read bytes from uart
00500  */
00501 inline int suli_uart_read_bytes(UART_T *uart, uint8_t *buff, int len)
00502 {
00503     return (*uart)->readBytes((char *)buff, len);
00504 }
00505 
00506 /**
00507  * read bytes from uart with timeout ms
00508  */
00509 inline int suli_uart_read_bytes_timeout(UART_T *uart, uint8_t *buff, int len, int timeout_ms = 1000)
00510 {
00511     (*uart)->setTimeout((unsigned long)timeout_ms);
00512     return (*uart)->readBytes((char *)buff, len);
00513 }
00514 
00515 /**
00516  * if uart get data, return 1-readable, 0-unreadable
00517  */
00518 inline int suli_uart_readable(UART_T *uart)
00519 {
00520     return (*uart)->available();
00521 }
00522 
00523 #endif
00524 
00525 
00526 /***************************************************************************
00527  * Event related APIs
00528  ***************************************************************************/
00529  
00530 typedef void (*event_callback_t)(char *event_name, uint32_t event_data);
00531 typedef event_callback_t        EVENT_T;
00532 typedef event_callback_t        CALLBACK_T;
00533 
00534 inline void suli_event_init(EVENT_T *event, CALLBACK_T cb)
00535 {
00536     *event = cb;
00537 }
00538 inline void suli_event_trigger(EVENT_T *event, char *event_name, uint32_t event_data)
00539 {
00540     if (event)
00541     {
00542         (*event)(event_name, event_data);
00543     }
00544 }
00545 
00546 
00547 #endif  //__SULI2_H__