Define pin accessors more like <Arduino.h>

2.0.x
Scott Lahteine 7 years ago
parent 358656acc3
commit 599f2ad983

@ -25,6 +25,7 @@
#include <lpc17xx_pinsel.h> #include <lpc17xx_pinsel.h>
#include "HAL.h" #include "HAL.h"
#include "../../core/macros.h" #include "../../core/macros.h"
#include "../../core/types.h"
// Interrupts // Interrupts
void cli(void) { __disable_irq(); } // Disable void cli(void) { __disable_irq(); } // Disable
@ -32,7 +33,7 @@ void sei(void) { __enable_irq(); } // Enable
// Time functions // Time functions
void _delay_ms(int delay_ms) { void _delay_ms(int delay_ms) {
delay (delay_ms); delay(delay_ms);
} }
uint32_t millis() { uint32_t millis() {
@ -72,16 +73,16 @@ void delayMicroseconds(uint32_t us) {
} }
} }
extern "C" void delay(int msec) { extern "C" void delay(const int msec) {
volatile int32_t end = _millis + msec; volatile millis_t end = _millis + msec;
SysTick->VAL = SysTick->LOAD; // reset systick counter so next systick is in exactly 1ms SysTick->VAL = SysTick->LOAD; // reset systick counter so next systick is in exactly 1ms
// this could extend the time between systicks by upto 1ms // this could extend the time between systicks by upto 1ms
while (_millis < end) __WFE(); while PENDING(_millis, end) __WFE();
} }
// IO functions // IO functions
// As defined by Arduino INPUT(0x0), OUPUT(0x1), INPUT_PULLUP(0x2) // 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) if (!WITHIN(pin, 0, NUM_DIGITAL_PINS - 1) || pin_map[pin].port == 0xFF)
return; 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) if (!WITHIN(pin, 0, NUM_DIGITAL_PINS - 1) || pin_map[pin].port == 0xFF)
return; 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) { if (!WITHIN(pin, 0, NUM_DIGITAL_PINS - 1) || pin_map[pin].port == 0xFF) {
return false; return false;
} }
return LPC_GPIO(pin_map[pin].port)->FIOPIN & LPC_PIN(pin_map[pin].pin) ? 1 : 0; return LPC_GPIO(pin_map[pin].port)->FIOPIN & LPC_PIN(pin_map[pin].pin) ? 1 : 0;
} }
void analogWrite(uint8_t pin, int pwm_value) { // 1 - 254: pwm_value, 0: LOW, 255: HIGH
void analogWrite(int 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_attach_pin(uint8_t, uint32_t, uint32_t, uint8_t);
extern bool LPC1768_PWM_write(uint8_t, uint32_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(); extern bool HAL_adc_finished();
uint16_t analogRead(int adc_pin) { uint16_t analogRead(uint8_t adc_pin) {
HAL_adc_start_conversion(adc_pin); HAL_adc_start_conversion(adc_pin);
while (!HAL_adc_finished()); // Wait for conversion to finish while (!HAL_adc_finished()); // Wait for conversion to finish
return HAL_adc_get_result(); return HAL_adc_get_result();

@ -92,18 +92,18 @@ extern "C" void GpioDisableInt(uint32_t port, uint32_t pin);
// Time functions // Time functions
extern "C" { extern "C" {
void delay(int milis); void delay(const int milis);
} }
void _delay_ms(int delay); void _delay_ms(int delay);
void delayMicroseconds(unsigned long); void delayMicroseconds(unsigned long);
uint32_t millis(); uint32_t millis();
//IO functions //IO functions
void pinMode(int pin_number, int mode); void pinMode(uint8_t, uint8_t);
void digitalWrite(int pin_number, int pin_status); void digitalWrite(uint8_t, uint8_t);
bool digitalRead(int pin); int digitalRead(uint8_t);
void analogWrite(int pin_number, int pin_status); void analogWrite(uint8_t, int);
uint16_t analogRead(int adc_pin); int analogRead(uint8_t);
// EEPROM // EEPROM
void eeprom_write_byte(unsigned char *pos, unsigned char value); void eeprom_write_byte(unsigned char *pos, unsigned char value);

Loading…
Cancel
Save