summaryrefslogtreecommitdiff
path: root/platforms/avr/drivers
diff options
context:
space:
mode:
authorDrashna Jael're <drashna@live.com>2021-12-07 09:27:44 -0800
committerDrashna Jael're <drashna@live.com>2021-12-07 09:27:44 -0800
commit7c18b1c9d3d968ded45e072af3483547c3ec7859 (patch)
treeed7c8a4176033046eacff21228364290b44fcfdb /platforms/avr/drivers
parent43002bdf77ab0f48af6b04e87edcc37f7cb7b905 (diff)
parent6d0a62920410f50d7f6707960ca1ca0c8fd1d1fa (diff)
Merge commit '6d0a62920410f50d7f6707960ca1ca0c8fd1d1fa' into firmware21
Diffstat (limited to 'platforms/avr/drivers')
-rw-r--r--platforms/avr/drivers/analog.c23
-rw-r--r--platforms/avr/drivers/analog.h3
-rw-r--r--platforms/avr/drivers/audio_pwm.h17
-rw-r--r--platforms/avr/drivers/audio_pwm_hardware.c332
-rw-r--r--platforms/avr/drivers/i2c_master.c56
-rw-r--r--platforms/avr/drivers/i2c_master.h2
-rw-r--r--platforms/avr/drivers/ps2/ps2_io.c51
-rw-r--r--platforms/avr/drivers/ps2/ps2_usart.c227
-rw-r--r--platforms/avr/drivers/uart.c26
-rw-r--r--platforms/avr/drivers/uart.h8
-rw-r--r--platforms/avr/drivers/ws2812.c11
11 files changed, 714 insertions, 42 deletions
diff --git a/platforms/avr/drivers/analog.c b/platforms/avr/drivers/analog.c
index 8d299ffdb9..628835ccef 100644
--- a/platforms/avr/drivers/analog.c
+++ b/platforms/avr/drivers/analog.c
@@ -23,29 +23,6 @@ static uint8_t aref = ADC_REF_POWER;
void analogReference(uint8_t mode) { aref = mode & (_BV(REFS1) | _BV(REFS0)); }
-// Arduino compatible pin input
-int16_t analogRead(uint8_t pin) {
-#if defined(__AVR_ATmega32U4__)
- // clang-format off
- static const uint8_t PROGMEM pin_to_mux[] = {
- //A0 A1 A2 A3 A4 A5
- //F7 F6 F5 F4 F1 F0
- 0x07, 0x06, 0x05, 0x04, 0x01, 0x00,
- //A6 A7 A8 A9 A10 A11
- //D4 D7 B4 B5 B6 D6
- 0x20, 0x22, 0x23, 0x24, 0x25, 0x21
- };
- // clang-format on
- if (pin >= 12) return 0;
- return adc_read(pgm_read_byte(pin_to_mux + pin));
-#elif defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB647__) || defined(__AVR_AT90USB1286__) || defined(__AVR_AT90USB1287__) || defined(__AVR_ATmega328P__) || defined(__AVR_ATmega328__)
- if (pin >= 8) return 0;
- return adc_read(pin);
-#else
- return 0;
-#endif
-}
-
int16_t analogReadPin(pin_t pin) { return adc_read(pinToMux(pin)); }
uint8_t pinToMux(pin_t pin) {
diff --git a/platforms/avr/drivers/analog.h b/platforms/avr/drivers/analog.h
index 058882450d..fa2fb0d89b 100644
--- a/platforms/avr/drivers/analog.h
+++ b/platforms/avr/drivers/analog.h
@@ -22,8 +22,7 @@
#ifdef __cplusplus
extern "C" {
#endif
-void analogReference(uint8_t mode);
-int16_t analogRead(uint8_t pin);
+void analogReference(uint8_t mode);
int16_t analogReadPin(pin_t pin);
uint8_t pinToMux(pin_t pin);
diff --git a/platforms/avr/drivers/audio_pwm.h b/platforms/avr/drivers/audio_pwm.h
new file mode 100644
index 0000000000..d6eb3571da
--- /dev/null
+++ b/platforms/avr/drivers/audio_pwm.h
@@ -0,0 +1,17 @@
+/* Copyright 2020 Jack Humbert
+ * Copyright 2020 JohSchneider
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ */
+#pragma once
diff --git a/platforms/avr/drivers/audio_pwm_hardware.c b/platforms/avr/drivers/audio_pwm_hardware.c
new file mode 100644
index 0000000000..df03a4558c
--- /dev/null
+++ b/platforms/avr/drivers/audio_pwm_hardware.c
@@ -0,0 +1,332 @@
+/* Copyright 2016 Jack Humbert
+ * Copyright 2020 JohSchneider
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ */
+
+#if defined(__AVR__)
+# include <avr/pgmspace.h>
+# include <avr/interrupt.h>
+# include <avr/io.h>
+#endif
+
+#include "audio.h"
+
+extern bool playing_note;
+extern bool playing_melody;
+extern uint8_t note_timbre;
+
+#define CPU_PRESCALER 8
+
+/*
+ Audio Driver: PWM
+
+ drive up to two speakers through the AVR PWM hardware-peripheral, using timer1 and/or timer3 on Atmega32U4.
+
+ the primary channel_1 can be connected to either pin PC4 PC5 or PC6 (the later being used by most AVR based keyboards) with a PMW signal generated by timer3
+ and an optional secondary channel_2 on either pin PB5, PB6 or PB7, with a PWM signal from timer1
+
+ alternatively, the PWM pins on PORTB can be used as only/primary speaker
+*/
+
+#if defined(AUDIO_PIN) && (AUDIO_PIN != C4) && (AUDIO_PIN != C5) && (AUDIO_PIN != C6) && (AUDIO_PIN != B5) && (AUDIO_PIN != B6) && (AUDIO_PIN != B7) && (AUDIO_PIN != D5)
+# error "Audio feature enabled, but no suitable pin selected as AUDIO_PIN - see docs/feature_audio under the AVR settings for available options."
+#endif
+
+#if (AUDIO_PIN == C4) || (AUDIO_PIN == C5) || (AUDIO_PIN == C6)
+# define AUDIO1_PIN_SET
+# define AUDIO1_TIMSKx TIMSK3
+# define AUDIO1_TCCRxA TCCR3A
+# define AUDIO1_TCCRxB TCCR3B
+# define AUDIO1_ICRx ICR3
+# define AUDIO1_WGMx0 WGM30
+# define AUDIO1_WGMx1 WGM31
+# define AUDIO1_WGMx2 WGM32
+# define AUDIO1_WGMx3 WGM33
+# define AUDIO1_CSx0 CS30
+# define AUDIO1_CSx1 CS31
+# define AUDIO1_CSx2 CS32
+
+# if (AUDIO_PIN == C6)
+# define AUDIO1_COMxy0 COM3A0
+# define AUDIO1_COMxy1 COM3A1
+# define AUDIO1_OCIExy OCIE3A
+# define AUDIO1_OCRxy OCR3A
+# define AUDIO1_PIN C6
+# define AUDIO1_TIMERx_COMPy_vect TIMER3_COMPA_vect
+# elif (AUDIO_PIN == C5)
+# define AUDIO1_COMxy0 COM3B0
+# define AUDIO1_COMxy1 COM3B1
+# define AUDIO1_OCIExy OCIE3B
+# define AUDIO1_OCRxy OCR3B
+# define AUDIO1_PIN C5
+# define AUDIO1_TIMERx_COMPy_vect TIMER3_COMPB_vect
+# elif (AUDIO_PIN == C4)
+# define AUDIO1_COMxy0 COM3C0
+# define AUDIO1_COMxy1 COM3C1
+# define AUDIO1_OCIExy OCIE3C
+# define AUDIO1_OCRxy OCR3C
+# define AUDIO1_PIN C4
+# define AUDIO1_TIMERx_COMPy_vect TIMER3_COMPC_vect
+# endif
+#endif
+
+#if defined(AUDIO_PIN) && defined(AUDIO_PIN_ALT) && (AUDIO_PIN == AUDIO_PIN_ALT)
+# error "Audio feature: AUDIO_PIN and AUDIO_PIN_ALT on the same pin makes no sense."
+#endif
+
+#if ((AUDIO_PIN == B5) && ((AUDIO_PIN_ALT == B6) || (AUDIO_PIN_ALT == B7))) || ((AUDIO_PIN == B6) && ((AUDIO_PIN_ALT == B5) || (AUDIO_PIN_ALT == B7))) || ((AUDIO_PIN == B7) && ((AUDIO_PIN_ALT == B5) || (AUDIO_PIN_ALT == B6)))
+# error "Audio feature: PORTB as AUDIO_PIN and AUDIO_PIN_ALT at the same time is not supported."
+#endif
+
+#if defined(AUDIO_PIN_ALT) && (AUDIO_PIN_ALT != B5) && (AUDIO_PIN_ALT != B6) && (AUDIO_PIN_ALT != B7)
+# error "Audio feature: the pin selected as AUDIO_PIN_ALT is not supported."
+#endif
+
+#if (AUDIO_PIN == B5) || (AUDIO_PIN == B6) || (AUDIO_PIN == B7) || (AUDIO_PIN_ALT == B5) || (AUDIO_PIN_ALT == B6) || (AUDIO_PIN_ALT == B7) || (AUDIO_PIN == D5)
+# define AUDIO2_PIN_SET
+# define AUDIO2_TIMSKx TIMSK1
+# define AUDIO2_TCCRxA TCCR1A
+# define AUDIO2_TCCRxB TCCR1B
+# define AUDIO2_ICRx ICR1
+# define AUDIO2_WGMx0 WGM10
+# define AUDIO2_WGMx1 WGM11
+# define AUDIO2_WGMx2 WGM12
+# define AUDIO2_WGMx3 WGM13
+# define AUDIO2_CSx0 CS10
+# define AUDIO2_CSx1 CS11
+# define AUDIO2_CSx2 CS12
+
+# if (AUDIO_PIN == B5) || (AUDIO_PIN_ALT == B5)
+# define AUDIO2_COMxy0 COM1A0
+# define AUDIO2_COMxy1 COM1A1
+# define AUDIO2_OCIExy OCIE1A
+# define AUDIO2_OCRxy OCR1A
+# define AUDIO2_PIN B5
+# define AUDIO2_TIMERx_COMPy_vect TIMER1_COMPA_vect
+# elif (AUDIO_PIN == B6) || (AUDIO_PIN_ALT == B6)
+# define AUDIO2_COMxy0 COM1B0
+# define AUDIO2_COMxy1 COM1B1
+# define AUDIO2_OCIExy OCIE1B
+# define AUDIO2_OCRxy OCR1B
+# define AUDIO2_PIN B6
+# define AUDIO2_TIMERx_COMPy_vect TIMER1_COMPB_vect
+# elif (AUDIO_PIN == B7) || (AUDIO_PIN_ALT == B7)
+# define AUDIO2_COMxy0 COM1C0
+# define AUDIO2_COMxy1 COM1C1
+# define AUDIO2_OCIExy OCIE1C
+# define AUDIO2_OCRxy OCR1C
+# define AUDIO2_PIN B7
+# define AUDIO2_TIMERx_COMPy_vect TIMER1_COMPC_vect
+# elif (AUDIO_PIN == D5) && defined(__AVR_ATmega32A__)
+# pragma message "Audio support for ATmega32A is experimental and can cause crashes."
+# undef AUDIO2_TIMSKx
+# define AUDIO2_TIMSKx TIMSK
+# define AUDIO2_COMxy0 COM1A0
+# define AUDIO2_COMxy1 COM1A1
+# define AUDIO2_OCIExy OCIE1A
+# define AUDIO2_OCRxy OCR1A
+# define AUDIO2_PIN D5
+# define AUDIO2_TIMERx_COMPy_vect TIMER1_COMPA_vect
+# endif
+#endif
+
+// C6 seems to be the assumed default by many existing keyboard - but sill warn the user
+#if !defined(AUDIO1_PIN_SET) && !defined(AUDIO2_PIN_SET)
+# pragma message "Audio feature enabled, but no suitable pin selected - see docs/feature_audio under the AVR settings for available options. Don't expect to hear anything... :-)"
+// TODO: make this an error - go through the breaking-change-process and change all keyboards to the new define
+#endif
+// -----------------------------------------------------------------------------
+
+#ifdef AUDIO1_PIN_SET
+static float channel_1_frequency = 0.0f;
+void channel_1_set_frequency(float freq) {
+ if (freq == 0.0f) // a pause/rest is a valid "note" with freq=0
+ {
+ // disable the output, but keep the pwm-ISR going (with the previous
+ // frequency) so the audio-state keeps getting updated
+ // Note: setting the duty-cycle 0 is not possible on non-inverting PWM mode - see the AVR data-sheet
+ AUDIO1_TCCRxA &= ~(_BV(AUDIO1_COMxy1) | _BV(AUDIO1_COMxy0));
+ return;
+ } else {
+ AUDIO1_TCCRxA |= _BV(AUDIO1_COMxy1); // enable output, PWM mode
+ }
+
+ channel_1_frequency = freq;
+
+ // set pwm period
+ AUDIO1_ICRx = (uint16_t)(((float)F_CPU) / (freq * CPU_PRESCALER));
+ // and duty cycle
+ AUDIO1_OCRxy = (uint16_t)((((float)F_CPU) / (freq * CPU_PRESCALER)) * note_timbre / 100);
+}
+
+void channel_1_start(void) {
+ // enable timer-counter ISR
+ AUDIO1_TIMSKx |= _BV(AUDIO1_OCIExy);
+ // enable timer-counter output
+ AUDIO1_TCCRxA |= _BV(AUDIO1_COMxy1);
+}
+
+void channel_1_stop(void) {
+ // disable timer-counter ISR
+ AUDIO1_TIMSKx &= ~_BV(AUDIO1_OCIExy);
+ // disable timer-counter output
+ AUDIO1_TCCRxA &= ~(_BV(AUDIO1_COMxy1) | _BV(AUDIO1_COMxy0));
+}
+#endif
+
+#ifdef AUDIO2_PIN_SET
+static float channel_2_frequency = 0.0f;
+void channel_2_set_frequency(float freq) {
+ if (freq == 0.0f) {
+ AUDIO2_TCCRxA &= ~(_BV(AUDIO2_COMxy1) | _BV(AUDIO2_COMxy0));
+ return;
+ } else {
+ AUDIO2_TCCRxA |= _BV(AUDIO2_COMxy1);
+ }
+
+ channel_2_frequency = freq;
+
+ AUDIO2_ICRx = (uint16_t)(((float)F_CPU) / (freq * CPU_PRESCALER));
+ AUDIO2_OCRxy = (uint16_t)((((float)F_CPU) / (freq * CPU_PRESCALER)) * note_timbre / 100);
+}
+
+float channel_2_get_frequency(void) { return channel_2_frequency; }
+
+void channel_2_start(void) {
+ AUDIO2_TIMSKx |= _BV(AUDIO2_OCIExy);
+ AUDIO2_TCCRxA |= _BV(AUDIO2_COMxy1);
+}
+
+void channel_2_stop(void) {
+ AUDIO2_TIMSKx &= ~_BV(AUDIO2_OCIExy);
+ AUDIO2_TCCRxA &= ~(_BV(AUDIO2_COMxy1) | _BV(AUDIO2_COMxy0));
+}
+#endif
+
+void audio_driver_initialize() {
+#ifdef AUDIO1_PIN_SET
+ channel_1_stop();
+ setPinOutput(AUDIO1_PIN);
+#endif
+
+#ifdef AUDIO2_PIN_SET
+ channel_2_stop();
+ setPinOutput(AUDIO2_PIN);
+#endif
+
+ // TCCR3A / TCCR3B: Timer/Counter #3 Control Registers TCCR3A/TCCR3B, TCCR1A/TCCR1B
+ // Compare Output Mode (COM3An and COM1An) = 0b00 = Normal port operation
+ // OC3A -- PC6
+ // OC3B -- PC5
+ // OC3C -- PC4
+ // OC1A -- PB5
+ // OC1B -- PB6
+ // OC1C -- PB7
+
+ // Waveform Generation Mode (WGM3n) = 0b1110 = Fast PWM Mode 14. Period = ICR3, Duty Cycle OCR3A)
+ // OCR3A - PC6
+ // OCR3B - PC5
+ // OCR3C - PC4
+ // OCR1A - PB5
+ // OCR1B - PB6
+ // OCR1C - PB7
+
+ // Clock Select (CS3n) = 0b010 = Clock / 8
+#ifdef AUDIO1_PIN_SET
+ // initialize timer-counter
+ AUDIO1_TCCRxA = (0 << AUDIO1_COMxy1) | (0 << AUDIO1_COMxy0) | (1 << AUDIO1_WGMx1) | (0 << AUDIO1_WGMx0);
+ AUDIO1_TCCRxB = (1 << AUDIO1_WGMx3) | (1 << AUDIO1_WGMx2) | (0 << AUDIO1_CSx2) | (1 << AUDIO1_CSx1) | (0 << AUDIO1_CSx0);
+#endif
+
+#ifdef AUDIO2_PIN_SET
+ AUDIO2_TCCRxA = (0 << AUDIO2_COMxy1) | (0 << AUDIO2_COMxy0) | (1 << AUDIO2_WGMx1) | (0 << AUDIO2_WGMx0);
+ AUDIO2_TCCRxB = (1 << AUDIO2_WGMx3) | (1 << AUDIO2_WGMx2) | (0 << AUDIO2_CSx2) | (1 << AUDIO2_CSx1) | (0 << AUDIO2_CSx0);
+#endif
+}
+
+void audio_driver_stop() {
+#ifdef AUDIO1_PIN_SET
+ channel_1_stop();
+#endif
+
+#ifdef AUDIO2_PIN_SET
+ channel_2_stop();
+#endif
+}
+
+void audio_driver_start(void) {
+#ifdef AUDIO1_PIN_SET
+ channel_1_start();
+ if (playing_note) {
+ channel_1_set_frequency(audio_get_processed_frequency(0));
+ }
+#endif
+
+#if !defined(AUDIO1_PIN_SET) && defined(AUDIO2_PIN_SET)
+ channel_2_start();
+ if (playing_note) {
+ channel_2_set_frequency(audio_get_processed_frequency(0));
+ }
+#endif
+}
+
+static volatile uint32_t isr_counter = 0;
+#ifdef AUDIO1_PIN_SET
+ISR(AUDIO1_TIMERx_COMPy_vect) {
+ isr_counter++;
+ if (isr_counter < channel_1_frequency / (CPU_PRESCALER * 8)) return;
+
+ isr_counter = 0;
+ bool state_changed = audio_update_state();
+
+ if (!playing_note && !playing_melody) {
+ channel_1_stop();
+# ifdef AUDIO2_PIN_SET
+ channel_2_stop();
+# endif
+ return;
+ }
+
+ if (state_changed) {
+ channel_1_set_frequency(audio_get_processed_frequency(0));
+# ifdef AUDIO2_PIN_SET
+ if (audio_get_number_of_active_tones() > 1) {
+ channel_2_set_frequency(audio_get_processed_frequency(1));
+ } else {
+ channel_2_stop();
+ }
+# endif
+ }
+}
+#endif
+
+#if !defined(AUDIO1_PIN_SET) && defined(AUDIO2_PIN_SET)
+ISR(AUDIO2_TIMERx_COMPy_vect) {
+ isr_counter++;
+ if (isr_counter < channel_2_frequency / (CPU_PRESCALER * 8)) return;
+
+ isr_counter = 0;
+ bool state_changed = audio_update_state();
+
+ if (!playing_note && !playing_melody) {
+ channel_2_stop();
+ return;
+ }
+
+ if (state_changed) {
+ channel_2_set_frequency(audio_get_processed_frequency(0));
+ }
+}
+#endif
diff --git a/platforms/avr/drivers/i2c_master.c b/platforms/avr/drivers/i2c_master.c
index 2773e00778..111b55d6b0 100644
--- a/platforms/avr/drivers/i2c_master.c
+++ b/platforms/avr/drivers/i2c_master.c
@@ -202,6 +202,25 @@ i2c_status_t i2c_writeReg(uint8_t devaddr, uint8_t regaddr, const uint8_t* data,
return status;
}
+i2c_status_t i2c_writeReg16(uint8_t devaddr, uint16_t regaddr, const uint8_t* data, uint16_t length, uint16_t timeout) {
+ i2c_status_t status = i2c_start(devaddr | 0x00, timeout);
+ if (status >= 0) {
+ status = i2c_write(regaddr >> 8, timeout);
+
+ if (status >= 0) {
+ status = i2c_write(regaddr & 0xFF, timeout);
+
+ for (uint16_t i = 0; i < length && status >= 0; i++) {
+ status = i2c_write(data[i], timeout);
+ }
+ }
+ }
+
+ i2c_stop();
+
+ return status;
+}
+
i2c_status_t i2c_readReg(uint8_t devaddr, uint8_t regaddr, uint8_t* data, uint16_t length, uint16_t timeout) {
i2c_status_t status = i2c_start(devaddr, timeout);
if (status < 0) {
@@ -235,6 +254,43 @@ error:
return (status < 0) ? status : I2C_STATUS_SUCCESS;
}
+i2c_status_t i2c_readReg16(uint8_t devaddr, uint16_t regaddr, uint8_t* data, uint16_t length, uint16_t timeout) {
+ i2c_status_t status = i2c_start(devaddr, timeout);
+ if (status < 0) {
+ goto error;
+ }
+
+ status = i2c_write(regaddr >> 8, timeout);
+ if (status < 0) {
+ goto error;
+ }
+ status = i2c_write(regaddr & 0xFF, timeout);
+ if (status < 0) {
+ goto error;
+ }
+
+ status = i2c_start(devaddr | 0x01, timeout);
+
+ for (uint16_t i = 0; i < (length - 1) && status >= 0; i++) {
+ status = i2c_read_ack(timeout);
+ if (status >= 0) {
+ data[i] = status;
+ }
+ }
+
+ if (status >= 0) {
+ status = i2c_read_nack(timeout);
+ if (status >= 0) {
+ data[(length - 1)] = status;
+ }
+ }
+
+error:
+ i2c_stop();
+
+ return (status < 0) ? status : I2C_STATUS_SUCCESS;
+}
+
void i2c_stop(void) {
// transmit STOP condition
TWCR = (1 << TWINT) | (1 << TWEN) | (1 << TWSTO);
diff --git a/platforms/avr/drivers/i2c_master.h b/platforms/avr/drivers/i2c_master.h
index e5af73364b..2d95846db5 100644
--- a/platforms/avr/drivers/i2c_master.h
+++ b/platforms/avr/drivers/i2c_master.h
@@ -39,5 +39,7 @@ int16_t i2c_read_nack(uint16_t timeout);
i2c_status_t i2c_transmit(uint8_t address, const uint8_t* data, uint16_t length, uint16_t timeout);
i2c_status_t i2c_receive(uint8_t address, uint8_t* data, uint16_t length, uint16_t timeout);
i2c_status_t i2c_writeReg(uint8_t devaddr, uint8_t regaddr, const uint8_t* data, uint16_t length, uint16_t timeout);
+i2c_status_t i2c_writeReg16(uint8_t devaddr, uint16_t regaddr, const uint8_t* data, uint16_t length, uint16_t timeout);
i2c_status_t i2c_readReg(uint8_t devaddr, uint8_t regaddr, uint8_t* data, uint16_t length, uint16_t timeout);
+i2c_status_t i2c_readReg16(uint8_t devaddr, uint16_t regaddr, uint8_t* data, uint16_t length, uint16_t timeout);
void i2c_stop(void);
diff --git a/platforms/avr/drivers/ps2/ps2_io.c b/platforms/avr/drivers/ps2/ps2_io.c
new file mode 100644
index 0000000000..7c826fbf1a
--- /dev/null
+++ b/platforms/avr/drivers/ps2/ps2_io.c
@@ -0,0 +1,51 @@
+#include <stdbool.h>
+#include "ps2_io.h"
+#include "gpio.h"
+#include "wait.h"
+
+/* Check port settings for clock and data line */
+#if !(defined(PS2_CLOCK_PIN))
+# error "PS/2 clock setting is required in config.h"
+#endif
+
+#if !(defined(PS2_DATA_PIN))
+# error "PS/2 data setting is required in config.h"
+#endif
+
+/*
+ * Clock
+ */
+void clock_init(void) {}
+
+void clock_lo(void) {
+ // Transition from input with pull-up to output low via Hi-Z instead of output high
+ writePinLow(PS2_CLOCK_PIN);
+ setPinOutput(PS2_CLOCK_PIN);
+}
+
+void clock_hi(void) { setPinInputHigh(PS2_CLOCK_PIN); }
+
+bool clock_in(void) {
+ setPinInputHigh(PS2_CLOCK_PIN);
+ wait_us(1);
+ return readPin(PS2_CLOCK_PIN);
+}
+
+/*
+ * Data
+ */
+void data_init(void) {}
+
+void data_lo(void) {
+ // Transition from input with pull-up to output low via Hi-Z instead of output high
+ writePinLow(PS2_DATA_PIN);
+ setPinOutput(PS2_DATA_PIN);
+}
+
+void data_hi(void) { setPinInputHigh(PS2_DATA_PIN); }
+
+bool data_in(void) {
+ setPinInputHigh(PS2_DATA_PIN);
+ wait_us(1);
+ return readPin(PS2_DATA_PIN);
+}
diff --git a/platforms/avr/drivers/ps2/ps2_usart.c b/platforms/avr/drivers/ps2/ps2_usart.c
new file mode 100644
index 0000000000..151cfcd68f
--- /dev/null
+++ b/platforms/avr/drivers/ps2/ps2_usart.c
@@ -0,0 +1,227 @@
+/*
+Copyright 2010,2011,2012,2013 Jun WAKO <wakojun@gmail.com>
+
+This software is licensed with a Modified BSD License.
+All of this is supposed to be Free Software, Open Source, DFSG-free,
+GPL-compatible, and OK to use in both free and proprietary applications.
+Additions and corrections to this file are welcome.
+
+
+Redistribution and use in source and binary forms, with or without
+modification, are permitted provided that the following conditions are met:
+
+* Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+
+* Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in
+ the documentation and/or other materials provided with the
+ distribution.
+
+* Neither the name of the copyright holders nor the names of
+ contributors may be used to endorse or promote products derived
+ from this software without specific prior written permission.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+POSSIBILITY OF SUCH DAMAGE.
+*/
+
+/*
+ * PS/2 protocol USART version
+ */
+
+#include <stdbool.h>
+#include <avr/interrupt.h>
+#include <util/delay.h>
+#include "gpio.h"
+#include "ps2.h"
+#include "ps2_io.h"
+#include "print.h"
+
+#ifndef PS2_CLOCK_DDR
+# define PS2_CLOCK_DDR PORTx_ADDRESS(PS2_CLOCK_PIN)
+#endif
+#ifndef PS2_CLOCK_BIT
+# define PS2_CLOCK_BIT (PS2_CLOCK_PIN & 0xF)
+#endif
+#ifndef PS2_DATA_DDR
+# define PS2_DATA_DDR PORTx_ADDRESS(PS2_DATA_PIN)
+#endif
+#ifndef PS2_DATA_BIT
+# define PS2_DATA_BIT (PS2_DATA_PIN & 0xF)
+#endif
+
+#define WAIT(stat, us, err) \
+ do { \
+ if (!wait_##stat(us)) { \
+ ps2_error = err; \
+ goto ERROR; \
+ } \
+ } while (0)
+
+uint8_t ps2_error = PS2_ERR_NONE;
+
+static inline uint8_t pbuf_dequeue(void);
+static inline void pbuf_enqueue(uint8_t data);
+static inline bool pbuf_has_data(void);
+static inline void pbuf_clear(void);
+
+void ps2_host_init(void) {
+ idle(); // without this many USART errors occur when cable is disconnected
+ PS2_USART_INIT();
+ PS2_USART_RX_INT_ON();
+ // POR(150-2000ms) plus BAT(300-500ms) may take 2.5sec([3]p.20)
+ //_delay_ms(2500);
+}
+
+uint8_t ps2_host_send(uint8_t data) {
+ bool parity = true;
+ ps2_error = PS2_ERR_NONE;
+
+ PS2_USART_OFF();
+
+ /* terminate a transmission if we have */
+ inhibit();
+ _delay_us(100); // [4]p.13
+
+ /* 'Request to Send' and Start bit */
+ data_lo();
+ clock_hi();
+ WAIT(clock_lo, 10000, 10); // 10ms [5]p.50
+
+ /* Data bit[2-9] */
+ for (uint8_t i = 0; i < 8; i++) {
+ _delay_us(15);
+ if (data & (1 << i)) {
+ parity = !parity;
+ data_hi();
+ } else {
+ data_lo();
+ }
+ WAIT(clock_hi, 50, 2);
+ WAIT(clock_lo, 50, 3);
+ }
+
+ /* Parity bit */
+ _delay_us(15);
+ if (parity) {
+ data_hi();
+ } else {
+ data_lo();
+ }
+ WAIT(clock_hi, 50, 4);
+ WAIT(clock_lo, 50, 5);
+
+ /* Stop bit */
+ _delay_us(15);
+ data_hi();
+
+ /* Ack */
+ WAIT(data_lo, 50, 6);
+ WAIT(clock_lo, 50, 7);
+
+ /* wait for idle state */
+ WAIT(clock_hi, 50, 8);
+ WAIT(data_hi, 50, 9);
+
+ idle();
+ PS2_USART_INIT();
+ PS2_USART_RX_INT_ON();
+ return ps2_host_recv_response();
+ERROR:
+ idle();
+ PS2_USART_INIT();
+ PS2_USART_RX_INT_ON();
+ return 0;
+}
+
+uint8_t ps2_host_recv_response(void) {
+ // Command may take 25ms/20ms at most([5]p.46, [3]p.21)
+ uint8_t retry = 25;
+ while (retry-- && !pbuf_has_data()) {
+ _delay_ms(1);
+ }
+ return pbuf_dequeue();
+}
+
+uint8_t ps2_host_recv(void) {
+ if (pbuf_has_data()) {
+ ps2_error = PS2_ERR_NONE;
+ return pbuf_dequeue();
+ } else {
+ ps2_error = PS2_ERR_NODATA;
+ return 0;
+ }
+}
+
+ISR(PS2_USART_RX_VECT) {
+ // TODO: request RESEND when error occurs?
+ uint8_t error = PS2_USART_ERROR; // USART error should be read before data
+ uint8_t data = PS2_USART_RX_DATA;
+ if (!error) {
+ pbuf_enqueue(data);
+ } else {
+ xprintf("PS2 USART error: %02X data: %02X\n", error, data);
+ }
+}
+
+/* send LED state to keyboard */
+void ps2_host_set_led(uint8_t led) {
+ ps2_host_send(0xED);
+ ps2_host_send(led);
+}
+
+/*--------------------------------------------------------------------
+ * Ring buffer to store scan codes from keyboard
+ *------------------------------------------------------------------*/
+#define PBUF_SIZE 32
+static uint8_t pbuf[PBUF_SIZE];
+static uint8_t pbuf_head = 0;
+static uint8_t pbuf_tail = 0;
+static inline void pbuf_enqueue(uint8_t data) {
+ uint8_t sreg = SREG;
+ cli();
+ uint8_t next = (pbuf_head + 1) % PBUF_SIZE;
+ if (next != pbuf_tail) {
+ pbuf[pbuf_head] = data;
+ pbuf_head = next;
+ } else {
+ print("pbuf: full\n");
+ }
+ SREG = sreg;
+}
+static inline uint8_t pbuf_dequeue(void) {
+ uint8_t val = 0;
+
+ uint8_t sreg = SREG;
+ cli();
+ if (pbuf_head != pbuf_tail) {
+ val = pbuf[pbuf_tail];
+ pbuf_tail = (pbuf_tail + 1) % PBUF_SIZE;
+ }
+ SREG = sreg;
+
+ return val;
+}
+static inline bool pbuf_has_data(void) {
+ uint8_t sreg = SREG;
+ cli();
+ bool has_data = (pbuf_head != pbuf_tail);
+ SREG = sreg;
+ return has_data;
+}
+static inline void pbuf_clear(void) {
+ uint8_t sreg = SREG;
+ cli();
+ pbuf_head = pbuf_tail = 0;
+ SREG = sreg;
+}
diff --git a/platforms/avr/drivers/uart.c b/platforms/avr/drivers/uart.c
index c6abcb6fe0..01cf6b1fb8 100644
--- a/platforms/avr/drivers/uart.c
+++ b/platforms/avr/drivers/uart.c
@@ -100,7 +100,7 @@ void uart_init(uint32_t baud) {
}
// Transmit a byte
-void uart_putchar(uint8_t c) {
+void uart_write(uint8_t data) {
uint8_t i;
i = tx_buffer_head + 1;
@@ -110,27 +110,39 @@ void uart_putchar(uint8_t c) {
while (tx_buffer_tail == i)
; // wait until space in buffer
// cli();
- tx_buffer[i] = c;
+ tx_buffer[i] = data;
tx_buffer_head = i;
UCSRnB = (1 << RXENn) | (1 << TXENn) | (1 << RXCIEn) | (1 << UDRIEn);
// sei();
}
// Receive a byte
-uint8_t uart_getchar(void) {
- uint8_t c, i;
+uint8_t uart_read(void) {
+ uint8_t data, i;
while (rx_buffer_head == rx_buffer_tail)
; // wait for character
i = rx_buffer_tail + 1;
if (i >= RX_BUFFER_SIZE) i = 0;
- c = rx_buffer[i];
+ data = rx_buffer[i];
rx_buffer_tail = i;
- return c;
+ return data;
+}
+
+void uart_transmit(const uint8_t *data, uint16_t length) {
+ for (uint16_t i = 0; i < length; i++) {
+ uart_write(data[i]);
+ }
+}
+
+void uart_receive(uint8_t *data, uint16_t length) {
+ for (uint16_t i = 0; i < length; i++) {
+ data[i] = uart_read();
+ }
}
// Return whether the number of bytes waiting in the receive buffer is nonzero.
-// Call this before uart_getchar() to check if it will need
+// Call this before uart_read() to check if it will need
// to wait for a byte to arrive.
bool uart_available(void) {
uint8_t head, tail;
diff --git a/platforms/avr/drivers/uart.h b/platforms/avr/drivers/uart.h
index 602eb3d8b0..e2dc664eda 100644
--- a/platforms/avr/drivers/uart.h
+++ b/platforms/avr/drivers/uart.h
@@ -28,8 +28,12 @@
void uart_init(uint32_t baud);
-void uart_putchar(uint8_t c);
+void uart_write(uint8_t data);
-uint8_t uart_getchar(void);
+uint8_t uart_read(void);
+
+void uart_transmit(const uint8_t *data, uint16_t length);
+
+void uart_receive(uint8_t *data, uint16_t length);
bool uart_available(void);
diff --git a/platforms/avr/drivers/ws2812.c b/platforms/avr/drivers/ws2812.c
index 77c492cd4c..9150b3c520 100644
--- a/platforms/avr/drivers/ws2812.c
+++ b/platforms/avr/drivers/ws2812.c
@@ -52,20 +52,15 @@ void ws2812_setleds(LED_TYPE *ledarray, uint16_t number_of_leds) {
using the fast 800kHz clockless WS2811/2812 protocol.
*/
-// Timing in ns
-#define w_zeropulse 350
-#define w_onepulse 900
-#define w_totalperiod 1250
-
// Fixed cycles used by the inner loop
#define w_fixedlow 2
#define w_fixedhigh 4
#define w_fixedtotal 8
// Insert NOPs to match the timing, if possible
-#define w_zerocycles (((F_CPU / 1000) * w_zeropulse) / 1000000)
-#define w_onecycles (((F_CPU / 1000) * w_onepulse + 500000) / 1000000)
-#define w_totalcycles (((F_CPU / 1000) * w_totalperiod + 500000) / 1000000)
+#define w_zerocycles (((F_CPU / 1000) * WS2812_T0H) / 1000000)
+#define w_onecycles (((F_CPU / 1000) * WS2812_T1H + 500000) / 1000000)
+#define w_totalcycles (((F_CPU / 1000) * WS2812_TIMING + 500000) / 1000000)
// w1_nops - nops between rising edge and falling edge - low
#if w_zerocycles >= w_fixedlow