docs: docs/

This commit is contained in:
Frederik Beimgraben 2025-07-03 08:37:46 +02:00
parent 276ac618b3
commit 878077ffc3
14 changed files with 3023 additions and 132 deletions

File diff suppressed because it is too large Load Diff

BIN
docs/images/abstract.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 90 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 140 KiB

View File

@ -1096,7 +1096,7 @@ RECURSIVE = YES
# Note that relative paths are relative to the directory from which Doxygen is # Note that relative paths are relative to the directory from which Doxygen is
# run. # run.
EXCLUDE = driverlib/ EXCLUDE = driverlib/ jsmn/ src/Board.h
# The EXCLUDE_SYMLINKS tag can be used to select whether or not files or # The EXCLUDE_SYMLINKS tag can be used to select whether or not files or
# directories that are symbolic links (a Unix file system feature) are excluded # directories that are symbolic links (a Unix file system feature) are excluded

View File

@ -1,3 +1,11 @@
/**
* \file door_sensor.c
* \brief Implementation of the door sensor driver using MSP430 GPIO interrupts.
*
* This module configures a GPIO pin to detect door open/close events and invokes
* user-provided callbacks on confirmed state changes.
*/
#include <stdint.h> #include <stdint.h>
#include <msp430.h> #include <msp430.h>
#include <driverlib.h> #include <driverlib.h>
@ -5,32 +13,60 @@
#include "door_sensor.h" #include "door_sensor.h"
#include "constants.h" #include "constants.h"
/**\brief GPIO port used for the door sensor. */
#define SENSOR_PORT GPIO_PORT_P2 #define SENSOR_PORT GPIO_PORT_P2
/**\brief GPIO pin used for the door sensor. */
#define SENSOR_PIN GPIO_PIN0 #define SENSOR_PIN GPIO_PIN0
/**\brief Interrupt vector associated with the sensor port. */
#define SENSOR_VECTOR PORT2_VECTOR #define SENSOR_VECTOR PORT2_VECTOR
/** User callback invoked on confirmed key press */ /**
* \brief Callback invoked when the door is detected as opened.
*
* User must supply a function matching this type to be notified of an open event.
*/
static DoorOpenedCallback_t doorOpenedCallback = NULL; static DoorOpenedCallback_t doorOpenedCallback = NULL;
/**
* \brief Callback invoked when the door is detected as closed.
*
* User must supply a function matching this type to be notified of a close event.
*/
static DoorClosedCallback_t doorClosedCallback = NULL; static DoorClosedCallback_t doorClosedCallback = NULL;
/**
* \brief Initialize the door sensor driver.
*
* Configures the GPIO pin for input with pull-up resistor and enables
* interrupts on the specified edge. Also stores the user-provided callbacks.
*
* \param ocb Function to call when the door opens (rising edge).
* \param ccb Function to call when the door closes (falling edge).
*/
void door_init(DoorOpenedCallback_t ocb, DoorClosedCallback_t ccb) { void door_init(DoorOpenedCallback_t ocb, DoorClosedCallback_t ccb) {
doorOpenedCallback = ocb; doorOpenedCallback = ocb;
doorClosedCallback = ccb; doorClosedCallback = ccb;
/* Configure port as pull up with interrupt */ /* Configure port as pull up with interrupt */
GPIO_setAsInputPinWithPullUpResistor(GPIO_PORT_P2, GPIO_PIN0); GPIO_setAsInputPinWithPullUpResistor(SENSOR_PORT, SENSOR_PIN);
GPIO_clearInterrupt(GPIO_PORT_P2, GPIO_PIN0); GPIO_clearInterrupt(SENSOR_PORT, SENSOR_PIN);
GPIO_selectInterruptEdge(GPIO_PORT_P2, GPIO_PIN0, GPIO_LOW_TO_HIGH_TRANSITION); GPIO_selectInterruptEdge(SENSOR_PORT, SENSOR_PIN, GPIO_LOW_TO_HIGH_TRANSITION);
GPIO_enableInterrupt(GPIO_PORT_P2, GPIO_PIN0); GPIO_enableInterrupt(SENSOR_PORT, SENSOR_PIN);
/* Enable global interrupts */ /* Enable global interrupts */
__enable_interrupt(); __enable_interrupt();
} }
/**
* \brief Tracks the last known door state (open = true, closed = false).
*/
volatile bool door_last_open = false; volatile bool door_last_open = false;
/** /**
* @brief Interrupt Service Routine for PORT2 * \brief ISR for PORT2 interrupt handling door sensor events.
*
* Detects whether the door is opening or closing based on interrupt edge,
* invokes the corresponding callback, and reconfigures the interrupt edge
* for the next transition.
*/ */
#pragma vector=SENSOR_VECTOR #pragma vector=SENSOR_VECTOR
__interrupt void SENSOR_ISR(void) __interrupt void SENSOR_ISR(void)
@ -39,17 +75,19 @@ __interrupt void SENSOR_ISR(void)
if (status) { if (status) {
if (door_last_open) { if (door_last_open) {
/* Door was open, now closed */
if (doorClosedCallback) if (doorClosedCallback)
doorClosedCallback(); doorClosedCallback();
GPIO_selectInterruptEdge(GPIO_PORT_P2, GPIO_PIN0, GPIO_LOW_TO_HIGH_TRANSITION); GPIO_selectInterruptEdge(SENSOR_PORT, SENSOR_PIN, GPIO_LOW_TO_HIGH_TRANSITION);
} else { } else {
/* Door was closed, now opened */
if (doorOpenedCallback) if (doorOpenedCallback)
doorOpenedCallback(); doorOpenedCallback();
GPIO_selectInterruptEdge(GPIO_PORT_P2, GPIO_PIN0, GPIO_HIGH_TO_LOW_TRANSITION); GPIO_selectInterruptEdge(SENSOR_PORT, SENSOR_PIN, GPIO_HIGH_TO_LOW_TRANSITION);
} }
} }
/* Clear the interrupt flag and toggle stored state */
GPIO_clearInterrupt(SENSOR_PORT, SENSOR_PIN); GPIO_clearInterrupt(SENSOR_PORT, SENSOR_PIN);
door_last_open = !door_last_open; door_last_open = !door_last_open;
} }

