Define pin accessors more like <Arduino.h>
This commit is contained in:
parent
358656acc3
commit
599f2ad983
@ -25,6 +25,7 @@
|
||||
#include <lpc17xx_pinsel.h>
|
||||
#include "HAL.h"
|
||||
#include "../../core/macros.h"
|
||||
#include "../../core/types.h"
|
||||
|
||||
// Interrupts
|
||||
void cli(void) { __disable_irq(); } // Disable
|
||||
@ -32,7 +33,7 @@ void sei(void) { __enable_irq(); } // Enable
|
||||
|
||||
// Time functions
|
||||
void _delay_ms(int delay_ms) {
|
||||
delay (delay_ms);
|
||||
delay(delay_ms);
|
||||
}
|
||||
|
||||
uint32_t millis() {
|
||||
@ -72,16 +73,16 @@ void delayMicroseconds(uint32_t us) {
|
||||
}
|
||||
}
|
||||
|
||||
extern "C" void delay(int msec) {
|
||||
volatile int32_t end = _millis + msec;
|
||||
SysTick->VAL = SysTick->LOAD; // reset systick counter so next systick is in exactly 1ms
|
||||
// this could extend the time between systicks by upto 1ms
|
||||
while (_millis < end) __WFE();
|
||||
extern "C" void delay(const int msec) {
|
||||
volatile millis_t end = _millis + msec;
|
||||
SysTick->VAL = SysTick->LOAD; // reset systick counter so next systick is in exactly 1ms
|
||||
// this could extend the time between systicks by upto 1ms
|
||||
while PENDING(_millis, end) __WFE();
|
||||
}
|
||||
|
||||
// IO functions
|
||||
// As defined by Arduino INPUT(0x0), OUPUT(0x1), INPUT_PULLUP(0x2)
|
||||
void pinMode(int pin, int mode) {
|
||||
void pinMode(uint8_t pin, uint8_t mode) {
|
||||
if (!WITHIN(pin, 0, NUM_DIGITAL_PINS - 1) || pin_map[pin].port == 0xFF)
|
||||
return;
|
||||
|
||||
@ -109,7 +110,7 @@ void pinMode(int pin, int mode) {
|
||||
}
|
||||
}
|
||||
|
||||
void digitalWrite(int pin, int pin_status) {
|
||||
void digitalWrite(uint8_t pin, uint8_t pin_status) {
|
||||
if (!WITHIN(pin, 0, NUM_DIGITAL_PINS - 1) || pin_map[pin].port == 0xFF)
|
||||
return;
|
||||
|
||||
@ -129,16 +130,14 @@ void digitalWrite(int pin, int pin_status) {
|
||||
*/
|
||||
}
|
||||
|
||||
bool digitalRead(int pin) {
|
||||
bool digitalRead(uint8_t pin) {
|
||||
if (!WITHIN(pin, 0, NUM_DIGITAL_PINS - 1) || pin_map[pin].port == 0xFF) {
|
||||
return false;
|
||||
}
|
||||
return LPC_GPIO(pin_map[pin].port)->FIOPIN & LPC_PIN(pin_map[pin].pin) ? 1 : 0;
|
||||
}
|
||||
|
||||
|
||||
|
||||
void analogWrite(int pin, int pwm_value) { // 1 - 254: pwm_value, 0: LOW, 255: HIGH
|
||||
void analogWrite(uint8_t pin, int pwm_value) { // 1 - 254: pwm_value, 0: LOW, 255: HIGH
|
||||
|
||||
extern bool LPC1768_PWM_attach_pin(uint8_t, uint32_t, uint32_t, uint8_t);
|
||||
extern bool LPC1768_PWM_write(uint8_t, uint32_t);
|
||||
@ -168,7 +167,7 @@ void analogWrite(int pin, int pwm_value) { // 1 - 254: pwm_value, 0: LOW, 255:
|
||||
|
||||
extern bool HAL_adc_finished();
|
||||
|
||||
uint16_t analogRead(int adc_pin) {
|
||||
uint16_t analogRead(uint8_t adc_pin) {
|
||||
HAL_adc_start_conversion(adc_pin);
|
||||
while (!HAL_adc_finished()); // Wait for conversion to finish
|
||||
return HAL_adc_get_result();
|
||||
|
@ -92,18 +92,18 @@ extern "C" void GpioDisableInt(uint32_t port, uint32_t pin);
|
||||
|
||||
// Time functions
|
||||
extern "C" {
|
||||
void delay(int milis);
|
||||
void delay(const int milis);
|
||||
}
|
||||
void _delay_ms(int delay);
|
||||
void delayMicroseconds(unsigned long);
|
||||
uint32_t millis();
|
||||
|
||||
//IO functions
|
||||
void pinMode(int pin_number, int mode);
|
||||
void digitalWrite(int pin_number, int pin_status);
|
||||
bool digitalRead(int pin);
|
||||
void analogWrite(int pin_number, int pin_status);
|
||||
uint16_t analogRead(int adc_pin);
|
||||
void pinMode(uint8_t, uint8_t);
|
||||
void digitalWrite(uint8_t, uint8_t);
|
||||
int digitalRead(uint8_t);
|
||||
void analogWrite(uint8_t, int);
|
||||
int analogRead(uint8_t);
|
||||
|
||||
// EEPROM
|
||||
void eeprom_write_byte(unsigned char *pos, unsigned char value);
|
||||
|
Loading…
Reference in New Issue
Block a user