aboutsummaryrefslogtreecommitdiffstats
diff options
context:
space:
mode:
authorKevin O'Connor <kevin@koconnor.net>2017-04-10 17:38:52 -0400
committerKevin O'Connor <kevin@koconnor.net>2017-04-11 10:00:54 -0400
commitf9ebb8b23ec80c4462408a46a0ec7d4fa2690467 (patch)
treebef35e9687613300e80b175f7810f41a67459fdc
parent77b94451ded0d720599b88635a311f509b7980a6 (diff)
downloadkutter-f9ebb8b23ec80c4462408a46a0ec7d4fa2690467.tar.gz
kutter-f9ebb8b23ec80c4462408a46a0ec7d4fa2690467.tar.xz
kutter-f9ebb8b23ec80c4462408a46a0ec7d4fa2690467.zip
avr: Move code around in gpio.c
Move the PWM, ADC, and SPI pin tables closer to their corresponding code. This is code movement only - no code changes. Signed-off-by: Kevin O'Connor <kevin@koconnor.net>
-rw-r--r--src/avr/gpio.c212
1 files changed, 110 insertions, 102 deletions
diff --git a/src/avr/gpio.c b/src/avr/gpio.c
index 7a9c5c7c..330e8d63 100644
--- a/src/avr/gpio.c
+++ b/src/avr/gpio.c
@@ -14,7 +14,7 @@
/****************************************************************
- * AVR chip definitions
+ * General Purpose Input Output (GPIO) pins
****************************************************************/
#define GPIO(PORT, NUM) (((PORT)-'A') * 8 + (NUM))
@@ -44,6 +44,67 @@ struct gpio_digital_regs {
#define GPIO2REGS(pin) \
((struct gpio_digital_regs*)READP(digital_regs[GPIO2PORT(pin)]))
+struct gpio_out
+gpio_out_setup(uint8_t pin, uint8_t val)
+{
+ if (GPIO2PORT(pin) >= ARRAY_SIZE(digital_regs))
+ goto fail;
+ struct gpio_digital_regs *regs = GPIO2REGS(pin);
+ if (! regs)
+ goto fail;
+ uint8_t bit = GPIO2BIT(pin);
+ irqstatus_t flag = irq_save();
+ regs->out = val ? (regs->out | bit) : (regs->out & ~bit);
+ regs->mode |= bit;
+ irq_restore(flag);
+ return (struct gpio_out){ .regs=regs, .bit=bit };
+fail:
+ shutdown("Not an output pin");
+}
+
+void
+gpio_out_toggle(struct gpio_out g)
+{
+ g.regs->in = g.bit;
+}
+
+void
+gpio_out_write(struct gpio_out g, uint8_t val)
+{
+ irqstatus_t flag = irq_save();
+ g.regs->out = val ? (g.regs->out | g.bit) : (g.regs->out & ~g.bit);
+ irq_restore(flag);
+}
+
+struct gpio_in
+gpio_in_setup(uint8_t pin, int8_t pull_up)
+{
+ if (GPIO2PORT(pin) >= ARRAY_SIZE(digital_regs))
+ goto fail;
+ struct gpio_digital_regs *regs = GPIO2REGS(pin);
+ if (! regs)
+ goto fail;
+ uint8_t bit = GPIO2BIT(pin);
+ irqstatus_t flag = irq_save();
+ regs->out = pull_up > 0 ? (regs->out | bit) : (regs->out & ~bit);
+ regs->mode &= ~bit;
+ irq_restore(flag);
+ return (struct gpio_in){ .regs=regs, .bit=bit };
+fail:
+ shutdown("Not an input pin");
+}
+
+uint8_t
+gpio_in_read(struct gpio_in g)
+{
+ return !!(g.regs->in & g.bit);
+}
+
+
+/****************************************************************
+ * Hardware Pulse Width Modulation (PWM) pins
+ ****************************************************************/
+
struct gpio_pwm_info {
volatile void *ocr;
volatile uint8_t *rega, *regb;
@@ -101,107 +162,6 @@ static const uint8_t pwm_pins[ARRAY_SIZE(pwm_regs)] PROGMEM = {
#endif
};
-static const uint8_t adc_pins[] PROGMEM = {
-#if CONFIG_MACH_atmega168
- GPIO('C', 0), GPIO('C', 1), GPIO('C', 2), GPIO('C', 3),
- GPIO('C', 4), GPIO('C', 5), GPIO('E', 0), GPIO('E', 1),
-#elif CONFIG_MACH_atmega644p
- GPIO('A', 0), GPIO('A', 1), GPIO('A', 2), GPIO('A', 3),
- GPIO('A', 4), GPIO('A', 5), GPIO('A', 6), GPIO('A', 7),
-#elif CONFIG_MACH_at90usb1286
- GPIO('F', 0), GPIO('F', 1), GPIO('F', 2), GPIO('F', 3),
- GPIO('F', 4), GPIO('F', 5), GPIO('F', 6), GPIO('F', 7),
-#elif CONFIG_MACH_atmega1280 || CONFIG_MACH_atmega2560
- GPIO('F', 0), GPIO('F', 1), GPIO('F', 2), GPIO('F', 3),
- GPIO('F', 4), GPIO('F', 5), GPIO('F', 6), GPIO('F', 7),
- GPIO('K', 0), GPIO('K', 1), GPIO('K', 2), GPIO('K', 3),
- GPIO('K', 4), GPIO('K', 5), GPIO('K', 6), GPIO('K', 7),
-#endif
-};
-
-#if CONFIG_MACH_atmega168
-static const uint8_t SS = GPIO('B', 2), SCK = GPIO('B', 5), MOSI = GPIO('B', 3);
-#elif CONFIG_MACH_atmega644p
-static const uint8_t SS = GPIO('B', 4), SCK = GPIO('B', 7), MOSI = GPIO('B', 5);
-#elif CONFIG_MACH_at90usb1286 || CONFIG_MACH_atmega1280 || CONFIG_MACH_atmega2560
-static const uint8_t SS = GPIO('B', 0), SCK = GPIO('B', 1), MOSI = GPIO('B', 2);
-#endif
-
-static const uint8_t ADMUX_DEFAULT = 0x40;
-
-
-/****************************************************************
- * gpio functions
- ****************************************************************/
-
-struct gpio_out
-gpio_out_setup(uint8_t pin, uint8_t val)
-{
- if (GPIO2PORT(pin) >= ARRAY_SIZE(digital_regs))
- goto fail;
- struct gpio_digital_regs *regs = GPIO2REGS(pin);
- if (! regs)
- goto fail;
- uint8_t bit = GPIO2BIT(pin);
- irqstatus_t flag = irq_save();
- regs->out = val ? (regs->out | bit) : (regs->out & ~bit);
- regs->mode |= bit;
- irq_restore(flag);
- return (struct gpio_out){ .regs=regs, .bit=bit };
-fail:
- shutdown("Not an output pin");
-}
-
-void gpio_out_toggle(struct gpio_out g)
-{
- g.regs->in = g.bit;
-}
-
-void
-gpio_out_write(struct gpio_out g, uint8_t val)
-{
- irqstatus_t flag = irq_save();
- g.regs->out = val ? (g.regs->out | g.bit) : (g.regs->out & ~g.bit);
- irq_restore(flag);
-}
-
-struct gpio_in
-gpio_in_setup(uint8_t pin, int8_t pull_up)
-{
- if (GPIO2PORT(pin) >= ARRAY_SIZE(digital_regs))
- goto fail;
- struct gpio_digital_regs *regs = GPIO2REGS(pin);
- if (! regs)
- goto fail;
- uint8_t bit = GPIO2BIT(pin);
- irqstatus_t flag = irq_save();
- regs->out = pull_up > 0 ? (regs->out | bit) : (regs->out & ~bit);
- regs->mode &= ~bit;
- irq_restore(flag);
- return (struct gpio_in){ .regs=regs, .bit=bit };
-fail:
- shutdown("Not an input pin");
-}
-
-uint8_t
-gpio_in_read(struct gpio_in g)
-{
- return !!(g.regs->in & g.bit);
-}
-
-
-void
-gpio_pwm_write(struct gpio_pwm g, uint8_t val)
-{
- if (g.size8) {
- *(volatile uint8_t*)g.reg = val;
- } else {
- irqstatus_t flag = irq_save();
- *(volatile uint16_t*)g.reg = val;
- irq_restore(flag);
- }
-}
-
struct gpio_pwm
gpio_pwm_setup(uint8_t pin, uint32_t cycle_time, uint8_t val)
{
@@ -257,6 +217,42 @@ gpio_pwm_setup(uint8_t pin, uint32_t cycle_time, uint8_t val)
shutdown("Not a valid PWM pin");
}
+void
+gpio_pwm_write(struct gpio_pwm g, uint8_t val)
+{
+ if (g.size8) {
+ *(volatile uint8_t*)g.reg = val;
+ } else {
+ irqstatus_t flag = irq_save();
+ *(volatile uint16_t*)g.reg = val;
+ irq_restore(flag);
+ }
+}
+
+
+/****************************************************************
+ * Analog to Digital Converter (ADC) pins
+ ****************************************************************/
+
+static const uint8_t adc_pins[] PROGMEM = {
+#if CONFIG_MACH_atmega168
+ GPIO('C', 0), GPIO('C', 1), GPIO('C', 2), GPIO('C', 3),
+ GPIO('C', 4), GPIO('C', 5), GPIO('E', 0), GPIO('E', 1),
+#elif CONFIG_MACH_atmega644p
+ GPIO('A', 0), GPIO('A', 1), GPIO('A', 2), GPIO('A', 3),
+ GPIO('A', 4), GPIO('A', 5), GPIO('A', 6), GPIO('A', 7),
+#elif CONFIG_MACH_at90usb1286
+ GPIO('F', 0), GPIO('F', 1), GPIO('F', 2), GPIO('F', 3),
+ GPIO('F', 4), GPIO('F', 5), GPIO('F', 6), GPIO('F', 7),
+#elif CONFIG_MACH_atmega1280 || CONFIG_MACH_atmega2560
+ GPIO('F', 0), GPIO('F', 1), GPIO('F', 2), GPIO('F', 3),
+ GPIO('F', 4), GPIO('F', 5), GPIO('F', 6), GPIO('F', 7),
+ GPIO('K', 0), GPIO('K', 1), GPIO('K', 2), GPIO('K', 3),
+ GPIO('K', 4), GPIO('K', 5), GPIO('K', 6), GPIO('K', 7),
+#endif
+};
+
+static const uint8_t ADMUX_DEFAULT = 0x40;
DECL_CONSTANT(ADC_MAX, 1024);
@@ -335,6 +331,18 @@ gpio_adc_cancel_sample(struct gpio_adc g)
}
+/****************************************************************
+ * Serial Peripheral Interface (SPI) hardware
+ ****************************************************************/
+
+#if CONFIG_MACH_atmega168
+static const uint8_t SS = GPIO('B', 2), SCK = GPIO('B', 5), MOSI = GPIO('B', 3);
+#elif CONFIG_MACH_atmega644p
+static const uint8_t SS = GPIO('B', 4), SCK = GPIO('B', 7), MOSI = GPIO('B', 5);
+#elif CONFIG_MACH_at90usb1286 || CONFIG_MACH_atmega1280 || CONFIG_MACH_atmega2560
+static const uint8_t SS = GPIO('B', 0), SCK = GPIO('B', 1), MOSI = GPIO('B', 2);
+#endif
+
void
spi_config(void)
{