View File

@ -1,13 +1,38 @@
/**
* \file door_sensor.h
* \brief Public interface for the door sensor driver.
*
* This header declares the callback types and initialization function
* for detecting door open and close events using GPIO interrupts.
*/
#ifndef DOOR_H #ifndef DOOR_H
#define DOOR_H #define DOOR_H
/** /**
* @brief Callback invoked on a confirmed key press. * \brief Callback type invoked when the door is detected as opened.
* @param key ASCII character of the pressed key. *
* This function is called by the driver on a confirmed open event.
*/ */
typedef void (*DoorOpenedCallback_t)(void); typedef void (*DoorOpenedCallback_t)(void);
/**
* \brief Callback type invoked when the door is detected as closed.
*
* This function is called by the driver on a confirmed close event.
*/
typedef void (*DoorClosedCallback_t)(void); typedef void (*DoorClosedCallback_t)(void);
/**
* \brief Initialize the door sensor driver.
*
* Configures the GPIO pin for input with pull-up resistor and enables
* interrupts on the door sensor line. The provided callbacks are invoked
* on door open and close events respectively.
*
* \param ocb User-provided callback to invoke on door open.
* \param ccb User-provided callback to invoke on door close.
*/
void door_init(DoorOpenedCallback_t ocb, DoorClosedCallback_t ccb); void door_init(DoorOpenedCallback_t ocb, DoorClosedCallback_t ccb);
#endif // DOOR_H #endif // DOOR_H

183
src/i2c.c
View File

@ -1,12 +1,13 @@
/* ========================================================================== */ /* File: i2c.c */
/* I2C.c */
/* ========================================================================== */
/** /**
* @file I2C.c * @file i2c.c
* @author wehrberger * @brief I²C master routines and missing standard C90 constants for MSP430FR2355.
* @date 31.05.2025
* *
* @brief Implementierung eines minimalen blockierenden I²C-Master-Treibers. * Implements byte-wise I²C transmit and single-register read with automatic
* STOP handling and interrupt-driven operation.
*
* @author (based on work by) Luis Wehrberger
* @date 2025-07-02
*/ */
#include "i2c.h" #include "i2c.h"
@ -14,104 +15,127 @@
#include <stdint.h> #include <stdint.h>
#include <stdbool.h> #include <stdbool.h>
/** Pointer auf das aktuell zu übertragende Byte. */ /** Pointer to the current transmit buffer. */
static char *packet; static char *i2c_tx_buffer;
/** Index des nächsten zu übertragenden Bytes. */ /** Number of bytes left to send (buffer length). */
static unsigned int dataCount; static unsigned int i2c_tx_length;
/** Anzahl der Bytes in @ref packet. */ /** Index of the next byte to transmit. */
static unsigned int packetLength; static unsigned int i2c_tx_index;
/** Speicher für das zuletzt vom ISR empfangene Byte. */ /** Last byte received by the ISR. */
static char dataIn; static char i2c_rx_byte;
static volatile bool i2cDone = false; /** Flag set when I²C transfer completes (STOP or NACK). */
static volatile bool i2c_transfer_complete = false;
/**
* @brief Initialize USCI_B0 module for I²C master mode at 50 kHz.
*
* Configures SMCLK source, sets clock divider, 7-bit addressing,
* automatic STOP generation, port mapping for SDA/SCL, and enables
* relevant interrupts.
*/
void i2c_init(void) void i2c_init(void)
{ {
// USCI in Reset setzen um Konfiguration zu ermöglichen // Put eUSCI_B0 into reset state for configuration
UCB0CTLW0 |= UCSWRST; UCB0CTLW0 |= UCSWRST;
// SMCLK wählen und durch 20 teilen → 50 kHz SCL // Select SMCLK and divide by 20 → 50 kHz SCL
UCB0CTLW0 |= UCSSEL_3; UCB0CTLW0 |= UCSSEL_3;
UCB0BRW = 50; UCB0BRW = 50;
// I²C Master, 7-Bit Adressierung // Configure as I²C master with 7-bit addressing
UCB0CTLW0 |= UCMODE_3 | UCMST; UCB0CTLW0 |= UCMODE_3 | UCMST;
// Automatischer STOP nach Byte-Zähler (UCB0TBCNT) erreicht Null // Enable automatic STOP when byte counter (UCB0TBCNT) reaches zero
UCB0CTLW1 |= UCASTP_2; UCB0CTLW1 |= UCASTP_2;
// Port-Mapping: P1.2 = SDA, P1.3 = SCL // Assign P1.2 = SDA, P1.3 = SCL via port mapping
P1SEL1 &= ~(BIT2 | BIT3); P1SEL1 &= ~(BIT2 | BIT3);
P1SEL0 |= BIT2 | BIT3; P1SEL0 |= (BIT2 | BIT3);
// Modul aktivieren // Release eUSCI_B0 for operation
UCB0CTLW0 &= ~UCSWRST; UCB0CTLW0 &= ~UCSWRST;
// Interrupts: RX, TX, STOP, NACK // Enable RX, TX, STOP, and NACK interrupts
UCB0IE |= UCRXIE0 | UCTXIE0 | UCSTPIE | UCNACKIE; UCB0IE |= UCRXIE0 | UCTXIE0 | UCSTPIE | UCNACKIE;
__enable_interrupt(); __enable_interrupt();
} }
/**
* @brief Transmit a sequence of bytes to a given I²C slave.
*
* @param slaveAddress 7-bit I²C address of the slave device.
* @param data Pointer to data buffer to send.
* @param length Number of bytes to transmit.
*/
void i2c_write(uint8_t slaveAddress, char data[], uint8_t length) void i2c_write(uint8_t slaveAddress, char data[], uint8_t length)
{ {
// Set target slave address
UCB0I2CSA = slaveAddress; UCB0I2CSA = slaveAddress;
packet = data;
packetLength = length;
dataCount = 0;
// Master-Transmit-Modus // Initialize transmit buffer and counters
i2c_tx_buffer = data;
i2c_tx_length = length;
i2c_tx_index = 0;
// Configure for master-transmit mode and set byte counter
UCB0CTLW0 |= UCTR; UCB0CTLW0 |= UCTR;
UCB0TBCNT = length; UCB0TBCNT = length;
// START generieren, dann schlafen bis STOP // Generate START and wait for STOP flag in ISR
UCB0CTLW0 |= UCTXSTT; UCB0CTLW0 |= UCTXSTT;
i2cDone = false; i2c_transfer_complete = false;
while (!i2cDone) while (!i2c_transfer_complete)
{ {
LPM3; // Warten auf STOP → ISR weckt uns auf LPM3; // Enter low-power mode, will wake on STOP or NACK
} }
} }
char i2c_read_reg(uint8_t slaveAddress, uint8_t registerAddress)
{
// Registeradresse zuerst senden
char addressBuffer[1] = {registerAddress};
i2c_write(slaveAddress, addressBuffer, 1);
// In Empfangsmodus wechseln und 1 Byte anfordern
UCB0CTLW0 &= ~UCTR;
UCB0TBCNT = 1;
UCB0CTLW0 |= UCTXSTT; // Repeated START
i2cDone = false;
while (!i2cDone)
{
LPM3; // Warten auf STOP → ISR weckt uns auf
}
return dataIn;
}
/* ========================================================================== */
/* Interrupt Service Routine */
/* ========================================================================== */
/** /**
* @brief Vereinheitlichte ISR für alle USCI_B0 I²C-Ereignisse. * @brief Read a single register byte from an I²C slave.
* *
* Nur vier Interrupt-Ursachen werden derzeit behandelt: * Performs a write of the register address, followed by a repeated START
* - UCNACKIFG : Kennzeichnet fehlendes ACK (nur Debug-Hook) * to read one byte, with automatic STOP and interrupt-based wake-up.
* - UCSTPIFG : STOP erkannt LPM3 verlassen
* - UCRXIFG0 : Ein Byte empfangen
* - UCTXIFG0 : Sendepuffer bereit für nächstes Byte
* *
* Alle anderen Ursachen fallen durch zum default. * @param slaveAddress 7-bit I²C address of the slave device.
* @param registerAddress Register address to read.
* @return Byte read from the register.
*/
char i2c_read_reg(uint8_t slaveAddress, uint8_t registerAddress)
{
// Send register address first
char addr_buf[1] = { (char)registerAddress };
i2c_write(slaveAddress, addr_buf, 1);
// Switch to master-receive mode and request one byte
UCB0CTLW0 &= ~UCTR;
UCB0TBCNT = 1;
// Generate repeated START condition
UCB0CTLW0 |= UCTXSTT;
i2c_transfer_complete = false;
while (!i2c_transfer_complete)
{
LPM3; // Wait for ISR to clear STOP flag
}
return i2c_rx_byte;
}
/**
* @brief USCI_B0 I²C interrupt handler.
*
* Handles NACK, STOP, RX, and TX events:
* - NACK: terminate transfer and wake CPU
* - STOP: terminate transfer and wake CPU
* - RXBUF: store received byte
* - TXBUF: send next byte or reset index
*/ */
#pragma vector = EUSCI_B0_VECTOR #pragma vector = EUSCI_B0_VECTOR
__interrupt void EUSCI_B0_I2C_ISR(void) __interrupt void EUSCI_B0_I2C_ISR(void)
@ -119,31 +143,34 @@ __interrupt void EUSCI_B0_I2C_ISR(void)
switch (__even_in_range(UCB0IV, USCI_I2C_UCBIT9IFG)) switch (__even_in_range(UCB0IV, USCI_I2C_UCBIT9IFG))
{ {
case USCI_I2C_UCNACKIFG: case USCI_I2C_UCNACKIFG:
// NACK → CPU aufwecken (LPM3 verlassen) // NACK received: signal completion and wake CPU
i2cDone = true; i2c_transfer_complete = true;
__bic_SR_register_on_exit(LPM3_bits); __bic_SR_register_on_exit(LPM3_bits);
break; break;
case USCI_I2C_UCSTPIFG: case USCI_I2C_UCSTPIFG:
// STOP → CPU aufwecken (LPM3 verlassen) // STOP condition detected: signal completion and wake CPU
i2cDone = true; i2c_transfer_complete = true;
__bic_SR_register_on_exit(LPM3_bits); __bic_SR_register_on_exit(LPM3_bits);
break; break;
case USCI_I2C_UCRXIFG0: case USCI_I2C_UCRXIFG0:
// Empfangenes Byte speichern // Read received byte into buffer
dataIn = UCB0RXBUF; i2c_rx_byte = UCB0RXBUF;
break; break;
case USCI_I2C_UCTXIFG0: case USCI_I2C_UCTXIFG0:
// Nächstes Datenbyte senden oder Übertragung beenden // Transmit next byte or reset index if done
UCB0TXBUF = packet[dataCount++]; UCB0TXBUF = i2c_tx_buffer[i2c_tx_index++];
if (dataCount >= packetLength) if (i2c_tx_index >= i2c_tx_length)
dataCount = 0; // Für nächste Transaktion zurücksetzen {
// Reset index for subsequent transactions
i2c_tx_index = 0;
}
break; break;
default: default:
// Unbehandelter Vektor nichts zu tun // Unhandled interrupts: no action
break; break;
} }
} }

View File

@ -19,7 +19,7 @@
#include <stdbool.h> #include <stdbool.h>
/** /**
* @brief Initialize the I2C module as master (SMCLK/20 50 kHz SCL). * @brief Initialize the I2C module as master.
*/ */
void i2c_init(void); void i2c_init(void);

View File

@ -13,7 +13,7 @@
* - Wait for key release and debounce * - Wait for key release and debounce
* - Clear flags and re-enable column interrupts * - Clear flags and re-enable column interrupts
* *
* @author * @author Frederik Beimgraben
* @date 2025-07-02 * @date 2025-07-02
*/ */

View File

@ -5,10 +5,7 @@
* *
* Interrupt-driven scanning with callback on key press. * Interrupt-driven scanning with callback on key press.
* *
* @authors * @author Frederik Beimgraben
* Frederik Beimgraben
* Minh Dan Cam
* Luis Meyer
* @date 2025-07-02 * @date 2025-07-02
*/ */

View File

@ -1,34 +1,65 @@
/**
* \file lcd.c
* \brief I2C-based LCD driver for MSP430FR2355.
*
* This module provides initialization and basic control functions
* for a character LCD connected via an I2C expander. It supports
* 4-bit communication mode and includes routines for sending commands
* and data to the display.
*/
#include "lcd.h" #include "lcd.h"
#include "i2c.h" /* Ihr I²C-Master-Treiber */ #include "i2c.h" /**< I²C master driver */
#include <msp430fr2355.h> /* für __delay_cycles() */ #include <msp430fr2355.h> /**< MSP430 definitions for __delay_cycles() */
#include <stdint.h> #include <stdint.h>
/* --- Interne Helfer: sendet eine 4-Bit-Halbnibble plus Control-Bits --- */ /**
* \brief Send a 4-bit nibble with control flags over I2C to the LCD.
*
* This helper composes a byte containing the nibble (in the high 4 bits),
* the control signals (RS, RW, EN), and the backlight bit, then toggles
* the enable line to latch the data.
*
* \param nibble 4-bit data to send (lower nibble used).
* \param control Control flags (e.g., RS, R/W).
*/
static void lcd_write_nibble(uint8_t nibble, uint8_t control) static void lcd_write_nibble(uint8_t nibble, uint8_t control)
{ {
char buf[1]; char buf[1];
/* High-Nibble in die oberen 4 Bits */ /* High nibble placed in upper data bits, include control and backlight */
buf[0] = (nibble << 4) | control | LCD_BACKLIGHT; buf[0] = (uint8_t)((nibble << 4) | control | LCD_BACKLIGHT);
/* EN=1 */ /* Pulse EN high */
i2c_write(LCD_I2C_ADDR, buf, 1); i2c_write(LCD_I2C_ADDR, buf, 1);
buf[0] |= LCD_ENABLE; buf[0] |= LCD_ENABLE;
i2c_write(LCD_I2C_ADDR, buf, 1); i2c_write(LCD_I2C_ADDR, buf, 1);
__delay_cycles(500); /* ca. 50 µs @ 1 MHz */ __delay_cycles(500); /**< ~50µs at 1MHz */
/* EN=0 */ /* EN low */
buf[0] &= ~LCD_ENABLE; buf[0] &= (char)~LCD_ENABLE;
i2c_write(LCD_I2C_ADDR, buf, 1); i2c_write(LCD_I2C_ADDR, buf, 1);
__delay_cycles(500); __delay_cycles(500);
} }
/* Sendet ein volles Byte (2×4-Bit) als Befehl (RS=0) */ /**
* \brief Send an 8-bit command to the LCD.
*
* Splits the command into two 4-bit nibbles and sends each with RS=0.
*
* \param cmd Command byte to send.
*/
static void lcd_send_cmd(uint8_t cmd) static void lcd_send_cmd(uint8_t cmd)
{ {
lcd_write_nibble(cmd >> 4, 0x00); lcd_write_nibble(cmd >> 4, 0x00);
lcd_write_nibble(cmd & 0x0F, 0x00); lcd_write_nibble(cmd & 0x0F, 0x00);
} }
/* Sendet ein volles Byte als Daten (RS=1) */ /**
* \brief Send an 8-bit data value (character) to the LCD.
*
* Splits the data into two 4-bit nibbles and sends each with RS=1.
*
* \param data Data byte (character) to display.
*/
static void lcd_send_data(uint8_t data) static void lcd_send_data(uint8_t data)
{ {
lcd_write_nibble(data >> 4, LCD_RS); lcd_write_nibble(data >> 4, LCD_RS);
@ -37,10 +68,10 @@ static void lcd_send_data(uint8_t data)
void lcd_init(void) void lcd_init(void)
{ {
/* Wartezeit nach Power-Up */ /* Delay for LCD power-up (approx. 50 ms) */
__delay_cycles(50000); /* ca. 50 ms */ __delay_cycles(50000);
/* Initial­sequenz 8-Bit-Befehle (3×) */ /* Initialization sequence in 8-bit mode: 3 pulses */
lcd_write_nibble(0x03, 0x00); lcd_write_nibble(0x03, 0x00);
__delay_cycles(20000); __delay_cycles(20000);
lcd_write_nibble(0x03, 0x00); lcd_write_nibble(0x03, 0x00);
@ -48,37 +79,57 @@ void lcd_init(void)
lcd_write_nibble(0x03, 0x00); lcd_write_nibble(0x03, 0x00);
__delay_cycles(2000); __delay_cycles(2000);
/* In 4-Bit-Modus schalten */ /* Switch to 4-bit mode */
lcd_write_nibble(0x02, 0x00); lcd_write_nibble(0x02, 0x00);
__delay_cycles(2000); __delay_cycles(2000);
/* Funktion: 4-Bit, 2 Zeilen, 5×8 Punkte */ /* Function set: 4-bit, 2 lines, 5x8 dots */
lcd_send_cmd(0x28); lcd_send_cmd(0x28);
/* Display off */ /* Display off */
lcd_send_cmd(0x08); lcd_send_cmd(0x08);
/* Clear */ /* Clear display */
lcd_send_cmd(0x01); lcd_send_cmd(0x01);
__delay_cycles(2000); __delay_cycles(2000);
/* Entry mode: Cursor++ */ /* Entry mode set: increment cursor */
lcd_send_cmd(0x06); lcd_send_cmd(0x06);
/* Display on, Cursor off, Blink off */ /* Display on, cursor off, blink off */
lcd_send_cmd(0x0C); lcd_send_cmd(0x0C);
} }
void lcd_clear(void) void lcd_clear(void)
{ {
/**
* \brief Clear display and reset cursor.
*
* Sends the clear command and waits for the LCD to process it.
*/
lcd_send_cmd(0x01); lcd_send_cmd(0x01);
__delay_cycles(2000); __delay_cycles(2000);
} }
void lcd_set_cursor(uint8_t row, uint8_t col) void lcd_set_cursor(uint8_t row, uint8_t col)
{ {
/**
* \brief Set cursor to specified position.
*
* Calculates the DDRAM address based on row and column.
*
* \param row Row index (0 or 1).
* \param col Column index (0-15).
*/
uint8_t addr = (row == 0 ? 0x00 : 0x40) + (col & 0x0F); uint8_t addr = (row == 0 ? 0x00 : 0x40) + (col & 0x0F);
lcd_send_cmd(0x80 | addr); lcd_send_cmd(0x80 | addr);
} }
void lcd_print(const char *str) void lcd_print(const char *str)
{ {
/**
* \brief Print a null-terminated string to the LCD.
*
* Iterates through the string and sends each character as data.
*
* \param str Pointer to a null-terminated C string.
*/
while (*str) while (*str)
{ {
lcd_send_data((uint8_t)*str++); lcd_send_data((uint8_t)*str++);

View File

@ -6,9 +6,10 @@
* This module drives a keypadandLCD UI to select beverage types (AD), * This module drives a keypadandLCD UI to select beverage types (AD),
* choose quantities, confirm orders, detect door events, and edit stock levels. * choose quantities, confirm orders, detect door events, and edit stock levels.
* *
* @author Frederik Beimgraben * @authors
* @author Minh Dan Cam * Frederik Beimgraben
* @author Luis Meyer * Minh Dan Cam
* Luis Meyer
* @date 2025-07-03 * @date 2025-07-03
*/ */

View File

@ -1,41 +1,70 @@
/**
* \file timer.c
* \brief MSP430 Timer B driver and blocking delay implementation.
*
* This module provides a millisecond-level blocking delay function using
* low-power mode and global interrupts, as well as initialization for Timer B
* in up mode to generate periodic 1ms interrupts.
*/
#include <stdint.h> #include <stdint.h>
#include <msp430.h> #include <msp430.h>
#include <driverlib.h> #include <driverlib.h>
#include "timer.h" #include "timer.h"
/** /**
* @brief Führt eine blockierende Wartezeit aus. * \brief Block execution for a given number of milliseconds.
* @param ms Zeit in Millisekunden *
* Implements a blocking delay by entering LPM0 and waking up via the
* Timer interrupt on each millisecond tick.
*
* \param ms Number of milliseconds to delay.
*/ */
void sleep(uint16_t ms) { void sleep(uint16_t ms) {
while (ms--) { while (ms--) {
/* Enter low-power mode 0 with interrupts enabled */
__bis_SR_register(LPM0_bits + GIE); __bis_SR_register(LPM0_bits + GIE);
/* No operation, wait for interrupt */
__no_operation(); __no_operation();
} }
} }
/**
* \brief Initialize Timer B0 in up mode to generate 1ms period interrupts.
*
* Configures Timer B0 to use SMCLK, no divider, and a period of 999 ticks
* to achieve a 1ms overflow (assuming 1MHz SMCLK). Enables CCR0 interrupt
* to exit low-power mode on each tick.
*/
void init_timer(void) { void init_timer(void) {
static Timer_B_initUpModeParam param = {0}; static Timer_B_initUpModeParam param = {0};
/* Select SMCLK as clock source */
param.clockSource = TIMER_B_CLOCKSOURCE_SMCLK; param.clockSource = TIMER_B_CLOCKSOURCE_SMCLK;
/* No division: tick = 1MHz / 1 = 1MHz */
param.clockSourceDivider = TIMER_B_CLOCKSOURCE_DIVIDER_1; param.clockSourceDivider = TIMER_B_CLOCKSOURCE_DIVIDER_1;
param.timerPeriod = 999; // wenn 1000 Taktimpulse gezählt /* Period = 999 -> interrupt every 1000 ticks => 1ms */
// wurden, erfolgt ein Interrupt param.timerPeriod = 999;
// Periodendauer somit 1ms /* Disable interrupt on timer rollover (TBIE) */
param.timerInterruptEnable_TBIE = param.timerInterruptEnable_TBIE = TIMER_B_TBIE_INTERRUPT_DISABLE;
TIMER_B_TBIE_INTERRUPT_DISABLE; // no interrupt on 0x0000 /* Enable CCR0 interrupt on timer compare match */
param.captureCompareInterruptEnable_CCR0_CCIE = param.captureCompareInterruptEnable_CCR0_CCIE =
TIMER_B_CAPTURECOMPARE_INTERRUPT_ENABLE; // interrupt on TRmax TIMER_B_CAPTURECOMPARE_INTERRUPT_ENABLE;
/* Clear timer and start immediately */
param.timerClear = TIMER_B_DO_CLEAR; param.timerClear = TIMER_B_DO_CLEAR;
param.startTimer = true; param.startTimer = true;
// start Timer: /* Initialize and start Timer B0 in up mode */
Timer_B_initUpMode(TB0_BASE, &param); Timer_B_initUpMode(TB0_BASE, &param);
} }
// TimerB0 Interrupt Vector (TBxIV) handler /**
* \brief ISR for Timer0_B0 (CCR0) comparison event.
*
* Exits low-power mode 0 to resume the sleeping function.
*/
#pragma vector=TIMER0_B0_VECTOR #pragma vector=TIMER0_B0_VECTOR
__interrupt void TIMER0_B0_ISR(void) __interrupt void TIMER0_B0_ISR(void) {
{ /* Clear LPM0 bits on exit to wake up CPU */
__bic_SR_register_on_exit(LPM0_bits); __bic_SR_register_on_exit(LPM0_bits);
} }

View File

@ -1,7 +1,31 @@
/**
* \file timer.h
* \brief Interface for millisecond delay and Timer B initialization on MSP430.
*
* This header declares functions for creating a blocking delay using low-power
* mode and for initializing Timer B0 in up mode to generate periodic 1ms interrupts.
*/
#ifndef TIMER_H #ifndef TIMER_H
#define TIMER_H #define TIMER_H
/**
* \brief Block execution for a specified number of milliseconds.
*
* This function enters low-power mode 0 (LPM0) and wakes on each
* Timer B CCR0 interrupt to achieve an approximate millisecond delay.
*
* \param ms Number of milliseconds to sleep.
*/
void sleep(uint16_t ms); void sleep(uint16_t ms);
/**
* \brief Initialize Timer B0 to generate 1ms interrupts.
*
* Configures Timer B0 with SMCLK as the clock source, no divider,
* and a period of 999 ticks (for a 1MHz clock) to create a 1ms interval.
* Enables CCR0 compare interrupt to wake from low-power mode on each tick.
*/
void init_timer(void); void init_timer(void);
#endif // TIMER_H #endif // TIMER_H