This commit is contained in:
James Goppert 2011-09-30 18:53:04 -04:00
commit 1446e50577
197 changed files with 39074 additions and 0 deletions

View File

@ -0,0 +1,465 @@
// ------------------------------------------------------------------------------------------------------------------------------------------------------------
// ARDUCODER Version v0.9.85
// ------------------------------------------------------------------------------------------------------------------------------------------------------------
// ARDUCOPTER 2 : PPM ENCODER for AT Mega 328p and APM v1.4 Boards
// By:John Arne Birkeland - 2011
//
// By: Olivier ADLER - 2011 - APM v1.4 adaptation and testing
//
// Compiled with Atmel AVR Studio 4.0 / AVR GCC
// ------------------------------------------------------------------------------------------------------------------------------------------------------------
// Changelog //
//
// Code based on John Arne PPM v1 encoder. Mux / Led / Failsafe control from Olivier ADLER.
// Adaptation to APM v1.4 / ATMEGA 328p by Olivier ADLER, with great code base, help and advices from John Arne.
//
// 0.9.0 -> 0.9.4 : experimental versions. Not publicly available. Jitter problems, good reliability.
//
// New PPM code base V2 from John Arne designed for 32u2 AVRs
//
// 0.9.5 : first reliable and jitter free version based on new John PPM V2 code and Olivier interrupt nesting idea.
// 0.9.6 : enhanced jitter free version with non bloking servo interrupt and ultra fast ppm generator interrupt(John's ideas)
// 0.9.7 : mux (passthrough mode) switchover reliability enhancements and error reporting improvements.
// 0.9.75 : implemented ppm_encoder.h library with support for both atmega328p and atmega32u2 chips
// 0.9.76 : timers 0 and 2 replaced by a delayed loop for simplicity. Timer 0 and 2 are now free for use.
// reworked error detection with settable time window, errors threshold and Led delay
// 0.9.77 : Implemented ppm_encoder.h into latest version.
// 0.9.78 : Implemented optimzed assembly compare interrupt
// 0.9.79 : Removed Non Blocking attribute for servo input interrupt
// 0.9.80 : Removed non blocking for compare interrupt, added optionnal jitter filter and optionnal non blocking attribute for assembly version of compare interrupt
// 0.9.81 : Added PPM PASSTROUGH Mode and LED Codes function to report special modes
// 0.9.82 : LED codes function simplification
// 0.9.83 : Implemented PPM passtrough failsafe
// 0.9.84 : Corrected pin and port names in Encoder-PPM.c according to #define for Mega32U2 compatibility
// 0.9.85 : Added brownout reset detection flag
// ------------------------------------------------------------------------------------------------------------------------------------------------------------
// PREPROCESSOR DIRECTIVES
// ------------------------------------------------------------------------------------------------------------------------------------------------------------
#include "ppm_encoder.h"
#include <util/delay.h>
#define ERROR_THRESHOLD 1 // Number of servo input errors before alerting
#define ERROR_DETECTION_WINDOW 3000 * LOOP_TIMER_10MS // Detection window for error detection (default to 30s)
#define ERROR_CONDITION_DELAY 500 * LOOP_TIMER_10MS // Servo error condition LED delay (LED blinking duration)
#define PASSTHROUGH_CHANNEL 8 * 2 // Channel for passthrough mode selection
#define PASSTHROUGH_CHANNEL_OFF_US ONE_US * 1600 - PPM_PRE_PULSE // Passthrough off threshold
#define PASSTHROUGH_CHANNEL_ON_US ONE_US * 1800 - PPM_PRE_PULSE // Passthrough on threshold
#define THROTTLE_CHANNEL 3 * 2 // Throttle Channel
#define THROTTLE_CHANNEL_LED_TOGGLE_US ONE_US * 1200 - PPM_PRE_PULSE // Throttle Channel Led toggle threshold
#define LED_LOW_BLINKING_RATE 125 * LOOP_TIMER_10MS // Led blink rate for low throttle position (half period)
// Timers
#define TIMER0_10MS 156 // Timer0 ticks for 10 ms duration
#define TIMER1_10MS 20000 // Timer1 ticks for 10 ms duration
#define TIMER2_100MS 1562 // Timer2 ticks for 100 ms duration
#define LOOP_TIMER_10MS 10 // Loop timer ticks for 10 ms duration
// LED Code
#define SPACE_SHORT_DURATION 40 * LOOP_TIMER_10MS // Space after short symbol
#define SPACE_LONG_DURATION 75 * LOOP_TIMER_10MS // Space after long symbol
#define SYMBOL_SHORT_DURATION 20 * LOOP_TIMER_10MS // Short symbol duration
#define SYMBOL_LONG_DURATION 100 * LOOP_TIMER_10MS // Long symbol duration
#define INTER_CODE_DURATION 150 * LOOP_TIMER_10MS // Inter code duration
#define INTER_CODE 0 // Symbols value for coding
#define SHORT_SYMBOL 1
#define LONG_SYMBOL 2
#define SHORT_SPACE 3
#define LONG_SPACE 4
#define LOOP 5
// ------------------------------------------------------------------------------------------------------------------------------------------------------------
// PPM ENCODER INIT AND AUXILIARY TASKS
// ------------------------------------------------------------------------------------------------------------------------------------------------------------
int main(void)
{
// ------------------------------------------------------------------------------------------------------------------------------------------------------------
// LOCAL VARIABLES
// ------------------------------------------------------------------------------------------------------------------------------------------------------------
bool init = true; // We are inside init sequence
int8_t mux_check = 0;
uint16_t mux_ppm = 500;
bool mux_passthrough = false; // Mux passthrough mode status Flag : passthrough is off
uint16_t led_acceleration; // Led acceleration based on throttle stick position
bool servo_error_condition = false; // Servo signal error condition
static uint16_t servo_error_detection_timer=0; // Servo error detection timer
static uint16_t servo_error_condition_timer=0; // Servo error condition timer
static uint16_t blink_led_timer = 0; // Blink led timer
static uint8_t mux_timer = 0; // Mux timer
static uint8_t mux_counter = 0; // Mux counter
static uint16_t led_code_timer = 0; // Blink Code Timer
static uint8_t led_code_symbol = 0; // Blink Code current symbol
// ------------------------------------------------------------------------------------------------------------------------------------------------------------
// LOCAL FUNCTIONS
// ------------------------------------------------------------------------------------------------------------------------------------------------------------
// ------------------------------------------------------------------------------
// Led blinking (non blocking) function
// ------------------------------------------------------------------------------
uint8_t blink_led ( uint16_t half_period ) // ( half_period max = 65 s )
{
blink_led_timer++;
if ( blink_led_timer < half_period ) // If half period has not been reached
{
return 0; // Exit timer function and return 0
}
else // half period reached - LED Toggle
{
PPM_PORT ^= ( 1 << PB0 ); // Toggle status LED
blink_led_timer = 0; // Blink led timer reset
return 1; // half period reached - Exit timer function and return 1
}
}
// ------------------------------------------------------------------------------
// Led code (non blocking) function
// ------------------------------------------------------------------------------
void blink_code_led ( uint8_t code )
{
const uint8_t coding[2][14] = {
// PPM_PASSTROUGH_MODE
{ INTER_CODE, LONG_SYMBOL, LONG_SPACE, SHORT_SYMBOL, SHORT_SPACE, SHORT_SYMBOL, LOOP },
// JETI_MODE
{ INTER_CODE, LONG_SYMBOL, LONG_SPACE, SHORT_SYMBOL, SHORT_SPACE, SHORT_SYMBOL, SHORT_SPACE, SHORT_SYMBOL,LOOP }
};
led_code_timer++;
switch ( coding [ code - 2 ] [ led_code_symbol ] )
{
case INTER_CODE:
if ( led_code_timer < ( INTER_CODE_DURATION ) ) return;
else PPM_PORT |= ( 1 << PB0 ); // Enable status LED
break;
case LONG_SYMBOL: // Long symbol
if ( led_code_timer < ( SYMBOL_LONG_DURATION ) ) return;
else PPM_PORT &= ~( 1 << PB0 ); // Disable status LED
break;
case SHORT_SYMBOL: // Short symbol
if ( led_code_timer < ( SYMBOL_SHORT_DURATION ) ) return;
else PPM_PORT &= ~( 1 << PB0 ); // Disable status LED
break;
case SHORT_SPACE: // Short space
if ( led_code_timer < ( SPACE_SHORT_DURATION ) ) return;
else PPM_PORT |= ( 1 << PB0 ); // Enable status LED
break;
case LONG_SPACE: // Long space
if ( led_code_timer < ( SPACE_LONG_DURATION ) ) return;
else PPM_PORT |= ( 1 << PB0 ); // Enable status LED
break;
case LOOP: // Loop to code start
led_code_symbol = 0;
return;
break;
}
led_code_timer = 0; // Code led timer reset
led_code_symbol++; // Next symbol
return; // LED code function return
}
// ------------------------------------------------------------------------------
// ppm reading helper - interrupt safe and non blocking function
// ------------------------------------------------------------------------------
uint16_t ppm_read( uint8_t channel )
{
uint16_t ppm_tmp = ppm[ channel ];
while( ppm_tmp != ppm[ channel ] ) ppm_tmp = ppm[ channel ];
return ppm_tmp;
}
// ------------------------------------------------------------------------------------------------------------------------------------------------------------
// INITIALISATION CODE
// ------------------------------------------------------------------------------------------------------------------------------------------------------------
// ------------------------------------------------------------------------------
// Reset Source checkings
// ------------------------------------------------------------------------------
if (MCUSR & 1) // Power-on Reset
{
MCUSR=0; // Clear MCU Status register
// custom code here
}
else if (MCUSR & 2) // External Reset
{
MCUSR=0; // Clear MCU Status register
// custom code here
}
else if (MCUSR & 4) // Brown-Out Reset
{
MCUSR=0; // Clear MCU Status register
brownout_reset=true;
}
else // Watchdog Reset
{
MCUSR=0; // Clear MCU Status register
// custom code here
}
// ------------------------------------------------------------------------------
// Servo input and PPM generator init
// ------------------------------------------------------------------------------
ppm_encoder_init();
// ------------------------------------------------------------------------------
// Outputs init
// ------------------------------------------------------------------------------
PPM_DDR |= ( 1 << PB0 ); // Set LED pin (PB0) to output
PPM_DDR |= ( 1 << PB1 ); // Set MUX pin (PB1) to output
PPM_DDR |= ( 1 << PPM_OUTPUT_PIN ); // Set PPM pin (PPM_OUTPUT_PIN, OC1B) to output
// ------------------------------------------------------------------------------
// Timer0 init (normal mode) used for LED control and custom code
// ------------------------------------------------------------------------------
TCCR0A = 0x00; // Clock source: System Clock
TCCR0B = 0x05; // Set 1024x prescaler - Clock value: 15.625 kHz - 16 ms max time
TCNT0 = 0x00;
OCR0A = 0x00; // OC0x outputs: Disconnected
OCR0B = 0x00;
TIMSK0 = 0x00; // Timer 1 interrupt disable
// ------------------------------------------------------------------------------
// Enable global interrupt
// ------------------------------------------------------------------------------
sei(); // Enable Global interrupt flag
// ------------------------------------------------------------------------------
// Disable radio passthrough (mux chip A/B control)
// ------------------------------------------------------------------------------
PPM_PORT |= ( 1 << PB1 ); // Set PIN B1 to disable Radio passthrough (mux)
// ------------------------------------------------------------------------------
// Check for first valid servo signal
// ------------------------------------------------------------------------------
while( 1 )
{
if ( servo_error_condition || servo_input_missing ) // We have an error
{
blink_led ( 6 * LOOP_TIMER_10MS ); // Status LED very fast blink if invalid servo input or missing signal
}
else // We are running normally
{
init = false; // initialisation is done,
switch ( servo_input_mode )
{
case SERVO_PWM_MODE: // Normal PWM mode
goto PWM_LOOP;
break;
case PPM_PASSTROUGH_MODE: // PPM_PASSTROUGH_MODE
goto PPM_PASSTHROUGH_LOOP;
break;
default: // Normal PWM mode
goto PWM_LOOP;
break;
}
}
_delay_us (970); // Slow down while loop
}
// ------------------------------------------------------------------------------------------------------------------------------------------------------------
// AUXILIARY TASKS
// ------------------------------------------------------------------------------------------------------------------------------------------------------------
PWM_LOOP: // SERVO_PWM_MODE
while( 1 )
{
// ------------------------------------------------------------------------------
// Radio passthrough control (mux chip A/B control)
// ------------------------------------------------------------------------------
mux_timer++; // Increment mux timer
if ( mux_timer > ( 3 * LOOP_TIMER_10MS ) ) // Check Passthrough Channel every 30ms
{
mux_timer = 0; // Reset mux timer
if ( mux_counter++ < 5) // Check passthrough channel position 5 times
{
mux_ppm = ppm_read( PASSTHROUGH_CHANNEL - 1 ); // Safely read passthrough channel ppm position
if ( mux_ppm < ( PASSTHROUGH_CHANNEL_OFF_US ) ) // Check ppm value and update validation counter
{
mux_check -= 1;
}
else if ( mux_ppm > ( PASSTHROUGH_CHANNEL_ON_US ) )
{
mux_check += 1;
}
}
else // Check
{
switch ( mux_check ) // If all 5 checks are the same, update mux status flag
{
case -5:
mux_passthrough = false;
PPM_PORT |= ( 1 << PB1 ); // Set PIN B1 (Mux) to disable Radio passthrough
break;
case 5:
mux_passthrough = true;
PPM_PORT &= ~( 1 << PB1 ); // Reset PIN B1 (Mux) to enable Radio passthrough
break;
}
mux_check = 0; // Reset mux validation counter
mux_counter = 0; // Reset mux counter
}
}
// ------------------------------------------------------------------------------
// Status LED control
// ------------------------------------------------------------------------------
if ( servo_error_condition || servo_input_missing ) // We have an error
{
blink_led ( 6 * LOOP_TIMER_10MS ); // Status LED very fast blink if invalid servo input or missing signal
}
else // We are running normally
{
if ( mux_passthrough == false ) // Normal mode : status LED toggle speed from throttle position
{
led_acceleration = ( ppm[THROTTLE_CHANNEL - 1] - ( PPM_SERVO_MIN ) ) / 2;
blink_led ( LED_LOW_BLINKING_RATE - led_acceleration );
}
else // Passthrough mode : status LED never flashing
{
// Enable status LED if throttle > THROTTLE_CHANNEL_LED_TOGGLE_US
if ( ppm[THROTTLE_CHANNEL - 1] > ( THROTTLE_CHANNEL_LED_TOGGLE_US ) )
{
PPM_PORT |= ( 1 << PB0 );
}
// Disable status LED if throttle <= THROTTLE_CHANNEL_LED_TOGGLE_US
else if ( ppm[THROTTLE_CHANNEL - 1] <= ( THROTTLE_CHANNEL_LED_TOGGLE_US ) )
{
PPM_PORT &= ~( 1 << PB0 );
}
}
}
// ------------------------------------------------------------------------------
// Servo input error detection
// ------------------------------------------------------------------------------
// If there are too many errors during the detection time window, then trig servo error condition
if ( servo_input_errors > 0 ) // Start error rate checking if an error did occur
{
if ( servo_error_detection_timer > ( ERROR_DETECTION_WINDOW ) ) // If 10s delay reached
{
servo_error_detection_timer = 0; // Reset error detection timer
servo_input_errors = 0; // Reset servo input error counter
}
else // If 10s delay is not reached
{
servo_error_detection_timer++; // Increment servo error timer value
if ( servo_input_errors >= ( ERROR_THRESHOLD ) ) // If there are too many errors
{
servo_error_condition = true; // Enable error condition flag
servo_input_errors = 0; // Reset servo input error counter
servo_error_detection_timer = 0; // Reset servo error detection timer
servo_error_condition_timer = 0; // Reset servo error condition timer
}
}
}
// Servo error condition flag (will control blinking LED)
if ( servo_error_condition == true ) // We are in error condition
{
if ( servo_error_condition_timer > ( ERROR_CONDITION_DELAY ) ) // If 3s delay reached
{
servo_error_condition_timer = 0; // Reset servo error condition timer
servo_error_condition = false; // Reset servo error condition flag (Led will stop very fast blink)
}
else servo_error_condition_timer++; // If 3s delay is not reached update servo error condition timer value
}
_delay_us (950); // Slow down while loop
} // PWM Loop end
PPM_PASSTHROUGH_LOOP: // PPM_PASSTROUGH_MODE
while (1)
{
// ------------------------------------------------------------------------------
// Status LED control
// ------------------------------------------------------------------------------
if ( servo_input_missing ) // We have an error
{
blink_led ( 6 * LOOP_TIMER_10MS ); // Status LED very fast blink if invalid servo input or missing signal
}
else // We are running normally
{
blink_code_led ( PPM_PASSTROUGH_MODE ); // Blink LED according to mode 2 code (one long, two shorts).
}
_delay_us (970); // Slow down this loop
} // PPM_PASSTHROUGH Loop end
} // main function end

View File

@ -0,0 +1,77 @@
###############################################################################
# Makefile for the project Encoder-PPM
###############################################################################
## General Flags
PROJECT = Encoder-PPM
MCU = atmega328p
TARGET = Encoder-PPM.elf
CC = avr-gcc
CPP = avr-g++
## Options common to compile, link and assembly rules
COMMON = -mmcu=$(MCU)
## Compile options common for all C compilation units.
CFLAGS = $(COMMON)
CFLAGS += -Wall -gdwarf-2 -std=gnu99 -DF_CPU=16000000UL -Os -funsigned-char -funsigned-bitfields -fpack-struct -fshort-enums
CFLAGS += -MD -MP -MT $(*F).o -MF dep/$(@F).d
## Assembly specific flags
ASMFLAGS = $(COMMON)
ASMFLAGS += $(CFLAGS)
ASMFLAGS += -x assembler-with-cpp -Wa,-gdwarf2
## Linker flags
LDFLAGS = $(COMMON)
LDFLAGS += -Wl,-Map=Encoder-PPM.map
## Intel Hex file production flags
HEX_FLASH_FLAGS = -R .eeprom -R .fuse -R .lock -R .signature
HEX_EEPROM_FLAGS = -j .eeprom
HEX_EEPROM_FLAGS += --set-section-flags=.eeprom="alloc,load"
HEX_EEPROM_FLAGS += --change-section-lma .eeprom=0 --no-change-warnings
## Objects that must be built in order to link
OBJECTS = Encoder-PPM.o
## Objects explicitly added by the user
LINKONLYOBJECTS =
## Build
all: $(TARGET) Encoder-PPM.hex Encoder-PPM.eep Encoder-PPM.lss size
## Compile
Encoder-PPM.o: ./Encoder-PPM.c
$(CC) $(INCLUDES) $(CFLAGS) -c $<
##Link
$(TARGET): $(OBJECTS)
$(CC) $(LDFLAGS) $(OBJECTS) $(LINKONLYOBJECTS) $(LIBDIRS) $(LIBS) -o $(TARGET)
%.hex: $(TARGET)
avr-objcopy -O ihex $(HEX_FLASH_FLAGS) $< $@
%.eep: $(TARGET)
-avr-objcopy $(HEX_EEPROM_FLAGS) -O ihex $< $@ || exit 0
%.lss: $(TARGET)
avr-objdump -h -S $< > $@
size: ${TARGET}
@echo
@avr-size -C --mcu=${MCU} ${TARGET}
## Clean target
.PHONY: clean
clean:
-rm -rf $(OBJECTS) Encoder-PPM.elf dep/* Encoder-PPM.hex Encoder-PPM.eep Encoder-PPM.lss Encoder-PPM.map
## Other dependencies
-include $(shell mkdir dep 2>NUL) $(wildcard dep/*)

View File

@ -0,0 +1,81 @@
Arducoder is the new 8 channels ppm encoder code for ArduPilot Mega / Arducopter boards.
It is compatible with APM v1.x board (ATMEGA 328p), Phonedrone and futur boards using ATmega32u2
Emphasis has been put on code simplicity and reliability.
--------------------------------------------------------------------------------------------------
Manual
--------------------------------------------------------------------------------------------------
--------------------------------------------------
Warning - Warning - Warning - Warning
--------------------------------------------------
Code has not yet been extensively tested in the field.
Nevertheless extensive tests have been done in the lab with a limited set of different receivers.
Carefully check that your radio is working perfectly before you fly.
If you see the blue status LED blinking blinking very fast, this is an indication that something is wrong in the decoding.
If you have problems, please report the problem and what brand/modell receiver you are using.
------------------------------------------
Normal mode
------------------------------------------
Normal mode :
Blue status LED is used for status reports :
- slow to fast blinking according to throttle channel position
- very fast blinking if missing receiver servo signals, or if the servo signals are wrong (invalid pulse widths)
------------------------------------------
Passthrough mode (mux)
------------------------------------------
Passthrough mode is trigged by channel 8 > 1800 us.
Blue status LED has different behavior in passthrough mode :
- If throttle position < 1200 us, status LED is off
- If throttle position > 1200 us, status LED is on
------------------------------------------
Failsafe mode
------------------------------------------
If a receiver servo channel is lost, the last know channel position is used.
If all contact with the receiver is lost, an internal failsafe is trigged after 250ms.
Default failsafe values are :
Throttle channel low (channel 3 = 1000 us)
All other channels set to midstick (1500 us)
------------------------------------------
PPM passtrough mode
------------------------------------------
If your receiver has a PPM sum signal output, it is now possible to pass on the PPM signal from servo channel 1 to the PPM pin (APM atmega1280/2560 PPM decoder).
To enable PPM passtrough, short the servo input channel 2 & 3 signal pins together using a jumper strap and use the channel 1 signal pin as PPM input.
Please note that the PPM sum signal must be standard 8 channel PPM to work with the APM PPM decoder.
In this mode, the blue LED will blink like this : Long - Short - short
--------------------------------------------------------------------------------------------------

View File

@ -0,0 +1,3 @@
This is the second generation ppm encoder code designed for APM v1.x boards using ATMega328P.

View File

@ -0,0 +1,728 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
*
* Main source file for the DFU class bootloader. This file contains the complete bootloader logic.
*/
#define INCLUDE_FROM_BOOTLOADER_C
#include "Arduino-usbdfu.h"
/** Flag to indicate if the bootloader should be running, or should exit and allow the application code to run
* via a soft reset. When cleared, the bootloader will abort, the USB interface will shut down and the application
* jumped to via an indirect jump to location 0x0000 (or other location specified by the host).
*/
bool RunBootloader = true;
/** Flag to indicate if the bootloader is waiting to exit. When the host requests the bootloader to exit and
* jump to the application address it specifies, it sends two sequential commands which must be properly
* acknowledged. Upon reception of the first the RunBootloader flag is cleared and the WaitForExit flag is set,
* causing the bootloader to wait for the final exit command before shutting down.
*/
bool WaitForExit = false;
/** Current DFU state machine state, one of the values in the DFU_State_t enum. */
uint8_t DFU_State = dfuIDLE;
/** Status code of the last executed DFU command. This is set to one of the values in the DFU_Status_t enum after
* each operation, and returned to the host when a Get Status DFU request is issued.
*/
uint8_t DFU_Status = OK;
/** Data containing the DFU command sent from the host. */
DFU_Command_t SentCommand;
/** Response to the last issued Read Data DFU command. Unlike other DFU commands, the read command
* requires a single byte response from the bootloader containing the read data when the next DFU_UPLOAD command
* is issued by the host.
*/
uint8_t ResponseByte;
/** Pointer to the start of the user application. By default this is 0x0000 (the reset vector), however the host
* may specify an alternate address when issuing the application soft-start command.
*/
AppPtr_t AppStartPtr = (AppPtr_t)0x0000;
/** 64-bit flash page number. This is concatenated with the current 16-bit address on USB AVRs containing more than
* 64KB of flash memory.
*/
uint8_t Flash64KBPage = 0;
/** Memory start address, indicating the current address in the memory being addressed (either FLASH or EEPROM
* depending on the issued command from the host).
*/
uint16_t StartAddr = 0x0000;
/** Memory end address, indicating the end address to read to/write from in the memory being addressed (either FLASH
* of EEPROM depending on the issued command from the host).
*/
uint16_t EndAddr = 0x0000;
/** Pulse generation counters to keep track of the number of milliseconds remaining for each pulse type */
volatile struct
{
uint8_t TxLEDPulse; /**< Milliseconds remaining for data Tx LED pulse */
uint8_t RxLEDPulse; /**< Milliseconds remaining for data Rx LED pulse */
uint8_t PingPongLEDPulse; /**< Milliseconds remaining for enumeration Tx/Rx ping-pong LED pulse */
} PulseMSRemaining;
/** Main program entry point. This routine configures the hardware required by the bootloader, then continuously
* runs the bootloader processing routine until instructed to soft-exit, or hard-reset via the watchdog to start
* the loaded application code.
*/
int main(void)
{
/* Configure hardware required by the bootloader */
SetupHardware();
/* Enable global interrupts so that the USB stack can function */
sei();
/* Run the USB management task while the bootloader is supposed to be running */
while (RunBootloader || WaitForExit)
USB_USBTask();
/* Reset configured hardware back to their original states for the user application */
ResetHardware();
/* Start the user application */
AppStartPtr();
}
/** Configures all hardware required for the bootloader. */
void SetupHardware(void)
{
/* Disable watchdog if enabled by bootloader/fuses */
MCUSR &= ~(1 << WDRF);
wdt_disable();
/* Disable clock division */
// clock_prescale_set(clock_div_1);
/* Relocate the interrupt vector table to the bootloader section */
MCUCR = (1 << IVCE);
MCUCR = (1 << IVSEL);
LEDs_Init();
/* Initialize the USB subsystem */
USB_Init();
}
/** Resets all configured hardware required for the bootloader back to their original states. */
void ResetHardware(void)
{
/* Shut down the USB subsystem */
USB_ShutDown();
/* Relocate the interrupt vector table back to the application section */
MCUCR = (1 << IVCE);
MCUCR = 0;
}
/** Event handler for the USB_UnhandledControlRequest event. This is used to catch standard and class specific
* control requests that are not handled internally by the USB library (including the DFU commands, which are
* all issued via the control endpoint), so that they can be handled appropriately for the application.
*/
void EVENT_USB_Device_UnhandledControlRequest(void)
{
/* Get the size of the command and data from the wLength value */
SentCommand.DataSize = USB_ControlRequest.wLength;
/* Turn off TX LED(s) once the TX pulse period has elapsed */
if (PulseMSRemaining.TxLEDPulse && !(--PulseMSRemaining.TxLEDPulse))
LEDs_TurnOffLEDs(LEDMASK_TX);
/* Turn off RX LED(s) once the RX pulse period has elapsed */
if (PulseMSRemaining.RxLEDPulse && !(--PulseMSRemaining.RxLEDPulse))
LEDs_TurnOffLEDs(LEDMASK_RX);
switch (USB_ControlRequest.bRequest)
{
case DFU_DNLOAD:
LEDs_TurnOnLEDs(LEDMASK_RX);
PulseMSRemaining.RxLEDPulse = TX_RX_LED_PULSE_MS;
Endpoint_ClearSETUP();
/* Check if bootloader is waiting to terminate */
if (WaitForExit)
{
/* Bootloader is terminating - process last received command */
ProcessBootloaderCommand();
/* Turn off TX/RX status LEDs so that they're not left on when application starts */
LEDs_TurnOffLEDs(LEDMASK_TX);
LEDs_TurnOffLEDs(LEDMASK_RX);
/* Indicate that the last command has now been processed - free to exit bootloader */
WaitForExit = false;
}
/* If the request has a data stage, load it into the command struct */
if (SentCommand.DataSize)
{
while (!(Endpoint_IsOUTReceived()))
{
if (USB_DeviceState == DEVICE_STATE_Unattached)
return;
}
/* First byte of the data stage is the DNLOAD request's command */
SentCommand.Command = Endpoint_Read_Byte();
/* One byte of the data stage is the command, so subtract it from the total data bytes */
SentCommand.DataSize--;
/* Load in the rest of the data stage as command parameters */
for (uint8_t DataByte = 0; (DataByte < sizeof(SentCommand.Data)) &&
Endpoint_BytesInEndpoint(); DataByte++)
{
SentCommand.Data[DataByte] = Endpoint_Read_Byte();
SentCommand.DataSize--;
}
/* Process the command */
ProcessBootloaderCommand();
}
/* Check if currently downloading firmware */
if (DFU_State == dfuDNLOAD_IDLE)
{
if (!(SentCommand.DataSize))
{
DFU_State = dfuIDLE;
}
else
{
/* Throw away the filler bytes before the start of the firmware */
DiscardFillerBytes(DFU_FILLER_BYTES_SIZE);
/* Throw away the packet alignment filler bytes before the start of the firmware */
DiscardFillerBytes(StartAddr % FIXED_CONTROL_ENDPOINT_SIZE);
/* Calculate the number of bytes remaining to be written */
uint16_t BytesRemaining = ((EndAddr - StartAddr) + 1);
if (IS_ONEBYTE_COMMAND(SentCommand.Data, 0x00)) // Write flash
{
/* Calculate the number of words to be written from the number of bytes to be written */
uint16_t WordsRemaining = (BytesRemaining >> 1);
union
{
uint16_t Words[2];
uint32_t Long;
} CurrFlashAddress = {.Words = {StartAddr, Flash64KBPage}};
uint32_t CurrFlashPageStartAddress = CurrFlashAddress.Long;
uint8_t WordsInFlashPage = 0;
while (WordsRemaining--)
{
/* Check if endpoint is empty - if so clear it and wait until ready for next packet */
if (!(Endpoint_BytesInEndpoint()))
{
Endpoint_ClearOUT();
while (!(Endpoint_IsOUTReceived()))
{
if (USB_DeviceState == DEVICE_STATE_Unattached)
return;
}
}
/* Write the next word into the current flash page */
boot_page_fill(CurrFlashAddress.Long, Endpoint_Read_Word_LE());
/* Adjust counters */
WordsInFlashPage += 1;
CurrFlashAddress.Long += 2;
/* See if an entire page has been written to the flash page buffer */
if ((WordsInFlashPage == (SPM_PAGESIZE >> 1)) || !(WordsRemaining))
{
/* Commit the flash page to memory */
boot_page_write(CurrFlashPageStartAddress);
boot_spm_busy_wait();
/* Check if programming incomplete */
if (WordsRemaining)
{
CurrFlashPageStartAddress = CurrFlashAddress.Long;
WordsInFlashPage = 0;
/* Erase next page's temp buffer */
boot_page_erase(CurrFlashAddress.Long);
boot_spm_busy_wait();
}
}
}
/* Once programming complete, start address equals the end address */
StartAddr = EndAddr;
/* Re-enable the RWW section of flash */
boot_rww_enable();
}
else // Write EEPROM
{
while (BytesRemaining--)
{
/* Check if endpoint is empty - if so clear it and wait until ready for next packet */
if (!(Endpoint_BytesInEndpoint()))
{
Endpoint_ClearOUT();
while (!(Endpoint_IsOUTReceived()))
{
if (USB_DeviceState == DEVICE_STATE_Unattached)
return;
}
}
/* Read the byte from the USB interface and write to to the EEPROM */
eeprom_write_byte((uint8_t*)StartAddr, Endpoint_Read_Byte());
/* Adjust counters */
StartAddr++;
}
}
/* Throw away the currently unused DFU file suffix */
DiscardFillerBytes(DFU_FILE_SUFFIX_SIZE);
}
}
Endpoint_ClearOUT();
Endpoint_ClearStatusStage();
break;
case DFU_UPLOAD:
Endpoint_ClearSETUP();
LEDs_TurnOnLEDs(LEDMASK_TX);
PulseMSRemaining.TxLEDPulse = TX_RX_LED_PULSE_MS;
while (!(Endpoint_IsINReady()))
{
if (USB_DeviceState == DEVICE_STATE_Unattached)
return;
}
if (DFU_State != dfuUPLOAD_IDLE)
{
if ((DFU_State == dfuERROR) && IS_ONEBYTE_COMMAND(SentCommand.Data, 0x01)) // Blank Check
{
/* Blank checking is performed in the DFU_DNLOAD request - if we get here we've told the host
that the memory isn't blank, and the host is requesting the first non-blank address */
Endpoint_Write_Word_LE(StartAddr);
}
else
{
/* Idle state upload - send response to last issued command */
Endpoint_Write_Byte(ResponseByte);
}
}
else
{
/* Determine the number of bytes remaining in the current block */
uint16_t BytesRemaining = ((EndAddr - StartAddr) + 1);
if (IS_ONEBYTE_COMMAND(SentCommand.Data, 0x00)) // Read FLASH
{
/* Calculate the number of words to be written from the number of bytes to be written */
uint16_t WordsRemaining = (BytesRemaining >> 1);
union
{
uint16_t Words[2];
uint32_t Long;
} CurrFlashAddress = {.Words = {StartAddr, Flash64KBPage}};
while (WordsRemaining--)
{
/* Check if endpoint is full - if so clear it and wait until ready for next packet */
if (Endpoint_BytesInEndpoint() == FIXED_CONTROL_ENDPOINT_SIZE)
{
Endpoint_ClearIN();
while (!(Endpoint_IsINReady()))
{
if (USB_DeviceState == DEVICE_STATE_Unattached)
return;
}
}
/* Read the flash word and send it via USB to the host */
#if (FLASHEND > 0xFFFF)
Endpoint_Write_Word_LE(pgm_read_word_far(CurrFlashAddress.Long));
#else
Endpoint_Write_Word_LE(pgm_read_word(CurrFlashAddress.Long));
#endif
/* Adjust counters */
CurrFlashAddress.Long += 2;
}
/* Once reading is complete, start address equals the end address */
StartAddr = EndAddr;
}
else if (IS_ONEBYTE_COMMAND(SentCommand.Data, 0x02)) // Read EEPROM
{
while (BytesRemaining--)
{
/* Check if endpoint is full - if so clear it and wait until ready for next packet */
if (Endpoint_BytesInEndpoint() == FIXED_CONTROL_ENDPOINT_SIZE)
{
Endpoint_ClearIN();
while (!(Endpoint_IsINReady()))
{
if (USB_DeviceState == DEVICE_STATE_Unattached)
return;
}
}
/* Read the EEPROM byte and send it via USB to the host */
Endpoint_Write_Byte(eeprom_read_byte((uint8_t*)StartAddr));
/* Adjust counters */
StartAddr++;
}
}
/* Return to idle state */
DFU_State = dfuIDLE;
}
Endpoint_ClearIN();
Endpoint_ClearStatusStage();
break;
case DFU_GETSTATUS:
Endpoint_ClearSETUP();
/* Write 8-bit status value */
Endpoint_Write_Byte(DFU_Status);
/* Write 24-bit poll timeout value */
Endpoint_Write_Byte(0);
Endpoint_Write_Word_LE(0);
/* Write 8-bit state value */
Endpoint_Write_Byte(DFU_State);
/* Write 8-bit state string ID number */
Endpoint_Write_Byte(0);
Endpoint_ClearIN();
Endpoint_ClearStatusStage();
break;
case DFU_CLRSTATUS:
Endpoint_ClearSETUP();
/* Reset the status value variable to the default OK status */
DFU_Status = OK;
Endpoint_ClearStatusStage();
break;
case DFU_GETSTATE:
Endpoint_ClearSETUP();
/* Write the current device state to the endpoint */
Endpoint_Write_Byte(DFU_State);
Endpoint_ClearIN();
Endpoint_ClearStatusStage();
break;
case DFU_ABORT:
Endpoint_ClearSETUP();
/* Turn off TX/RX status LEDs so that they're not left on when application starts */
LEDs_TurnOffLEDs(LEDMASK_TX);
LEDs_TurnOffLEDs(LEDMASK_RX);
/* Reset the current state variable to the default idle state */
DFU_State = dfuIDLE;
Endpoint_ClearStatusStage();
break;
}
}
/** Routine to discard the specified number of bytes from the control endpoint stream. This is used to
* discard unused bytes in the stream from the host, including the memory program block suffix.
*
* \param[in] NumberOfBytes Number of bytes to discard from the host from the control endpoint
*/
static void DiscardFillerBytes(uint8_t NumberOfBytes)
{
while (NumberOfBytes--)
{
if (!(Endpoint_BytesInEndpoint()))
{
Endpoint_ClearOUT();
/* Wait until next data packet received */
while (!(Endpoint_IsOUTReceived()))
{
if (USB_DeviceState == DEVICE_STATE_Unattached)
return;
}
}
else
{
Endpoint_Discard_Byte();
}
}
}
/** Routine to process an issued command from the host, via a DFU_DNLOAD request wrapper. This routine ensures
* that the command is allowed based on the current secure mode flag value, and passes the command off to the
* appropriate handler function.
*/
static void ProcessBootloaderCommand(void)
{
/* Check if device is in secure mode */
// if (IsSecure)
// {
// /* Don't process command unless it is a READ or chip erase command */
// if (!(((SentCommand.Command == COMMAND_WRITE) &&
// IS_TWOBYTE_COMMAND(SentCommand.Data, 0x00, 0xFF)) ||
// (SentCommand.Command == COMMAND_READ)))
// {
// /* Set the state and status variables to indicate the error */
// DFU_State = dfuERROR;
// DFU_Status = errWRITE;
//
// /* Stall command */
// Endpoint_StallTransaction();
//
// /* Don't process the command */
// return;
// }
// }
/* Dispatch the required command processing routine based on the command type */
switch (SentCommand.Command)
{
case COMMAND_PROG_START:
ProcessMemProgCommand();
break;
case COMMAND_DISP_DATA:
ProcessMemReadCommand();
break;
case COMMAND_WRITE:
ProcessWriteCommand();
break;
case COMMAND_READ:
ProcessReadCommand();
break;
case COMMAND_CHANGE_BASE_ADDR:
if (IS_TWOBYTE_COMMAND(SentCommand.Data, 0x03, 0x00)) // Set 64KB flash page command
Flash64KBPage = SentCommand.Data[2];
break;
}
}
/** Routine to concatenate the given pair of 16-bit memory start and end addresses from the host, and store them
* in the StartAddr and EndAddr global variables.
*/
static void LoadStartEndAddresses(void)
{
union
{
uint8_t Bytes[2];
uint16_t Word;
} Address[2] = {{.Bytes = {SentCommand.Data[2], SentCommand.Data[1]}},
{.Bytes = {SentCommand.Data[4], SentCommand.Data[3]}}};
/* Load in the start and ending read addresses from the sent data packet */
StartAddr = Address[0].Word;
EndAddr = Address[1].Word;
}
/** Handler for a Memory Program command issued by the host. This routine handles the preparations needed
* to write subsequent data from the host into the specified memory.
*/
static void ProcessMemProgCommand(void)
{
if (IS_ONEBYTE_COMMAND(SentCommand.Data, 0x00) || // Write FLASH command
IS_ONEBYTE_COMMAND(SentCommand.Data, 0x01)) // Write EEPROM command
{
/* Load in the start and ending read addresses */
LoadStartEndAddresses();
/* If FLASH is being written to, we need to pre-erase the first page to write to */
if (IS_ONEBYTE_COMMAND(SentCommand.Data, 0x00))
{
union
{
uint16_t Words[2];
uint32_t Long;
} CurrFlashAddress = {.Words = {StartAddr, Flash64KBPage}};
/* Erase the current page's temp buffer */
boot_page_erase(CurrFlashAddress.Long);
boot_spm_busy_wait();
}
/* Set the state so that the next DNLOAD requests reads in the firmware */
DFU_State = dfuDNLOAD_IDLE;
}
}
/** Handler for a Memory Read command issued by the host. This routine handles the preparations needed
* to read subsequent data from the specified memory out to the host, as well as implementing the memory
* blank check command.
*/
static void ProcessMemReadCommand(void)
{
if (IS_ONEBYTE_COMMAND(SentCommand.Data, 0x00) || // Read FLASH command
IS_ONEBYTE_COMMAND(SentCommand.Data, 0x02)) // Read EEPROM command
{
/* Load in the start and ending read addresses */
LoadStartEndAddresses();
/* Set the state so that the next UPLOAD requests read out the firmware */
DFU_State = dfuUPLOAD_IDLE;
}
else if (IS_ONEBYTE_COMMAND(SentCommand.Data, 0x01)) // Blank check FLASH command
{
uint32_t CurrFlashAddress = 0;
while (CurrFlashAddress < BOOT_START_ADDR)
{
/* Check if the current byte is not blank */
#if (FLASHEND > 0xFFFF)
if (pgm_read_byte_far(CurrFlashAddress) != 0xFF)
#else
if (pgm_read_byte(CurrFlashAddress) != 0xFF)
#endif
{
/* Save the location of the first non-blank byte for response back to the host */
Flash64KBPage = (CurrFlashAddress >> 16);
StartAddr = CurrFlashAddress;
/* Set state and status variables to the appropriate error values */
DFU_State = dfuERROR;
DFU_Status = errCHECK_ERASED;
break;
}
CurrFlashAddress++;
}
}
}
/** Handler for a Data Write command issued by the host. This routine handles non-programming commands such as
* bootloader exit (both via software jumps and hardware watchdog resets) and flash memory erasure.
*/
static void ProcessWriteCommand(void)
{
if (IS_ONEBYTE_COMMAND(SentCommand.Data, 0x03)) // Start application
{
/* Indicate that the bootloader is terminating */
WaitForExit = true;
/* Check if data supplied for the Start Program command - no data executes the program */
if (SentCommand.DataSize)
{
if (SentCommand.Data[1] == 0x01) // Start via jump
{
union
{
uint8_t Bytes[2];
AppPtr_t FuncPtr;
} Address = {.Bytes = {SentCommand.Data[4], SentCommand.Data[3]}};
/* Load in the jump address into the application start address pointer */
AppStartPtr = Address.FuncPtr;
}
}
else
{
if (SentCommand.Data[1] == 0x00) // Start via watchdog
{
/* Start the watchdog to reset the AVR once the communications are finalized */
wdt_enable(WDTO_250MS);
}
else // Start via jump
{
/* Set the flag to terminate the bootloader at next opportunity */
RunBootloader = false;
}
}
}
else if (IS_TWOBYTE_COMMAND(SentCommand.Data, 0x00, 0xFF)) // Erase flash
{
uint32_t CurrFlashAddress = 0;
/* Clear the application section of flash */
while (CurrFlashAddress < BOOT_START_ADDR)
{
boot_page_erase(CurrFlashAddress);
boot_spm_busy_wait();
boot_page_write(CurrFlashAddress);
boot_spm_busy_wait();
CurrFlashAddress += SPM_PAGESIZE;
}
/* Re-enable the RWW section of flash as writing to the flash locks it out */
boot_rww_enable();
/* Memory has been erased, reset the security bit so that programming/reading is allowed */
// IsSecure = false;
}
}
/** Handler for a Data Read command issued by the host. This routine handles bootloader information retrieval
* commands such as device signature and bootloader version retrieval.
*/
static void ProcessReadCommand(void)
{
const uint8_t BootloaderInfo[3] = {BOOTLOADER_VERSION, BOOTLOADER_ID_BYTE1, BOOTLOADER_ID_BYTE2};
const uint8_t SignatureInfo[3] = {AVR_SIGNATURE_1, AVR_SIGNATURE_2, AVR_SIGNATURE_3};
uint8_t DataIndexToRead = SentCommand.Data[1];
if (IS_ONEBYTE_COMMAND(SentCommand.Data, 0x00)) // Read bootloader info
ResponseByte = BootloaderInfo[DataIndexToRead];
else if (IS_ONEBYTE_COMMAND(SentCommand.Data, 0x01)) // Read signature byte
ResponseByte = SignatureInfo[DataIndexToRead - 0x30];
}

View File

@ -0,0 +1,220 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
*
* Header file for Arduino-usbdfu.c.
*/
#ifndef _ARDUINO_USB_DFU_BOOTLOADER_H_
#define _ARDUINO_USB_DFU_BOOTLOADER_H_
/* Includes: */
#include <avr/io.h>
#include <avr/wdt.h>
#include <avr/boot.h>
#include <avr/pgmspace.h>
#include <avr/eeprom.h>
#include <avr/power.h>
#include <avr/interrupt.h>
#include <stdbool.h>
#include "Descriptors.h"
#include <LUFA/Drivers/Board/LEDs.h>
#include <LUFA/Drivers/USB/USB.h>
/* Macros: */
/** LED mask for the library LED driver, to indicate TX activity. */
#define LEDMASK_TX LEDS_LED1
/** LED mask for the library LED driver, to indicate RX activity. */
#define LEDMASK_RX LEDS_LED2
/** LED mask for the library LED driver, to indicate that an error has occurred in the USB interface. */
#define LEDMASK_ERROR (LEDS_LED1 | LEDS_LED2)
/** LED mask for the library LED driver, to indicate that the USB interface is busy. */
#define LEDMASK_BUSY (LEDS_LED1 | LEDS_LED2)
/** Configuration define. Define this token to true to case the bootloader to reject all memory commands
* until a memory erase has been performed. When used in conjunction with the lockbits of the AVR, this
* can protect the AVR's firmware from being dumped from a secured AVR. When false, memory operations are
* allowed at any time.
*/
// #define SECURE_MODE false
/** Major bootloader version number. */
#define BOOTLOADER_VERSION_MINOR 2
/** Minor bootloader version number. */
#define BOOTLOADER_VERSION_REV 0
/** Complete bootloader version number expressed as a packed byte, constructed from the
* two individual bootloader version macros.
*/
#define BOOTLOADER_VERSION ((BOOTLOADER_VERSION_MINOR << 4) | BOOTLOADER_VERSION_REV)
/** First byte of the bootloader identification bytes, used to identify a device's bootloader. */
#define BOOTLOADER_ID_BYTE1 0xDC
/** Second byte of the bootloader identification bytes, used to identify a device's bootloader. */
#define BOOTLOADER_ID_BYTE2 0xFB
/** Convenience macro, used to determine if the issued command is the given one-byte long command.
*
* \param[in] dataarr Command byte array to check against
* \param[in] cb1 First command byte to check
*/
#define IS_ONEBYTE_COMMAND(dataarr, cb1) (dataarr[0] == (cb1))
/** Convenience macro, used to determine if the issued command is the given two-byte long command.
*
* \param[in] dataarr Command byte array to check against
* \param[in] cb1 First command byte to check
* \param[in] cb2 Second command byte to check
*/
#define IS_TWOBYTE_COMMAND(dataarr, cb1, cb2) ((dataarr[0] == (cb1)) && (dataarr[1] == (cb2)))
/** Length of the DFU file suffix block, appended to the end of each complete memory write command.
* The DFU file suffix is currently unused (but is designed to give extra file information, such as
* a CRC of the complete firmware for error checking) and so is discarded.
*/
#define DFU_FILE_SUFFIX_SIZE 16
/** Length of the DFU file filler block, appended to the start of each complete memory write command.
* Filler bytes are added to the start of each complete memory write command, and must be discarded.
*/
#define DFU_FILLER_BYTES_SIZE 26
/** DFU class command request to detach from the host. */
#define DFU_DETATCH 0x00
/** DFU class command request to send data from the host to the bootloader. */
#define DFU_DNLOAD 0x01
/** DFU class command request to send data from the bootloader to the host. */
#define DFU_UPLOAD 0x02
/** DFU class command request to get the current DFU status and state from the bootloader. */
#define DFU_GETSTATUS 0x03
/** DFU class command request to reset the current DFU status and state variables to their defaults. */
#define DFU_CLRSTATUS 0x04
/** DFU class command request to get the current DFU state of the bootloader. */
#define DFU_GETSTATE 0x05
/** DFU class command request to abort the current multi-request transfer and return to the dfuIDLE state. */
#define DFU_ABORT 0x06
/** DFU command to begin programming the device's memory. */
#define COMMAND_PROG_START 0x01
/** DFU command to begin reading the device's memory. */
#define COMMAND_DISP_DATA 0x03
/** DFU command to issue a write command. */
#define COMMAND_WRITE 0x04
/** DFU command to issue a read command. */
#define COMMAND_READ 0x05
/** DFU command to issue a memory base address change command, to set the current 64KB flash page
* that subsequent flash operations should use. */
#define COMMAND_CHANGE_BASE_ADDR 0x06
/* Type Defines: */
/** Type define for a non-returning function pointer to the loaded application. */
typedef void (*AppPtr_t)(void) ATTR_NO_RETURN;
/** Type define for a structure containing a complete DFU command issued by the host. */
typedef struct
{
uint8_t Command; /**< Single byte command to perform, one of the COMMAND_* macro values */
uint8_t Data[5]; /**< Command parameters */
uint16_t DataSize; /**< Size of the command parameters */
} DFU_Command_t;
/* Enums: */
/** DFU bootloader states. Refer to the DFU class specification for information on each state. */
enum DFU_State_t
{
appIDLE = 0,
appDETACH = 1,
dfuIDLE = 2,
dfuDNLOAD_SYNC = 3,
dfuDNBUSY = 4,
dfuDNLOAD_IDLE = 5,
dfuMANIFEST_SYNC = 6,
dfuMANIFEST = 7,
dfuMANIFEST_WAIT_RESET = 8,
dfuUPLOAD_IDLE = 9,
dfuERROR = 10
};
/** DFU command status error codes. Refer to the DFU class specification for information on each error code. */
enum DFU_Status_t
{
OK = 0,
errTARGET = 1,
errFILE = 2,
errWRITE = 3,
errERASE = 4,
errCHECK_ERASED = 5,
errPROG = 6,
errVERIFY = 7,
errADDRESS = 8,
errNOTDONE = 9,
errFIRMWARE = 10,
errVENDOR = 11,
errUSBR = 12,
errPOR = 13,
errUNKNOWN = 14,
errSTALLEDPKT = 15
};
/* Function Prototypes: */
void SetupHardware(void);
void ResetHardware(void);
void EVENT_USB_Device_UnhandledControlRequest(void);
#if defined(INCLUDE_FROM_BOOTLOADER_C)
static void DiscardFillerBytes(uint8_t NumberOfBytes);
static void ProcessBootloaderCommand(void);
static void LoadStartEndAddresses(void);
static void ProcessMemProgCommand(void);
static void ProcessMemReadCommand(void);
static void ProcessWriteCommand(void);
static void ProcessReadCommand(void);
#endif
#endif /* _ARDUINO_USB_DFU_BOOTLOADER_H_ */

View File

@ -0,0 +1,110 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/*
Board LEDs driver for the Benito board, from www.dorkbotpdx.org.
*/
#ifndef __LEDS_ARDUINOUNO_H__
#define __LEDS_ARDUINOUNO_H__
/* Includes: */
#include <avr/io.h>
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(INCLUDE_FROM_LEDS_H)
#error Do not include this file directly. Include LUFA/Drivers/Board/LEDS.h instead.
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** LED mask for the first LED on the board. */
#define LEDS_LED1 (1 << 5)
/** LED mask for the second LED on the board. */
#define LEDS_LED2 (1 << 4)
/** LED mask for all the LEDs on the board. */
#define LEDS_ALL_LEDS (LEDS_LED1 | LEDS_LED2)
/** LED mask for the none of the board LEDs */
#define LEDS_NO_LEDS 0
/* Inline Functions: */
#if !defined(__DOXYGEN__)
static inline void LEDs_Init(void)
{
DDRD |= LEDS_ALL_LEDS;
PORTD |= LEDS_ALL_LEDS;
}
static inline void LEDs_TurnOnLEDs(const uint8_t LEDMask)
{
PORTD &= ~LEDMask;
}
static inline void LEDs_TurnOffLEDs(const uint8_t LEDMask)
{
PORTD |= LEDMask;
}
static inline void LEDs_SetAllLEDs(const uint8_t LEDMask)
{
PORTD = ((PORTD | LEDS_ALL_LEDS) & ~LEDMask);
}
static inline void LEDs_ChangeLEDs(const uint8_t LEDMask, const uint8_t ActiveMask)
{
PORTD = ((PORTD | ActiveMask) & ~LEDMask);
}
static inline void LEDs_ToggleLEDs(const uint8_t LEDMask)
{
PORTD ^= LEDMask;
}
static inline uint8_t LEDs_GetLEDs(void) ATTR_WARN_UNUSED_RESULT;
static inline uint8_t LEDs_GetLEDs(void)
{
return (PORTD & LEDS_ALL_LEDS);
}
#endif
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif

View File

@ -0,0 +1,189 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
*
* USB Device Descriptors, for library use when in USB device mode. Descriptors are special
* computer-readable structures which the host requests upon device enumeration, to determine
* the device's capabilities and functions.
*/
#include "Descriptors.h"
/** Device descriptor structure. This descriptor, located in FLASH memory, describes the overall
* device characteristics, including the supported USB version, control endpoint size and the
* number of device configurations. The descriptor is read out by the USB host when the enumeration
* process begins.
*/
USB_Descriptor_Device_t DeviceDescriptor =
{
.Header = {.Size = sizeof(USB_Descriptor_Device_t), .Type = DTYPE_Device},
.USBSpecification = VERSION_BCD(01.10),
.Class = 0x00,
.SubClass = 0x00,
.Protocol = 0x00,
.Endpoint0Size = FIXED_CONTROL_ENDPOINT_SIZE,
.VendorID = 0x03EB, // Atmel
.ProductID = PRODUCT_ID_CODE, // MCU-dependent
.ReleaseNumber = 0x0000,
.ManufacturerStrIndex = NO_DESCRIPTOR,
.ProductStrIndex = 0x01,
.SerialNumStrIndex = NO_DESCRIPTOR,
.NumberOfConfigurations = FIXED_NUM_CONFIGURATIONS
};
/** Configuration descriptor structure. This descriptor, located in FLASH memory, describes the usage
* of the device in one of its supported configurations, including information about any device interfaces
* and endpoints. The descriptor is read out by the USB host during the enumeration process when selecting
* a configuration so that the host may correctly communicate with the USB device.
*/
USB_Descriptor_Configuration_t ConfigurationDescriptor =
{
.Config =
{
.Header = {.Size = sizeof(USB_Descriptor_Configuration_Header_t), .Type = DTYPE_Configuration},
.TotalConfigurationSize = sizeof(USB_Descriptor_Configuration_t),
.TotalInterfaces = 1,
.ConfigurationNumber = 1,
.ConfigurationStrIndex = NO_DESCRIPTOR,
.ConfigAttributes = USB_CONFIG_ATTR_BUSPOWERED,
.MaxPowerConsumption = USB_CONFIG_POWER_MA(100)
},
.DFU_Interface =
{
.Header = {.Size = sizeof(USB_Descriptor_Interface_t), .Type = DTYPE_Interface},
.InterfaceNumber = 0,
.AlternateSetting = 0,
.TotalEndpoints = 0,
.Class = 0xFE,
.SubClass = 0x01,
.Protocol = 0x02,
.InterfaceStrIndex = NO_DESCRIPTOR
},
.DFU_Functional =
{
.Header = {.Size = sizeof(USB_DFU_Functional_Descriptor_t), .Type = DTYPE_DFUFunctional},
.Attributes = (ATTR_CAN_UPLOAD | ATTR_CAN_DOWNLOAD),
.DetachTimeout = 0x0000,
.TransferSize = 0x0c00,
.DFUSpecification = VERSION_BCD(01.01)
}
};
/** Language descriptor structure. This descriptor, located in FLASH memory, is returned when the host requests
* the string descriptor with index 0 (the first index). It is actually an array of 16-bit integers, which indicate
* via the language ID table available at USB.org what languages the device supports for its string descriptors.
*/
USB_Descriptor_String_t LanguageString =
{
.Header = {.Size = USB_STRING_LEN(1), .Type = DTYPE_String},
.UnicodeString = {LANGUAGE_ID_ENG}
};
/** Product descriptor string. This is a Unicode string containing the product's details in human readable form,
* and is read out upon request by the host when the appropriate string ID is requested, listed in the Device
* Descriptor.
*/
USB_Descriptor_String_t ProductString =
{
#if (ARDUINO_MODEL_PID == ARDUINO_UNO_PID)
.Header = {.Size = USB_STRING_LEN(15), .Type = DTYPE_String},
.UnicodeString = L"Arduino Uno DFU"
#elif (ARDUINO_MODEL_PID == ARDUINO_MEGA2560_PID)
.Header = {.Size = USB_STRING_LEN(21), .Type = DTYPE_String},
.UnicodeString = L"Arduino Mega 2560 DFU"
#endif
};
/** This function is called by the library when in device mode, and must be overridden (see library "USB Descriptors"
* documentation) by the application code so that the address and size of a requested descriptor can be given
* to the USB library. When the device receives a Get Descriptor request on the control endpoint, this function
* is called so that the descriptor details can be passed back and the appropriate descriptor sent back to the
* USB host.
*/
uint16_t CALLBACK_USB_GetDescriptor(const uint16_t wValue,
const uint8_t wIndex,
void** const DescriptorAddress)
{
const uint8_t DescriptorType = (wValue >> 8);
const uint8_t DescriptorNumber = (wValue & 0xFF);
void* Address = NULL;
uint16_t Size = NO_DESCRIPTOR;
switch (DescriptorType)
{
case DTYPE_Device:
Address = &DeviceDescriptor;
Size = sizeof(USB_Descriptor_Device_t);
break;
case DTYPE_Configuration:
Address = &ConfigurationDescriptor;
Size = sizeof(USB_Descriptor_Configuration_t);
break;
case DTYPE_String:
if (!(DescriptorNumber))
{
Address = &LanguageString;
Size = LanguageString.Header.Size;
}
else
{
Address = &ProductString;
Size = ProductString.Header.Size;
}
break;
}
*DescriptorAddress = Address;
return Size;
}

View File

@ -0,0 +1,177 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
*
* Header file for Descriptors.c.
*/
#ifndef _DESCRIPTORS_H_
#define _DESCRIPTORS_H_
/* Includes: */
#include <LUFA/Drivers/USB/USB.h>
/* Product-specific definitions: */
#define ARDUINO_UNO_PID 0x0001
#define ARDUINO_MEGA2560_PID 0x0010
/* Macros: */
/** Descriptor type value for a DFU class functional descriptor. */
#define DTYPE_DFUFunctional 0x21
/** DFU attribute mask, indicating that the DFU device will detach and re-attach when a DFU_DETACH
* command is issued, rather than the host issuing a USB Reset.
*/
#define ATTR_WILL_DETATCH (1 << 3)
/** DFU attribute mask, indicating that the DFU device can communicate during the manifestation phase
* (memory programming phase).
*/
#define ATTR_MANEFESTATION_TOLLERANT (1 << 2)
/** DFU attribute mask, indicating that the DFU device can accept DFU_UPLOAD requests to send data from
* the device to the host.
*/
#define ATTR_CAN_UPLOAD (1 << 1)
/** DFU attribute mask, indicating that the DFU device can accept DFU_DNLOAD requests to send data from
* the host to the device.
*/
#define ATTR_CAN_DOWNLOAD (1 << 0)
#if defined(__AVR_AT90USB1287__)
#define PRODUCT_ID_CODE 0x2FFB
#define AVR_SIGNATURE_1 0x1E
#define AVR_SIGNATURE_2 0x97
#define AVR_SIGNATURE_3 0x82
#elif defined(__AVR_AT90USB1286__)
#define PRODUCT_ID_CODE 0x2FFB
#define AVR_SIGNATURE_1 0x1E
#define AVR_SIGNATURE_2 0x97
#define AVR_SIGNATURE_3 0x82
#elif defined(__AVR_AT90USB647__)
#define PRODUCT_ID_CODE 0x2FF9
#define AVR_SIGNATURE_1 0x1E
#define AVR_SIGNATURE_2 0x96
#define AVR_SIGNATURE_3 0x82
#elif defined(__AVR_AT90USB646__)
#define PRODUCT_ID_CODE 0x2FF9
#define AVR_SIGNATURE_1 0x1E
#define AVR_SIGNATURE_2 0x96
#define AVR_SIGNATURE_3 0x82
#elif defined(__AVR_ATmega32U6__)
#define PRODUCT_ID_CODE 0x2FFB
#define AVR_SIGNATURE_1 0x1E
#define AVR_SIGNATURE_2 0x95
#define AVR_SIGNATURE_3 0x88
#elif defined(__AVR_ATmega32U4__)
#define PRODUCT_ID_CODE 0x2FF4
#define AVR_SIGNATURE_1 0x1E
#define AVR_SIGNATURE_2 0x95
#define AVR_SIGNATURE_3 0x87
#elif defined(__AVR_ATmega32U2__)
#define PRODUCT_ID_CODE 0x2FF0
#define AVR_SIGNATURE_1 0x1E
#define AVR_SIGNATURE_2 0x95
#define AVR_SIGNATURE_3 0x8A
#elif defined(__AVR_ATmega16U4__)
#define PRODUCT_ID_CODE 0x2FF3
#define AVR_SIGNATURE_1 0x1E
#define AVR_SIGNATURE_2 0x94
#define AVR_SIGNATURE_3 0x88
#elif defined(__AVR_ATmega16U2__)
#define PRODUCT_ID_CODE 0x2FEF
#define AVR_SIGNATURE_1 0x1E
#define AVR_SIGNATURE_2 0x94
#define AVR_SIGNATURE_3 0x89
#elif defined(__AVR_AT90USB162__)
#define PRODUCT_ID_CODE 0x2FFA
#define AVR_SIGNATURE_1 0x1E
#define AVR_SIGNATURE_2 0x94
#define AVR_SIGNATURE_3 0x82
#elif defined(__AVR_AT90USB82__)
#define PRODUCT_ID_CODE 0x2FEE
#define AVR_SIGNATURE_1 0x1E
#define AVR_SIGNATURE_2 0x93
#define AVR_SIGNATURE_3 0x89
#elif defined(__AVR_ATmega8U2__)
#define PRODUCT_ID_CODE 0x2FF7
#define AVR_SIGNATURE_1 0x1E
#define AVR_SIGNATURE_2 0x93
#define AVR_SIGNATURE_3 0x82
#else
#error The selected AVR part is not currently supported by this bootloader.
#endif
#if !defined(PRODUCT_ID_CODE)
#error Current AVR model is not supported by this bootloader.
#endif
/* Type Defines: */
/** Type define for a DFU class function descriptor. This descriptor gives DFU class information
* to the host when read, indicating the DFU device's capabilities.
*/
typedef struct
{
USB_Descriptor_Header_t Header; /**< Standard descriptor header structure */
uint8_t Attributes; /**< DFU device attributes, a mask comprising of the
* ATTR_* macros listed in this source file
*/
uint16_t DetachTimeout; /**< Timeout in milliseconds between a USB_DETACH
* command being issued and the device detaching
* from the USB bus
*/
uint16_t TransferSize; /**< Maximum number of bytes the DFU device can accept
* from the host in a transaction
*/
uint16_t DFUSpecification; /**< BCD packed DFU specification number this DFU
* device complies with
*/
} USB_DFU_Functional_Descriptor_t;
/** Type define for the device configuration descriptor structure. This must be defined in the
* application code, as the configuration descriptor contains several sub-descriptors which
* vary between devices, and which describe the device's usage to the host.
*/
typedef struct
{
USB_Descriptor_Configuration_Header_t Config;
USB_Descriptor_Interface_t DFU_Interface;
USB_DFU_Functional_Descriptor_t DFU_Functional;
} USB_Descriptor_Configuration_t;
/* Function Prototypes: */
uint16_t CALLBACK_USB_GetDescriptor(const uint16_t wValue,
const uint8_t wIndex,
void** const DescriptorAddress) ATTR_WARN_UNUSED_RESULT ATTR_NON_NULL_PTR_ARG(3);
#endif

View File

@ -0,0 +1,716 @@
# Hey Emacs, this is a -*- makefile -*-
#----------------------------------------------------------------------------
# WinAVR Makefile Template written by Eric B. Weddington, Jörg Wunsch, et al.
# >> Modified for use with the LUFA project. <<
#
# Released to the Public Domain
#
# Additional material for this makefile was written by:
# Peter Fleury
# Tim Henigan
# Colin O'Flynn
# Reiner Patommel
# Markus Pfaff
# Sander Pool
# Frederik Rouleau
# Carlos Lamas
# Dean Camera
# Opendous Inc.
# Denver Gingerich
#
#----------------------------------------------------------------------------
# On command line:
#
# make all = Make software.
#
# make clean = Clean out built project files.
#
# make coff = Convert ELF to AVR COFF.
#
# make extcoff = Convert ELF to AVR Extended COFF.
#
# make program = Download the hex file to the device, using avrdude.
# Please customize the avrdude settings below first!
#
# make doxygen = Generate DoxyGen documentation for the project (must have
# DoxyGen installed)
#
# make debug = Start either simulavr or avarice as specified for debugging,
# with avr-gdb or avr-insight as the front end for debugging.
#
# make filename.s = Just compile filename.c into the assembler code only.
#
# make filename.i = Create a preprocessed source file for use in submitting
# bug reports to the GCC project.
#
# To rebuild project do "make clean" then "make all".
#----------------------------------------------------------------------------
# MCU name
#MCU = atmega8u2
#MCU = atmega16u2
MCU = atmega32u2
MCU_AVRDUDE = $(F_CPU)
# Specify the Arduino model using the assigned PID. This is used by Descriptors.c
# to set the product descriptor string (for DFU we must use the PID for each
# chip that dfu-bootloader or Flip expect)
# Uno PID:
#ARDUINO_MODEL_PID = 0x0001
# Mega 2560 PID:
ARDUINO_MODEL_PID = 0x0010
# Target board (see library "Board Types" documentation, NONE for projects not requiring
# LUFA board drivers). If USER is selected, put custom board drivers in a directory called
# "Board" inside the application directory.
#BOARD = USER
BOARD = NONE
# Processor frequency.
# This will define a symbol, F_CPU, in all source code files equal to the
# processor frequency in Hz. You can then use this symbol in your source code to
# calculate timings. Do NOT tack on a 'UL' at the end, this will be done
# automatically to create a 32-bit value in your source code.
#
# This will be an integer division of F_CLOCK below, as it is sourced by
# F_CLOCK after it has run through any CPU prescalers. Note that this value
# does not *change* the processor frequency - it should merely be updated to
# reflect the processor speed set externally so that the code can use accurate
# software delays.
F_CPU = 16000000
# Input clock frequency.
# This will define a symbol, F_CLOCK, in all source code files equal to the
# input clock frequency (before any prescaling is performed) in Hz. This value may
# differ from F_CPU if prescaling is used on the latter, and is required as the
# raw input clock is fed directly to the PLL sections of the AVR for high speed
# clock generation for the USB and other AVR subsections. Do NOT tack on a 'UL'
# at the end, this will be done automatically to create a 32-bit value in your
# source code.
#
# If no clock division is performed on the input clock inside the AVR (via the
# CPU clock adjust registers or the clock division fuses), this will be equal to F_CPU.
F_CLOCK = $(F_CPU)
# Starting byte address of the bootloader, as a byte address - computed via the formula
# BOOT_START = ((TOTAL_FLASH_BYTES - BOOTLOADER_SECTION_SIZE_BYTES) * 1024)
#
# Note that the bootloader size and start address given in AVRStudio is in words and not
# bytes, and so will need to be doubled to obtain the byte address needed by AVR-GCC.
#BOOT_START = 0x1000
# ATMega32u2 boot start
BOOT_START = 0x7000
# Output format. (can be srec, ihex, binary)
FORMAT = ihex
# Target file name (without extension).
TARGET = Arduino-usbdfu
# Object files directory
# To put object files in current directory, use a dot (.), do NOT make
# this an empty or blank macro!
OBJDIR = .
# Path to the LUFA library
LUFA_PATH = ../..
# LUFA library compile-time options and predefined tokens
LUFA_OPTS = -D USB_DEVICE_ONLY
LUFA_OPTS += -D DEVICE_STATE_AS_GPIOR=0
LUFA_OPTS += -D CONTROL_ONLY_DEVICE
LUFA_OPTS += -D FIXED_CONTROL_ENDPOINT_SIZE=32
LUFA_OPTS += -D FIXED_NUM_CONFIGURATIONS=1
LUFA_OPTS += -D USE_RAM_DESCRIPTORS
LUFA_OPTS += -D USE_STATIC_OPTIONS="(USB_DEVICE_OPT_FULLSPEED | USB_OPT_REG_ENABLED | USB_OPT_AUTO_PLL)"
LUFA_OPTS += -D NO_INTERNAL_SERIAL
LUFA_OPTS += -D NO_DEVICE_SELF_POWER
LUFA_OPTS += -D NO_DEVICE_REMOTE_WAKEUP
LUFA_OPTS += -D NO_STREAM_CALLBACKS
# Create the LUFA source path variables by including the LUFA root makefile
include $(LUFA_PATH)/LUFA/makefile
# List C source files here. (C dependencies are automatically generated.)
SRC = $(TARGET).c \
Descriptors.c \
$(LUFA_SRC_USB) \
# List C++ source files here. (C dependencies are automatically generated.)
CPPSRC =
# List Assembler source files here.
# Make them always end in a capital .S. Files ending in a lowercase .s
# will not be considered source files but generated files (assembler
# output from the compiler), and will be deleted upon "make clean"!
# Even though the DOS/Win* filesystem matches both .s and .S the same,
# it will preserve the spelling of the filenames, and gcc itself does
# care about how the name is spelled on its command-line.
ASRC =
# Optimization level, can be [0, 1, 2, 3, s].
# 0 = turn off optimization. s = optimize for size.
# (Note: 3 is not always the best optimization level. See avr-libc FAQ.)
OPT = s
# Debugging format.
# Native formats for AVR-GCC's -g are dwarf-2 [default] or stabs.
# AVR Studio 4.10 requires dwarf-2.
# AVR [Extended] COFF format requires stabs, plus an avr-objcopy run.
DEBUG = dwarf-2
# List any extra directories to look for include files here.
# Each directory must be seperated by a space.
# Use forward slashes for directory separators.
# For a directory that has spaces, enclose it in quotes.
EXTRAINCDIRS = $(LUFA_PATH)/
# Compiler flag to set the C Standard level.
# c89 = "ANSI" C
# gnu89 = c89 plus GCC extensions
# c99 = ISO C99 standard (not yet fully implemented)
# gnu99 = c99 plus GCC extensions
CSTANDARD = -std=c99
# Place -D or -U options here for C sources
CDEFS = -DF_CPU=$(F_CPU)UL
CDEFS += -DARDUINO_MODEL_PID=$(ARDUINO_MODEL_PID)
CDEFS += -DF_CLOCK=$(F_CLOCK)UL
CDEFS += -DBOARD=BOARD_$(BOARD)
CDEFS += -DBOOT_START_ADDR=$(BOOT_START)UL
CDEFS += -DTX_RX_LED_PULSE_MS=3
CDEFS += $(LUFA_OPTS)
# Place -D or -U options here for ASM sources
ADEFS = -DF_CPU=$(F_CPU)
ADEFS += -DF_CLOCK=$(F_CLOCK)UL
ADEFS += -DBOARD=BOARD_$(BOARD)
CDEFS += -DBOOT_START_ADDR=$(BOOT_START)UL
ADEFS += $(LUFA_OPTS)
# Place -D or -U options here for C++ sources
CPPDEFS = -DF_CPU=$(F_CPU)UL
CPPDEFS += -DF_CLOCK=$(F_CLOCK)UL
CPPDEFS += -DBOARD=BOARD_$(BOARD)
CDEFS += -DBOOT_START_ADDR=$(BOOT_START)UL
CPPDEFS += $(LUFA_OPTS)
#CPPDEFS += -D__STDC_LIMIT_MACROS
#CPPDEFS += -D__STDC_CONSTANT_MACROS
#---------------- Compiler Options C ----------------
# -g*: generate debugging information
# -O*: optimization level
# -f...: tuning, see GCC manual and avr-libc documentation
# -Wall...: warning level
# -Wa,...: tell GCC to pass this to the assembler.
# -adhlns...: create assembler listing
CFLAGS = -g$(DEBUG)
CFLAGS += $(CDEFS)
CFLAGS += -O$(OPT)
CFLAGS += -funsigned-char
CFLAGS += -funsigned-bitfields
CFLAGS += -ffunction-sections
CFLAGS += -fno-inline-small-functions
CFLAGS += -fpack-struct
CFLAGS += -fshort-enums
CFLAGS += -fno-strict-aliasing
CFLAGS += -Wall
CFLAGS += -Wstrict-prototypes
#CFLAGS += -mshort-calls
#CFLAGS += -fno-unit-at-a-time
#CFLAGS += -Wundef
#CFLAGS += -Wunreachable-code
#CFLAGS += -Wsign-compare
CFLAGS += -Wa,-adhlns=$(<:%.c=$(OBJDIR)/%.lst)
CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS))
CFLAGS += $(CSTANDARD)
#---------------- Compiler Options C++ ----------------
# -g*: generate debugging information
# -O*: optimization level
# -f...: tuning, see GCC manual and avr-libc documentation
# -Wall...: warning level
# -Wa,...: tell GCC to pass this to the assembler.
# -adhlns...: create assembler listing
CPPFLAGS = -g$(DEBUG)
CPPFLAGS += $(CPPDEFS)
CPPFLAGS += -O$(OPT)
CPPFLAGS += -funsigned-char
CPPFLAGS += -funsigned-bitfields
CPPFLAGS += -fpack-struct
CPPFLAGS += -fshort-enums
CPPFLAGS += -fno-exceptions
CPPFLAGS += -Wall
CPPFLAGS += -Wundef
#CPPFLAGS += -mshort-calls
#CPPFLAGS += -fno-unit-at-a-time
#CPPFLAGS += -Wstrict-prototypes
#CPPFLAGS += -Wunreachable-code
#CPPFLAGS += -Wsign-compare
CPPFLAGS += -Wa,-adhlns=$(<:%.cpp=$(OBJDIR)/%.lst)
CPPFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS))
#CPPFLAGS += $(CSTANDARD)
#---------------- Assembler Options ----------------
# -Wa,...: tell GCC to pass this to the assembler.
# -adhlns: create listing
# -gstabs: have the assembler create line number information; note that
# for use in COFF files, additional information about filenames
# and function names needs to be present in the assembler source
# files -- see avr-libc docs [FIXME: not yet described there]
# -listing-cont-lines: Sets the maximum number of continuation lines of hex
# dump that will be displayed for a given single line of source input.
ASFLAGS = $(ADEFS) -Wa,-adhlns=$(<:%.S=$(OBJDIR)/%.lst),-gstabs,--listing-cont-lines=100
#---------------- Library Options ----------------
# Minimalistic printf version
PRINTF_LIB_MIN = -Wl,-u,vfprintf -lprintf_min
# Floating point printf version (requires MATH_LIB = -lm below)
PRINTF_LIB_FLOAT = -Wl,-u,vfprintf -lprintf_flt
# If this is left blank, then it will use the Standard printf version.
PRINTF_LIB =
#PRINTF_LIB = $(PRINTF_LIB_MIN)
#PRINTF_LIB = $(PRINTF_LIB_FLOAT)
# Minimalistic scanf version
SCANF_LIB_MIN = -Wl,-u,vfscanf -lscanf_min
# Floating point + %[ scanf version (requires MATH_LIB = -lm below)
SCANF_LIB_FLOAT = -Wl,-u,vfscanf -lscanf_flt
# If this is left blank, then it will use the Standard scanf version.
SCANF_LIB =
#SCANF_LIB = $(SCANF_LIB_MIN)
#SCANF_LIB = $(SCANF_LIB_FLOAT)
MATH_LIB = -lm
# List any extra directories to look for libraries here.
# Each directory must be seperated by a space.
# Use forward slashes for directory separators.
# For a directory that has spaces, enclose it in quotes.
EXTRALIBDIRS =
#---------------- External Memory Options ----------------
# 64 KB of external RAM, starting after internal RAM (ATmega128!),
# used for variables (.data/.bss) and heap (malloc()).
#EXTMEMOPTS = -Wl,-Tdata=0x801100,--defsym=__heap_end=0x80ffff
# 64 KB of external RAM, starting after internal RAM (ATmega128!),
# only used for heap (malloc()).
#EXTMEMOPTS = -Wl,--section-start,.data=0x801100,--defsym=__heap_end=0x80ffff
EXTMEMOPTS =
#---------------- Linker Options ----------------
# -Wl,...: tell GCC to pass this to linker.
# -Map: create map file
# --cref: add cross reference to map file
LDFLAGS = -Wl,-Map=$(TARGET).map,--cref
LDFLAGS += -Wl,--section-start=.text=$(BOOT_START)
LDFLAGS += -Wl,--relax
LDFLAGS += -Wl,--gc-sections
LDFLAGS += $(EXTMEMOPTS)
LDFLAGS += $(patsubst %,-L%,$(EXTRALIBDIRS))
LDFLAGS += $(PRINTF_LIB) $(SCANF_LIB) $(MATH_LIB)
#LDFLAGS += -T linker_script.x
#---------------- Programming Options (avrdude) ----------------
# Fuse settings for Arduino Uno DFU bootloader project
AVRDUDE_FUSES = -U efuse:w:0xF4:m -U hfuse:w:0xD9:m -U lfuse:w:0xFF:m
# Lock settings for Arduino Uno DFU bootloader project
AVRDUDE_LOCK = -U lock:w:0x0F:m
# Programming hardware
# Type: avrdude -c ?
# to get a full listing.
#
AVRDUDE_PROGRAMMER = avrispmkii
# com1 = serial port. Use lpt1 to connect to parallel port.
AVRDUDE_PORT = usb
AVRDUDE_WRITE_FLASH = -U flash:w:$(TARGET).hex
#AVRDUDE_WRITE_EEPROM = -U eeprom:w:$(TARGET).eep
# Uncomment the following if you want avrdude's erase cycle counter.
# Note that this counter needs to be initialized first using -Yn,
# see avrdude manual.
#AVRDUDE_ERASE_COUNTER = -y
# Uncomment the following if you do /not/ wish a verification to be
# performed after programming the device.
#AVRDUDE_NO_VERIFY = -V
# Increase verbosity level. Please use this when submitting bug
# reports about avrdude. See <http://savannah.nongnu.org/projects/avrdude>
# to submit bug reports.
#AVRDUDE_VERBOSE = -v -v
AVRDUDE_FLAGS = -p $(MCU_AVRDUDE) -F -P $(AVRDUDE_PORT) -c $(AVRDUDE_PROGRAMMER)
AVRDUDE_FLAGS += $(AVRDUDE_NO_VERIFY)
AVRDUDE_FLAGS += $(AVRDUDE_VERBOSE)
AVRDUDE_FLAGS += $(AVRDUDE_ERASE_COUNTER)
#---------------- Debugging Options ----------------
# For simulavr only - target MCU frequency.
DEBUG_MFREQ = $(F_CPU)
# Set the DEBUG_UI to either gdb or insight.
# DEBUG_UI = gdb
DEBUG_UI = insight
# Set the debugging back-end to either avarice, simulavr.
DEBUG_BACKEND = avarice
#DEBUG_BACKEND = simulavr
# GDB Init Filename.
GDBINIT_FILE = __avr_gdbinit
# When using avarice settings for the JTAG
JTAG_DEV = /dev/com1
# Debugging port used to communicate between GDB / avarice / simulavr.
DEBUG_PORT = 4242
# Debugging host used to communicate between GDB / avarice / simulavr, normally
# just set to localhost unless doing some sort of crazy debugging when
# avarice is running on a different computer.
DEBUG_HOST = localhost
#============================================================================
# Define programs and commands.
SHELL = sh
CC = avr-gcc
OBJCOPY = avr-objcopy
OBJDUMP = avr-objdump
SIZE = avr-size
AR = avr-ar rcs
NM = avr-nm
AVRDUDE = avrdude
REMOVE = rm -f
REMOVEDIR = rm -rf
COPY = cp
WINSHELL = cmd
# Define Messages
# English
MSG_ERRORS_NONE = Errors: none
MSG_BEGIN = -------- begin --------
MSG_END = -------- end --------
MSG_SIZE_BEFORE = Size before:
MSG_SIZE_AFTER = Size after:
MSG_COFF = Converting to AVR COFF:
MSG_EXTENDED_COFF = Converting to AVR Extended COFF:
MSG_FLASH = Creating load file for Flash:
MSG_EEPROM = Creating load file for EEPROM:
MSG_EXTENDED_LISTING = Creating Extended Listing:
MSG_SYMBOL_TABLE = Creating Symbol Table:
MSG_LINKING = Linking:
MSG_COMPILING = Compiling C:
MSG_COMPILING_CPP = Compiling C++:
MSG_ASSEMBLING = Assembling:
MSG_CLEANING = Cleaning project:
MSG_CREATING_LIBRARY = Creating library:
# Define all object files.
OBJ = $(SRC:%.c=$(OBJDIR)/%.o) $(CPPSRC:%.cpp=$(OBJDIR)/%.o) $(ASRC:%.S=$(OBJDIR)/%.o)
# Define all listing files.
LST = $(SRC:%.c=$(OBJDIR)/%.lst) $(CPPSRC:%.cpp=$(OBJDIR)/%.lst) $(ASRC:%.S=$(OBJDIR)/%.lst)
# Compiler flags to generate dependency files.
GENDEPFLAGS = -MMD -MP -MF .dep/$(@F).d
# Combine all necessary flags and optional flags.
# Add target processor to flags.
ALL_CFLAGS = -mmcu=$(MCU) -I. $(CFLAGS) $(GENDEPFLAGS)
ALL_CPPFLAGS = -mmcu=$(MCU) -I. -x c++ $(CPPFLAGS) $(GENDEPFLAGS)
ALL_ASFLAGS = -mmcu=$(MCU) -I. -x assembler-with-cpp $(ASFLAGS)
# Default target.
all: begin gccversion sizebefore build sizeafter end
# Change the build target to build a HEX file or a library.
build: elf hex eep lss sym
#build: lib
elf: $(TARGET).elf
hex: $(TARGET).hex
eep: $(TARGET).eep
lss: $(TARGET).lss
sym: $(TARGET).sym
LIBNAME=lib$(TARGET).a
lib: $(LIBNAME)
# Eye candy.
# AVR Studio 3.x does not check make's exit code but relies on
# the following magic strings to be generated by the compile job.
begin:
@echo
@echo $(MSG_BEGIN)
end:
@echo $(MSG_END)
@echo
# Display size of file.
HEXSIZE = $(SIZE) --target=$(FORMAT) $(TARGET).hex
ELFSIZE = $(SIZE) $(MCU_FLAG) $(FORMAT_FLAG) $(TARGET).elf
MCU_FLAG = $(shell $(SIZE) --help | grep -- --mcu > /dev/null && echo --mcu=$(MCU) )
FORMAT_FLAG = $(shell $(SIZE) --help | grep -- --format=.*avr > /dev/null && echo --format=avr )
sizebefore:
@if test -f $(TARGET).elf; then echo; echo $(MSG_SIZE_BEFORE); $(ELFSIZE); \
2>/dev/null; echo; fi
sizeafter:
@if test -f $(TARGET).elf; then echo; echo $(MSG_SIZE_AFTER); $(ELFSIZE); \
2>/dev/null; echo; fi
# Display compiler version information.
gccversion :
@$(CC) --version
# Program the device.
program: $(TARGET).hex $(TARGET).eep
$(AVRDUDE) $(AVRDUDE_FLAGS) $(AVRDUDE_WRITE_FLASH) $(AVRDUDE_WRITE_EEPROM) $(AVRDUDE_FUSES) $(AVRDUDE_LOCK)
# Generate avr-gdb config/init file which does the following:
# define the reset signal, load the target file, connect to target, and set
# a breakpoint at main().
gdb-config:
@$(REMOVE) $(GDBINIT_FILE)
@echo define reset >> $(GDBINIT_FILE)
@echo SIGNAL SIGHUP >> $(GDBINIT_FILE)
@echo end >> $(GDBINIT_FILE)
@echo file $(TARGET).elf >> $(GDBINIT_FILE)
@echo target remote $(DEBUG_HOST):$(DEBUG_PORT) >> $(GDBINIT_FILE)
ifeq ($(DEBUG_BACKEND),simulavr)
@echo load >> $(GDBINIT_FILE)
endif
@echo break main >> $(GDBINIT_FILE)
debug: gdb-config $(TARGET).elf
ifeq ($(DEBUG_BACKEND), avarice)
@echo Starting AVaRICE - Press enter when "waiting to connect" message displays.
@$(WINSHELL) /c start avarice --jtag $(JTAG_DEV) --erase --program --file \
$(TARGET).elf $(DEBUG_HOST):$(DEBUG_PORT)
@$(WINSHELL) /c pause
else
@$(WINSHELL) /c start simulavr --gdbserver --device $(MCU) --clock-freq \
$(DEBUG_MFREQ) --port $(DEBUG_PORT)
endif
@$(WINSHELL) /c start avr-$(DEBUG_UI) --command=$(GDBINIT_FILE)
# Convert ELF to COFF for use in debugging / simulating in AVR Studio or VMLAB.
COFFCONVERT = $(OBJCOPY) --debugging
COFFCONVERT += --change-section-address .data-0x800000
COFFCONVERT += --change-section-address .bss-0x800000
COFFCONVERT += --change-section-address .noinit-0x800000
COFFCONVERT += --change-section-address .eeprom-0x810000
coff: $(TARGET).elf
@echo
@echo $(MSG_COFF) $(TARGET).cof
$(COFFCONVERT) -O coff-avr $< $(TARGET).cof
extcoff: $(TARGET).elf
@echo
@echo $(MSG_EXTENDED_COFF) $(TARGET).cof
$(COFFCONVERT) -O coff-ext-avr $< $(TARGET).cof
# Create final output files (.hex, .eep) from ELF output file.
%.hex: %.elf
@echo
@echo $(MSG_FLASH) $@
$(OBJCOPY) -O $(FORMAT) -R .eeprom -R .fuse -R .lock $< $@
%.eep: %.elf
@echo
@echo $(MSG_EEPROM) $@
-$(OBJCOPY) -j .eeprom --set-section-flags=.eeprom="alloc,load" \
--change-section-lma .eeprom=0 --no-change-warnings -O $(FORMAT) $< $@ || exit 0
# Create extended listing file from ELF output file.
%.lss: %.elf
@echo
@echo $(MSG_EXTENDED_LISTING) $@
$(OBJDUMP) -h -S -z $< > $@
# Create a symbol table from ELF output file.
%.sym: %.elf
@echo
@echo $(MSG_SYMBOL_TABLE) $@
$(NM) -n $< > $@
# Create library from object files.
.SECONDARY : $(TARGET).a
.PRECIOUS : $(OBJ)
%.a: $(OBJ)
@echo
@echo $(MSG_CREATING_LIBRARY) $@
$(AR) $@ $(OBJ)
# Link: create ELF output file from object files.
.SECONDARY : $(TARGET).elf
.PRECIOUS : $(OBJ)
%.elf: $(OBJ)
@echo
@echo $(MSG_LINKING) $@
$(CC) $(ALL_CFLAGS) $^ --output $@ $(LDFLAGS)
# Compile: create object files from C source files.
$(OBJDIR)/%.o : %.c
@echo
@echo $(MSG_COMPILING) $<
$(CC) -c $(ALL_CFLAGS) $< -o $@
# Compile: create object files from C++ source files.
$(OBJDIR)/%.o : %.cpp
@echo
@echo $(MSG_COMPILING_CPP) $<
$(CC) -c $(ALL_CPPFLAGS) $< -o $@
# Compile: create assembler files from C source files.
%.s : %.c
$(CC) -S $(ALL_CFLAGS) $< -o $@
# Compile: create assembler files from C++ source files.
%.s : %.cpp
$(CC) -S $(ALL_CPPFLAGS) $< -o $@
# Assemble: create object files from assembler source files.
$(OBJDIR)/%.o : %.S
@echo
@echo $(MSG_ASSEMBLING) $<
$(CC) -c $(ALL_ASFLAGS) $< -o $@
# Create preprocessed source for use in sending a bug report.
%.i : %.c
$(CC) -E -mmcu=$(MCU) -I. $(CFLAGS) $< -o $@
# Target: clean project.
clean: begin clean_list end
clean_list :
@echo
@echo $(MSG_CLEANING)
$(REMOVE) $(TARGET).hex
$(REMOVE) $(TARGET).eep
$(REMOVE) $(TARGET).cof
$(REMOVE) $(TARGET).elf
$(REMOVE) $(TARGET).map
$(REMOVE) $(TARGET).sym
$(REMOVE) $(TARGET).lss
$(REMOVE) $(SRC:%.c=$(OBJDIR)/%.o)
$(REMOVE) $(SRC:%.c=$(OBJDIR)/%.lst)
$(REMOVE) $(SRC:.c=.s)
$(REMOVE) $(SRC:.c=.d)
$(REMOVE) $(SRC:.c=.i)
$(REMOVEDIR) .dep
doxygen:
@echo Generating Project Documentation...
@doxygen Doxygen.conf
@echo Documentation Generation Complete.
clean_doxygen:
rm -rf Documentation
# Create object files directory
$(shell mkdir $(OBJDIR) 2>/dev/null)
# Include the dependency files.
-include $(shell mkdir .dep 2>/dev/null) $(wildcard .dep/*)
# Listing of phony targets.
.PHONY : all begin finish end sizebefore sizeafter gccversion \
build elf hex eep lss sym coff extcoff doxygen clean \
clean_list clean_doxygen program debug gdb-config

View File

@ -0,0 +1,12 @@
To setup the project and program an ATMEG32U2 with the Arduino USB DFU bootloader:
> make clean
> make
> make program
Check that the board enumerates as "Atmega32u2".
Test by uploading the Arduino-usbserial application firmware (see instructions in Arduino-usbserial directory)

File diff suppressed because one or more lines are too long

View File

@ -0,0 +1,138 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief AVR-GCC special function/variable attribute macros.
*
* This file contains macros for applying GCC specific attributes to functions and variables to control various
* optimiser and code generation features of the compiler. Attributes may be placed in the function prototype
* or variable declaration in any order, and multiple attributes can be specified for a single item via a space
* separated list.
*
* On incompatible versions of GCC or on other compilers, these macros evaluate to nothing unless they are
* critical to the code's function and thus must throw a compiler error when used.
*
* \note Do not include this file directly, rather include the Common.h header file instead to gain this file's
* functionality.
*/
/** \ingroup Group_Common
* @defgroup Group_GCCAttr Function/Variable Attributes
*
* Macros for easy access GCC function and variable attributes, which can be applied to function prototypes or
* variable attributes.
*
* @{
*/
#ifndef __FUNCATTR_H__
#define __FUNCATTR_H__
/* Preprocessor Checks: */
#if !defined(__COMMON_H__)
#error Do not include this file directly. Include LUFA/Common/Common.h instead to gain this functionality.
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
#if (__GNUC__ >= 3) || defined(__DOXYGEN__)
/** Indicates to the compiler that the function can not ever return, so that any stack restoring or
* return code may be omitted by the compiler in the resulting binary.
*/
#define ATTR_NO_RETURN __attribute__ ((noreturn))
/** Indicates that the function returns a value which should not be ignored by the user code. When
* applied, any ignored return value from calling the function will produce a compiler warning.
*/
#define ATTR_WARN_UNUSED_RESULT __attribute__ ((warn_unused_result))
/** Indicates that the specified parameters of the function are pointers which should never be NULL.
* When applied as a 1-based comma separated list the compiler will emit a warning if the specified
* parameters are known at compiler time to be NULL at the point of calling the function.
*/
#define ATTR_NON_NULL_PTR_ARG(...) __attribute__ ((nonnull (__VA_ARGS__)))
/** Removes any preamble or postamble from the function. When used, the function will not have any
* register or stack saving code. This should be used with caution, and when used the programmer
* is responsible for maintaining stack and register integrity.
*/
#define ATTR_NAKED __attribute__ ((naked))
/** Prevents the compiler from considering a specified function for inlining. When applied, the given
* function will not be inlined under any circumstances.
*/
#define ATTR_NO_INLINE __attribute__ ((noinline))
/** Forces the compiler to inline the specified function. When applied, the given function will be
* inlined under all circumstances.
*/
#define ATTR_ALWAYS_INLINE __attribute__ ((always_inline))
/** Indicates that the specified function is pure, in that it has no side-effects other than global
* or parameter variable access.
*/
#define ATTR_PURE __attribute__ ((pure))
/** Indicates that the specified function is constant, in that it has no side effects other than
* parameter access.
*/
#define ATTR_CONST __attribute__ ((const))
/** Marks a given function as deprecated, which produces a warning if the function is called. */
#define ATTR_DEPRECATED __attribute__ ((deprecated))
/** Marks a function as a weak reference, which can be overridden by other functions with an
* identical name (in which case the weak reference is discarded at link time).
*/
#define ATTR_WEAK __attribute__ ((weak))
/** Forces the compiler to not automatically zero the given global variable on startup, so that the
* current RAM contents is retained. Under most conditions this value will be random due to the
* behaviour of volatile memory once power is removed, but may be used in some specific circumstances,
* like the passing of values back after a system watchdog reset.
*/
#define ATTR_NO_INIT __attribute__ ((section (".noinit")))
#endif
/** Places the function in one of the initialization sections, which execute before the main function
* of the application. Refer to the avr-libc manual for more information on the initialization sections.
*
* \param[in] SectionIndex Initialization section number where the function should be placed.
*/
#define ATTR_INIT_SECTION(SectionIndex) __attribute__ ((naked, section (".init" #SectionIndex )))
/** Marks a function as an alias for another function.
*
* \param[in] Func Name of the function which the given function name should alias.
*/
#define ATTR_ALIAS(Func) __attribute__ ((alias( #Func )))
#endif
/** @} */

View File

@ -0,0 +1,120 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Supported board hardware defines.
*
* This file contains constants which can be passed to the compiler (via setting the macro BOARD) in the
* user project makefile using the -D option to configure the library board-specific drivers.
*
* \note Do not include this file directly, rather include the Common.h header file instead to gain this file's
* functionality.
*/
/** \ingroup Group_Common
* @defgroup Group_BoardTypes Board Types
*
* Macros for indicating the chosen physical board hardware to the library. These macros should be used when
* defining the BOARD token to the chosen hardware via the -D switch in the project makefile.
*
* @{
*/
#ifndef __BOARDTYPES_H__
#define __BOARDTYPES_H__
/* Preprocessor Checks: */
#if !defined(__COMMON_H__)
#error Do not include this file directly. Include LUFA/Common/Common.h instead to gain this functionality.
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** Selects the USBKEY specific board drivers, including Temperature, Button, Dataflash, Joystick and LED drivers. */
#define BOARD_USBKEY 0
/** Selects the STK525 specific board drivers, including Temperature, Button, Dataflash, Joystick and LED drivers. */
#define BOARD_STK525 1
/** Selects the STK526 specific board drivers, including Temperature, Button, Dataflash, Joystick and LED drivers. */
#define BOARD_STK526 2
/** Selects the RZUSBSTICK specific board drivers, including the driver for the boards LEDs. */
#define BOARD_RZUSBSTICK 3
/** Selects the ATAVRUSBRF01 specific board drivers, including the driver for the board LEDs. */
#define BOARD_ATAVRUSBRF01 4
/** Selects the user-defined board drivers, which should be placed in the user project's folder
* under a directory named /Board/. Each board driver should be named identically to the LUFA
* master board driver (i.e., driver in the LUFA/Drivers/Board director) so that the library
* can correctly identify it.
*/
#define BOARD_USER 5
/** Selects the BUMBLEB specific board drivers, using the officially recommended peripheral layout. */
#define BOARD_BUMBLEB 6
/** Selects the XPLAIN (Revision 2 or newer) specific board drivers, including LED and Dataflash driver. */
#define BOARD_XPLAIN 7
/** Selects the XPLAIN (Revision 1) specific board drivers, including LED and Dataflash driver. */
#define BOARD_XPLAIN_REV1 8
/** Selects the EVK527 specific board drivers, including Temperature, Button, Dataflash, Joystick and LED drivers. */
#define BOARD_EVK527 9
/** Disables board drivers when operation will not be adversely affected (e.g. LEDs) - use of board drivers
* such as the Joystick driver, where the removal would adversely affect the code's operation is still disallowed. */
#define BOARD_NONE 10
/** Selects the Teensy (all versions) specific board drivers, including the driver for the board LEDs. */
#define BOARD_TEENSY 11
/** Selects the USBTINY MKII specific board drivers, including the Button and LEDs drivers. */
#define BOARD_USBTINYMKII 12
/** Selects the Benito specific board drivers, including the Button and LEDs drivers. */
#define BOARD_BENITO 13
/** Selects the JM-DB-U2 specific board drivers, including the Button and LEDs drivers. */
#define BOARD_JMDBU2 14
#if !defined(__DOXYGEN__)
#define BOARD_ BOARD_NONE
#if !defined(BOARD)
#define BOARD BOARD_NONE
#endif
#endif
#endif
/** @} */

View File

@ -0,0 +1,252 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Common library convenience macros and functions.
*
* This file contains macros which are common to all library elements, and which may be useful in user code. It
* also includes other common headers, such as Atomic.h, Attributes.h and BoardTypes.h.
*/
/** @defgroup Group_Common Common Utility Headers - LUFA/Drivers/Common/Common.h
*
* Common utility headers containing macros, functions, enums and types which are common to all
* aspects of the library.
*
* @{
*/
/** @defgroup Group_Debugging Debugging Macros
*
* Macros for debugging use.
*/
/** @defgroup Group_BitManip Endian and Bit Macros
*
* Functions for swapping endianness and reversing bit orders.
*/
#ifndef __COMMON_H__
#define __COMMON_H__
/* Includes: */
#include <stdint.h>
#include <stdbool.h>
#include "Attributes.h"
#include "BoardTypes.h"
/* Public Interface - May be used in end-application: */
/* Macros: */
/** Macro for encasing other multi-statement macros. This should be used along with an opening brace
* before the start of any multi-statement macro, so that the macros contents as a whole are treated
* as a discrete block and not as a list of separate statements which may cause problems when used as
* a block (such as inline IF statements).
*/
#define MACROS do
/** Macro for encasing other multi-statement macros. This should be used along with a preceding closing
* brace at the end of any multi-statement macro, so that the macros contents as a whole are treated
* as a discrete block and not as a list of separate statements which may cause problems when used as
* a block (such as inline IF statements).
*/
#define MACROE while (0)
/** Defines a volatile NOP statement which cannot be optimized out by the compiler, and thus can always
* be set as a breakpoint in the resulting code. Useful for debugging purposes, where the optimiser
* removes/reorders code to the point where break points cannot reliably be set.
*
* \ingroup Group_Debugging
*/
#define JTAG_DEBUG_POINT() asm volatile ("NOP" ::)
/** Defines an explicit JTAG break point in the resulting binary via the ASM BREAK statement. When
* a JTAG is used, this causes the program execution to halt when reached until manually resumed.
*
* \ingroup Group_Debugging
*/
#define JTAG_DEBUG_BREAK() asm volatile ("BREAK" ::)
/** Macro for testing condition "x" and breaking via JTAG_DEBUG_BREAK() if the condition is false.
*
* \ingroup Group_Debugging
*/
#define JTAG_DEBUG_ASSERT(x) MACROS{ if (!(x)) { JTAG_DEBUG_BREAK(); } }MACROE
/** Macro for testing condition "x" and writing debug data to the stdout stream if false. The stdout stream
* must be pre-initialized before this macro is run and linked to an output device, such as the AVR's USART
* peripheral.
*
* The output takes the form "{FILENAME}: Function {FUNCTION NAME}, Line {LINE NUMBER}: Assertion {x} failed."
*
* \ingroup Group_Debugging
*/
#define STDOUT_ASSERT(x) MACROS{ if (!(x)) { printf_P(PSTR("%s: Function \"%s\", Line %d: " \
"Assertion \"%s\" failed.\r\n"), \
__FILE__, __func__, __LINE__, #x); } }MACROE
#if !defined(pgm_read_ptr) || defined(__DOXYGEN__)
/** Reads a pointer out of PROGMEM space. This is currently a wrapper for the avr-libc pgm_read_ptr()
* macro with a void* cast, so that its value can be assigned directly to a pointer variable or used
* in pointer arithmetic without further casting in C. In a future avr-libc distribution this will be
* part of the standard API and will be implemented in a more formal manner.
*
* \param[in] Addr Address of the pointer to read.
*
* \return Pointer retrieved from PROGMEM space.
*/
#define pgm_read_ptr(Addr) (void*)pgm_read_word(Addr)
#endif
/** Swaps the byte ordering of a 16-bit value at compile time. Do not use this macro for swapping byte orderings
* of dynamic values computed at runtime, use \ref SwapEndian_16() instead. The result of this macro can be used
* inside struct or other variable initializers outside of a function, something that is not possible with the
* inline function variant.
*
* \param[in] x 16-bit value whose byte ordering is to be swapped.
*
* \return Input value with the byte ordering reversed.
*/
#define SWAPENDIAN_16(x) ((((x) & 0xFF00) >> 8) | (((x) & 0x00FF) << 8))
/** Swaps the byte ordering of a 32-bit value at compile time. Do not use this macro for swapping byte orderings
* of dynamic values computed at runtime- use \ref SwapEndian_32() instead. The result of this macro can be used
* inside struct or other variable initializers outside of a function, something that is not possible with the
* inline function variant.
*
* \param[in] x 32-bit value whose byte ordering is to be swapped.
*
* \return Input value with the byte ordering reversed.
*/
#define SWAPENDIAN_32(x) ((((x) & 0xFF000000UL) >> 24UL) | (((x) & 0x00FF0000UL) >> 8UL) | \
(((x) & 0x0000FF00UL) << 8UL) | (((x) & 0x000000FFUL) << 24UL))
/* Inline Functions: */
/** Function to reverse the individual bits in a byte - i.e. bit 7 is moved to bit 0, bit 6 to bit 1,
* etc.
*
* \ingroup Group_BitManip
*
* \param[in] Byte Byte of data whose bits are to be reversed.
*/
static inline uint8_t BitReverse(uint8_t Byte) ATTR_WARN_UNUSED_RESULT ATTR_CONST;
static inline uint8_t BitReverse(uint8_t Byte)
{
Byte = (((Byte & 0xF0) >> 4) | ((Byte & 0x0F) << 4));
Byte = (((Byte & 0xCC) >> 2) | ((Byte & 0x33) << 2));
Byte = (((Byte & 0xAA) >> 1) | ((Byte & 0x55) << 1));
return Byte;
}
/** Function to reverse the byte ordering of the individual bytes in a 16 bit number.
*
* \ingroup Group_BitManip
*
* \param[in] Word Word of data whose bytes are to be swapped.
*/
static inline uint16_t SwapEndian_16(const uint16_t Word) ATTR_WARN_UNUSED_RESULT ATTR_CONST;
static inline uint16_t SwapEndian_16(const uint16_t Word)
{
uint8_t Temp;
union
{
uint16_t Word;
uint8_t Bytes[2];
} Data;
Data.Word = Word;
Temp = Data.Bytes[0];
Data.Bytes[0] = Data.Bytes[1];
Data.Bytes[1] = Temp;
return Data.Word;
}
/** Function to reverse the byte ordering of the individual bytes in a 32 bit number.
*
* \ingroup Group_BitManip
*
* \param[in] DWord Double word of data whose bytes are to be swapped.
*/
static inline uint32_t SwapEndian_32(const uint32_t DWord) ATTR_WARN_UNUSED_RESULT ATTR_CONST;
static inline uint32_t SwapEndian_32(const uint32_t DWord)
{
uint8_t Temp;
union
{
uint32_t DWord;
uint8_t Bytes[4];
} Data;
Data.DWord = DWord;
Temp = Data.Bytes[0];
Data.Bytes[0] = Data.Bytes[3];
Data.Bytes[3] = Temp;
Temp = Data.Bytes[1];
Data.Bytes[1] = Data.Bytes[2];
Data.Bytes[2] = Temp;
return Data.DWord;
}
/** Function to reverse the byte ordering of the individual bytes in a n byte number.
*
* \ingroup Group_BitManip
*
* \param[in,out] Data Pointer to a number containing an even number of bytes to be reversed.
* \param[in] Bytes Length of the data in bytes.
*/
static inline void SwapEndian_n(void* Data,
uint8_t Bytes) ATTR_NON_NULL_PTR_ARG(1);
static inline void SwapEndian_n(void* Data,
uint8_t Bytes)
{
uint8_t* CurrDataPos = (uint8_t*)Data;
while (Bytes > 1)
{
uint8_t Temp = *CurrDataPos;
*CurrDataPos = *(CurrDataPos + Bytes - 1);
*(CurrDataPos + Bytes - 1) = Temp;
CurrDataPos++;
Bytes -= 2;
}
}
#endif
/** @} */

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,85 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/*
This is a stub driver header file, for implementing custom board
layout hardware with compatible LUFA board specific drivers. If
the library is configured to use the BOARD_USER board mode, this
driver file should be completed and copied into the "/Board/" folder
inside the application's folder.
This stub is for the board-specific component of the LUFA Buttons driver,
for the control of physical board-mounted GPIO pushbuttons.
*/
#ifndef __BUTTONS_USER_H__
#define __BUTTONS_USER_H__
/* Includes: */
#include <avr/io.h>
#include <stdbool.h>
// TODO: Add any required includes here
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_BUTTONS_H)
#error Do not include this file directly. Include LUFA/Drivers/Board/Buttons.h instead.
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** Button mask for the first button on the board. */
#define BUTTONS_BUTTON1 // TODO: Add mask for first board button here
/* Inline Functions: */
#if !defined(__DOXYGEN__)
static inline void Buttons_Init(void)
{
// TODO: Initialize the appropriate port pins as an inputs here, with pull-ups
}
static inline uint8_t Buttons_GetStatus(void) ATTR_WARN_UNUSED_RESULT;
static inline uint8_t Buttons_GetStatus(void)
{
// TODO: Return current button status here, debounced if required
}
#endif
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif

View File

@ -0,0 +1,185 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/*
This is a stub driver header file, for implementing custom board
layout hardware with compatible LUFA board specific drivers. If
the library is configured to use the BOARD_USER board mode, this
driver file should be completed and copied into the "/Board/" folder
inside the application's folder.
This stub is for the board-specific component of the LUFA Dataflash
driver.
*/
#ifndef __DATAFLASH_USER_H__
#define __DATAFLASH_USER_H__
/* Includes: */
// TODO: Add any required includes here
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_DATAFLASH_H)
#error Do not include this file directly. Include LUFA/Drivers/Board/Dataflash.h instead.
#endif
/* Private Interface - For use in library only: */
#if !defined(__DOXYGEN__)
/* Macros: */
#define DATAFLASH_CHIPCS_MASK // TODO: Replace this with a mask of all the /CS pins of all Dataflashes
#define DATAFLASH_CHIPCS_DDR // TODO: Replace with the DDR register name for the board's Dataflash ICs
#define DATAFLASH_CHIPCS_PORT // TODO: Replace with the PORT register name for the board's Dataflash ICs
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** Constant indicating the total number of dataflash ICs mounted on the selected board. */
#define DATAFLASH_TOTALCHIPS // TODO: Replace with the number of Dataflashes on the board, max 2
/** Mask for no dataflash chip selected. */
#define DATAFLASH_NO_CHIP DATAFLASH_CHIPCS_MASK
/** Mask for the first dataflash chip selected. */
#define DATAFLASH_CHIP1 // TODO: Replace with mask to hold /CS of first Dataflash low, and all others high
/** Mask for the second dataflash chip selected. */
#define DATAFLASH_CHIP2 // TODO: Replace with mask to hold /CS of second Dataflash low, and all others high
/** Internal main memory page size for the board's dataflash ICs. */
#define DATAFLASH_PAGE_SIZE // TODO: Replace with the page size for the Dataflash ICs
/** Total number of pages inside each of the board's dataflash ICs. */
#define DATAFLASH_PAGES // TODO: Replace with the total number of pages inside one of the Dataflash ICs
/* Inline Functions: */
/** Initialises the dataflash driver so that commands and data may be sent to an attached dataflash IC.
* The AVR's SPI driver MUST be initialized before any of the dataflash commands are used.
*/
static inline void Dataflash_Init(void)
{
DATAFLASH_CHIPCS_DDR |= DATAFLASH_CHIPCS_MASK;
DATAFLASH_CHIPCS_PORT |= DATAFLASH_CHIPCS_MASK;
}
/** Determines the currently selected dataflash chip.
*
* \return Mask of the currently selected Dataflash chip, either \ref DATAFLASH_NO_CHIP if no chip is selected
* or a DATAFLASH_CHIPn mask (where n is the chip number).
*/
static inline uint8_t Dataflash_GetSelectedChip(void) ATTR_ALWAYS_INLINE ATTR_WARN_UNUSED_RESULT;
static inline uint8_t Dataflash_GetSelectedChip(void)
{
return (DATAFLASH_CHIPCS_PORT & DATAFLASH_CHIPCS_MASK);
}
/** Selects the given dataflash chip.
*
* \param[in] ChipMask Mask of the Dataflash IC to select, in the form of DATAFLASH_CHIPn mask (where n is
* the chip number).
*/
static inline void Dataflash_SelectChip(const uint8_t ChipMask) ATTR_ALWAYS_INLINE;
static inline void Dataflash_SelectChip(const uint8_t ChipMask)
{
DATAFLASH_CHIPCS_PORT = ((DATAFLASH_CHIPCS_PORT & ~DATAFLASH_CHIPCS_MASK) | ChipMask);
}
/** Deselects the current dataflash chip, so that no dataflash is selected. */
static inline void Dataflash_DeselectChip(void) ATTR_ALWAYS_INLINE;
static inline void Dataflash_DeselectChip(void)
{
Dataflash_SelectChip(DATAFLASH_NO_CHIP);
}
/** Selects a dataflash IC from the given page number, which should range from 0 to
* ((DATAFLASH_PAGES * DATAFLASH_TOTALCHIPS) - 1). For boards containing only one
* dataflash IC, this will select DATAFLASH_CHIP1. If the given page number is outside
* the total number of pages contained in the boards dataflash ICs, all dataflash ICs
* are deselected.
*
* \param[in] PageAddress Address of the page to manipulate, ranging from
* ((DATAFLASH_PAGES * DATAFLASH_TOTALCHIPS) - 1).
*/
static inline void Dataflash_SelectChipFromPage(const uint16_t PageAddress)
{
Dataflash_DeselectChip();
if (PageAddress >= (DATAFLASH_PAGES * DATAFLASH_TOTALCHIPS))
return;
#if (DATAFLASH_TOTALCHIPS == 2)
if (PageAddress & 0x01)
Dataflash_SelectChip(DATAFLASH_CHIP2);
else
Dataflash_SelectChip(DATAFLASH_CHIP1);
#else
Dataflash_SelectChip(DATAFLASH_CHIP1);
#endif
}
/** Toggles the select line of the currently selected dataflash IC, so that it is ready to receive
* a new command.
*/
static inline void Dataflash_ToggleSelectedChipCS(void)
{
uint8_t SelectedChipMask = Dataflash_GetSelectedChip();
Dataflash_DeselectChip();
Dataflash_SelectChip(SelectedChipMask);
}
/** Spin-loops while the currently selected dataflash is busy executing a command, such as a main
* memory page program or main memory to buffer transfer.
*/
static inline void Dataflash_WaitWhileBusy(void)
{
Dataflash_ToggleSelectedChipCS();
Dataflash_SendByte(DF_CMD_GETSTATUS);
while (!(Dataflash_ReceiveByte() & DF_STATUS_READY));
Dataflash_ToggleSelectedChipCS();
}
/** Sends a set of page and buffer address bytes to the currently selected dataflash IC, for use with
* dataflash commands which require a complete 24-byte address.
*
* \param[in] PageAddress Page address within the selected dataflash IC
* \param[in] BufferByte Address within the dataflash's buffer
*/
static inline void Dataflash_SendAddressBytes(uint16_t PageAddress, const uint16_t BufferByte)
{
#if (DATAFLASH_TOTALCHIPS == 2)
PageAddress >>= 1;
#endif
Dataflash_SendByte(PageAddress >> 5);
Dataflash_SendByte((PageAddress << 3) | (BufferByte >> 8));
Dataflash_SendByte(BufferByte);
}
#endif

View File

@ -0,0 +1,97 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/*
This is a stub driver header file, for implementing custom board
layout hardware with compatible LUFA board specific drivers. If
the library is configured to use the BOARD_USER board mode, this
driver file should be completed and copied into the "/Board/" folder
inside the application's folder.
This stub is for the board-specific component of the LUFA Joystick
driver, a small surface mount four-way (plus button) digital joystick
on most USB AVR boards.
*/
#ifndef __JOYSTICK_USER_H__
#define __JOYSTICK_USER_H__
/* Includes: */
#include <avr/io.h>
// TODO: Add any required includes here
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_JOYSTICK_H)
#error Do not include this file directly. Include LUFA/Drivers/Board/Joystick.h instead.
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** Mask for the joystick being pushed in the left direction. */
#define JOY_LEFT // TODO: Add mask to indicate joystick left position here
/** Mask for the joystick being pushed in the right direction. */
#define JOY_RIGHT // TODO: Add mask to indicate joystick right position here
/** Mask for the joystick being pushed in the upward direction. */
#define JOY_UP // TODO: Add mask to indicate joystick up position here
/** Mask for the joystick being pushed in the downward direction. */
#define JOY_DOWN // TODO: Add mask to indicate joystick down position here
/** Mask for the joystick being pushed inward. */
#define JOY_PRESS // TODO: Add mask to indicate joystick pressed position here
/* Inline Functions: */
#if !defined(__DOXYGEN__)
static inline void Joystick_Init(void)
{
// TODO: Initialize joystick port pins as inputs with pull-ups
}
static inline uint8_t Joystick_GetStatus(void) ATTR_WARN_UNUSED_RESULT;
static inline uint8_t Joystick_GetStatus(void)
{
// TODO: Return current joystick position data which can be obtained by masking against the JOY_* macros
}
#endif
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif

View File

@ -0,0 +1,124 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/*
This is a stub driver header file, for implementing custom board
layout hardware with compatible LUFA board specific drivers. If
the library is configured to use the BOARD_USER board mode, this
driver file should be completed and copied into the "/Board/" folder
inside the application's folder.
This stub is for the board-specific component of the LUFA LEDs driver,
for the LEDs (up to four) mounted on most USB AVR boards.
*/
#ifndef __LEDS_USER_H__
#define __LEDS_USER_H__
/* Includes: */
#include <avr/io.h>
// TODO: Add any required includes here
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_LEDS_H)
#error Do not include this file directly. Include LUFA/Drivers/Board/LEDS.h instead.
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** LED mask for the first LED on the board. */
#define LEDS_LED1 // TODO: Add mask for first board LED here
/** LED mask for the second LED on the board. */
#define LEDS_LED2 // TODO: Add mask for second board LED here
/** LED mask for the third LED on the board. */
#define LEDS_LED3 // TODO: Add mask for third board LED here
/** LED mask for the fourth LED on the board. */
#define LEDS_LED4 // TODO: Add mask for fourth board LED here
/** LED mask for all the LEDs on the board. */
#define LEDS_ALL_LEDS (LEDS_LED1 | LEDS_LED2 | LEDS_LED3 | LEDS_LED4)
/** LED mask for the none of the board LEDs. */
#define LEDS_NO_LEDS 0
/* Inline Functions: */
#if !defined(__DOXYGEN__)
static inline void LEDs_Init(void)
{
// TODO: Add code to initialize LED port pins as outputs here
}
static inline void LEDs_TurnOnLEDs(const uint8_t LEDMask)
{
// TODO: Add code to turn on LEDs given in the LEDMask mask here, leave others as-is
}
static inline void LEDs_TurnOffLEDs(const uint8_t LEDMask)
{
// TODO: Add code to turn off LEDs given in the LEDMask mask here, leave others as-is
}
static inline void LEDs_SetAllLEDs(const uint8_t LEDMask)
{
// TODO: Add code to turn on only LEDs given in the LEDMask mask here, all others off
}
static inline void LEDs_ChangeLEDs(const uint8_t LEDMask, const uint8_t ActiveMask)
{
// TODO: Add code to set the Leds in the given LEDMask to the status given in ActiveMask here
}
static inline void LEDs_ToggleLEDs(const uint8_t LEDMask)
{
// TODO: Add code to toggle the Leds in the given LEDMask, ignoring all others
}
static inline uint8_t LEDs_GetLEDs(void) ATTR_WARN_UNUSED_RESULT;
static inline uint8_t LEDs_GetLEDs(void)
{
// TODO: Add code to return the current LEDs status' here which can be masked against LED_LED* macros
}
#endif
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif

View File

@ -0,0 +1,97 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Board specific Buttons driver header for the ATAVRUSBRF01.
*
* Board specific Buttons driver header for the ATAVRUSBRF01.
*
* \note This file should not be included directly. It is automatically included as needed by the Buttons driver
* dispatch header located in LUFA/Drivers/Board/Buttons.h.
*/
/** \ingroup Group_Buttons
* @defgroup Group_Buttons_ATAVRUSBRF01 ATAVRUSBRF01
*
* Board specific Buttons driver header for the ATAVRUSBRF01.
*
* \note This file should not be included directly. It is automatically included as needed by the Buttons driver
* dispatch header located in LUFA/Drivers/Board/Buttons.h.
*
* @{
*/
#ifndef __BUTTONS_ATAVRUSBRF01_H__
#define __BUTTONS_ATAVRUSBRF01_H__
/* Includes: */
#include <avr/io.h>
#include <stdbool.h>
#include "../../../Common/Common.h"
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_BUTTONS_H)
#error Do not include this file directly. Include LUFA/Drivers/Board/Buttons.h instead.
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** Button mask for the first button on the board. */
#define BUTTONS_BUTTON1 (1 << 7)
/* Inline Functions: */
#if !defined(__DOXYGEN__)
static inline void Buttons_Init(void)
{
DDRD &= ~BUTTONS_BUTTON1;
PORTD |= BUTTONS_BUTTON1;
}
static inline uint8_t Buttons_GetStatus(void) ATTR_WARN_UNUSED_RESULT;
static inline uint8_t Buttons_GetStatus(void)
{
return ((PIND & BUTTONS_BUTTON1) ^ BUTTONS_BUTTON1);
}
#endif
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,140 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Board specific LED driver header for the ATAVRUSBRF01.
*
* Board specific LED driver header for the ATAVRUSBRF01.
*
* \note This file should not be included directly. It is automatically included as needed by the LEDs driver
* dispatch header located in LUFA/Drivers/Board/LEDs.h.
*/
/** \ingroup Group_LEDs
* @defgroup Group_LEDs_ATAVRUSBRF01 ATAVRUSBRF01
*
* Board specific LED driver header for the ATAVRUSBRF01.
*
* \note This file should not be included directly. It is automatically included as needed by the LEDs driver
* dispatch header located in LUFA/Drivers/Board/LEDs.h.
*
* @{
*/
#ifndef __LEDS_ATAVRUSBRF01_H__
#define __LEDS_ATAVRUSBRF01_H__
/* Includes: */
#include <avr/io.h>
#include "../../../Common/Common.h"
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_LEDS_H)
#error Do not include this file directly. Include LUFA/Drivers/Board/LEDS.h instead.
#endif
/* Private Interface - For use in library only: */
#if !defined(__DOXYGEN__)
/* Macros: */
#define LEDS_PORTD_LEDS (LEDS_LED1 | LEDS_LED2)
#define LEDS_PORTE_LEDS (LEDS_LED3 | LEDS_LED4)
#define LEDS_PORTE_MASK_SHIFT 4
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** LED mask for the first LED on the board. */
#define LEDS_LED1 (1 << 0)
/** LED mask for the second LED on the board. */
#define LEDS_LED2 (1 << 1)
/** LED mask for all the LEDs on the board. */
#define LEDS_ALL_LEDS (LEDS_LED1 | LEDS_LED2)
/** LED mask for the none of the board LEDs. */
#define LEDS_NO_LEDS 0
/* Inline Functions: */
#if !defined(__DOXYGEN__)
static inline void LEDs_Init(void)
{
DDRD |= LEDS_ALL_LEDS;
PORTD &= ~LEDS_ALL_LEDS;
}
static inline void LEDs_TurnOnLEDs(const uint8_t LEDMask)
{
PORTD |= (LEDMask & LEDS_ALL_LEDS);
}
static inline void LEDs_TurnOffLEDs(const uint8_t LEDMask)
{
PORTD &= ~(LEDMask & LEDS_ALL_LEDS);
}
static inline void LEDs_SetAllLEDs(const uint8_t LEDMask)
{
PORTD = (PORTD & ~LEDS_ALL_LEDS) | (LEDMask & LEDS_ALL_LEDS);
}
static inline void LEDs_ChangeLEDs(const uint8_t LEDMask,
const uint8_t ActiveMask)
{
PORTD = ((PORTD & ~(LEDMask & LEDS_ALL_LEDS)) | (ActiveMask & LEDS_ALL_LEDS));
}
static inline void LEDs_ToggleLEDs(const uint8_t LEDMask)
{
PORTD = (PORTD ^ (LEDMask & LEDS_ALL_LEDS));
}
static inline uint8_t LEDs_GetLEDs(void) ATTR_WARN_UNUSED_RESULT;
static inline uint8_t LEDs_GetLEDs(void)
{
return (PORTD & LEDS_ALL_LEDS);
}
#endif
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,97 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Board specific Buttons driver header for the Benito.
*
* Board specific Buttons driver header for the Benito (http://dorkbotpdx.org/wiki/benito).
*
* \note This file should not be included directly. It is automatically included as needed by the Buttons driver
* dispatch header located in LUFA/Drivers/Board/Buttons.h.
*/
/** \ingroup Group_Buttons
* @defgroup Group_Buttons_BENITO BENITO
*
* Board specific Buttons driver header for the Benito (http://dorkbotpdx.org/wiki/benito).
*
* \note This file should not be included directly. It is automatically included as needed by the Buttons driver
* dispatch header located in LUFA/Drivers/Board/Buttons.h.
*
* @{
*/
#ifndef __BUTTONS_BENITO_H__
#define __BUTTONS_BENITO_H__
/* Includes: */
#include <avr/io.h>
#include <stdbool.h>
#include "../../../Common/Common.h"
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_BUTTONS_H)
#error Do not include this file directly. Include LUFA/Drivers/Board/Buttons.h instead.
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** Button mask for the first button on the board. */
#define BUTTONS_BUTTON1 (1 << 7)
/* Inline Functions: */
#if !defined(__DOXYGEN__)
static inline void Buttons_Init(void)
{
DDRD &= ~BUTTONS_BUTTON1;
PORTD |= BUTTONS_BUTTON1;
}
static inline uint8_t Buttons_GetStatus(void) ATTR_WARN_UNUSED_RESULT;
static inline uint8_t Buttons_GetStatus(void)
{
return ((PIND & BUTTONS_BUTTON1) ^ BUTTONS_BUTTON1);
}
#endif
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,129 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Board specific LED driver header for the Benito.
*
* Board specific LED driver header for the Benito (http://dorkbotpdx.org/wiki/benito).
*
* \note This file should not be included directly. It is automatically included as needed by the LEDs driver
* dispatch header located in LUFA/Drivers/Board/LEDs.h.
*/
/** \ingroup Group_LEDs
* @defgroup Group_LEDs_BENITO BENITO
*
* Board specific LED driver header for the Benito (http://dorkbotpdx.org/wiki/benito).
*
* \note This file should not be included directly. It is automatically included as needed by the LEDs driver
* dispatch header located in LUFA/Drivers/Board/LEDs.h.
*
* @{
*/
#ifndef __LEDS_BENITO_H__
#define __LEDS_BENITO_H__
/* Includes: */
#include <avr/io.h>
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(INCLUDE_FROM_LEDS_H)
#error Do not include this file directly. Include LUFA/Drivers/Board/LEDS.h instead.
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** LED mask for the first LED on the board. */
#define LEDS_LED1 (1 << 7)
/** LED mask for the second LED on the board. */
#define LEDS_LED2 (1 << 6)
/** LED mask for all the LEDs on the board. */
#define LEDS_ALL_LEDS (LEDS_LED1 | LEDS_LED2)
/** LED mask for the none of the board LEDs. */
#define LEDS_NO_LEDS 0
/* Inline Functions: */
#if !defined(__DOXYGEN__)
static inline void LEDs_Init(void)
{
DDRC |= LEDS_ALL_LEDS;
PORTC |= LEDS_ALL_LEDS;
}
static inline void LEDs_TurnOnLEDs(const uint8_t LEDMask)
{
PORTC &= ~LEDMask;
}
static inline void LEDs_TurnOffLEDs(const uint8_t LEDMask)
{
PORTC |= LEDMask;
}
static inline void LEDs_SetAllLEDs(const uint8_t LEDMask)
{
PORTC = ((PORTC | LEDS_ALL_LEDS) & ~LEDMask);
}
static inline void LEDs_ChangeLEDs(const uint8_t LEDMask,
const uint8_t ActiveMask)
{
PORTC = ((PORTC | ActiveMask) & ~LEDMask);
}
static inline void LEDs_ToggleLEDs(const uint8_t LEDMask)
{
PORTC ^= LEDMask;
}
static inline uint8_t LEDs_GetLEDs(void) ATTR_WARN_UNUSED_RESULT;
static inline uint8_t LEDs_GetLEDs(void)
{
return (PORTC & LEDS_ALL_LEDS);
}
#endif
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,102 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Board specific Buttons driver header for the BUMBLEB.
*
* Board specific Buttons driver header for the BUMBLEB (http://fletchtronics.net/bumble-b).
*
* The BUMBLEB third-party board does not include any on-board peripherals, but does have an officially recommended
* external peripheral layout for buttons, LEDs and a Joystick.
*
* \note This file should not be included directly. It is automatically included as needed by the Buttons driver
* dispatch header located in LUFA/Drivers/Board/Buttons.h.
*/
/** \ingroup Group_Buttons
* @defgroup Group_Buttons_BUMBLEB BUMBLEB
*
* Board specific buttons driver header for the BUMBLEB (http://fletchtronics.net/bumble-b). The BUMBLEB third-party
* board does not include any on-board peripherals, but does have an officially recommended external peripheral layout
* for buttons, LEDs and a Joystick.
*
* \note This file should not be included directly. It is automatically included as needed by the Buttons driver
* dispatch header located in LUFA/Drivers/Board/Buttons.h.
*
* @{
*/
#ifndef __BUTTONS_BUMBLEB_H__
#define __BUTTONS_BUMBLEB_H__
/* Includes: */
#include <avr/io.h>
#include <stdbool.h>
#include "../../../Common/Common.h"
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_BUTTONS_H)
#error Do not include this file directly. Include LUFA/Drivers/Board/Buttons.h instead.
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** Button mask for the first button on the board. */
#define BUTTONS_BUTTON1 (1 << 7)
/* Inline Functions: */
#if !defined(__DOXYGEN__)
static inline void Buttons_Init(void)
{
DDRD &= ~BUTTONS_BUTTON1;
PORTD |= BUTTONS_BUTTON1;
}
static inline uint8_t Buttons_GetStatus(void) ATTR_WARN_UNUSED_RESULT;
static inline uint8_t Buttons_GetStatus(void)
{
return ((PIND & BUTTONS_BUTTON1) ^ BUTTONS_BUTTON1);
}
#endif
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,119 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Board specific joystick driver header for the BUMLEB.
*
* Board specific joystick driver header for the BUMBLEB (http://fletchtronics.net/bumble-b).
*
* The BUMBLEB third-party board does not include any on-board peripherals, but does have an officially recommended
* external peripheral layout for buttons, LEDs and a Joystick.
*
* \note This file should not be included directly. It is automatically included as needed by the joystick driver
* dispatch header located in LUFA/Drivers/Board/Joystick.h.
*/
/** \ingroup Group_Joystick
* @defgroup Group_Joystick_BUMBLEB BUMBLEB
*
* Board specific joystick driver header for the BUMBLEB (http://fletchtronics.net/bumble-b). The BUMBLEB third-party
* board does not include any on-board peripherals, but does have an officially recommended external peripheral layout
* for buttons, LEDs and a Joystick.
*
* \note This file should not be included directly. It is automatically included as needed by the joystick driver
* dispatch header located in LUFA/Drivers/Board/Joystick.h.
*
* @{
*/
#ifndef __JOYSTICK_BUMBLEB_H__
#define __JOYSTICK_BUMBLEB_H__
/* Includes: */
#include <avr/io.h>
#include "../../../Common/Common.h"
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_JOYSTICK_H)
#error Do not include this file directly. Include LUFA/Drivers/Board/Joystick.h instead.
#endif
/* Private Interface - For use in library only: */
#if !defined(__DOXYGEN__)
/* Macros: */
#define JOY_MASK ((1 << 0) | (1 << 1) | (1 << 2) | (1 << 3) | (1 << 4))
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** Mask for the joystick being pushed in the left direction. */
#define JOY_LEFT (1 << 2)
/** Mask for the joystick being pushed in the upward direction. */
#define JOY_UP (1 << 3)
/** Mask for the joystick being pushed in the right direction. */
#define JOY_RIGHT (1 << 0)
/** Mask for the joystick being pushed in the downward direction. */
#define JOY_DOWN (1 << 1)
/** Mask for the joystick being pushed inward. */
#define JOY_PRESS (1 << 4)
/* Inline Functions: */
#if !defined(__DOXYGEN__)
static inline void Joystick_Init(void)
{
DDRD &= ~JOY_MASK;
PORTD |= JOY_MASK;
}
static inline uint8_t Joystick_GetStatus(void) ATTR_WARN_UNUSED_RESULT;
static inline uint8_t Joystick_GetStatus(void)
{
return (uint8_t)(~PIND & JOY_MASK);
}
#endif
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,137 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Board specific LED driver header for the BUMBLEB.
*
* Board specific LED driver header for the BUMBLEB (http://fletchtronics.net/bumble-b).
*
* The BUMBLEB third-party board does not include any on-board peripherals, but does have an officially recommended
* external peripheral layout for buttons, LEDs and a Joystick.
*
* \note This file should not be included directly. It is automatically included as needed by the LEDs driver
* dispatch header located in LUFA/Drivers/Board/LEDs.h.
*/
/** \ingroup Group_LEDs
* @defgroup Group_LEDs_BUMBLEB BUMBLEB
*
* Board specific LED driver header for the BUMBLEB (http://fletchtronics.net/bumble-b). The BUMBLEB third-party board
* does not include any on-board peripherals, but does have an officially recommended external peripheral layout for
* buttons, LEDs and a Joystick.
*
* \note This file should not be included directly. It is automatically included as needed by the LEDs driver
* dispatch header located in LUFA/Drivers/Board/LEDs.h.
*
* @{
*/
#ifndef __LEDS_BUMBLEB_H__
#define __LEDS_BUMBLEB_H__
/* Includes: */
#include <avr/io.h>
#include "../../../Common/Common.h"
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_LEDS_H)
#error Do not include this file directly. Include LUFA/Drivers/Board/LEDS.h instead.
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** LED mask for the first LED on the board. */
#define LEDS_LED1 (1 << 4)
/** LED mask for the second LED on the board. */
#define LEDS_LED2 (1 << 5)
/** LED mask for the third LED on the board. */
#define LEDS_LED3 (1 << 6)
/** LED mask for the fourth LED on the board. */
#define LEDS_LED4 (1 << 7)
/** LED mask for all the LEDs on the board. */
#define LEDS_ALL_LEDS (LEDS_LED1 | LEDS_LED2 | LEDS_LED3 | LEDS_LED4)
/** LED mask for the none of the board LEDs. */
#define LEDS_NO_LEDS 0
/* Inline Functions: */
#if !defined(__DOXYGEN__)
static inline void LEDs_Init(void)
{
DDRB |= LEDS_ALL_LEDS;
PORTB &= ~LEDS_ALL_LEDS;
}
static inline void LEDs_TurnOnLEDs(const uint8_t LedMask)
{
PORTB |= LedMask;
}
static inline void LEDs_TurnOffLEDs(const uint8_t LedMask)
{
PORTB &= ~LedMask;
}
static inline void LEDs_SetAllLEDs(const uint8_t LedMask)
{
PORTB = ((PORTB & ~LEDS_ALL_LEDS) | LedMask);
}
static inline void LEDs_ChangeLEDs(const uint8_t LedMask,
const uint8_t ActiveMask)
{
PORTB = ((PORTB & ~LedMask) | ActiveMask);
}
static inline uint8_t LEDs_GetLEDs(void) ATTR_WARN_UNUSED_RESULT;
static inline uint8_t LEDs_GetLEDs(void)
{
return (PORTB & LEDS_ALL_LEDS);
}
#endif
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,118 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Master include file for the board digital button driver.
*
* This file is the master dispatch header file for the board-specific Buttons driver, for boards containing
* physical pushbuttons connected to the AVR's GPIO pins.
*
* User code should include this file, which will in turn include the correct Button driver header file for the
* currently selected board.
*
* If the BOARD value is set to BOARD_USER, this will include the /Board/Buttons.h file in the user project
* directory.
*/
/** \ingroup Group_BoardDrivers
* @defgroup Group_Buttons Buttons Driver - LUFA/Drivers/Board/Buttons.h
*
* \section Sec_Dependencies Module Source Dependencies
* The following files must be built with any user project that uses this module:
* - None
*
* \section Module Description
* Hardware buttons driver. This provides an easy to use driver for the hardware buttons present on many boards.
* It provides a way to easily configure and check the status of all the buttons on the board so that appropriate
* actions can be taken.
*
* If the BOARD value is set to BOARD_USER, this will include the /Board/Dataflash.h file in the user project
* directory. Otherwise, it will include the appropriate built in board driver header file.
*
* @{
*/
#ifndef __BUTTONS_H__
#define __BUTTONS_H__
/* Macros: */
#if !defined(__DOXYGEN__)
#define __INCLUDE_FROM_BUTTONS_H
#define INCLUDE_FROM_BUTTONS_H
#endif
/* Includes: */
#include "../../Common/Common.h"
#if (BOARD == BOARD_NONE)
#error The Board Buttons driver cannot be used if the makefile BOARD option is not set.
#elif (BOARD == BOARD_USBKEY)
#include "USBKEY/Buttons.h"
#elif (BOARD == BOARD_STK525)
#include "STK525/Buttons.h"
#elif (BOARD == BOARD_STK526)
#include "STK526/Buttons.h"
#elif (BOARD == BOARD_ATAVRUSBRF01)
#include "ATAVRUSBRF01/Buttons.h"
#elif (BOARD == BOARD_BUMBLEB)
#include "BUMBLEB/Buttons.h"
#elif (BOARD == BOARD_EVK527)
#include "EVK527/Buttons.h"
#elif (BOARD == BOARD_USBTINYMKII)
#include "USBTINYMKII/Buttons.h"
#elif (BOARD == BOARD_BENITO)
#include "BENITO/Buttons.h"
#elif (BOARD == BOARD_JMDBU2)
#include "JMDBU2/Buttons.h"
#elif (BOARD == BOARD_USER)
#include "Board/Buttons.h"
#else
#error The selected board does not contain any GPIO buttons.
#endif
/* Pseudo-Functions for Doxygen: */
#if defined(__DOXYGEN__)
/** Initialises the BUTTONS driver, so that the current button position can be read. This sets the appropriate
* I/O pins to an inputs with pull-ups enabled.
*
* This must be called before any Button driver functions are used.
*/
static inline void Buttons_Init(void);
/** Returns a mask indicating which board buttons are currently pressed.
*
* \return Mask indicating which board buttons are currently pressed.
*/
static inline uint8_t Buttons_GetStatus(void) ATTR_WARN_UNUSED_RESULT;
#endif
#endif
/** @} */

View File

@ -0,0 +1,207 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Master include file for the board dataflash IC driver.
*
* This file is the master dispatch header file for the board-specific dataflash driver, for boards containing
* dataflash ICs for external non-volatile storage.
*
* User code should include this file, which will in turn include the correct dataflash driver header file for
* the currently selected board.
*
* If the BOARD value is set to BOARD_USER, this will include the /Board/Dataflash.h file in the user project
* directory.
*/
/** \ingroup Group_BoardDrivers
* @defgroup Group_Dataflash Dataflash Driver - LUFA/Drivers/Board/Dataflash.h
*
* \section Sec_Dependencies Module Source Dependencies
* The following files must be built with any user project that uses this module:
* - None
*
* \section Module Description
* Dataflash driver. This module provides an easy to use interface for the Dataflash ICs located on many boards,
* for the storage of large amounts of data into the Dataflash's non-volatile memory.
*
* If the BOARD value is set to BOARD_USER, this will include the /Board/Dataflash.h file in the user project
* directory. Otherwise, it will include the appropriate built in board driver header file.
*
* @{
*/
#ifndef __DATAFLASH_H__
#define __DATAFLASH_H__
/* Macros: */
#if !defined(__DOXYGEN__)
#define __INCLUDE_FROM_DATAFLASH_H
#define INCLUDE_FROM_DATAFLASH_H
#endif
/* Includes: */
#include "../Peripheral/SPI.h"
#include "../../Common/Common.h"
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
#if !defined(__DOXYGEN__)
#define __GET_DATAFLASH_MASK2(x, y) x ## y
#define __GET_DATAFLASH_MASK(x) __GET_DATAFLASH_MASK2(DATAFLASH_CHIP,x)
#endif
/** Retrieves the Dataflash chip select mask for the given Dataflash chip index.
*
* \param[in] index Index of the dataflash chip mask to retrieve
*
* \return Mask for the given Dataflash chip's /CS pin
*/
#define DATAFLASH_CHIP_MASK(index) __GET_DATAFLASH_MASK(index)
/* Inline Functions: */
/** Initialises the dataflash driver so that commands and data may be sent to an attached dataflash IC.
* The AVR's SPI driver MUST be initialized before any of the dataflash commands are used.
*/
static inline void Dataflash_Init(void);
/** Determines the currently selected dataflash chip.
*
* \return Mask of the currently selected Dataflash chip, either \ref DATAFLASH_NO_CHIP if no chip is selected
* or a DATAFLASH_CHIPn mask (where n is the chip number).
*/
static inline uint8_t Dataflash_GetSelectedChip(void) ATTR_ALWAYS_INLINE ATTR_WARN_UNUSED_RESULT;
/** Selects the given dataflash chip.
*
* \param[in] ChipMask Mask of the Dataflash IC to select, in the form of DATAFLASH_CHIPn mask (where n is
* the chip number).
*/
static inline void Dataflash_SelectChip(const uint8_t ChipMask) ATTR_ALWAYS_INLINE;
/** Deselects the current dataflash chip, so that no dataflash is selected. */
static inline void Dataflash_DeselectChip(void) ATTR_ALWAYS_INLINE;
/** Selects a dataflash IC from the given page number, which should range from 0 to
* ((DATAFLASH_PAGES * DATAFLASH_TOTALCHIPS) - 1). For boards containing only one
* dataflash IC, this will select DATAFLASH_CHIP1. If the given page number is outside
* the total number of pages contained in the boards dataflash ICs, all dataflash ICs
* are deselected.
*
* \param[in] PageAddress Address of the page to manipulate, ranging from
* ((DATAFLASH_PAGES * DATAFLASH_TOTALCHIPS) - 1).
*/
static inline void Dataflash_SelectChipFromPage(const uint16_t PageAddress);
/** Toggles the select line of the currently selected dataflash IC, so that it is ready to receive
* a new command.
*/
static inline void Dataflash_ToggleSelectedChipCS(void);
/** Spin-loops while the currently selected dataflash is busy executing a command, such as a main
* memory page program or main memory to buffer transfer.
*/
static inline void Dataflash_WaitWhileBusy(void);
/** Sends a set of page and buffer address bytes to the currently selected dataflash IC, for use with
* dataflash commands which require a complete 24-byte address.
*
* \param[in] PageAddress Page address within the selected dataflash IC
* \param[in] BufferByte Address within the dataflash's buffer
*/
static inline void Dataflash_SendAddressBytes(uint16_t PageAddress,
const uint16_t BufferByte);
/** Sends a byte to the currently selected dataflash IC, and returns a byte from the dataflash.
*
* \param[in] Byte of data to send to the dataflash
*
* \return Last response byte from the dataflash
*/
static inline uint8_t Dataflash_TransferByte(const uint8_t Byte) ATTR_ALWAYS_INLINE;
static inline uint8_t Dataflash_TransferByte(const uint8_t Byte)
{
return SPI_TransferByte(Byte);
}
/** Sends a byte to the currently selected dataflash IC, and ignores the next byte from the dataflash.
*
* \param[in] Byte of data to send to the dataflash
*/
static inline void Dataflash_SendByte(const uint8_t Byte) ATTR_ALWAYS_INLINE;
static inline void Dataflash_SendByte(const uint8_t Byte)
{
SPI_SendByte(Byte);
}
/** Sends a dummy byte to the currently selected dataflash IC, and returns the next byte from the dataflash.
*
* \return Last response byte from the dataflash
*/
static inline uint8_t Dataflash_ReceiveByte(void) ATTR_ALWAYS_INLINE ATTR_WARN_UNUSED_RESULT;
static inline uint8_t Dataflash_ReceiveByte(void)
{
return SPI_ReceiveByte();
}
/* Includes: */
#if (BOARD == BOARD_NONE)
#error The Board Buttons driver cannot be used if the makefile BOARD option is not set.
#elif (BOARD == BOARD_USBKEY)
#include "USBKEY/Dataflash.h"
#elif (BOARD == BOARD_STK525)
#include "STK525/Dataflash.h"
#elif (BOARD == BOARD_STK526)
#include "STK526/Dataflash.h"
#elif (BOARD == BOARD_XPLAIN)
#include "XPLAIN/Dataflash.h"
#elif (BOARD == BOARD_XPLAIN_REV1)
#include "XPLAIN/Dataflash.h"
#elif (BOARD == BOARD_EVK527)
#include "EVK527/Dataflash.h"
#elif (BOARD == BOARD_USER)
#include "Board/Dataflash.h"
#else
#error The selected board does not contain a dataflash IC.
#endif
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,98 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Board specific Dataflash commands header for the AT45DB321C as mounted on the EVK527.
*
* Board specific Dataflash commands header for the AT45DB321C as mounted on the EVK527.
*
* \note This file should not be included directly. It is automatically included as needed by the dataflash driver
* dispatch header located in LUFA/Drivers/Board/Dataflash.h.
*/
/** \ingroup Group_Dataflash_EVK527
* @defgroup Group_Dataflash_EVK527_AT45DB321C AT45DB321C
*
* Board specific Dataflash commands header for the AT45DB321C as mounted on the EVK527.
*
* \note This file should not be included directly. It is automatically included as needed by the dataflash driver
* dispatch header located in LUFA/Drivers/Board/Dataflash.h.
*
* @{
*/
#ifndef __DATAFLASH_CMDS_H__
#define __DATAFLASH_CMDS_H__
/* Public Interface - May be used in end-application: */
/* Macros: */
#define DF_STATUS_READY (1 << 7)
#define DF_STATUS_COMPMISMATCH (1 << 6)
#define DF_STATUS_SECTORPROTECTION_ON (1 << 1)
#define DF_MANUFACTURER_ATMEL 0x1F
#define DF_CMD_GETSTATUS 0xD7
#define DF_CMD_MAINMEMTOBUFF1 0x53
#define DF_CMD_MAINMEMTOBUFF2 0x55
#define DF_CMD_MAINMEMTOBUFF1COMP 0x60
#define DF_CMD_MAINMEMTOBUFF2COMP 0x61
#define DF_CMD_AUTOREWRITEBUFF1 0x58
#define DF_CMD_AUTOREWRITEBUFF2 0x59
#define DF_CMD_MAINMEMPAGEREAD 0xD2
#define DF_CMD_CONTARRAYREAD_LF 0xE8
#define DF_CMD_BUFF1READ_LF 0xD4
#define DF_CMD_BUFF2READ_LF 0xD6
#define DF_CMD_BUFF1WRITE 0x84
#define DF_CMD_BUFF2WRITE 0x87
#define DF_CMD_BUFF1TOMAINMEMWITHERASE 0x83
#define DF_CMD_BUFF2TOMAINMEMWITHERASE 0x86
#define DF_CMD_BUFF1TOMAINMEM 0x88
#define DF_CMD_BUFF2TOMAINMEM 0x89
#define DF_CMD_MAINMEMPAGETHROUGHBUFF1 0x82
#define DF_CMD_MAINMEMPAGETHROUGHBUFF2 0x85
#define DF_CMD_PAGEERASE 0x81
#define DF_CMD_BLOCKERASE 0x50
#define DF_CMD_SECTORPROTECTIONOFF ((char[]){0x3D, 0x2A, 0x7F, 0xCF})
#define DF_CMD_SECTORPROTECTIONOFF_BYTE1 0x3D
#define DF_CMD_SECTORPROTECTIONOFF_BYTE2 0x2A
#define DF_CMD_SECTORPROTECTIONOFF_BYTE3 0x7F
#define DF_CMD_SECTORPROTECTIONOFF_BYTE4 0xCF
#define DF_CMD_READMANUFACTURERDEVICEINFO 0x9F
#endif
/** @} */

View File

@ -0,0 +1,103 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Board specific Buttons driver header for the EVK527.
*
* Board specific Buttons driver header for the EVK527.
*
* \note This file should not be included directly. It is automatically included as needed by the Buttons driver
* dispatch header located in LUFA/Drivers/Board/Buttons.h.
*/
/** \ingroup Group_Buttons
* @defgroup Group_Buttons_EVK527 EVK527
*
* Board specific Buttons driver header for the EVK527.
*
* \note This file should not be included directly. It is automatically included as needed by the Buttons driver
* dispatch header located in LUFA/Drivers/Board/Buttons.h.
*
* @{
*/
#ifndef __BUTTONS_EVK527_H__
#define __BUTTONS_EVK527_H__
/* Includes: */
#include <avr/io.h>
#include <stdbool.h>
#include "../../../Common/Common.h"
/* Includes: */
#include <avr/io.h>
#include <stdbool.h>
#include "../../../Common/Common.h"
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_BUTTONS_H)
#error Do not include this file directly. Include LUFA/Drivers/Board/Buttons.h instead.
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** Button mask for the first button on the board. */
#define BUTTONS_BUTTON1 (1 << 2)
/* Inline Functions: */
#if !defined(__DOXYGEN__)
static inline void Buttons_Init(void)
{
DDRE &= ~BUTTONS_BUTTON1;
PORTE |= BUTTONS_BUTTON1;
}
static inline uint8_t Buttons_GetStatus(void) ATTR_WARN_UNUSED_RESULT;
static inline uint8_t Buttons_GetStatus(void)
{
return ((PINE & BUTTONS_BUTTON1) ^ BUTTONS_BUTTON1);
}
#endif
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,183 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Board specific Dataflash driver header for the EVK527.
*
* Board specific Dataflash driver header for the EVK527.
*
* \note This file should not be included directly. It is automatically included as needed by the dataflash driver
* dispatch header located in LUFA/Drivers/Board/Dataflash.h.
*/
/** \ingroup Group_Dataflash
* @defgroup Group_Dataflash_EVK527 EVK527
*
* Board specific Dataflash driver header for the EVK527.
*
* \note This file should not be included directly. It is automatically included as needed by the dataflash driver
* dispatch header located in LUFA/Drivers/Board/Dataflash.h.
*
* @{
*/
#ifndef __DATAFLASH_EVK527_H__
#define __DATAFLASH_EVK527_H__
/* Includes: */
#include "AT45DB321C.h"
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_DATAFLASH_H)
#error Do not include this file directly. Include LUFA/Drivers/Board/Dataflash.h instead.
#endif
/* Private Interface - For use in library only: */
#if !defined(__DOXYGEN__)
/* Macros: */
#define DATAFLASH_CHIPCS_MASK (1 << 6)
#define DATAFLASH_CHIPCS_DDR DDRE
#define DATAFLASH_CHIPCS_PORT PORTE
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** Constant indicating the total number of dataflash ICs mounted on the selected board. */
#define DATAFLASH_TOTALCHIPS 1
/** Mask for no dataflash chip selected. */
#define DATAFLASH_NO_CHIP DATAFLASH_CHIPCS_MASK
/** Mask for the first dataflash chip selected. */
#define DATAFLASH_CHIP1 0
/** Internal main memory page size for the board's dataflash IC. */
#define DATAFLASH_PAGE_SIZE 512
/** Total number of pages inside the board's dataflash IC. */
#define DATAFLASH_PAGES 8192
/* Inline Functions: */
/** Initialises the dataflash driver so that commands and data may be sent to an attached dataflash IC.
* The AVR's SPI driver MUST be initialized before any of the dataflash commands are used.
*/
static inline void Dataflash_Init(void)
{
DATAFLASH_CHIPCS_DDR |= DATAFLASH_CHIPCS_MASK;
DATAFLASH_CHIPCS_PORT |= DATAFLASH_CHIPCS_MASK;
}
/** Determines the currently selected dataflash chip.
*
* \return Mask of the currently selected Dataflash chip, either \ref DATAFLASH_NO_CHIP if no chip is selected
* or a DATAFLASH_CHIPn mask (where n is the chip number).
*/
static inline uint8_t Dataflash_GetSelectedChip(void) ATTR_ALWAYS_INLINE ATTR_WARN_UNUSED_RESULT;
static inline uint8_t Dataflash_GetSelectedChip(void)
{
return (DATAFLASH_CHIPCS_PORT & DATAFLASH_CHIPCS_MASK);
}
/** Selects the given dataflash chip.
*
* \param[in] ChipMask Mask of the Dataflash IC to select, in the form of DATAFLASH_CHIPn mask (where n is
* the chip number).
*/
static inline void Dataflash_SelectChip(const uint8_t ChipMask) ATTR_ALWAYS_INLINE;
static inline void Dataflash_SelectChip(const uint8_t ChipMask)
{
DATAFLASH_CHIPCS_PORT = ((DATAFLASH_CHIPCS_PORT & ~DATAFLASH_CHIPCS_MASK) | ChipMask);
}
/** Deselects the current dataflash chip, so that no dataflash is selected. */
static inline void Dataflash_DeselectChip(void) ATTR_ALWAYS_INLINE;
static inline void Dataflash_DeselectChip(void)
{
Dataflash_SelectChip(DATAFLASH_NO_CHIP);
}
/** Selects a dataflash IC from the given page number, which should range from 0 to
* ((DATAFLASH_PAGES * DATAFLASH_TOTALCHIPS) - 1). For boards containing only one
* dataflash IC, this will select DATAFLASH_CHIP1. If the given page number is outside
* the total number of pages contained in the boards dataflash ICs, all dataflash ICs
* are deselected.
*
* \param[in] PageAddress Address of the page to manipulate, ranging from
* ((DATAFLASH_PAGES * DATAFLASH_TOTALCHIPS) - 1).
*/
static inline void Dataflash_SelectChipFromPage(const uint16_t PageAddress)
{
Dataflash_DeselectChip();
if (PageAddress >= DATAFLASH_PAGES)
return;
Dataflash_SelectChip(DATAFLASH_CHIP1);
}
/** Toggles the select line of the currently selected dataflash IC, so that it is ready to receive
* a new command.
*/
static inline void Dataflash_ToggleSelectedChipCS(void)
{
uint8_t SelectedChipMask = Dataflash_GetSelectedChip();
Dataflash_DeselectChip();
Dataflash_SelectChip(SelectedChipMask);
}
/** Spin-loops while the currently selected dataflash is busy executing a command, such as a main
* memory page program or main memory to buffer transfer.
*/
static inline void Dataflash_WaitWhileBusy(void)
{
Dataflash_ToggleSelectedChipCS();
Dataflash_SendByte(DF_CMD_GETSTATUS);
while (!(Dataflash_ReceiveByte() & DF_STATUS_READY));
Dataflash_ToggleSelectedChipCS();
}
/** Sends a set of page and buffer address bytes to the currently selected dataflash IC, for use with
* dataflash commands which require a complete 24-byte address.
*
* \param[in] PageAddress Page address within the selected dataflash IC
* \param[in] BufferByte Address within the dataflash's buffer
*/
static inline void Dataflash_SendAddressBytes(uint16_t PageAddress,
const uint16_t BufferByte)
{
Dataflash_SendByte(PageAddress >> 5);
Dataflash_SendByte((PageAddress << 3) | (BufferByte >> 8));
Dataflash_SendByte(BufferByte);
}
#endif
/** @} */

View File

@ -0,0 +1,118 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Board specific joystick driver header for the EVK527.
*
* Board specific joystick driver header for the EVK527.
*
* \note This file should not be included directly. It is automatically included as needed by the joystick driver
* dispatch header located in LUFA/Drivers/Board/Joystick.h.
*/
/** \ingroup Group_Joystick
* @defgroup Group_Joystick_EVK527 EVK527
*
* Board specific joystick driver header for the EVK527.
*
* \note This file should not be included directly. It is automatically included as needed by the joystick driver
* dispatch header located in LUFA/Drivers/Board/Joystick.h.
*
* @{
*/
#ifndef __JOYSTICK_EVK527_H__
#define __JOYSTICK_EVK527_H__
/* Includes: */
#include <avr/io.h>
#include "../../../Common/Common.h"
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_JOYSTICK_H)
#error Do not include this file directly. Include LUFA/Drivers/Board/Joystick.h instead.
#endif
/* Private Interface - For use in library only: */
#if !defined(__DOXYGEN__)
/* Macros: */
#define JOY_FMASK ((1 << 4) | (1 << 5) | (1 << 6) | (1 << 7))
#define JOY_CMASK (1 << 6))
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** Mask for the joystick being pushed in the left direction. */
#define JOY_LEFT (1 << 4)
/** Mask for the joystick being pushed in the right direction. */
#define JOY_RIGHT (1 << 7)
/** Mask for the joystick being pushed in the upward direction. */
#define JOY_UP (1 << 5)
/** Mask for the joystick being pushed in the downward direction. */
#define JOY_DOWN ((1 << 6) >> 3)
/** Mask for the joystick being pushed inward. */
#define JOY_PRESS (1 << 6)
/* Inline Functions: */
#if !defined(__DOXYGEN__)
static inline void Joystick_Init(void)
{
DDRF &= ~(JOY_FMASK);
DDRC &= ~(JOY_CMASK);
PORTF |= JOY_FMASK;
PORTC |= JOY_CMASK;
}
static inline uint8_t Joystick_GetStatus(void) ATTR_WARN_UNUSED_RESULT;
static inline uint8_t Joystick_GetStatus(void)
{
return (((uint8_t)~PINF & JOY_FMASK) | (((uint8_t)~PINC & JOY_CMASK) >> 3));
}
#endif
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,134 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Board specific LED driver header for the EVK527.
*
* Board specific LED driver header for the EVK527.
*
* \note This file should not be included directly. It is automatically included as needed by the LEDs driver
* dispatch header located in LUFA/Drivers/Board/LEDs.h.
*/
/** \ingroup Group_LEDs
* @defgroup Group_LEDs_EVK527 EVK527
*
* Board specific LED driver header for the EVK527.
*
* \note This file should not be included directly. It is automatically included as needed by the LEDs driver
* dispatch header located in LUFA/Drivers/Board/LEDs.h.
*
* @{
*/
#ifndef __LEDS_EVK527_H__
#define __LEDS_EVK527_H__
/* Includes: */
#include <avr/io.h>
#include "../../../Common/Common.h"
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_LEDS_H)
#error Do not include this file directly. Include LUFA/Drivers/Board/LEDS.h instead.
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** LED mask for the first LED on the board. */
#define LEDS_LED1 (1 << 5)
/** LED mask for the second LED on the board. */
#define LEDS_LED2 (1 << 6)
/** LED mask for the third LED on the board. */
#define LEDS_LED3 (1 << 7)
/** LED mask for all the LEDs on the board. */
#define LEDS_ALL_LEDS (LEDS_LED1 | LEDS_LED2 | LEDS_LED3)
/** LED mask for the none of the board LEDs. */
#define LEDS_NO_LEDS 0
/* Inline Functions: */
#if !defined(__DOXYGEN__)
static inline void LEDs_Init(void)
{
DDRD |= LEDS_ALL_LEDS;
PORTD &= ~LEDS_ALL_LEDS;
}
static inline void LEDs_TurnOnLEDs(const uint8_t LEDMask)
{
PORTD |= LEDMask;
}
static inline void LEDs_TurnOffLEDs(const uint8_t LEDMask)
{
PORTD &= ~LEDMask;
}
static inline void LEDs_SetAllLEDs(const uint8_t LEDMask)
{
PORTD = ((PORTD & ~LEDS_ALL_LEDS) | LEDMask);
}
static inline void LEDs_ChangeLEDs(const uint8_t LEDMask,
const uint8_t ActiveMask)
{
PORTD = ((PORTD & ~LEDMask) | ActiveMask);
}
static inline void LEDs_ToggleLEDs(const uint8_t LEDMask)
{
PORTD = (PORTD ^ (LEDMask & LEDS_ALL_LEDS));
}
static inline uint8_t LEDs_GetLEDs(void) ATTR_WARN_UNUSED_RESULT;
static inline uint8_t LEDs_GetLEDs(void)
{
return (PORTD & LEDS_ALL_LEDS);
}
#endif
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,97 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Board specific Buttons driver header for the JM-DB-U2.
*
* Board specific Buttons driver header for the JM-DB-U2 (http://u2.mattair.net/index.html).
*
* \note This file should not be included directly. It is automatically included as needed by the Buttons driver
* dispatch header located in LUFA/Drivers/Board/Buttons.h.
*/
/** \ingroup Group_Buttons
* @defgroup Group_Buttons_JMDBU2 JMDBU2
*
* Board specific Buttons driver header for the JM-DB-U2 (http://u2.mattair.net/index.html).
*
* \note This file should not be included directly. It is automatically included as needed by the Buttons driver
* dispatch header located in LUFA/Drivers/Board/Buttons.h.
*
* @{
*/
#ifndef __BUTTONS_JMDBU2_H__
#define __BUTTONS_JMDBU2_H__
/* Includes: */
#include <avr/io.h>
#include <stdbool.h>
#include "../../../Common/Common.h"
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_BUTTONS_H)
#error Do not include this file directly. Include LUFA/Drivers/Board/Buttons.h instead.
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** Button mask for the first button on the board. */
#define BUTTONS_BUTTON1 (1 << 7)
/* Inline Functions: */
#if !defined(__DOXYGEN__)
static inline void Buttons_Init(void)
{
DDRD &= ~BUTTONS_BUTTON1;
PORTD |= BUTTONS_BUTTON1;
}
static inline uint8_t Buttons_GetStatus(void) ATTR_WARN_UNUSED_RESULT;
static inline uint8_t Buttons_GetStatus(void)
{
return ((PIND & BUTTONS_BUTTON1) ^ BUTTONS_BUTTON1);
}
#endif
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,128 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Board specific LED driver header for the JM-DB-U2.
*
* Board specific LED driver header for the JM-DB-U2 (http://u2.mattair.net/index.html).
*
* \note This file should not be included directly. It is automatically included as needed by the LEDs driver
* dispatch header located in LUFA/Drivers/Board/LEDs.h.
*/
/** \ingroup Group_LEDs
* @defgroup Group_LEDs_JMDBU2 JMDBU2
*
* Board specific LED driver header for the JM-DB-U2 (http://u2.mattair.net/index.html).
*
* \note This file should not be included directly. It is automatically included as needed by the LEDs driver
* dispatch header located in LUFA/Drivers/Board/LEDs.h.
*
* @{
*/
#ifndef __LEDS_JMDBU2_H__
#define __LEDS_JMDBU2_H__
/* Includes: */
#include <avr/io.h>
#include "../../../Common/Common.h"
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_LEDS_H)
#error Do not include this file directly. Include LUFA/Drivers/Board/LEDS.h instead.
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** LED mask for the first LED on the board. */
#define LEDS_LED1 (1 << 4)
/** LED mask for all the LEDs on the board. */
#define LEDS_ALL_LEDS LEDS_LED1
/** LED mask for the none of the board LEDs. */
#define LEDS_NO_LEDS 0
/* Inline Functions: */
#if !defined(__DOXYGEN__)
static inline void LEDs_Init(void)
{
DDRD |= LEDS_ALL_LEDS;
PORTD &= ~LEDS_ALL_LEDS;
}
static inline void LEDs_TurnOnLEDs(const uint8_t LEDMask)
{
PORTD |= LEDMask;
}
static inline void LEDs_TurnOffLEDs(const uint8_t LEDMask)
{
PORTD &= ~LEDMask;
}
static inline void LEDs_SetAllLEDs(const uint8_t LEDMask)
{
PORTD = ((PORTD & ~LEDS_ALL_LEDS) | LEDMask);
}
static inline void LEDs_ChangeLEDs(const uint8_t LEDMask,
const uint8_t ActiveMask)
{
PORTD = ((PORTD & ~LEDMask) | ActiveMask);
}
static inline void LEDs_ToggleLEDs(const uint8_t LEDMask)
{
PORTD = (PORTD ^ (LEDMask & LEDS_ALL_LEDS));
}
static inline uint8_t LEDs_GetLEDs(void) ATTR_WARN_UNUSED_RESULT;
static inline uint8_t LEDs_GetLEDs(void)
{
return (PORTD & LEDS_ALL_LEDS);
}
#endif
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,109 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Master include file for the board digital joystick driver.
*
* This file is the master dispatch header file for the board-specific Joystick driver, for boards containing a
* 5-way joystick.
*
* User code should include this file, which will in turn include the correct joystick driver header file for the
* currently selected board.
*
* If the BOARD value is set to BOARD_USER, this will include the /Board/Joystick.h file in the user project
* directory.
*/
/** \ingroup Group_BoardDrivers
* @defgroup Group_Joystick Joystick Driver - LUFA/Drivers/Board/Joystick.h
*
* \section Sec_Dependencies Module Source Dependencies
* The following files must be built with any user project that uses this module:
* - None
*
* \section Module Description
* Hardware Joystick driver. This module provides an easy to use interface to control the hardware digital Joystick
* located on many boards.
*
* If the BOARD value is set to BOARD_USER, this will include the /Board/Dataflash.h file in the user project
* directory. Otherwise, it will include the appropriate built in board driver header file.
*
* @{
*/
#ifndef __JOYSTICK_H__
#define __JOYSTICK_H__
/* Macros: */
#if !defined(__DOXYGEN__)
#define __INCLUDE_FROM_JOYSTICK_H
#define INCLUDE_FROM_JOYSTICK_H
#endif
/* Includes: */
#include "../../Common/Common.h"
#if (BOARD == BOARD_NONE)
#error The Board Joystick driver cannot be used if the makefile BOARD option is not set.
#elif (BOARD == BOARD_USBKEY)
#include "USBKEY/Joystick.h"
#elif (BOARD == BOARD_STK525)
#include "STK525/Joystick.h"
#elif (BOARD == BOARD_STK526)
#include "STK526/Joystick.h"
#elif (BOARD == BOARD_BUMBLEB)
#include "BUMBLEB/Joystick.h"
#elif (BOARD == BOARD_EVK527)
#include "EVK527/Joystick.h"
#elif (BOARD == BOARD_USER)
#include "Board/Joystick.h"
#else
#error The selected board does not contain a joystick.
#endif
/* Pseudo-Functions for Doxygen: */
#if defined(__DOXYGEN__)
/** Initialises the joystick driver so that the joystick position can be read. This sets the appropriate
* I/O pins to inputs with their pull-ups enabled.
*/
static inline void Joystick_Init(void);
/** Returns the current status of the joystick, as a mask indicating the direction the joystick is
* currently facing in (multiple bits can be set).
*
* \return Mask indicating the joystick direction - see corresponding board specific Joystick.h file
* for direction masks.
*/
static inline uint8_t Joystick_GetStatus(void) ATTR_WARN_UNUSED_RESULT;
#endif
#endif
/** @} */

View File

@ -0,0 +1,185 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Master include file for the board LEDs driver.
*
* This file is the master dispatch header file for the board-specific LED driver, for boards containing user
* controllable LEDs.
*
* User code should include this file, which will in turn include the correct LED driver header file for the
* currently selected board.
*
* If the BOARD value is set to BOARD_USER, this will include the /Board/LEDs.h file in the user project
* directory.
*/
/** \ingroup Group_BoardDrivers
* @defgroup Group_LEDs LEDs Driver - LUFA/Drivers/Board/LEDs.h
*
* \section Sec_Dependencies Module Source Dependencies
* The following files must be built with any user project that uses this module:
* - None
*
* \section Module Description
* Hardware LEDs driver. This provides an easy to use driver for the hardware LEDs present on many boards. It
* provides an interface to configure, test and change the status of all the board LEDs.
*
* If the BOARD value is set to BOARD_USER, this will include the /Board/Dataflash.h file in the user project
* directory. Otherwise, it will include the appropriate built in board driver header file. If the BOARD value
* is set to BOARD_NONE, this driver is silently disabled.
*
* \note To make code as compatible as possible, it is assumed that all boards carry a minimum of four LEDs. If
* a board contains less than four LEDs, the remaining LED masks are defined to 0 so as to have no effect.
* If other behaviour is desired, either alias the remaining LED masks to existing LED masks via the -D
* switch in the project makefile, or alias them to nothing in the makefile to cause compilation errors when
* a non-existing LED is referenced in application code. Note that this means that it is possible to make
* compatible code for a board with no LEDs by making a board LED driver (see \ref Page_WritingBoardDrivers)
* which contains only stub functions and defines no LEDs.
*
* @{
*/
#ifndef __LEDS_H__
#define __LEDS_H__
/* Macros: */
#if !defined(__DOXYGEN__)
#define __INCLUDE_FROM_LEDS_H
#define INCLUDE_FROM_LEDS_H
#endif
/* Includes: */
#include "../../Common/Common.h"
#if (BOARD == BOARD_NONE)
static inline void LEDs_Init(void) {};
static inline void LEDs_TurnOnLEDs(const uint8_t LEDMask) {};
static inline void LEDs_TurnOffLEDs(const uint8_t LEDMask) {};
static inline void LEDs_SetAllLEDs(const uint8_t LEDMask) {};
static inline void LEDs_ChangeLEDs(const uint8_t LEDMask, const uint8_t ActiveMask) {};
static inline void LEDs_ToggleLEDs(const uint8_t LEDMask) {};
static inline uint8_t LEDs_GetLEDs(void) { return 0; }
#elif (BOARD == BOARD_USBKEY)
#include "USBKEY/LEDs.h"
#elif (BOARD == BOARD_STK525)
#include "STK525/LEDs.h"
#elif (BOARD == BOARD_STK526)
#include "STK526/LEDs.h"
#elif (BOARD == BOARD_RZUSBSTICK)
#include "RZUSBSTICK/LEDs.h"
#elif (BOARD == BOARD_ATAVRUSBRF01)
#include "ATAVRUSBRF01/LEDs.h"
#elif ((BOARD == BOARD_XPLAIN) || (BOARD == BOARD_XPLAIN_REV1))
#include "XPLAIN/LEDs.h"
#elif (BOARD == BOARD_BUMBLEB)
#include "BUMBLEB/LEDs.h"
#elif (BOARD == BOARD_EVK527)
#include "EVK527/LEDs.h"
#elif (BOARD == BOARD_TEENSY)
#include "TEENSY/LEDs.h"
#elif (BOARD == BOARD_USBTINYMKII)
#include "USBTINYMKII/LEDs.h"
#elif (BOARD == BOARD_BENITO)
#include "BENITO/LEDs.h"
#elif (BOARD == BOARD_JMDBU2)
#include "JMDBU2/LEDs.h"
#elif (BOARD == BOARD_USER)
#include "Board/LEDs.h"
#endif
#if !defined(LEDS_LED1)
#define LEDS_LED1 0
#endif
#if !defined(LEDS_LED2)
#define LEDS_LED2 0
#endif
#if !defined(LEDS_LED3)
#define LEDS_LED3 0
#endif
#if !defined(LEDS_LED4)
#define LEDS_LED4 0
#endif
/* Pseudo-Functions for Doxygen: */
#if defined(__DOXYGEN__)
/** Initialises the board LED driver so that the LEDs can be controlled. This sets the appropriate port
* I/O pins as outputs, and sets the LEDs to default to off.
*/
static inline void LEDs_Init(void);
/** Turns on the LEDs specified in the given LED mask.
*
* \param[in] LEDMask Mask of the board LEDs to manipulate (see board-specific LEDs.h driver file).
*/
static inline void LEDs_TurnOnLEDs(const uint8_t LEDMask);
/** Turns off the LEDs specified in the given LED mask.
*
* \param[in] LEDMask Mask of the board LEDs to manipulate (see board-specific LEDs.h driver file).
*/
static inline void LEDs_TurnOffLEDs(const uint8_t LEDMask);
/** Turns off all LEDs not specified in the given LED mask, and turns on all the LEDs in the given LED
* mask.
*
* \param[in] LEDMask Mask of the board LEDs to manipulate (see board-specific LEDs.h driver file).
*/
static inline void LEDs_SetAllLEDs(const uint8_t LEDMask);
/** Turns off all LEDs in the LED mask that are not set in the active mask, and turns on all the LEDs
* specified in both the LED and active masks.
*
* \param[in] LEDMask Mask of the board LEDs to manipulate (see board-specific LEDs.h driver file).
* \param[in] ActiveMask Mask of whether the LEDs in the LED mask should be turned on or off.
*/
static inline void LEDs_ChangeLEDs(const uint8_t LEDMask,
const uint8_t ActiveMask);
/** Toggles all LEDs in the LED mask, leaving all others in their current states.
*
* \param[in] LEDMask Mask of the board LEDs to manipulate (see board-specific LEDs.h driver file).
*/
static inline void LEDs_ToggleLEDs(const uint8_t LEDMask);
/** Returns the status of all the board LEDs; set LED masks in the return value indicate that the
* corresponding LED is on.
*
* \return Mask of the board LEDs which are currently turned on.
*/
static inline uint8_t LEDs_GetLEDs(void) ATTR_WARN_UNUSED_RESULT;
#endif
#endif
/** @} */

View File

@ -0,0 +1,162 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Board specific LED driver header for the RZUSBSTICK.
*
* Board specific LED driver header for the RZUSBSTICK.
*
* \note This file should not be included directly. It is automatically included as needed by the LEDs driver
* dispatch header located in LUFA/Drivers/Board/LEDs.h.
*/
/** \ingroup Group_LEDs
* @defgroup Group_LEDs_RZUSBSTICK RZUSBSTICK
*
* Board specific LED driver header for the RZUSBSTICK.
*
* \note This file should not be included directly. It is automatically included as needed by the LEDs driver
* dispatch header located in LUFA/Drivers/Board/LEDs.h.
*
* @{
*/
#ifndef __LEDS_RZUSBSTICK_H__
#define __LEDS_RZUSBSTICK_H__
/* Includes: */
#include <avr/io.h>
#include "../../../Common/Common.h"
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_LEDS_H)
#error Do not include this file directly. Include LUFA/Drivers/Board/LEDS.h instead.
#endif
/* Private Interface - For use in library only: */
#if !defined(__DOXYGEN__)
/* Macros: */
#define LEDS_PORTD_LEDS (LEDS_LED1 | LEDS_LED2)
#define LEDS_PORTE_LEDS (LEDS_LED3 | LEDS_LED4)
#define LEDS_PORTE_MASK_SHIFT 4
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** LED mask for the first LED on the board. */
#define LEDS_LED1 (1 << 7)
/** LED mask for the second LED on the board. */
#define LEDS_LED2 (1 << 5)
/** LED mask for the third LED on the board. */
#define LEDS_LED3 ((1 << 6) >> LEDS_PORTE_MASK_SHIFT)
/** LED mask for the fourth LED on the board. */
#define LEDS_LED4 ((1 << 7) >> LEDS_PORTE_MASK_SHIFT)
/** LED mask for all the LEDs on the board. */
#define LEDS_ALL_LEDS (LEDS_LED1 | LEDS_LED2 | LEDS_LED3 | LEDS_LED4)
/** LED mask for the none of the board LEDs. */
#define LEDS_NO_LEDS 0
/* Inline Functions: */
#if !defined(__DOXYGEN__)
static inline void LEDs_Init(void)
{
DDRD |= LEDS_PORTD_LEDS;
PORTD &= ~LEDS_LED1;
PORTD |= LEDS_LED2;
DDRE |= (LEDS_PORTE_LEDS << LEDS_PORTE_MASK_SHIFT);
PORTE |= (LEDS_PORTE_LEDS << LEDS_PORTE_MASK_SHIFT);
}
static inline void LEDs_TurnOnLEDs(const uint8_t LEDMask)
{
PORTD |= (LEDMask & LEDS_LED1);
PORTD &= ~(LEDMask & LEDS_LED2);
PORTE &= ~((LEDMask & LEDS_PORTE_LEDS) << LEDS_PORTE_MASK_SHIFT);
}
static inline void LEDs_TurnOffLEDs(const uint8_t LEDMask)
{
PORTD &= ~(LEDMask & LEDS_LED1);
PORTD |= (LEDMask & LEDS_LED2);
PORTE |= ((LEDMask & LEDS_PORTE_LEDS) << LEDS_PORTE_MASK_SHIFT);
}
static inline void LEDs_SetAllLEDs(const uint8_t LEDMask)
{
PORTD = (((PORTD & ~LEDS_LED1) | (LEDMask & LEDS_LED1)) |
((PORTD | LEDS_LED2) & ~(LEDMask & LEDS_LED2)));
PORTE = ((PORTE | (LEDS_PORTE_LEDS << LEDS_PORTE_MASK_SHIFT)) &
~((LEDMask & LEDS_PORTE_LEDS) << LEDS_PORTE_MASK_SHIFT));
}
static inline void LEDs_ChangeLEDs(const uint8_t LEDMask,
const uint8_t ActiveMask)
{
PORTD = (((PORTD & ~(LEDMask & LEDS_LED1)) | (ActiveMask & LEDS_LED1)) |
((PORTD | (LEDMask & LEDS_LED2)) & ~(ActiveMask & LEDS_LED2)));
PORTE = ((PORTE | ((LEDMask & LEDS_PORTE_LEDS) << LEDS_PORTE_MASK_SHIFT)) &
~((ActiveMask & LEDS_PORTE_LEDS) << LEDS_PORTE_MASK_SHIFT));
}
static inline void LEDs_ToggleLEDs(const uint8_t LEDMask)
{
PORTD = (PORTD ^ (LEDMask & LEDS_PORTD_LEDS));
PORTE = (PORTE ^ ((LEDMask & LEDS_PORTE_LEDS) << LEDS_PORTE_MASK_SHIFT));
}
static inline uint8_t LEDs_GetLEDs(void) ATTR_WARN_UNUSED_RESULT;
static inline uint8_t LEDs_GetLEDs(void)
{
return (((PORTD & LEDS_LED1) | (~PORTD & LEDS_LED2)) |
((~PORTE & (LEDS_PORTE_LEDS << LEDS_PORTE_MASK_SHIFT)) >> LEDS_PORTE_MASK_SHIFT));
}
#endif
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,98 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Board specific Dataflash commands header for the AT45DB321C as mounted on the STK525.
*
* Board specific Dataflash commands header for the AT45DB321C as mounted on the STK525.
*
* \note This file should not be included directly. It is automatically included as needed by the dataflash driver
* dispatch header located in LUFA/Drivers/Board/Dataflash.h.
*/
/** \ingroup Group_Dataflash_STK525
* @defgroup Group_Dataflash_STK525_AT45DB321C AT45DB321C
*
* Board specific Dataflash commands header for the AT45DB321C as mounted on the STK525.
*
* \note This file should not be included directly. It is automatically included as needed by the dataflash driver
* dispatch header located in LUFA/Drivers/Board/Dataflash.h.
*
* @{
*/
#ifndef __DATAFLASH_CMDS_H__
#define __DATAFLASH_CMDS_H__
/* Public Interface - May be used in end-application: */
/* Macros: */
#define DF_STATUS_READY (1 << 7)
#define DF_STATUS_COMPMISMATCH (1 << 6)
#define DF_STATUS_SECTORPROTECTION_ON (1 << 1)
#define DF_MANUFACTURER_ATMEL 0x1F
#define DF_CMD_GETSTATUS 0xD7
#define DF_CMD_MAINMEMTOBUFF1 0x53
#define DF_CMD_MAINMEMTOBUFF2 0x55
#define DF_CMD_MAINMEMTOBUFF1COMP 0x60
#define DF_CMD_MAINMEMTOBUFF2COMP 0x61
#define DF_CMD_AUTOREWRITEBUFF1 0x58
#define DF_CMD_AUTOREWRITEBUFF2 0x59
#define DF_CMD_MAINMEMPAGEREAD 0xD2
#define DF_CMD_CONTARRAYREAD_LF 0xE8
#define DF_CMD_BUFF1READ_LF 0xD4
#define DF_CMD_BUFF2READ_LF 0xD6
#define DF_CMD_BUFF1WRITE 0x84
#define DF_CMD_BUFF2WRITE 0x87
#define DF_CMD_BUFF1TOMAINMEMWITHERASE 0x83
#define DF_CMD_BUFF2TOMAINMEMWITHERASE 0x86
#define DF_CMD_BUFF1TOMAINMEM 0x88
#define DF_CMD_BUFF2TOMAINMEM 0x89
#define DF_CMD_MAINMEMPAGETHROUGHBUFF1 0x82
#define DF_CMD_MAINMEMPAGETHROUGHBUFF2 0x85
#define DF_CMD_PAGEERASE 0x81
#define DF_CMD_BLOCKERASE 0x50
#define DF_CMD_SECTORPROTECTIONOFF ((char[]){0x3D, 0x2A, 0x7F, 0xCF})
#define DF_CMD_SECTORPROTECTIONOFF_BYTE1 0x3D
#define DF_CMD_SECTORPROTECTIONOFF_BYTE2 0x2A
#define DF_CMD_SECTORPROTECTIONOFF_BYTE3 0x7F
#define DF_CMD_SECTORPROTECTIONOFF_BYTE4 0xCF
#define DF_CMD_READMANUFACTURERDEVICEINFO 0x9F
#endif
/** @} */

View File

@ -0,0 +1,103 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Board specific Buttons driver header for the STK525.
*
* Board specific Buttons driver header for the STK525.
*
* \note This file should not be included directly. It is automatically included as needed by the Buttons driver
* dispatch header located in LUFA/Drivers/Board/Buttons.h.
*/
/** \ingroup Group_Buttons
* @defgroup Group_Buttons_STK525 STK525
*
* Board specific Buttons driver header for the STK525.
*
* \note This file should not be included directly. It is automatically included as needed by the Buttons driver
* dispatch header located in LUFA/Drivers/Board/Buttons.h.
*
* @{
*/
#ifndef __BUTTONS_STK525_H__
#define __BUTTONS_STK525_H__
/* Includes: */
#include <avr/io.h>
#include <stdbool.h>
#include "../../../Common/Common.h"
/* Includes: */
#include <avr/io.h>
#include <stdbool.h>
#include "../../../Common/Common.h"
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_BUTTONS_H)
#error Do not include this file directly. Include LUFA/Drivers/Board/Buttons.h instead.
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** Button mask for the first button on the board. */
#define BUTTONS_BUTTON1 (1 << 2)
/* Inline Functions: */
#if !defined(__DOXYGEN__)
static inline void Buttons_Init(void)
{
DDRE &= ~BUTTONS_BUTTON1;
PORTE |= BUTTONS_BUTTON1;
}
static inline uint8_t Buttons_GetStatus(void) ATTR_WARN_UNUSED_RESULT;
static inline uint8_t Buttons_GetStatus(void)
{
return ((PINE & BUTTONS_BUTTON1) ^ BUTTONS_BUTTON1);
}
#endif
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,183 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Board specific Dataflash driver header for the STK525.
*
* Board specific Dataflash driver header for the STK525.
*
* \note This file should not be included directly. It is automatically included as needed by the dataflash driver
* dispatch header located in LUFA/Drivers/Board/Dataflash.h.
*/
/** \ingroup Group_Dataflash
* @defgroup Group_Dataflash_STK525 STK525
*
* Board specific Dataflash driver header for the STK525.
*
* \note This file should not be included directly. It is automatically included as needed by the dataflash driver
* dispatch header located in LUFA/Drivers/Board/Dataflash.h.
*
* @{
*/
#ifndef __DATAFLASH_STK525_H__
#define __DATAFLASH_STK525_H__
/* Includes: */
#include "AT45DB321C.h"
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_DATAFLASH_H)
#error Do not include this file directly. Include LUFA/Drivers/Board/Dataflash.h instead.
#endif
/* Private Interface - For use in library only: */
#if !defined(__DOXYGEN__)
/* Macros: */
#define DATAFLASH_CHIPCS_MASK (1 << 4)
#define DATAFLASH_CHIPCS_DDR DDRB
#define DATAFLASH_CHIPCS_PORT PORTB
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** Constant indicating the total number of dataflash ICs mounted on the selected board. */
#define DATAFLASH_TOTALCHIPS 1
/** Mask for no dataflash chip selected. */
#define DATAFLASH_NO_CHIP DATAFLASH_CHIPCS_MASK
/** Mask for the first dataflash chip selected. */
#define DATAFLASH_CHIP1 0
/** Internal main memory page size for the board's dataflash IC. */
#define DATAFLASH_PAGE_SIZE 512
/** Total number of pages inside the board's dataflash IC. */
#define DATAFLASH_PAGES 8192
/* Inline Functions: */
/** Initialises the dataflash driver so that commands and data may be sent to an attached dataflash IC.
* The AVR's SPI driver MUST be initialized before any of the dataflash commands are used.
*/
static inline void Dataflash_Init(void)
{
DATAFLASH_CHIPCS_DDR |= DATAFLASH_CHIPCS_MASK;
DATAFLASH_CHIPCS_PORT |= DATAFLASH_CHIPCS_MASK;
}
/** Determines the currently selected dataflash chip.
*
* \return Mask of the currently selected Dataflash chip, either \ref DATAFLASH_NO_CHIP if no chip is selected
* or a DATAFLASH_CHIPn mask (where n is the chip number).
*/
static inline uint8_t Dataflash_GetSelectedChip(void) ATTR_ALWAYS_INLINE ATTR_WARN_UNUSED_RESULT;
static inline uint8_t Dataflash_GetSelectedChip(void)
{
return (DATAFLASH_CHIPCS_PORT & DATAFLASH_CHIPCS_MASK);
}
/** Selects the given dataflash chip.
*
* \param[in] ChipMask Mask of the Dataflash IC to select, in the form of DATAFLASH_CHIPn mask (where n is
* the chip number).
*/
static inline void Dataflash_SelectChip(const uint8_t ChipMask) ATTR_ALWAYS_INLINE;
static inline void Dataflash_SelectChip(const uint8_t ChipMask)
{
DATAFLASH_CHIPCS_PORT = ((DATAFLASH_CHIPCS_PORT & ~DATAFLASH_CHIPCS_MASK) | ChipMask);
}
/** Deselects the current dataflash chip, so that no dataflash is selected. */
static inline void Dataflash_DeselectChip(void) ATTR_ALWAYS_INLINE;
static inline void Dataflash_DeselectChip(void)
{
Dataflash_SelectChip(DATAFLASH_NO_CHIP);
}
/** Selects a dataflash IC from the given page number, which should range from 0 to
* ((DATAFLASH_PAGES * DATAFLASH_TOTALCHIPS) - 1). For boards containing only one
* dataflash IC, this will select DATAFLASH_CHIP1. If the given page number is outside
* the total number of pages contained in the boards dataflash ICs, all dataflash ICs
* are deselected.
*
* \param[in] PageAddress Address of the page to manipulate, ranging from
* ((DATAFLASH_PAGES * DATAFLASH_TOTALCHIPS) - 1).
*/
static inline void Dataflash_SelectChipFromPage(const uint16_t PageAddress)
{
Dataflash_DeselectChip();
if (PageAddress >= DATAFLASH_PAGES)
return;
Dataflash_SelectChip(DATAFLASH_CHIP1);
}
/** Toggles the select line of the currently selected dataflash IC, so that it is ready to receive
* a new command.
*/
static inline void Dataflash_ToggleSelectedChipCS(void)
{
uint8_t SelectedChipMask = Dataflash_GetSelectedChip();
Dataflash_DeselectChip();
Dataflash_SelectChip(SelectedChipMask);
}
/** Spin-loops while the currently selected dataflash is busy executing a command, such as a main
* memory page program or main memory to buffer transfer.
*/
static inline void Dataflash_WaitWhileBusy(void)
{
Dataflash_ToggleSelectedChipCS();
Dataflash_SendByte(DF_CMD_GETSTATUS);
while (!(Dataflash_ReceiveByte() & DF_STATUS_READY));
Dataflash_ToggleSelectedChipCS();
}
/** Sends a set of page and buffer address bytes to the currently selected dataflash IC, for use with
* dataflash commands which require a complete 24-byte address.
*
* \param[in] PageAddress Page address within the selected dataflash IC
* \param[in] BufferByte Address within the dataflash's buffer
*/
static inline void Dataflash_SendAddressBytes(uint16_t PageAddress,
const uint16_t BufferByte)
{
Dataflash_SendByte(PageAddress >> 6);
Dataflash_SendByte((PageAddress << 2) | (BufferByte >> 8));
Dataflash_SendByte(BufferByte);
}
#endif
/** @} */

View File

@ -0,0 +1,118 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Board specific joystick driver header for the STK525.
*
* Board specific joystick driver header for the STK525.
*
* \note This file should not be included directly. It is automatically included as needed by the joystick driver
* dispatch header located in LUFA/Drivers/Board/Joystick.h.
*/
/** \ingroup Group_Joystick
* @defgroup Group_Joystick_STK525 STK525
*
* Board specific joystick driver header for the STK525.
*
* \note This file should not be included directly. It is automatically included as needed by the joystick driver
* dispatch header located in LUFA/Drivers/Board/Joystick.h.
*
* @{
*/
#ifndef __JOYSTICK_STK525_H__
#define __JOYSTICK_STK525_H__
/* Includes: */
#include <avr/io.h>
#include "../../../Common/Common.h"
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_JOYSTICK_H)
#error Do not include this file directly. Include LUFA/Drivers/Board/Joystick.h instead.
#endif
/* Private Interface - For use in library only: */
#if !defined(__DOXYGEN__)
/* Macros: */
#define JOY_BMASK ((1 << 5) | (1 << 6) | (1 << 7))
#define JOY_EMASK ((1 << 4) | (1 << 5))
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** Mask for the joystick being pushed in the left direction. */
#define JOY_LEFT (1 << 6)
/** Mask for the joystick being pushed in the right direction. */
#define JOY_RIGHT ((1 << 4) >> 1)
/** Mask for the joystick being pushed in the upward direction. */
#define JOY_UP (1 << 7)
/** Mask for the joystick being pushed in the downward direction. */
#define JOY_DOWN ((1 << 5) >> 1)
/** Mask for the joystick being pushed inward. */
#define JOY_PRESS (1 << 5)
/* Inline Functions: */
#if !defined(__DOXYGEN__)
static inline void Joystick_Init(void)
{
DDRB &= ~(JOY_BMASK);
DDRE &= ~(JOY_EMASK);
PORTB |= JOY_BMASK;
PORTE |= JOY_EMASK;
}
static inline uint8_t Joystick_GetStatus(void) ATTR_WARN_UNUSED_RESULT;
static inline uint8_t Joystick_GetStatus(void)
{
return (((uint8_t)~PINB & JOY_BMASK) | (((uint8_t)~PINE & JOY_EMASK) >> 1));
}
#endif
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,137 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Board specific LED driver header for the STK525.
*
* Board specific LED driver header for the STK525.
*
* \note This file should not be included directly. It is automatically included as needed by the LEDs driver
* dispatch header located in LUFA/Drivers/Board/LEDs.h.
*/
/** \ingroup Group_LEDs
* @defgroup Group_LEDs_STK525 STK525
*
* Board specific LED driver header for the STK525.
*
* \note This file should not be included directly. It is automatically included as needed by the LEDs driver
* dispatch header located in LUFA/Drivers/Board/LEDs.h.
*
* @{
*/
#ifndef __LEDS_STK525_H__
#define __LEDS_STK525_H__
/* Includes: */
#include <avr/io.h>
#include "../../../Common/Common.h"
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_LEDS_H)
#error Do not include this file directly. Include LUFA/Drivers/Board/LEDS.h instead.
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** LED mask for the first LED on the board. */
#define LEDS_LED1 (1 << 4)
/** LED mask for the second LED on the board. */
#define LEDS_LED2 (1 << 5)
/** LED mask for the third LED on the board. */
#define LEDS_LED3 (1 << 7)
/** LED mask for the fourth LED on the board. */
#define LEDS_LED4 (1 << 6)
/** LED mask for all the LEDs on the board. */
#define LEDS_ALL_LEDS (LEDS_LED1 | LEDS_LED2 | LEDS_LED3 | LEDS_LED4)
/** LED mask for the none of the board LEDs. */
#define LEDS_NO_LEDS 0
/* Inline Functions: */
#if !defined(__DOXYGEN__)
static inline void LEDs_Init(void)
{
DDRD |= LEDS_ALL_LEDS;
PORTD &= ~LEDS_ALL_LEDS;
}
static inline void LEDs_TurnOnLEDs(const uint8_t LEDMask)
{
PORTD |= LEDMask;
}
static inline void LEDs_TurnOffLEDs(const uint8_t LEDMask)
{
PORTD &= ~LEDMask;
}
static inline void LEDs_SetAllLEDs(const uint8_t LEDMask)
{
PORTD = ((PORTD & ~LEDS_ALL_LEDS) | LEDMask);
}
static inline void LEDs_ChangeLEDs(const uint8_t LEDMask,
const uint8_t ActiveMask)
{
PORTD = ((PORTD & ~LEDMask) | ActiveMask);
}
static inline void LEDs_ToggleLEDs(const uint8_t LEDMask)
{
PORTD = (PORTD ^ (LEDMask & LEDS_ALL_LEDS));
}
static inline uint8_t LEDs_GetLEDs(void) ATTR_WARN_UNUSED_RESULT;
static inline uint8_t LEDs_GetLEDs(void)
{
return (PORTD & LEDS_ALL_LEDS);
}
#endif
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,108 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Board specific Dataflash commands header for the AT45DB642D as mounted on the STK526.
*
* Board specific Dataflash commands header for the AT45DB642D as mounted on the STK526.
*
* \note This file should not be included directly. It is automatically included as needed by the dataflash driver
* dispatch header located in LUFA/Drivers/Board/Dataflash.h.
*/
/** \ingroup Group_Dataflash_STK526
* @defgroup Group_Dataflash_STK526_AT45DB642D AT45DB642D
*
* Board specific Dataflash commands header for the AT45DB642D as mounted on the STK526.
*
* \note This file should not be included directly. It is automatically included as needed by the dataflash driver
* dispatch header located in LUFA/Drivers/Board/Dataflash.h.
*
* @{
*/
#ifndef __DATAFLASH_CMDS_H__
#define __DATAFLASH_CMDS_H__
/* Public Interface - May be used in end-application: */
/* Macros: */
#define DF_STATUS_READY (1 << 7)
#define DF_STATUS_COMPMISMATCH (1 << 6)
#define DF_STATUS_SECTORPROTECTION_ON (1 << 1)
#define DF_STATUS_BINARYPAGESIZE_ON (1 << 0)
#define DF_MANUFACTURER_ATMEL 0x1F
#define DF_CMD_GETSTATUS 0xD7
#define DF_CMD_POWERDOWN 0xB9
#define DF_CMD_WAKEUP 0xAB
#define DF_CMD_MAINMEMTOBUFF1 0x53
#define DF_CMD_MAINMEMTOBUFF2 0x55
#define DF_CMD_MAINMEMTOBUFF1COMP 0x60
#define DF_CMD_MAINMEMTOBUFF2COMP 0x61
#define DF_CMD_AUTOREWRITEBUFF1 0x58
#define DF_CMD_AUTOREWRITEBUFF2 0x59
#define DF_CMD_MAINMEMPAGEREAD 0xD2
#define DF_CMD_CONTARRAYREAD_LF 0x03
#define DF_CMD_BUFF1READ_LF 0xD1
#define DF_CMD_BUFF2READ_LF 0xD3
#define DF_CMD_BUFF1WRITE 0x84
#define DF_CMD_BUFF2WRITE 0x87
#define DF_CMD_BUFF1TOMAINMEMWITHERASE 0x83
#define DF_CMD_BUFF2TOMAINMEMWITHERASE 0x86
#define DF_CMD_BUFF1TOMAINMEM 0x88
#define DF_CMD_BUFF2TOMAINMEM 0x89
#define DF_CMD_MAINMEMPAGETHROUGHBUFF1 0x82
#define DF_CMD_MAINMEMPAGETHROUGHBUFF2 0x85
#define DF_CMD_PAGEERASE 0x81
#define DF_CMD_BLOCKERASE 0x50
#define DF_CMD_SECTORERASE 0x7C
#define DF_CMD_CHIPERASE ((char[]){0xC7, 0x94, 0x80, 0x9A})
#define DF_CMD_CHIPERASE_BYTE1 0xC7
#define DF_CMD_CHIPERASE_BYTE2 0x94
#define DF_CMD_CHIPERASE_BYTE3 0x80
#define DF_CMD_CHIPERASE_BYTE4 0x9A
#define DF_CMD_SECTORPROTECTIONOFF ((char[]){0x3D, 0x2A, 0x7F, 0x9A})
#define DF_CMD_SECTORPROTECTIONOFF_BYTE1 0x3D
#define DF_CMD_SECTORPROTECTIONOFF_BYTE2 0x2A
#define DF_CMD_SECTORPROTECTIONOFF_BYTE3 0x7F
#define DF_CMD_SECTORPROTECTIONOFF_BYTE4 0x9A
#define DF_CMD_READMANUFACTURERDEVICEINFO 0x9F
#endif
/** @} */

View File

@ -0,0 +1,103 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Board specific Buttons driver header for the STK526.
*
* Board specific Buttons driver header for the STK526.
*
* \note This file should not be included directly. It is automatically included as needed by the Buttons driver
* dispatch header located in LUFA/Drivers/Board/Buttons.h.
*/
/** \ingroup Group_Buttons
* @defgroup Group_Buttons_STK526 STK526
*
* Board specific Buttons driver header for the STK526.
*
* \note This file should not be included directly. It is automatically included as needed by the Buttons driver
* dispatch header located in LUFA/Drivers/Board/Buttons.h.
*
* @{
*/
#ifndef __BUTTONS_STK526_H__
#define __BUTTONS_STK526_H__
/* Includes: */
#include <avr/io.h>
#include <stdbool.h>
#include "../../../Common/Common.h"
/* Includes: */
#include <avr/io.h>
#include <stdbool.h>
#include "../../../Common/Common.h"
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_BUTTONS_H)
#error Do not include this file directly. Include LUFA/Drivers/Board/Buttons.h instead.
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** Button mask for the first button on the board. */
#define BUTTONS_BUTTON1 (1 << 7)
/* Inline Functions: */
#if !defined(__DOXYGEN__)
static inline void Buttons_Init(void)
{
DDRD &= ~BUTTONS_BUTTON1;
PORTD |= BUTTONS_BUTTON1;
}
static inline uint8_t Buttons_GetStatus(void) ATTR_WARN_UNUSED_RESULT;
static inline uint8_t Buttons_GetStatus(void)
{
return ((PIND & BUTTONS_BUTTON1) ^ BUTTONS_BUTTON1);
}
#endif
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,183 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Board specific Dataflash driver header for the STK525.
*
* Board specific Dataflash driver header for the STK525.
*
* \note This file should not be included directly. It is automatically included as needed by the dataflash driver
* dispatch header located in LUFA/Drivers/Board/Dataflash.h.
*/
/** \ingroup Group_Dataflash
* @defgroup Group_Dataflash_STK526 STK526
*
* Board specific Dataflash driver header for the STK525.
*
* \note This file should not be included directly. It is automatically included as needed by the dataflash driver
* dispatch header located in LUFA/Drivers/Board/Dataflash.h.
*
* @{
*/
#ifndef __DATAFLASH_STK526_H__
#define __DATAFLASH_STK526_H__
/* Includes: */
#include "AT45DB642D.h"
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_DATAFLASH_H)
#error Do not include this file directly. Include LUFA/Drivers/Board/Dataflash.h instead.
#endif
/* Private Interface - For use in library only: */
#if !defined(__DOXYGEN__)
/* Macros: */
#define DATAFLASH_CHIPCS_MASK (1 << 2)
#define DATAFLASH_CHIPCS_DDR DDRC
#define DATAFLASH_CHIPCS_PORT PORTC
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** Constant indicating the total number of dataflash ICs mounted on the selected board. */
#define DATAFLASH_TOTALCHIPS 1
/** Mask for no dataflash chip selected. */
#define DATAFLASH_NO_CHIP DATAFLASH_CHIPCS_MASK
/** Mask for the first dataflash chip selected. */
#define DATAFLASH_CHIP1 0
/** Internal main memory page size for the board's dataflash IC. */
#define DATAFLASH_PAGE_SIZE 1024
/** Total number of pages inside the board's dataflash IC. */
#define DATAFLASH_PAGES 8192
/* Inline Functions: */
/** Initialises the dataflash driver so that commands and data may be sent to an attached dataflash IC.
* The AVR's SPI driver MUST be initialized before any of the dataflash commands are used.
*/
static inline void Dataflash_Init(void)
{
DATAFLASH_CHIPCS_DDR |= DATAFLASH_CHIPCS_MASK;
DATAFLASH_CHIPCS_PORT |= DATAFLASH_CHIPCS_MASK;
}
/** Determines the currently selected dataflash chip.
*
* \return Mask of the currently selected Dataflash chip, either \ref DATAFLASH_NO_CHIP if no chip is selected
* or a DATAFLASH_CHIPn mask (where n is the chip number).
*/
static inline uint8_t Dataflash_GetSelectedChip(void) ATTR_ALWAYS_INLINE ATTR_WARN_UNUSED_RESULT;
static inline uint8_t Dataflash_GetSelectedChip(void)
{
return (DATAFLASH_CHIPCS_PORT & DATAFLASH_CHIPCS_MASK);
}
/** Selects the given dataflash chip.
*
* \param[in] ChipMask Mask of the Dataflash IC to select, in the form of DATAFLASH_CHIPn mask (where n is
* the chip number).
*/
static inline void Dataflash_SelectChip(const uint8_t ChipMask) ATTR_ALWAYS_INLINE;
static inline void Dataflash_SelectChip(const uint8_t ChipMask)
{
DATAFLASH_CHIPCS_PORT = ((DATAFLASH_CHIPCS_PORT & ~DATAFLASH_CHIPCS_MASK) | ChipMask);
}
/** Deselects the current dataflash chip, so that no dataflash is selected. */
static inline void Dataflash_DeselectChip(void) ATTR_ALWAYS_INLINE;
static inline void Dataflash_DeselectChip(void)
{
Dataflash_SelectChip(DATAFLASH_NO_CHIP);
}
/** Selects a dataflash IC from the given page number, which should range from 0 to
* ((DATAFLASH_PAGES * DATAFLASH_TOTALCHIPS) - 1). For boards containing only one
* dataflash IC, this will select DATAFLASH_CHIP1. If the given page number is outside
* the total number of pages contained in the boards dataflash ICs, all dataflash ICs
* are deselected.
*
* \param[in] PageAddress Address of the page to manipulate, ranging from
* ((DATAFLASH_PAGES * DATAFLASH_TOTALCHIPS) - 1).
*/
static inline void Dataflash_SelectChipFromPage(const uint16_t PageAddress)
{
Dataflash_DeselectChip();
if (PageAddress >= DATAFLASH_PAGES)
return;
Dataflash_SelectChip(DATAFLASH_CHIP1);
}
/** Toggles the select line of the currently selected dataflash IC, so that it is ready to receive
* a new command.
*/
static inline void Dataflash_ToggleSelectedChipCS(void)
{
uint8_t SelectedChipMask = Dataflash_GetSelectedChip();
Dataflash_DeselectChip();
Dataflash_SelectChip(SelectedChipMask);
}
/** Spin-loops while the currently selected dataflash is busy executing a command, such as a main
* memory page program or main memory to buffer transfer.
*/
static inline void Dataflash_WaitWhileBusy(void)
{
Dataflash_ToggleSelectedChipCS();
Dataflash_SendByte(DF_CMD_GETSTATUS);
while (!(Dataflash_ReceiveByte() & DF_STATUS_READY));
Dataflash_ToggleSelectedChipCS();
}
/** Sends a set of page and buffer address bytes to the currently selected dataflash IC, for use with
* dataflash commands which require a complete 24-byte address.
*
* \param[in] PageAddress Page address within the selected dataflash IC
* \param[in] BufferByte Address within the dataflash's buffer
*/
static inline void Dataflash_SendAddressBytes(uint16_t PageAddress,
const uint16_t BufferByte)
{
Dataflash_SendByte(PageAddress >> 5);
Dataflash_SendByte((PageAddress << 3) | (BufferByte >> 8));
Dataflash_SendByte(BufferByte);
}
#endif
/** @} */

View File

@ -0,0 +1,115 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Board specific joystick driver header for the STK526.
*
* Board specific joystick driver header for the STK526.
*
* \note This file should not be included directly. It is automatically included as needed by the joystick driver
* dispatch header located in LUFA/Drivers/Board/Joystick.h.
*/
/** \ingroup Group_Joystick
* @defgroup Group_Joystick_STK526 STK526
*
* Board specific joystick driver header for the STK526.
*
* \note This file should not be included directly. It is automatically included as needed by the joystick driver
* dispatch header located in LUFA/Drivers/Board/Joystick.h.
*
* @{
*/
#ifndef __JOYSTICK_STK526_H__
#define __JOYSTICK_STK526_H__
/* Includes: */
#include <avr/io.h>
#include "../../../Common/Common.h"
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_JOYSTICK_H)
#error Do not include this file directly. Include LUFA/Drivers/Board/Joystick.h instead.
#endif
/* Private Interface - For use in library only: */
#if !defined(__DOXYGEN__)
/* Macros: */
#define JOY_BMASK ((1 << 0) | (1 << 4) | (1 << 5) | (1 << 6) | (1 << 7))
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** Mask for the joystick being pushed in the left direction. */
#define JOY_LEFT (1 << 4)
/** Mask for the joystick being pushed in the right direction. */
#define JOY_RIGHT (1 << 6)
/** Mask for the joystick being pushed in the upward direction. */
#define JOY_UP (1 << 5)
/** Mask for the joystick being pushed in the downward direction. */
#define JOY_DOWN (1 << 7)
/** Mask for the joystick being pushed inward. */
#define JOY_PRESS (1 << 0)
/* Inline Functions: */
#if !defined(__DOXYGEN__)
static inline void Joystick_Init(void)
{
DDRB &= ~JOY_BMASK;
PORTB |= JOY_BMASK;
}
static inline uint8_t Joystick_GetStatus(void) ATTR_WARN_UNUSED_RESULT;
static inline uint8_t Joystick_GetStatus(void)
{
return ((uint8_t)~PINB & JOY_BMASK);
}
#endif
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,137 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Board specific LED driver header for the STK526.
*
* Board specific LED driver header for the STK526.
*
* \note This file should not be included directly. It is automatically included as needed by the LEDs driver
* dispatch header located in LUFA/Drivers/Board/LEDs.h.
*/
/** \ingroup Group_LEDs
* @defgroup Group_LEDs_STK526 STK526
*
* Board specific LED driver header for the STK526.
*
* \note This file should not be included directly. It is automatically included as needed by the LEDs driver
* dispatch header located in LUFA/Drivers/Board/LEDs.h.
*
* @{
*/
#ifndef __LEDS_STK526_H__
#define __LEDS_STK526_H__
/* Includes: */
#include <avr/io.h>
#include "../../../Common/Common.h"
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_LEDS_H)
#error Do not include this file directly. Include LUFA/Drivers/Board/LEDS.h instead.
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** LED mask for the first LED on the board. */
#define LEDS_LED1 (1 << 1)
/** LED mask for the second LED on the board. */
#define LEDS_LED2 (1 << 0)
/** LED mask for the third LED on the board. */
#define LEDS_LED3 (1 << 5)
/** LED mask for the fourth LED on the board. */
#define LEDS_LED4 (1 << 4)
/** LED mask for all the LEDs on the board. */
#define LEDS_ALL_LEDS (LEDS_LED1 | LEDS_LED2 | LEDS_LED3 | LEDS_LED4)
/** LED mask for the none of the board LEDs. */
#define LEDS_NO_LEDS 0
/* Inline Functions: */
#if !defined(__DOXYGEN__)
static inline void LEDs_Init(void)
{
DDRD |= LEDS_ALL_LEDS;
PORTD &= ~LEDS_ALL_LEDS;
}
static inline void LEDs_TurnOnLEDs(const uint8_t LEDMask)
{
PORTD |= LEDMask;
}
static inline void LEDs_TurnOffLEDs(const uint8_t LEDMask)
{
PORTD &= ~LEDMask;
}
static inline void LEDs_SetAllLEDs(const uint8_t LEDMask)
{
PORTD = ((PORTD & ~LEDS_ALL_LEDS) | LEDMask);
}
static inline void LEDs_ChangeLEDs(const uint8_t LEDMask,
const uint8_t ActiveMask)
{
PORTD = ((PORTD & ~(LEDMask & LEDS_ALL_LEDS)) | (ActiveMask & LEDS_ALL_LEDS));
}
static inline void LEDs_ToggleLEDs(const uint8_t LEDMask)
{
PORTD = (PORTD ^ (LEDMask & LEDS_ALL_LEDS));
}
static inline uint8_t LEDs_GetLEDs(void) ATTR_WARN_UNUSED_RESULT;
static inline uint8_t LEDs_GetLEDs(void)
{
return (PORTD & LEDS_ALL_LEDS);
}
#endif
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,128 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Board specific LED driver header for the PJRC Teensy boards.
*
* Board specific LED driver header for the PJRC Teensy boards (http://www.pjrc.com/teensy/index.html).
*
* \note This file should not be included directly. It is automatically included as needed by the LEDs driver
* dispatch header located in LUFA/Drivers/Board/LEDs.h.
*/
/** \ingroup Group_LEDs
* @defgroup Group_LEDs_TEENSY TEENSY
*
* Board specific LED driver header for the PJRC Teensy boards (http://www.pjrc.com/teensy/index.html).
*
* \note This file should not be included directly. It is automatically included as needed by the LEDs driver
* dispatch header located in LUFA/Drivers/Board/LEDs.h.
*
* @{
*/
#ifndef __LEDS_TEENSY_H__
#define __LEDS_TEENSY_H__
/* Includes: */
#include <avr/io.h>
#include "../../../Common/Common.h"
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_LEDS_H)
#error Do not include this file directly. Include LUFA/Drivers/Board/LEDS.h instead.
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** LED mask for the first LED on the board. */
#define LEDS_LED1 (1 << 6)
/** LED mask for all the LEDs on the board. */
#define LEDS_ALL_LEDS (1 << 6)
/** LED mask for the none of the board LEDs. */
#define LEDS_NO_LEDS 0
/* Inline Functions: */
#if !defined(__DOXYGEN__)
static inline void LEDs_Init(void)
{
DDRD |= LEDS_ALL_LEDS;
PORTD |= LEDS_ALL_LEDS;
}
static inline void LEDs_TurnOnLEDs(const uint8_t LEDMask)
{
PORTD &= ~LEDMask;
}
static inline void LEDs_TurnOffLEDs(const uint8_t LEDMask)
{
PORTD |= LEDMask;
}
static inline void LEDs_SetAllLEDs(const uint8_t LEDMask)
{
PORTD = ((PORTD | LEDS_ALL_LEDS) & ~LEDMask);
}
static inline void LEDs_ChangeLEDs(const uint8_t LEDMask,
const uint8_t ActiveMask)
{
PORTD = ((PORTD | LEDMask) & ~ActiveMask);
}
static inline void LEDs_ToggleLEDs(const uint8_t LEDMask)
{
PORTD ^= LEDMask;
}
static inline uint8_t LEDs_GetLEDs(void) ATTR_WARN_UNUSED_RESULT;
static inline uint8_t LEDs_GetLEDs(void)
{
return (~PORTD & LEDS_ALL_LEDS);
}
#endif
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,60 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
#include "Temperature.h"
static const uint16_t PROGMEM Temperature_Lookup[] = {
0x3B4, 0x3B0, 0x3AB, 0x3A6, 0x3A0, 0x39A, 0x394, 0x38E, 0x388, 0x381, 0x37A, 0x373,
0x36B, 0x363, 0x35B, 0x353, 0x34A, 0x341, 0x338, 0x32F, 0x325, 0x31B, 0x311, 0x307,
0x2FC, 0x2F1, 0x2E6, 0x2DB, 0x2D0, 0x2C4, 0x2B8, 0x2AC, 0x2A0, 0x294, 0x288, 0x27C,
0x26F, 0x263, 0x256, 0x24A, 0x23D, 0x231, 0x225, 0x218, 0x20C, 0x200, 0x1F3, 0x1E7,
0x1DB, 0x1CF, 0x1C4, 0x1B8, 0x1AC, 0x1A1, 0x196, 0x18B, 0x180, 0x176, 0x16B, 0x161,
0x157, 0x14D, 0x144, 0x13A, 0x131, 0x128, 0x11F, 0x117, 0x10F, 0x106, 0x0FE, 0x0F7,
0x0EF, 0x0E8, 0x0E1, 0x0DA, 0x0D3, 0x0CD, 0x0C7, 0x0C0, 0x0BA, 0x0B5, 0x0AF, 0x0AA,
0x0A4, 0x09F, 0x09A, 0x096, 0x091, 0x08C, 0x088, 0x084, 0x080, 0x07C, 0x078, 0x074,
0x071, 0x06D, 0x06A, 0x067, 0x064, 0x061, 0x05E, 0x05B, 0x058, 0x055, 0x053, 0x050,
0x04E, 0x04C, 0x049, 0x047, 0x045, 0x043, 0x041, 0x03F, 0x03D, 0x03C, 0x03A, 0x038
};
int8_t Temperature_GetTemperature(void)
{
uint16_t Temp_ADC = ADC_GetChannelReading(ADC_REFERENCE_AVCC | ADC_RIGHT_ADJUSTED | TEMP_ADC_CHANNEL_MASK);
if (Temp_ADC > pgm_read_word(&Temperature_Lookup[0]))
return TEMP_MIN_TEMP;
for (uint16_t Index = 0; Index < TEMP_TABLE_SIZE; Index++)
{
if (Temp_ADC > pgm_read_word(&Temperature_Lookup[Index]))
return (Index + TEMP_TABLE_OFFSET);
}
return TEMP_MAX_TEMP;
}

View File

@ -0,0 +1,124 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Master include file for the board temperature sensor driver.
*
* Master include file for the board temperature sensor driver, for the USB boards which contain a temperature sensor.
*/
/** \ingroup Group_BoardDrivers
* @defgroup Group_Temperature Temperature Sensor Driver - LUFA/Drivers/Board/Temperature.h
*
* \section Sec_Dependencies Module Source Dependencies
* The following files must be built with any user project that uses this module:
* - LUFA/Drivers/Board/Temperature.c <i>(Makefile source module name: LUFA_SRC_TEMPERATURE)</i>
*
* \section Module Description
* Temperature sensor driver. This provides an easy to use interface for the hardware temperature sensor located
* on many boards. It provides an interface to configure the sensor and appropriate ADC channel, plus read out the
* current temperature in degrees C. It is designed for and will only work with the temperature sensor located on the
* official Atmel USB AVR boards, as each sensor has different characteristics.
*
* @{
*/
#ifndef __TEMPERATURE_H__
#define __TEMPERATURE_H__
/* Includes: */
#include <avr/pgmspace.h>
#include "../../Common/Common.h"
#include "../Peripheral/ADC.h"
#if (BOARD == BOARD_NONE)
#error The Board Temperature Sensor driver cannot be used if the makefile BOARD option is not set.
#elif ((BOARD != BOARD_USBKEY) && (BOARD != BOARD_STK525) && \
(BOARD != BOARD_STK526) && (BOARD != BOARD_USER) && \
(BOARD != BOARD_EVK527))
#error The selected board does not contain a temperature sensor.
#endif
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** ADC channel number for the temperature sensor. */
#define TEMP_ADC_CHANNEL 0
/** ADC channel MUX mask for the temperature sensor. */
#define TEMP_ADC_CHANNEL_MASK ADC_CHANNEL0
/** Minimum returnable temperature from the \ref Temperature_GetTemperature() function. */
#define TEMP_MIN_TEMP TEMP_TABLE_OFFSET
/** Maximum returnable temperature from the \ref Temperature_GetTemperature() function. */
#define TEMP_MAX_TEMP ((TEMP_TABLE_SIZE - 1) + TEMP_TABLE_OFFSET)
/* Inline Functions: */
/** Initialises the temperature sensor driver, including setting up the appropriate ADC channel.
* This must be called before any other temperature sensor routines.
*
* \pre The ADC itself (not the ADC channel) must be configured separately before calling the
* temperature sensor functions.
*/
static inline void Temperature_Init(void) ATTR_ALWAYS_INLINE;
static inline void Temperature_Init(void)
{
ADC_SetupChannel(TEMP_ADC_CHANNEL);
}
/* Function Prototypes: */
/** Performs a complete ADC on the temperature sensor channel, and converts the result into a
* valid temperature between \ref TEMP_MIN_TEMP and \ref TEMP_MAX_TEMP in degrees Celsius.
*
* \return Signed temperature value in degrees Celsius.
*/
int8_t Temperature_GetTemperature(void) ATTR_WARN_UNUSED_RESULT;
/* Private Interface - For use in library only: */
#if !defined(__DOXYGEN__)
/* Macros: */
#define TEMP_TABLE_SIZE (sizeof(Temperature_Lookup) / sizeof(Temperature_Lookup[0]))
#define TEMP_TABLE_OFFSET -21
#endif
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,108 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Board specific Dataflash commands header for the AT45DB642D as mounted on the USBKEY.
*
* Board specific Dataflash commands header for the AT45DB642D as mounted on the USBKEY.
*
* \note This file should not be included directly. It is automatically included as needed by the dataflash driver
* dispatch header located in LUFA/Drivers/Board/Dataflash.h.
*/
/** \ingroup Group_Dataflash_USBKEY
* @defgroup Group_Dataflash_USBKEY_AT45DB642D AT45DB642D
*
* Board specific Dataflash commands header for the AT45DB642D as mounted on the USBKEY.
*
* \note This file should not be included directly. It is automatically included as needed by the dataflash driver
* dispatch header located in LUFA/Drivers/Board/Dataflash.h.
*
* @{
*/
#ifndef __DATAFLASH_CMDS_H__
#define __DATAFLASH_CMDS_H__
/* Public Interface - May be used in end-application: */
/* Macros: */
#define DF_STATUS_READY (1 << 7)
#define DF_STATUS_COMPMISMATCH (1 << 6)
#define DF_STATUS_SECTORPROTECTION_ON (1 << 1)
#define DF_STATUS_BINARYPAGESIZE_ON (1 << 0)
#define DF_MANUFACTURER_ATMEL 0x1F
#define DF_CMD_GETSTATUS 0xD7
#define DF_CMD_POWERDOWN 0xB9
#define DF_CMD_WAKEUP 0xAB
#define DF_CMD_MAINMEMTOBUFF1 0x53
#define DF_CMD_MAINMEMTOBUFF2 0x55
#define DF_CMD_MAINMEMTOBUFF1COMP 0x60
#define DF_CMD_MAINMEMTOBUFF2COMP 0x61
#define DF_CMD_AUTOREWRITEBUFF1 0x58
#define DF_CMD_AUTOREWRITEBUFF2 0x59
#define DF_CMD_MAINMEMPAGEREAD 0xD2
#define DF_CMD_CONTARRAYREAD_LF 0x03
#define DF_CMD_BUFF1READ_LF 0xD1
#define DF_CMD_BUFF2READ_LF 0xD3
#define DF_CMD_BUFF1WRITE 0x84
#define DF_CMD_BUFF2WRITE 0x87
#define DF_CMD_BUFF1TOMAINMEMWITHERASE 0x83
#define DF_CMD_BUFF2TOMAINMEMWITHERASE 0x86
#define DF_CMD_BUFF1TOMAINMEM 0x88
#define DF_CMD_BUFF2TOMAINMEM 0x89
#define DF_CMD_MAINMEMPAGETHROUGHBUFF1 0x82
#define DF_CMD_MAINMEMPAGETHROUGHBUFF2 0x85
#define DF_CMD_PAGEERASE 0x81
#define DF_CMD_BLOCKERASE 0x50
#define DF_CMD_SECTORERASE 0x7C
#define DF_CMD_CHIPERASE ((char[]){0xC7, 0x94, 0x80, 0x9A})
#define DF_CMD_CHIPERASE_BYTE1 0xC7
#define DF_CMD_CHIPERASE_BYTE2 0x94
#define DF_CMD_CHIPERASE_BYTE3 0x80
#define DF_CMD_CHIPERASE_BYTE4 0x9A
#define DF_CMD_SECTORPROTECTIONOFF ((char[]){0x3D, 0x2A, 0x7F, 0x9A})
#define DF_CMD_SECTORPROTECTIONOFF_BYTE1 0x3D
#define DF_CMD_SECTORPROTECTIONOFF_BYTE2 0x2A
#define DF_CMD_SECTORPROTECTIONOFF_BYTE3 0x7F
#define DF_CMD_SECTORPROTECTIONOFF_BYTE4 0x9A
#define DF_CMD_READMANUFACTURERDEVICEINFO 0x9F
#endif
/** @} */

View File

@ -0,0 +1,97 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Board specific Buttons driver header for the USBKEY.
*
* Board specific Buttons driver header for the USBKEY.
*
* \note This file should not be included directly. It is automatically included as needed by the Buttons driver
* dispatch header located in LUFA/Drivers/Board/Buttons.h.
*/
/** \ingroup Group_Buttons
* @defgroup Group_Buttons_USBKEY USBKEY
*
* Board specific Buttons driver header for the USBKEY.
*
* \note This file should not be included directly. It is automatically included as needed by the Buttons driver
* dispatch header located in LUFA/Drivers/Board/Buttons.h.
*
* @{
*/
#ifndef __BUTTONS_USBKEY_H__
#define __BUTTONS_USBKEY_H__
/* Includes: */
#include <avr/io.h>
#include <stdbool.h>
#include "../../../Common/Common.h"
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_BUTTONS_H)
#error Do not include this file directly. Include LUFA/Drivers/Board/Buttons.h instead.
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** Button mask for the first button on the board. */
#define BUTTONS_BUTTON1 (1 << 2)
/* Inline Functions: */
#if !defined(__DOXYGEN__)
static inline void Buttons_Init(void)
{
DDRE &= ~BUTTONS_BUTTON1;
PORTE |= BUTTONS_BUTTON1;
}
static inline uint8_t Buttons_GetStatus(void) ATTR_WARN_UNUSED_RESULT;
static inline uint8_t Buttons_GetStatus(void)
{
return ((PINE & BUTTONS_BUTTON1) ^ BUTTONS_BUTTON1);
}
#endif
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,191 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Board specific Dataflash driver header for the USBKEY.
*
* Board specific Dataflash driver header for the USBKEY.
*
* \note This file should not be included directly. It is automatically included as needed by the dataflash driver
* dispatch header located in LUFA/Drivers/Board/Dataflash.h.
*/
/** \ingroup Group_Dataflash
* @defgroup Group_Dataflash_USBKEY USBKEY
*
* Board specific Dataflash driver header for the USBKEY board.
*
* \note This file should not be included directly. It is automatically included as needed by the dataflash driver
* dispatch header located in LUFA/Drivers/Board/Dataflash.h.
*
* @{
*/
#ifndef __DATAFLASH_USBKEY_H__
#define __DATAFLASH_USBKEY_H__
/* Includes: */
#include "AT45DB642D.h"
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_DATAFLASH_H)
#error Do not include this file directly. Include LUFA/Drivers/Board/Dataflash.h instead.
#endif
/* Private Interface - For use in library only: */
#if !defined(__DOXYGEN__)
/* Macros: */
#define DATAFLASH_CHIPCS_MASK ((1 << 1) | (1 << 0))
#define DATAFLASH_CHIPCS_DDR DDRE
#define DATAFLASH_CHIPCS_PORT PORTE
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** Constant indicating the total number of dataflash ICs mounted on the selected board. */
#define DATAFLASH_TOTALCHIPS 2
/** Mask for no dataflash chip selected. */
#define DATAFLASH_NO_CHIP DATAFLASH_CHIPCS_MASK
/** Mask for the first dataflash chip selected. */
#define DATAFLASH_CHIP1 (1 << 1)
/** Mask for the second dataflash chip selected. */
#define DATAFLASH_CHIP2 (1 << 0)
/** Internal main memory page size for the board's dataflash ICs. */
#define DATAFLASH_PAGE_SIZE 1024
/** Total number of pages inside each of the board's dataflash ICs. */
#define DATAFLASH_PAGES 8192
/* Inline Functions: */
/** Initialises the dataflash driver so that commands and data may be sent to an attached dataflash IC.
* The AVR's SPI driver MUST be initialized before any of the dataflash commands are used.
*/
static inline void Dataflash_Init(void)
{
DATAFLASH_CHIPCS_DDR |= DATAFLASH_CHIPCS_MASK;
DATAFLASH_CHIPCS_PORT |= DATAFLASH_CHIPCS_MASK;
}
/** Determines the currently selected dataflash chip.
*
* \return Mask of the currently selected Dataflash chip, either \ref DATAFLASH_NO_CHIP if no chip is selected
* or a DATAFLASH_CHIPn mask (where n is the chip number).
*/
static inline uint8_t Dataflash_GetSelectedChip(void) ATTR_ALWAYS_INLINE ATTR_WARN_UNUSED_RESULT;
static inline uint8_t Dataflash_GetSelectedChip(void)
{
return (DATAFLASH_CHIPCS_PORT & DATAFLASH_CHIPCS_MASK);
}
/** Selects the given dataflash chip.
*
* \param[in] ChipMask Mask of the Dataflash IC to select, in the form of DATAFLASH_CHIPn mask (where n is
* the chip number).
*/
static inline void Dataflash_SelectChip(const uint8_t ChipMask) ATTR_ALWAYS_INLINE;
static inline void Dataflash_SelectChip(const uint8_t ChipMask)
{
DATAFLASH_CHIPCS_PORT = ((DATAFLASH_CHIPCS_PORT & ~DATAFLASH_CHIPCS_MASK) | ChipMask);
}
/** Deselects the current dataflash chip, so that no dataflash is selected. */
static inline void Dataflash_DeselectChip(void) ATTR_ALWAYS_INLINE;
static inline void Dataflash_DeselectChip(void)
{
Dataflash_SelectChip(DATAFLASH_NO_CHIP);
}
/** Selects a dataflash IC from the given page number, which should range from 0 to
* ((DATAFLASH_PAGES * DATAFLASH_TOTALCHIPS) - 1). For boards containing only one
* dataflash IC, this will select DATAFLASH_CHIP1. If the given page number is outside
* the total number of pages contained in the boards dataflash ICs, all dataflash ICs
* are deselected.
*
* \param[in] PageAddress Address of the page to manipulate, ranging from
* ((DATAFLASH_PAGES * DATAFLASH_TOTALCHIPS) - 1).
*/
static inline void Dataflash_SelectChipFromPage(const uint16_t PageAddress)
{
Dataflash_DeselectChip();
if (PageAddress >= (DATAFLASH_PAGES * DATAFLASH_TOTALCHIPS))
return;
if (PageAddress & 0x01)
Dataflash_SelectChip(DATAFLASH_CHIP2);
else
Dataflash_SelectChip(DATAFLASH_CHIP1);
}
/** Toggles the select line of the currently selected dataflash IC, so that it is ready to receive
* a new command.
*/
static inline void Dataflash_ToggleSelectedChipCS(void)
{
uint8_t SelectedChipMask = Dataflash_GetSelectedChip();
Dataflash_DeselectChip();
Dataflash_SelectChip(SelectedChipMask);
}
/** Spin-loops while the currently selected dataflash is busy executing a command, such as a main
* memory page program or main memory to buffer transfer.
*/
static inline void Dataflash_WaitWhileBusy(void)
{
Dataflash_ToggleSelectedChipCS();
Dataflash_SendByte(DF_CMD_GETSTATUS);
while (!(Dataflash_ReceiveByte() & DF_STATUS_READY));
Dataflash_ToggleSelectedChipCS();
}
/** Sends a set of page and buffer address bytes to the currently selected dataflash IC, for use with
* dataflash commands which require a complete 24-byte address.
*
* \param[in] PageAddress Page address within the selected dataflash IC
* \param[in] BufferByte Address within the dataflash's buffer
*/
static inline void Dataflash_SendAddressBytes(uint16_t PageAddress,
const uint16_t BufferByte)
{
PageAddress >>= 1;
Dataflash_SendByte(PageAddress >> 5);
Dataflash_SendByte((PageAddress << 3) | (BufferByte >> 8));
Dataflash_SendByte(BufferByte);
}
#endif
/** @} */

View File

@ -0,0 +1,118 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Board specific joystick driver header for the USBKEY.
*
* Board specific joystick driver header for the USBKEY.
*
* \note This file should not be included directly. It is automatically included as needed by the joystick driver
* dispatch header located in LUFA/Drivers/Board/Joystick.h.
*/
/** \ingroup Group_Joystick
* @defgroup Group_Joystick_USBKEY USBKEY
*
* Board specific joystick driver header for the USBKEY.
*
* \note This file should not be included directly. It is automatically included as needed by the joystick driver
* dispatch header located in LUFA/Drivers/Board/Joystick.h.
*
* @{
*/
#ifndef __JOYSTICK_USBKEY_H__
#define __JOYSTICK_USBKEY_H__
/* Includes: */
#include <avr/io.h>
#include "../../../Common/Common.h"
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_JOYSTICK_H)
#error Do not include this file directly. Include LUFA/Drivers/Board/Joystick.h instead.
#endif
/* Private Interface - For use in library only: */
#if !defined(__DOXYGEN__)
/* Macros: */
#define JOY_BMASK ((1 << 5) | (1 << 6) | (1 << 7))
#define JOY_EMASK ((1 << 4) | (1 << 5))
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** Mask for the joystick being pushed in the left direction. */
#define JOY_LEFT (1 << 6)
/** Mask for the joystick being pushed in the right direction. */
#define JOY_RIGHT ((1 << 4) >> 1)
/** Mask for the joystick being pushed in the upward direction. */
#define JOY_UP (1 << 7)
/** Mask for the joystick being pushed in the downward direction. */
#define JOY_DOWN ((1 << 5) >> 1)
/** Mask for the joystick being pushed inward. */
#define JOY_PRESS (1 << 5)
/* Inline Functions: */
#if !defined(__DOXYGEN__)
static inline void Joystick_Init(void)
{
DDRB &= ~(JOY_BMASK);
DDRE &= ~(JOY_EMASK);
PORTB |= JOY_BMASK;
PORTE |= JOY_EMASK;
}
static inline uint8_t Joystick_GetStatus(void) ATTR_WARN_UNUSED_RESULT;
static inline uint8_t Joystick_GetStatus(void)
{
return (((uint8_t)~PINB & JOY_BMASK) | (((uint8_t)~PINE & JOY_EMASK) >> 1));
}
#endif
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,137 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Board specific LED driver header for the USBKEY.
*
* Board specific LED driver header for the USBKEY.
*
* \note This file should not be included directly. It is automatically included as needed by the LEDs driver
* dispatch header located in LUFA/Drivers/Board/LEDs.h.
*/
/** \ingroup Group_LEDs
* @defgroup Group_LEDs_USBKEY USBKEY
*
* Board specific LED driver header for the USBKEY.
*
* \note This file should not be included directly. It is automatically included as needed by the LEDs driver
* dispatch header located in LUFA/Drivers/Board/LEDs.h.
*
* @{
*/
#ifndef __LEDS_USBKEY_H__
#define __LEDS_USBKEY_H__
/* Includes: */
#include <avr/io.h>
#include "../../../Common/Common.h"
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_LEDS_H)
#error Do not include this file directly. Include LUFA/Drivers/Board/LEDS.h instead.
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** LED mask for the first LED on the board. */
#define LEDS_LED1 (1 << 4)
/** LED mask for the second LED on the board. */
#define LEDS_LED2 (1 << 5)
/** LED mask for the third LED on the board. */
#define LEDS_LED3 (1 << 7)
/** LED mask for the fourth LED on the board. */
#define LEDS_LED4 (1 << 6)
/** LED mask for all the LEDs on the board. */
#define LEDS_ALL_LEDS (LEDS_LED1 | LEDS_LED2 | LEDS_LED3 | LEDS_LED4)
/** LED mask for the none of the board LEDs. */
#define LEDS_NO_LEDS 0
/* Inline Functions: */
#if !defined(__DOXYGEN__)
static inline void LEDs_Init(void)
{
DDRD |= LEDS_ALL_LEDS;
PORTD &= ~LEDS_ALL_LEDS;
}
static inline void LEDs_TurnOnLEDs(const uint8_t LEDMask)
{
PORTD |= LEDMask;
}
static inline void LEDs_TurnOffLEDs(const uint8_t LEDMask)
{
PORTD &= ~LEDMask;
}
static inline void LEDs_SetAllLEDs(const uint8_t LEDMask)
{
PORTD = ((PORTD & ~LEDS_ALL_LEDS) | LEDMask);
}
static inline void LEDs_ChangeLEDs(const uint8_t LEDMask,
const uint8_t ActiveMask)
{
PORTD = ((PORTD & ~LEDMask) | ActiveMask);
}
static inline void LEDs_ToggleLEDs(const uint8_t LEDMask)
{
PORTD = (PORTD ^ (LEDMask & LEDS_ALL_LEDS));
}
static inline uint8_t LEDs_GetLEDs(void) ATTR_WARN_UNUSED_RESULT;
static inline uint8_t LEDs_GetLEDs(void)
{
return (PORTD & LEDS_ALL_LEDS);
}
#endif
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,97 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Board specific Buttons driver header for the USBTINY MKII.
*
* Board specific Buttons driver header for the USBTINY MKII (http://tom-itx.dyndns.org:81/~webpage/).
*
* \note This file should not be included directly. It is automatically included as needed by the Buttons driver
* dispatch header located in LUFA/Drivers/Board/Buttons.h.
*/
/** \ingroup Group_Buttons
* @defgroup Group_Buttons_USBTINYMKII USBTINYMKII
*
* Board specific Buttons driver header for the USBTINY MKII (http://tom-itx.dyndns.org:81/~webpage/).
*
* \note This file should not be included directly. It is automatically included as needed by the Buttons driver
* dispatch header located in LUFA/Drivers/Board/Buttons.h.
*
* @{
*/
#ifndef __BUTTONS_USBTINYMKII_H__
#define __BUTTONS_USBTINYMKII_H__
/* Includes: */
#include <avr/io.h>
#include <stdbool.h>
#include "../../../Common/Common.h"
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_BUTTONS_H)
#error Do not include this file directly. Include LUFA/Drivers/Board/Buttons.h instead.
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** Button mask for the first button on the board. */
#define BUTTONS_BUTTON1 (1 << 7)
/* Inline Functions: */
#if !defined(__DOXYGEN__)
static inline void Buttons_Init(void)
{
DDRD &= ~BUTTONS_BUTTON1;
PORTD |= BUTTONS_BUTTON1;
}
static inline uint8_t Buttons_GetStatus(void) ATTR_WARN_UNUSED_RESULT;
static inline uint8_t Buttons_GetStatus(void)
{
return ((PIND & BUTTONS_BUTTON1) ^ BUTTONS_BUTTON1);
}
#endif
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,127 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Board specific LED driver header for the USBTINY MKII.
*
* Board specific LED driver header for the USBTINY MKII (http://tom-itx.dyndns.org:81/~webpage/).
*
* \note This file should not be included directly. It is automatically included as needed by the LEDs driver
* dispatch header located in LUFA/Drivers/Board/LEDs.h.
*/
/** \ingroup Group_LEDs
* @defgroup Group_LEDs_USBTINYMKII USBTINYMKII
*
* Board specific LED driver header for the USBTINY MKII (http://tom-itx.dyndns.org:81/~webpage/).
*
* \note This file should not be included directly. It is automatically included as needed by the LEDs driver
* dispatch header located in LUFA/Drivers/Board/LEDs.h.
*
* @{
*/
#ifndef __LEDS_USBTINYMKII_H__
#define __LEDS_USBTINYMKII_H__
/* Includes: */
#include <avr/io.h>
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(INCLUDE_FROM_LEDS_H)
#error Do not include this file directly. Include LUFA/Drivers/Board/LEDS.h instead.
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** LED mask for the first LED on the board. */
#define LEDS_LED1 (1 << 6)
/** LED mask for the second LED on the board. */
#define LEDS_LED2 (1 << 7)
/** LED mask for the third LED on the board. */
#define LEDS_LED3 (1 << 5)
/** LED mask for all the LEDs on the board. */
#define LEDS_ALL_LEDS (LEDS_LED1 | LEDS_LED2 | LEDS_LED3)
/** LED mask for the none of the board LEDs. */
#define LEDS_NO_LEDS 0
/* Inline Functions: */
#if !defined(__DOXYGEN__)
static inline void LEDs_Init(void)
{
DDRB |= LEDS_ALL_LEDS;
PORTB &= ~LEDS_ALL_LEDS;
}
static inline void LEDs_TurnOnLEDs(const uint8_t LedMask)
{
PORTB |= LedMask;
}
static inline void LEDs_TurnOffLEDs(const uint8_t LedMask)
{
PORTB &= ~LedMask;
}
static inline void LEDs_SetAllLEDs(const uint8_t LedMask)
{
PORTB = ((PORTB & ~LEDS_ALL_LEDS) | LedMask);
}
static inline void LEDs_ChangeLEDs(const uint8_t LedMask,
const uint8_t ActiveMask)
{
PORTB = ((PORTB & ~LedMask) | ActiveMask);
}
static inline uint8_t LEDs_GetLEDs(void) ATTR_WARN_UNUSED_RESULT;
static inline uint8_t LEDs_GetLEDs(void)
{
return (PORTB & LEDS_ALL_LEDS);
}
#endif
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,108 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Board specific Dataflash commands header for the AT45DB642D as mounted on the XPLAIN.
*
* Board specific Dataflash commands header for the AT45DB642D as mounted on the XPLAIN.
*
* \note This file should not be included directly. It is automatically included as needed by the dataflash driver
* dispatch header located in LUFA/Drivers/Board/Dataflash.h.
*/
/** \ingroup Group_Dataflash_XPLAIN
* @defgroup Group_Dataflash_XPLAIN_AT45DB642D AT45DB642D
*
* Board specific Dataflash commands header for the AT45DB642D as mounted on the XPLAIN.
*
* \note This file should not be included directly. It is automatically included as needed by the dataflash driver
* dispatch header located in LUFA/Drivers/Board/Dataflash.h.
*
* @{
*/
#ifndef __DATAFLASH_CMDS_H__
#define __DATAFLASH_CMDS_H__
/* Public Interface - May be used in end-application: */
/* Macros: */
#define DF_STATUS_READY (1 << 7)
#define DF_STATUS_COMPMISMATCH (1 << 6)
#define DF_STATUS_SECTORPROTECTION_ON (1 << 1)
#define DF_STATUS_BINARYPAGESIZE_ON (1 << 0)
#define DF_MANUFACTURER_ATMEL 0x1F
#define DF_CMD_GETSTATUS 0xD7
#define DF_CMD_POWERDOWN 0xB9
#define DF_CMD_WAKEUP 0xAB
#define DF_CMD_MAINMEMTOBUFF1 0x53
#define DF_CMD_MAINMEMTOBUFF2 0x55
#define DF_CMD_MAINMEMTOBUFF1COMP 0x60
#define DF_CMD_MAINMEMTOBUFF2COMP 0x61
#define DF_CMD_AUTOREWRITEBUFF1 0x58
#define DF_CMD_AUTOREWRITEBUFF2 0x59
#define DF_CMD_MAINMEMPAGEREAD 0xD2
#define DF_CMD_CONTARRAYREAD_LF 0x03
#define DF_CMD_BUFF1READ_LF 0xD1
#define DF_CMD_BUFF2READ_LF 0xD3
#define DF_CMD_BUFF1WRITE 0x84
#define DF_CMD_BUFF2WRITE 0x87
#define DF_CMD_BUFF1TOMAINMEMWITHERASE 0x83
#define DF_CMD_BUFF2TOMAINMEMWITHERASE 0x86
#define DF_CMD_BUFF1TOMAINMEM 0x88
#define DF_CMD_BUFF2TOMAINMEM 0x89
#define DF_CMD_MAINMEMPAGETHROUGHBUFF1 0x82
#define DF_CMD_MAINMEMPAGETHROUGHBUFF2 0x85
#define DF_CMD_PAGEERASE 0x81
#define DF_CMD_BLOCKERASE 0x50
#define DF_CMD_SECTORERASE 0x7C
#define DF_CMD_CHIPERASE ((char[]){0xC7, 0x94, 0x80, 0x9A})
#define DF_CMD_CHIPERASE_BYTE1 0xC7
#define DF_CMD_CHIPERASE_BYTE2 0x94
#define DF_CMD_CHIPERASE_BYTE3 0x80
#define DF_CMD_CHIPERASE_BYTE4 0x9A
#define DF_CMD_SECTORPROTECTIONOFF ((char[]){0x3D, 0x2A, 0x7F, 0x9A})
#define DF_CMD_SECTORPROTECTIONOFF_BYTE1 0x3D
#define DF_CMD_SECTORPROTECTIONOFF_BYTE2 0x2A
#define DF_CMD_SECTORPROTECTIONOFF_BYTE3 0x7F
#define DF_CMD_SECTORPROTECTIONOFF_BYTE4 0x9A
#define DF_CMD_READMANUFACTURERDEVICEINFO 0x9F
#endif
/** @} */

View File

@ -0,0 +1,189 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Board specific Dataflash driver header for the XPLAIN.
*
* Board specific Dataflash driver header for the XPLAIN.
*
* \note This file should not be included directly. It is automatically included as needed by the dataflash driver
* dispatch header located in LUFA/Drivers/Board/Dataflash.h.
*/
/** \ingroup Group_Dataflash
* @defgroup Group_Dataflash_XPLAIN XPLAIN
*
* Board specific Dataflash driver header for the XPLAIN.
*
* \note This file should not be included directly. It is automatically included as needed by the dataflash driver
* dispatch header located in LUFA/Drivers/Board/Dataflash.h.
*
* @{
*/
#ifndef __DATAFLASH_XPLAIN_H__
#define __DATAFLASH_XPLAIN_H__
/* Includes: */
#include "AT45DB642D.h"
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_DATAFLASH_H)
#error Do not include this file directly. Include LUFA/Drivers/Board/Dataflash.h instead.
#endif
/* Private Interface - For use in library only: */
#if !defined(__DOXYGEN__)
/* Macros: */
#define DATAFLASH_CHIPCS_MASK (1 << 5)
#define DATAFLASH_CHIPCS_DDR DDRB
#define DATAFLASH_CHIPCS_PORT PORTB
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** Constant indicating the total number of dataflash ICs mounted on the selected board. */
#define DATAFLASH_TOTALCHIPS 1
/** Mask for no dataflash chip selected. */
#define DATAFLASH_NO_CHIP DATAFLASH_CHIPCS_MASK
/** Mask for the first dataflash chip selected. */
#define DATAFLASH_CHIP1 0
#if (BOARD == BOARD_XPLAIN_REV1)
#define DATAFLASH_PAGE_SIZE 256
#define DATAFLASH_PAGES 2048
#else
/** Internal main memory page size for the board's dataflash ICs. */
#define DATAFLASH_PAGE_SIZE 1024
/** Total number of pages inside each of the board's dataflash ICs. */
#define DATAFLASH_PAGES 8192
#endif
/* Inline Functions: */
/** Initialises the dataflash driver so that commands and data may be sent to an attached dataflash IC.
* The AVR's SPI driver MUST be initialized before any of the dataflash commands are used.
*/
static inline void Dataflash_Init(void)
{
DATAFLASH_CHIPCS_DDR |= DATAFLASH_CHIPCS_MASK;
DATAFLASH_CHIPCS_PORT |= DATAFLASH_CHIPCS_MASK;
}
/** Determines the currently selected dataflash chip.
*
* \return Mask of the currently selected Dataflash chip, either \ref DATAFLASH_NO_CHIP if no chip is selected
* or a DATAFLASH_CHIPn mask (where n is the chip number).
*/
static inline uint8_t Dataflash_GetSelectedChip(void) ATTR_ALWAYS_INLINE ATTR_WARN_UNUSED_RESULT;
static inline uint8_t Dataflash_GetSelectedChip(void)
{
return (DATAFLASH_CHIPCS_PORT & DATAFLASH_CHIPCS_MASK);
}
/** Selects the given dataflash chip.
*
* \param[in] ChipMask Mask of the Dataflash IC to select, in the form of DATAFLASH_CHIPn mask (where n is
* the chip number).
*/
static inline void Dataflash_SelectChip(const uint8_t ChipMask) ATTR_ALWAYS_INLINE;
static inline void Dataflash_SelectChip(const uint8_t ChipMask)
{
DATAFLASH_CHIPCS_PORT = ((DATAFLASH_CHIPCS_PORT & ~DATAFLASH_CHIPCS_MASK) | ChipMask);
}
/** Deselects the current dataflash chip, so that no dataflash is selected. */
static inline void Dataflash_DeselectChip(void) ATTR_ALWAYS_INLINE;
static inline void Dataflash_DeselectChip(void)
{
Dataflash_SelectChip(DATAFLASH_NO_CHIP);
}
/** Selects a dataflash IC from the given page number, which should range from 0 to
* ((DATAFLASH_PAGES * DATAFLASH_TOTALCHIPS) - 1). For boards containing only one
* dataflash IC, this will select DATAFLASH_CHIP1. If the given page number is outside
* the total number of pages contained in the boards dataflash ICs, all dataflash ICs
* are deselected.
*
* \param[in] PageAddress Address of the page to manipulate, ranging from
* ((DATAFLASH_PAGES * DATAFLASH_TOTALCHIPS) - 1).
*/
static inline void Dataflash_SelectChipFromPage(const uint16_t PageAddress)
{
Dataflash_DeselectChip();
if (PageAddress >= DATAFLASH_PAGES)
return;
Dataflash_SelectChip(DATAFLASH_CHIP1);
}
/** Toggles the select line of the currently selected dataflash IC, so that it is ready to receive
* a new command.
*/
static inline void Dataflash_ToggleSelectedChipCS(void)
{
uint8_t SelectedChipMask = Dataflash_GetSelectedChip();
Dataflash_DeselectChip();
Dataflash_SelectChip(SelectedChipMask);
}
/** Spin-loops while the currently selected dataflash is busy executing a command, such as a main
* memory page program or main memory to buffer transfer.
*/
static inline void Dataflash_WaitWhileBusy(void)
{
Dataflash_ToggleSelectedChipCS();
Dataflash_SendByte(DF_CMD_GETSTATUS);
while (!(Dataflash_ReceiveByte() & DF_STATUS_READY));
Dataflash_ToggleSelectedChipCS();
}
/** Sends a set of page and buffer address bytes to the currently selected dataflash IC, for use with
* dataflash commands which require a complete 24-byte address.
*
* \param[in] PageAddress Page address within the selected dataflash IC
* \param[in] BufferByte Address within the dataflash's buffer
*/
static inline void Dataflash_SendAddressBytes(uint16_t PageAddress,
const uint16_t BufferByte)
{
Dataflash_SendByte(PageAddress >> 5);
Dataflash_SendByte((PageAddress << 3) | (BufferByte >> 8));
Dataflash_SendByte(BufferByte);
}
#endif
/** @} */

View File

@ -0,0 +1,128 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Board specific LED driver header for the XPLAIN.
*
* Board specific LED driver header for the XPLAIN.
*
* \note This file should not be included directly. It is automatically included as needed by the LEDs driver
* dispatch header located in LUFA/Drivers/Board/LEDs.h.
*/
/** \ingroup Group_LEDs
* @defgroup Group_LEDs_XPLAIN XPLAIN
*
* Board specific LED driver header for the XPLAIN.
*
* \note This file should not be included directly. It is automatically included as needed by the LEDs driver
* dispatch header located in LUFA/Drivers/Board/LEDs.h.
*
* @{
*/
#ifndef __LEDS_XPLAIN_H__
#define __LEDS_XPLAIN_H__
/* Includes: */
#include <avr/io.h>
#include "../../../Common/Common.h"
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_LEDS_H)
#error Do not include this file directly. Include LUFA/Drivers/Board/LEDS.h instead.
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** LED mask for the first LED on the board. */
#define LEDS_LED1 (1 << 6)
/** LED mask for all the LEDs on the board. */
#define LEDS_ALL_LEDS LEDS_LED1
/** LED mask for the none of the board LEDs. */
#define LEDS_NO_LEDS 0
/* Inline Functions: */
#if !defined(__DOXYGEN__)
static inline void LEDs_Init(void)
{
DDRB |= LEDS_ALL_LEDS;
PORTB |= LEDS_ALL_LEDS;
}
static inline void LEDs_TurnOnLEDs(const uint8_t LEDMask)
{
PORTB &= ~LEDMask;
}
static inline void LEDs_TurnOffLEDs(const uint8_t LEDMask)
{
PORTB |= LEDMask;
}
static inline void LEDs_SetAllLEDs(const uint8_t LEDMask)
{
PORTB = ((PORTB | LEDS_ALL_LEDS) & ~LEDMask);
}
static inline void LEDs_ChangeLEDs(const uint8_t LEDMask,
const uint8_t ActiveMask)
{
PORTB = ((PORTB | (LEDMask & LEDS_ALL_LEDS)) & (~ActiveMask & LEDS_ALL_LEDS));
}
static inline void LEDs_ToggleLEDs(const uint8_t LEDMask)
{
PORTD = (PORTB ^ (LEDMask & LEDS_ALL_LEDS));
}
static inline uint8_t LEDs_GetLEDs(void) ATTR_WARN_UNUSED_RESULT;
static inline uint8_t LEDs_GetLEDs(void)
{
return (~PORTB & LEDS_ALL_LEDS);
}
#endif
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,195 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief ANSI terminal special escape code macros.
*
* ANSI terminal compatible escape sequences. These escape sequences are designed to be concatenated with existing
* strings to modify their display on a compatible terminal application.
*/
/** \ingroup Group_MiscDrivers
* @defgroup Group_Terminal ANSI Terminal Escape Codes - LUFA/Drivers/Misc/TerminalCodes.h
*
* \section Sec_Dependencies Module Source Dependencies
* The following files must be built with any user project that uses this module:
* - None
*
* \section Module Description
* Escape code macros for ANSI compliant text terminals.
*
* \note If desired, the macro DISABLE_TERMINAL_CODES can be defined in the project makefile and passed to the GCC
* compiler via the -D switch to disable the terminal codes without modifying the source, for use with non
* compatible terminals (any terminal codes then equate to empty strings).
*
* Example Usage:
* \code
* printf("Some String, " ESC_BOLD_ON " Some bold string");
* \endcode
*
* @{
*/
#ifndef __TERMINALCODES_H__
#define __TERMINALCODES_H__
/* Public Interface - May be used in end-application: */
/* Macros: */
#if !defined(DISABLE_TERMINAL_CODES)
/** Creates an ANSI escape sequence with the payload specified by "c".
*
* \param[in] c Payload to encode as an ANSI escape sequence, a ESC_* mask.
*/
#define ANSI_ESCAPE_SEQUENCE(c) "\33[" c
#else
#define ANSI_ESCAPE_SEQUENCE(c)
#endif
/** Resets any escape sequence modifiers back to their defaults. */
#define ESC_RESET ANSI_ESCAPE_SEQUENCE("0m")
/** Turns on bold so that any following text is printed to the terminal in bold. */
#define ESC_BOLD_ON ANSI_ESCAPE_SEQUENCE("1m")
/** Turns on italics so that any following text is printed to the terminal in italics. */
#define ESC_ITALICS_ON ANSI_ESCAPE_SEQUENCE("3m")
/** Turns on underline so that any following text is printed to the terminal underlined. */
#define ESC_UNDERLINE_ON ANSI_ESCAPE_SEQUENCE("4m")
/** Turns on inverse so that any following text is printed to the terminal in inverted colours. */
#define ESC_INVERSE_ON ANSI_ESCAPE_SEQUENCE("7m")
/** Turns on strikethrough so that any following text is printed to the terminal with a line through the
* center.
*/
#define ESC_STRIKETHROUGH_ON ANSI_ESCAPE_SEQUENCE("9m")
/** Turns off bold so that any following text is printed to the terminal in non bold. */
#define ESC_BOLD_OFF ANSI_ESCAPE_SEQUENCE("22m")
/** Turns off italics so that any following text is printed to the terminal in non italics. */
#define ESC_ITALICS_OFF ANSI_ESCAPE_SEQUENCE("23m")
/** Turns off underline so that any following text is printed to the terminal non underlined. */
#define ESC_UNDERLINE_OFF ANSI_ESCAPE_SEQUENCE("24m")
/** Turns off inverse so that any following text is printed to the terminal in non inverted colours. */
#define ESC_INVERSE_OFF ANSI_ESCAPE_SEQUENCE("27m")
/** Turns off strikethrough so that any following text is printed to the terminal without a line through
* the center.
*/
#define ESC_STRIKETHROUGH_OFF ANSI_ESCAPE_SEQUENCE("29m")
/** Sets the foreground (text) colour to black. */
#define ESC_FG_BLACK ANSI_ESCAPE_SEQUENCE("30m")
/** Sets the foreground (text) colour to red. */
#define ESC_FG_RED ANSI_ESCAPE_SEQUENCE("31m")
/** Sets the foreground (text) colour to green. */
#define ESC_FG_GREEN ANSI_ESCAPE_SEQUENCE("32m")
/** Sets the foreground (text) colour to yellow. */
#define ESC_FG_YELLOW ANSI_ESCAPE_SEQUENCE("33m")
/** Sets the foreground (text) colour to blue. */
#define ESC_FG_BLUE ANSI_ESCAPE_SEQUENCE("34m")
/** Sets the foreground (text) colour to magenta. */
#define ESC_FG_MAGENTA ANSI_ESCAPE_SEQUENCE("35m")
/** Sets the foreground (text) colour to cyan. */
#define ESC_FG_CYAN ANSI_ESCAPE_SEQUENCE("36m")
/** Sets the foreground (text) colour to white. */
#define ESC_FG_WHITE ANSI_ESCAPE_SEQUENCE("37m")
/** Sets the foreground (text) colour to the terminal's default. */
#define ESC_FG_DEFAULT ANSI_ESCAPE_SEQUENCE("39m")
/** Sets the text background colour to black. */
#define ESC_BG_BLACK ANSI_ESCAPE_SEQUENCE("40m")
/** Sets the text background colour to red. */
#define ESC_BG_RED ANSI_ESCAPE_SEQUENCE("41m")
/** Sets the text background colour to green. */
#define ESC_BG_GREEN ANSI_ESCAPE_SEQUENCE("42m")
/** Sets the text background colour to yellow. */
#define ESC_BG_YELLOW ANSI_ESCAPE_SEQUENCE("43m")
/** Sets the text background colour to blue. */
#define ESC_BG_BLUE ANSI_ESCAPE_SEQUENCE("44m")
/** Sets the text background colour to magenta. */
#define ESC_BG_MAGENTA ANSI_ESCAPE_SEQUENCE("45m")
/** Sets the text background colour to cyan. */
#define ESC_BG_CYAN ANSI_ESCAPE_SEQUENCE("46m")
/** Sets the text background colour to white. */
#define ESC_BG_WHITE ANSI_ESCAPE_SEQUENCE("47m")
/** Sets the text background colour to the terminal's default. */
#define ESC_BG_DEFAULT ANSI_ESCAPE_SEQUENCE("49m")
/** Sets the cursor position to the given line and column. */
#define ESC_CURSOR_POS(L, C) ANSI_ESCAPE_SEQUENCE(#L ";" #C "H")
/** Moves the cursor up the given number of lines. */
#define ESC_CURSOR_UP(L) ANSI_ESCAPE_SEQUENCE(#L "A")
/** Moves the cursor down the given number of lines. */
#define ESC_CURSOR_DOWN(L) ANSI_ESCAPE_SEQUENCE(#L "B")
/** Moves the cursor to the right the given number of columns. */
#define ESC_CURSOR_FORWARD(C) ANSI_ESCAPE_SEQUENCE(#C "C")
/** Moves the cursor to the left the given number of columns. */
#define ESC_CURSOR_BACKWARD(C) ANSI_ESCAPE_SEQUENCE(#C "D")
/** Saves the current cursor position so that it may be restored with \ref ESC_CURSOR_POS_RESTORE. */
#define ESC_CURSOR_POS_SAVE ANSI_ESCAPE_SEQUENCE("s")
/** Restores the cursor position to the last position saved with \ref ESC_CURSOR_POS_SAVE. */
#define ESC_CURSOR_POS_RESTORE ANSI_ESCAPE_SEQUENCE("u")
/** Erases the entire display, returning the cursor to the top left. */
#define ESC_ERASE_DISPLAY ANSI_ESCAPE_SEQUENCE("2J")
/** Erases the current line, returning the cursor to the far left. */
#define ESC_ERASE_LINE ANSI_ESCAPE_SEQUENCE("K")
#endif
/** @} */

View File

@ -0,0 +1,71 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Master include file for the ADC peripheral driver.
*
* This file is the master dispatch header file for the device-specific ADC driver, for AVRs containing an ADC.
*
* User code should include this file, which will in turn include the correct ADC driver header file for the
* currently selected AVR model.
*/
/** \ingroup Group_PeripheralDrivers
* @defgroup Group_ADC ADC Driver - LUFA/Drivers/Peripheral/ADC.h
*
* \section Sec_Dependencies Module Source Dependencies
* The following files must be built with any user project that uses this module:
* - None
*
* \section Module Description
* Hardware ADC driver. This module provides an easy to use driver for the hardware
* ADC present on many AVR models, for the conversion of analogue signals into the
* digital domain.
*/
#ifndef __ADC_H__
#define __ADC_H__
/* Macros: */
#if !defined(__DOXYGEN__)
#define __INCLUDE_FROM_ADC_H
#endif
/* Includes: */
#if (defined(__AVR_AT90USB1286__) || defined(__AVR_AT90USB646__) || \
defined(__AVR_AT90USB1287__) || defined(__AVR_AT90USB647__) || \
defined(__AVR_ATmega16U4__) || defined(__AVR_ATmega32U4__) || \
defined(__AVR_ATmega32U6__))
#include "AVRU4U6U7/ADC.h"
#else
#error "ADC is not available for the currently selected AVR model."
#endif
#endif

View File

@ -0,0 +1,391 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief ADC peripheral driver for the U7, U6 and U4 USB AVRs.
*
* ADC driver for the AT90USB1287, AT90USB1286, AT90USB647, AT90USB646, ATMEGA16U4 and ATMEGA32U4 AVRs.
*
* \note This file should not be included directly. It is automatically included as needed by the ADC driver
* dispatch header located in LUFA/Drivers/Peripheral/ADC.h.
*/
/** \ingroup Group_ADC
* @defgroup Group_ADC_AVRU4U6U7 Series U4, U6 and U7 Model ADC Driver
*
* ADC driver for the AT90USB1287, AT90USB1286, AT90USB647, AT90USB646, ATMEGA16U4 and ATMEGA32U4 AVRs.
*
* \note This file should not be included directly. It is automatically included as needed by the ADC driver
* dispatch header located in LUFA/Drivers/Peripheral/ADC.h.
*
* @{
*/
#ifndef __ADC_AVRU4U6U7_H__
#define __ADC_AVRU4U6U7_H__
/* Includes: */
#include "../../../Common/Common.h"
#include <avr/io.h>
#include <stdbool.h>
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_ADC_H)
#error Do not include this file directly. Include LUFA/Drivers/Peripheral/ADC.h instead.
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** Reference mask, for using the voltage present at the AVR's AREF pin for the ADC reference. */
#define ADC_REFERENCE_AREF 0
/** Reference mask, for using the voltage present at the AVR's AVCC pin for the ADC reference. */
#define ADC_REFERENCE_AVCC (1 << REFS0)
/** Reference mask, for using the internally generated 2.56V reference voltage as the ADC reference. */
#define ADC_REFERENCE_INT2560MV ((1 << REFS1) | (1 << REFS0))
/** Left-adjusts the 10-bit ADC result, so that the upper 8 bits of the value returned by the
* ADC_GetResult() macro contain the 8 most significant bits of the result. */
#define ADC_LEFT_ADJUSTED (1 << ADLAR)
/** Right-adjusts the 10-bit ADC result, so that the lower 8 bits of the value returned by the
* ADC_GetResult() macro contain the 8 least significant bits of the result. */
#define ADC_RIGHT_ADJUSTED (0 << ADLAR)
/** Sets the ADC mode to free running, so that conversions take place continuously as fast as the ADC
* is capable of at the given input clock speed. */
#define ADC_FREE_RUNNING (1 << ADATE)
/** Sets the ADC mode to single conversion, so that only a single conversion will take place before
* the ADC returns to idle. */
#define ADC_SINGLE_CONVERSION (0 << ADATE)
/** Sets the ADC input clock to prescale by a factor of 2 the AVR's system clock. */
#define ADC_PRESCALE_2 (1 << ADPS0)
/** Sets the ADC input clock to prescale by a factor of 4 the AVR's system clock. */
#define ADC_PRESCALE_4 (1 << ADPS1)
/** Sets the ADC input clock to prescale by a factor of 8 the AVR's system clock. */
#define ADC_PRESCALE_8 ((1 << ADPS0) | (1 << ADPS1))
/** Sets the ADC input clock to prescale by a factor of 16 the AVR's system clock. */
#define ADC_PRESCALE_16 (1 << ADPS2)
/** Sets the ADC input clock to prescale by a factor of 32 the AVR's system clock. */
#define ADC_PRESCALE_32 ((1 << ADPS2) | (1 << ADPS0))
/** Sets the ADC input clock to prescale by a factor of 64 the AVR's system clock. */
#define ADC_PRESCALE_64 ((1 << ADPS2) | (1 << ADPS1))
/** Sets the ADC input clock to prescale by a factor of 128 the AVR's system clock. */
#define ADC_PRESCALE_128 ((1 << ADPS2) | (1 << ADPS1) | (1 << ADPS0))
//@{
/** MUX mask define for the ADC0 channel of the ADC. See \ref ADC_StartReading and \ref ADC_GetChannelReading. */
#define ADC_CHANNEL0 (0x00 << MUX0)
/** MUX mask define for the ADC1 channel of the ADC. See \ref ADC_StartReading and \ref ADC_GetChannelReading. */
#define ADC_CHANNEL1 (0x01 << MUX0)
#if !(defined(__AVR_ATmega16U4__) || defined(__AVR_ATmega32U4__) || defined(__DOXYGEN__))
/** MUX mask define for the ADC2 channel of the ADC. See \ref ADC_StartReading and \ref ADC_GetChannelReading.
*
* \note Not available on all AVR models.
*/
#define ADC_CHANNEL2 (0x02 << MUX0)
/** MUX mask define for the ADC3 channel of the ADC. See \ref ADC_StartReading and \ref ADC_GetChannelReading.
*
* \note Not available on all AVR models.
*/
#define ADC_CHANNEL3 (0x03 << MUX0)
#endif
/** MUX mask define for the ADC4 channel of the ADC. See \ref ADC_StartReading and \ref ADC_GetChannelReading. */
#define ADC_CHANNEL4 (0x04 << MUX0)
/** MUX mask define for the ADC5 channel of the ADC. See \ref ADC_StartReading and \ref ADC_GetChannelReading. */
#define ADC_CHANNEL5 (0x05 << MUX0)
/** MUX mask define for the ADC6 channel of the ADC. See \ref ADC_StartReading and \ref ADC_GetChannelReading. */
#define ADC_CHANNEL6 (0x06 << MUX0)
/** MUX mask define for the ADC7 channel of the ADC. See \ref ADC_StartReading and \ref ADC_GetChannelReading. */
#define ADC_CHANNEL7 (0x07 << MUX0)
/** MUX mask define for the internal 1.1V bandgap channel of the ADC. See \ref ADC_StartReading and \ref ADC_GetChannelReading. */
#define ADC_1100MV_BANDGAP (0x1E << MUX0)
#if (defined(__AVR_ATmega16U4__) || defined(__AVR_ATmega32U4__) || defined(__DOXYGEN__))
/** MUX mask define for the ADC8 channel of the ADC. See \ref ADC_StartReading and \ref ADC_GetChannelReading.
*
* \note Not available on all AVR models.
*/
#define ADC_CHANNEL8 ((1 << 8) | (0x00 << MUX0))
/** MUX mask define for the ADC9 channel of the ADC. See \ref ADC_StartReading and \ref ADC_GetChannelReading.
*
* \note Not available on all AVR models.
*/
#define ADC_CHANNEL9 ((1 << 8) | (0x01 << MUX0))
/** MUX mask define for the ADC10 channel of the ADC. See \ref ADC_StartReading and \ref ADC_GetChannelReading.
*
* \note Not available on all AVR models.
*/
#define ADC_CHANNEL10 ((1 << 8) | (0x02 << MUX0))
/** MUX mask define for the ADC11 channel of the ADC. See \ref ADC_StartReading and \ref ADC_GetChannelReading.
*
* \note Not available on all AVR models.
*/
#define ADC_CHANNEL11 ((1 << 8) | (0x03 << MUX0))
/** MUX mask define for the ADC12 channel of the ADC. See \ref ADC_StartReading and \ref ADC_GetChannelReading.
*
* \note Not available on all AVR models.
*/
#define ADC_CHANNEL12 ((1 << 8) | (0x04 << MUX0))
/** MUX mask define for the ADC13 channel of the ADC. See \ref ADC_StartReading and \ref ADC_GetChannelReading.
*
* \note Not available on all AVR models.
*/
#define ADC_CHANNEL13 ((1 << 8) | (0x05 << MUX0))
/** MUX mask define for the internal temperature sensor channel of the ADC. See \ref ADC_StartReading and
* \ref ADC_GetChannelReading.
*
* \note Not available on all AVR models.
*/
#define ADC_INT_TEMP_SENS ((1 << 8) | (0x07 << MUX0))
#endif
//@}
/* Inline Functions: */
/** Configures the given ADC channel, ready for ADC conversions. This function sets the
* associated port pin as an input and disables the digital portion of the I/O to reduce
* power consumption.
*
* \note This must only be called for ADC channels with are connected to a physical port
* pin of the AVR, denoted by its special alternative function ADCx.
* \n\n
*
* \note The channel number must be specified as an integer, and NOT a ADC_CHANNELx mask.
*
* \param[in] Channel ADC channel number to set up for conversions.
*/
static inline void ADC_SetupChannel(const uint8_t Channel)
{
#if (defined(__AVR_AT90USB1286__) || defined(__AVR_AT90USB646__) || \
defined(__AVR_AT90USB1287__) || defined(__AVR_AT90USB647__) || \
defined(__AVR_ATmega32U6__))
DDRF &= ~(1 << Channel);
DIDR0 |= (1 << Channel);
#elif (defined(__AVR_ATmega16U4__) || defined(__AVR_ATmega32U4__))
if (Channel < 8)
{
DDRF &= ~(1 << Channel);
DIDR0 |= (1 << Channel);
}
else if (Channel == 8)
{
DDRD &= ~(1 << 4);
DIDR2 |= (1 << 0);
}
else if (Channel < 11)
{
DDRD &= ~(1 << (Channel - 3));
DIDR2 |= (1 << (Channel - 8));
}
else
{
DDRB &= ~(1 << (Channel - 7));
DIDR2 |= (1 << (Channel - 8));
}
#endif
}
/** De-configures the given ADC channel, re-enabling digital I/O mode instead of analog. This
* function sets the associated port pin as an input and re-enabled the digital portion of
* the I/O.
*
* \note This must only be called for ADC channels with are connected to a physical port
* pin of the AVR, denoted by its special alternative function ADCx.
* \n\n
*
* \note The channel number must be specified as an integer, and NOT a ADC_CHANNELx mask.
*
* \param[in] Channel ADC channel number to set up for conversions.
*/
static inline void ADC_DisableChannel(const uint8_t Channel)
{
#if (defined(__AVR_AT90USB1286__) || defined(__AVR_AT90USB646__) || \
defined(__AVR_AT90USB1287__) || defined(__AVR_AT90USB647__) || \
defined(__AVR_ATmega32U6__))
DDRF &= ~(1 << Channel);
DIDR0 &= ~(1 << Channel);
#elif (defined(__AVR_ATmega16U4__) || defined(__AVR_ATmega32U4__))
if (Channel < 8)
{
DDRF &= ~(1 << Channel);
DIDR0 &= ~(1 << Channel);
}
else if (Channel == 8)
{
DDRD &= ~(1 << 4);
DIDR2 &= ~(1 << 0);
}
else if (Channel < 11)
{
DDRD &= ~(1 << (Channel - 3));
DIDR2 &= ~(1 << (Channel - 8));
}
else
{
DDRB &= ~(1 << (Channel - 7));
DIDR2 &= ~(1 << (Channel - 8));
}
#endif
}
/** Starts the reading of the given channel, but does not wait until the conversion has completed.
* Once executed, the conversion status can be determined via the \ref ADC_IsReadingComplete() macro and
* the result read via the \ref ADC_GetResult() macro.
*
* If the ADC has been initialized in free running mode, calling this function once will begin the repeated
* conversions. If the ADC is in single conversion mode (or the channel to convert from is to be changed),
* this function must be called each time a conversion is to take place.
*
* \param[in] MUXMask Mask comprising of an ADC channel mask, reference mask and adjustment mask.
*/
static inline void ADC_StartReading(const uint16_t MUXMask)
{
ADMUX = MUXMask;
#if (defined(__AVR_ATmega16U4__) || defined(__AVR_ATmega32U4__) || defined(__DOXYGEN__))
if (MUXMask & (1 << 8))
ADCSRB |= (1 << MUX5);
else
ADCSRB &= ~(1 << MUX5);
#endif
ADCSRA |= (1 << ADSC);
}
/** Indicates if the current ADC conversion is completed, or still in progress.
*
* \return Boolean false if the reading is still taking place, or true if the conversion is
* complete and ready to be read out with \ref ADC_GetResult().
*/
static inline bool ADC_IsReadingComplete(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE;
static inline bool ADC_IsReadingComplete(void)
{
return ((ADCSRA & (1 << ADIF)) ? true : false);
}
/** Retrieves the conversion value of the last completed ADC conversion and clears the reading
* completion flag.
*
* \return The result of the last ADC conversion as an unsigned value.
*/
static inline uint16_t ADC_GetResult(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE;
static inline uint16_t ADC_GetResult(void)
{
ADCSRA |= (1 << ADIF);
return ADC;
}
/** Performs a complete single reading from channel, including a polling spin-loop to wait for the
* conversion to complete, and the returning of the converted value.
*
* \note For free running mode, the automated conversions should be initialized with a single call
* to \ref ADC_StartReading() to select the channel and begin the automated conversions, and
* the results read directly from the \ref ADC_GetResult() instead to reduce overhead.
*
* \param[in] MUXMask Mask comprising of an ADC channel mask, reference mask and adjustment mask.
*/
static inline uint16_t ADC_GetChannelReading(const uint16_t MUXMask) ATTR_WARN_UNUSED_RESULT;
static inline uint16_t ADC_GetChannelReading(const uint16_t MUXMask)
{
ADC_StartReading(MUXMask);
while (!(ADC_IsReadingComplete()));
return ADC_GetResult();
}
/** Initialises the ADC, ready for conversions. This must be called before any other ADC operations.
* The "mode" parameter should be a mask comprised of a conversion mode (free running or single) and
* prescaler masks.
*
* \param[in] Mode Mask of ADC settings, including adjustment, prescale, mode and reference.
*/
static inline void ADC_Init(uint8_t Mode) ATTR_ALWAYS_INLINE;
static inline void ADC_Init(uint8_t Mode)
{
ADCSRA = ((1 << ADEN) | Mode);
}
/** Turns off the ADC. If this is called, any further ADC operations will require a call to
* \ref ADC_Init() before the ADC can be used again.
*/
static inline void ADC_ShutDown(void) ATTR_ALWAYS_INLINE;
static inline void ADC_ShutDown(void)
{
ADCSRA = 0;
}
/** Indicates if the ADC is currently enabled.
*
* \return Boolean true if the ADC subsystem is currently enabled, false otherwise.
*/
static inline bool ADC_GetStatus(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE;
static inline bool ADC_GetStatus(void)
{
return ((ADCSRA & (1 << ADEN)) ? true : false);
}
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,154 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief TWI peripheral driver for the U7, U6 and U4 USB AVRs.
*
* Master mode TWI driver for the AT90USB1287, AT90USB1286, AT90USB647, AT90USB646, ATMEGA16U4 and ATMEGA32U4 AVRs.
*
* \note This file should not be included directly. It is automatically included as needed by the TWI driver
* dispatch header located in LUFA/Drivers/Peripheral/TWI.h.
*/
/** \ingroup Group_TWI
* @defgroup Group_TWI_AVRU4U6U7 Series U4, U6 and U7 Model TWI Driver
*
* Master mode TWI driver for the AT90USB1287, AT90USB1286, AT90USB647, AT90USB646, ATMEGA16U4 and ATMEGA32U4 AVRs.
*
* \note This file should not be included directly. It is automatically included as needed by the TWI driver
* dispatch header located in LUFA/Drivers/Peripheral/TWI.h.
*
* @{
*/
#ifndef __TWI_AVRU4U6U7_H__
#define __TWI_AVRU4U6U7_H__
/* Includes: */
#include "../../../Common/Common.h"
#include <avr/io.h>
#include <stdbool.h>
#include <util/twi.h>
#include <util/delay.h>
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_TWI_H)
#error Do not include this file directly. Include LUFA/Drivers/Peripheral/TWI.h instead.
#endif
/* Public Interface - May be used in end-application: */
/* Inline Functions: */
/** Initialises the TWI hardware into master mode, ready for data transmission and reception. This must be
* before any other TWI operations.
*/
static inline void TWI_Init(void) ATTR_ALWAYS_INLINE;
static inline void TWI_Init(void)
{
TWCR |= (1 << TWEN);
}
/** Turns off the TWI driver hardware. If this is called, any further TWI operations will require a call to
* \ref TWI_Init() before the TWI can be used again.
*/
static inline void TWI_ShutDown(void) ATTR_ALWAYS_INLINE;
static inline void TWI_ShutDown(void)
{
TWCR &= ~(1 << TWEN);
}
/** Sends a TWI STOP onto the TWI bus, terminating communication with the currently addressed device. */
static inline void TWI_StopTransmission(void) ATTR_ALWAYS_INLINE;
static inline void TWI_StopTransmission(void)
{
TWCR = ((1 << TWINT) | (1 << TWSTO) | (1 << TWEN));
}
/** Sends a byte to the currently addressed device on the TWI bus.
*
* \param[in] Byte Byte to send to the currently addressed device
*
* \return Boolean true if the recipient ACKed the byte, false otherwise
*/
static inline bool TWI_SendByte(const uint8_t Byte)
{
TWDR = Byte;
TWCR = ((1 << TWINT) | (1 << TWEN));
while (!(TWCR & (1 << TWINT)));
return ((TWSR & TW_STATUS_MASK) == TW_MT_DATA_ACK);
}
/** Receives a byte from the currently addressed device on the TWI bus.
*
* \param[in] Byte Location where the read byte is to be stored
* \param[in] LastByte Indicates if the byte should be ACKed if false, NAKed if true
*
* \return Boolean true if the byte reception successfully completed, false otherwise
*/
static inline bool TWI_ReceiveByte(uint8_t* const Byte,
const bool LastByte)
{
uint8_t TWCRMask = ((1 << TWINT) | (1 << TWEN));
if (!(LastByte))
TWCRMask |= (1 << TWEA);
TWCR = TWCRMask;
while (!(TWCR & (1 << TWINT)));
*Byte = TWDR;
return ((TWSR & TW_STATUS_MASK) == TW_MR_DATA_ACK);
}
/* Function Prototypes: */
/** Begins a master mode TWI bus communication with the given slave device address.
*
* \param[in] SlaveAddress Address of the slave TWI device to communicate with
* \param[in] TimeoutMS Timeout period within which the slave must respond, in milliseconds
*
* \return Boolean true if the device is ready for data, false otherwise
*/
bool TWI_StartTransmission(const uint8_t SlaveAddress,
const uint8_t TimeoutMS);
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,191 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Master include file for the SPI peripheral driver.
*
* Hardware SPI subsystem driver for the supported USB AVRs models.
*/
/** \ingroup Group_PeripheralDrivers
* @defgroup Group_SPI SPI Driver - LUFA/Drivers/Peripheral/SPI.h
*
* \section Sec_Dependencies Module Source Dependencies
* The following files must be built with any user project that uses this module:
* - None
*
* \section Module Description
* Driver for the hardware SPI port available on most AVR models. This module provides
* an easy to use driver for the setup of and transfer of data over the AVR's SPI port.
*
* @{
*/
#ifndef __SPI_H__
#define __SPI_H__
/* Includes: */
#include <stdbool.h>
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Private Interface - For use in library only: */
#if !defined(__DOXYGEN__)
/* Macros: */
#define SPI_USE_DOUBLESPEED (1 << SPE)
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** SPI prescaler mask for SPI_Init(). Divides the system clock by a factor of 2. */
#define SPI_SPEED_FCPU_DIV_2 SPI_USE_DOUBLESPEED
/** SPI prescaler mask for SPI_Init(). Divides the system clock by a factor of 4. */
#define SPI_SPEED_FCPU_DIV_4 0
/** SPI prescaler mask for SPI_Init(). Divides the system clock by a factor of 8. */
#define SPI_SPEED_FCPU_DIV_8 (SPI_USE_DOUBLESPEED | (1 << SPR0))
/** SPI prescaler mask for SPI_Init(). Divides the system clock by a factor of 16. */
#define SPI_SPEED_FCPU_DIV_16 (1 << SPR0)
/** SPI prescaler mask for SPI_Init(). Divides the system clock by a factor of 32. */
#define SPI_SPEED_FCPU_DIV_32 (SPI_USE_DOUBLESPEED | (1 << SPR1))
/** SPI prescaler mask for SPI_Init(). Divides the system clock by a factor of 64. */
#define SPI_SPEED_FCPU_DIV_64 (SPI_USE_DOUBLESPEED | (1 << SPR1) | (1 << SPR0))
/** SPI prescaler mask for SPI_Init(). Divides the system clock by a factor of 128. */
#define SPI_SPEED_FCPU_DIV_128 ((1 << SPR1) | (1 << SPR0))
/** SPI clock polarity mask for SPI_Init(). Indicates that the SCK should lead on the rising edge. */
#define SPI_SCK_LEAD_RISING (0 << CPOL)
/** SPI clock polarity mask for SPI_Init(). Indicates that the SCK should lead on the falling edge. */
#define SPI_SCK_LEAD_FALLING (1 << CPOL)
/** SPI data sample mode mask for SPI_Init(). Indicates that the data should sampled on the leading edge. */
#define SPI_SAMPLE_LEADING (0 << CPHA)
/** SPI data sample mode mask for SPI_Init(). Indicates that the data should be sampled on the trailing edge. */
#define SPI_SAMPLE_TRAILING (1 << CPHA)
/** SPI data order mask for SPI_Init(). Indicates that data should be shifted out MSB first. */
#define SPI_ORDER_MSB_FIRST (0 << DORD)
/** SPI data order mask for SPI_Init(). Indicates that data should be shifted out MSB first. */
#define SPI_ORDER_LSB_FIRST (1 << DORD)
/** SPI mode mask for SPI_Init(). Indicates that the SPI interface should be initialized into slave mode. */
#define SPI_MODE_SLAVE (0 << MSTR)
/** SPI mode mask for SPI_Init(). Indicates that the SPI interface should be initialized into master mode. */
#define SPI_MODE_MASTER (1 << MSTR)
/* Inline Functions: */
/** Initialises the SPI subsystem, ready for transfers. Must be called before calling any other
* SPI routines.
*
* \param[in] SPIOptions SPI Options, a mask consisting of one of each of the SPI_SPEED_*,
* SPI_SCK_*, SPI_SAMPLE_*, SPI_ORDER_* and SPI_MODE_* masks.
*/
static inline void SPI_Init(const uint8_t SPIOptions)
{
DDRB |= ((1 << 1) | (1 << 2));
PORTB |= ((1 << 0) | (1 << 3));
SPCR = ((1 << SPE) | SPIOptions);
if (SPIOptions & SPI_USE_DOUBLESPEED)
SPSR |= (1 << SPI2X);
else
SPSR &= ~(1 << SPI2X);
}
/** Turns off the SPI driver, disabling and returning used hardware to their default configuration. */
static inline void SPI_ShutDown(void)
{
DDRB &= ~((1 << 1) | (1 << 2));
PORTB &= ~((1 << 0) | (1 << 3));
SPCR = 0;
SPSR = 0;
}
/** Sends and receives a byte through the SPI interface, blocking until the transfer is complete.
*
* \param[in] Byte Byte to send through the SPI interface.
*
* \return Response byte from the attached SPI device.
*/
static inline uint8_t SPI_TransferByte(const uint8_t Byte) ATTR_ALWAYS_INLINE;
static inline uint8_t SPI_TransferByte(const uint8_t Byte)
{
SPDR = Byte;
while (!(SPSR & (1 << SPIF)));
return SPDR;
}
/** Sends a byte through the SPI interface, blocking until the transfer is complete. The response
* byte sent to from the attached SPI device is ignored.
*
* \param[in] Byte Byte to send through the SPI interface.
*/
static inline void SPI_SendByte(const uint8_t Byte) ATTR_ALWAYS_INLINE;
static inline void SPI_SendByte(const uint8_t Byte)
{
SPDR = Byte;
while (!(SPSR & (1 << SPIF)));
}
/** Sends a dummy byte through the SPI interface, blocking until the transfer is complete. The response
* byte from the attached SPI device is returned.
*
* \return The response byte from the attached SPI device.
*/
static inline uint8_t SPI_ReceiveByte(void) ATTR_ALWAYS_INLINE ATTR_WARN_UNUSED_RESULT;
static inline uint8_t SPI_ReceiveByte(void)
{
SPDR = 0x00;
while (!(SPSR & (1 << SPIF)));
return SPDR;
}
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,53 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
#include "Serial.h"
void Serial_TxString_P(const char* FlashStringPtr)
{
uint8_t CurrByte;
while ((CurrByte = pgm_read_byte(FlashStringPtr)) != 0x00)
{
Serial_TxByte(CurrByte);
FlashStringPtr++;
}
}
void Serial_TxString(const char* StringPtr)
{
uint8_t CurrByte;
while ((CurrByte = *StringPtr) != 0x00)
{
Serial_TxByte(CurrByte);
StringPtr++;
}
}

View File

@ -0,0 +1,166 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Master include file for the USART peripheral driver.
*
* Driver for the USART subsystem on supported USB AVRs.
*/
/** \ingroup Group_PeripheralDrivers
* @defgroup Group_Serial Serial USART Driver - LUFA/Drivers/Peripheral/Serial.h
*
* \section Sec_Dependencies Module Source Dependencies
* The following files must be built with any user project that uses this module:
* - LUFA/Drivers/Peripheral/Serial.c <i>(Makefile source module name: LUFA_SRC_SERIAL)</i>
*
* \section Module Description
* Hardware serial USART driver. This module provides an easy to use driver for
* the setup of and transfer of data over the AVR's USART port.
*
* @{
*/
#ifndef __SERIAL_H__
#define __SERIAL_H__
/* Includes: */
#include <avr/io.h>
#include <avr/pgmspace.h>
#include <stdbool.h>
#include "../../Common/Common.h"
#include "../Misc/TerminalCodes.h"
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Public Interface - May be used in end-application: */
/* Macros: */
/** Macro for calculating the baud value from a given baud rate when the U2X (double speed) bit is
* not set.
*/
#define SERIAL_UBBRVAL(baud) ((((F_CPU / 16) + (baud / 2)) / (baud)) - 1)
/** Macro for calculating the baud value from a given baud rate when the U2X (double speed) bit is
* set.
*/
#define SERIAL_2X_UBBRVAL(baud) ((((F_CPU / 8) + (baud / 2)) / (baud)) - 1)
/* Function Prototypes: */
/** Transmits a given string located in program space (FLASH) through the USART.
*
* \param[in] FlashStringPtr Pointer to a string located in program space.
*/
void Serial_TxString_P(const char* FlashStringPtr) ATTR_NON_NULL_PTR_ARG(1);
/** Transmits a given string located in SRAM memory through the USART.
*
* \param[in] StringPtr Pointer to a string located in SRAM space.
*/
void Serial_TxString(const char* StringPtr) ATTR_NON_NULL_PTR_ARG(1);
/* Inline Functions: */
/** Initializes the USART, ready for serial data transmission and reception. This initializes the interface to
* standard 8-bit, no parity, 1 stop bit settings suitable for most applications.
*
* \param[in] BaudRate Serial baud rate, in bits per second.
* \param[in] DoubleSpeed Enables double speed mode when set, halving the sample time to double the baud rate.
*/
static inline void Serial_Init(const uint32_t BaudRate,
const bool DoubleSpeed)
{
UBRR1 = (DoubleSpeed ? SERIAL_2X_UBBRVAL(BaudRate) : SERIAL_UBBRVAL(BaudRate));
UCSR1C = ((1 << UCSZ11) | (1 << UCSZ10));
UCSR1A = (DoubleSpeed ? (1 << U2X1) : 0);
UCSR1B = ((1 << TXEN1) | (1 << RXEN1));
DDRD |= (1 << 3);
PORTD |= (1 << 2);
}
/** Turns off the USART driver, disabling and returning used hardware to their default configuration. */
static inline void Serial_ShutDown(void)
{
UCSR1B = 0;
UCSR1A = 0;
UCSR1C = 0;
UBRR1 = 0;
DDRD &= ~(1 << 3);
PORTD &= ~(1 << 2);
}
/** Indicates whether a character has been received through the USART.
*
* \return Boolean true if a character has been received, false otherwise.
*/
static inline bool Serial_IsCharReceived(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE;
static inline bool Serial_IsCharReceived(void)
{
return ((UCSR1A & (1 << RXC1)) ? true : false);
}
/** Transmits a given byte through the USART.
*
* \param[in] DataByte Byte to transmit through the USART.
*/
static inline void Serial_TxByte(const char DataByte) ATTR_ALWAYS_INLINE;
static inline void Serial_TxByte(const char DataByte)
{
while (!(UCSR1A & (1 << UDRE1)));
UDR1 = DataByte;
}
/** Receives a byte from the USART. This function blocks until a byte has been
* received; if non-blocking behaviour is required, test for a received character
* beforehand with \ref Serial_IsCharReceived().
*
* \return Byte received from the USART.
*/
static inline char Serial_RxByte(void) ATTR_ALWAYS_INLINE;
static inline char Serial_RxByte(void)
{
while (!(UCSR1A & (1 << RXC1)));
return UDR1;
}
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,53 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
#define __INCLUDE_FROM_SERIALSTREAM_C
#include "SerialStream.h"
FILE USARTStream = FDEV_SETUP_STREAM(SerialStream_TxByte, SerialStream_RxByte, _FDEV_SETUP_RW);
static int SerialStream_TxByte(char DataByte,
FILE *Stream)
{
(void)Stream;
Serial_TxByte(DataByte);
return 0;
}
static int SerialStream_RxByte(FILE *Stream)
{
(void)Stream;
if (!(Serial_IsCharReceived()))
return _FDEV_EOF;
return Serial_RxByte();
}

View File

@ -0,0 +1,115 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Standard avr-libc character stream driver for the USART.
*
* Serial stream driver for the USART subsystem on supported USB AVRs. This makes use of the functions in the
* regular USART driver (see \ref Group_Serial), but allows the avr-libc standard stream functions (printf,
* puts, etc.) to work with the
* USART.
*/
/** \ingroup Group_PeripheralDrivers
* @defgroup Group_SerialStream Serial Stream Driver - LUFA/Drivers/Peripheral/SerialStream.h
*
* \section Sec_Dependencies Module Source Dependencies
* The following files must be built with any user project that uses this module:
* - LUFA/Drivers/Peripheral/SerialStream.c <i>(Makefile source module name: LUFA_SRC_SERIALSTREAM)</i>
*
* \section Module Description
* Serial stream driver for the USART subsystem on supported USB AVRs. This makes use of the functions in the
* regular USART driver (see \ref Group_Serial), but allows the avr-libc standard stream functions (printf,
* puts, etc.) to work with the
* USART.
*
* @{
*/
#ifndef __SERIAL_STREAM_H__
#define __SERIAL_STREAM_H__
/* Includes: */
#include <avr/io.h>
#include <stdio.h>
#include "Serial.h"
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Private Interface - For use in library only: */
#if !defined(__DOXYGEN__)
/* External Variables: */
extern FILE USARTStream;
/* Function Prototypes: */
#if defined(__INCLUDE_FROM_SERIALSTREAM_C)
static int SerialStream_TxByte(char DataByte,
FILE *Stream) ATTR_NON_NULL_PTR_ARG(2);
static int SerialStream_RxByte(FILE *Stream) ATTR_NON_NULL_PTR_ARG(1);
#endif
#endif
/* Public Interface - May be used in end-application: */
/* Inline Functions: */
/** Initialises the serial stream (and regular USART driver) so that both the stream and regular
* USART driver functions can be used. Must be called before any stream or regular USART functions.
*
* \param[in] BaudRate Baud rate to configure the USART to.
* \param[in] DoubleSpeed Enables double speed mode when set, halving the sample time to double the baud rate.
*/
static inline void SerialStream_Init(const uint32_t BaudRate,
const bool DoubleSpeed)
{
Serial_Init(BaudRate, DoubleSpeed);
stdout = &USARTStream;
stdin = &USARTStream;
}
/** Turns off the serial stream (and regular USART driver), disabling and returning used hardware to
* their default configuration.
*/
static inline void SerialStream_ShutDown(void)
{
Serial_ShutDown();
}
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,74 @@
/*
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
#include "TWI.h"
bool TWI_StartTransmission(const uint8_t SlaveAddress,
const uint8_t TimeoutMS)
{
for (;;)
{
bool BusCaptured = false;
uint16_t TimeoutRemaining;
TWCR = ((1 << TWINT) | (1 << TWSTA) | (1 << TWEN));
TimeoutRemaining = (TimeoutMS * 100);
while (TimeoutRemaining-- && !(BusCaptured))
{
if (TWCR & (1 << TWINT))
{
switch (TWSR & TW_STATUS_MASK)
{
case TW_START:
case TW_REP_START:
BusCaptured = true;
break;
case TW_MT_ARB_LOST:
TWCR = ((1 << TWINT) | (1 << TWSTA) | (1 << TWEN));
continue;
default:
TWCR = (1 << TWEN);
return false;
}
}
_delay_us(10);
}
if (!(BusCaptured))
{
TWCR = (1 << TWEN);
return false;
}
TWDR = SlaveAddress;
TWCR = ((1 << TWINT) | (1 << TWEN));
TimeoutRemaining = (TimeoutMS * 100);
while (TimeoutRemaining--)
{
if (TWCR & (1 << TWINT))
break;
_delay_us(10);
}
if (!(TimeoutRemaining))
return false;
switch (TWSR & TW_STATUS_MASK)
{
case TW_MT_SLA_ACK:
case TW_MR_SLA_ACK:
return true;
default:
TWCR = ((1 << TWINT) | (1 << TWSTO) | (1 << TWEN));
return false;
}
}
}

View File

@ -0,0 +1,71 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Master include file for the TWI peripheral driver.
*
* This file is the master dispatch header file for the device-specific ADC driver, for AVRs containing an ADC.
*
* User code should include this file, which will in turn include the correct ADC driver header file for the
* currently selected AVR model.
*/
/** \ingroup Group_PeripheralDrivers
* @defgroup Group_TWI TWI Driver - LUFA/Drivers/Peripheral/TWI.h
*
* \section Sec_Dependencies Module Source Dependencies
* The following files must be built with any user project that uses this module:
* - LUFA/Drivers/Peripheral/TWI.c <i>(Makefile source module name: LUFA_SRC_TWI)</i>
*
*
* \section Module Description
* Master Mode Hardware TWI driver. This module provides an easy to use driver for the hardware
* TWI present on many AVR models, for the transmission and reception of data on a TWI bus.
*/
#ifndef __TWI_H__
#define __TWI_H__
/* Macros: */
#if !defined(__DOXYGEN__)
#define __INCLUDE_FROM_TWI_H
#endif
/* Includes: */
#if (defined(__AVR_AT90USB1286__) || defined(__AVR_AT90USB646__) || \
defined(__AVR_AT90USB1287__) || defined(__AVR_AT90USB647__) || \
defined(__AVR_ATmega16U4__) || defined(__AVR_ATmega32U4__) || \
defined(__AVR_ATmega32U6__))
#include "AVRU4U6U7/TWI.h"
#else
#error "TWI is not available for the currently selected AVR model."
#endif
#endif

View File

@ -0,0 +1,78 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Master include file for the library USB Audio Class driver.
*
* Master include file for the library USB Audio Class driver, for both host and device modes, where available.
*
* This file should be included in all user projects making use of this optional class driver, instead of
* including any headers in the USB/ClassDriver/Device, USB/ClassDriver/Host or USB/ClassDriver/Common subdirectories.
*/
/** \ingroup Group_USBClassDrivers
* @defgroup Group_USBClassAudio Audio Class Driver - LUFA/Drivers/Class/Audio.h
*
* \section Sec_Dependencies Module Source Dependencies
* The following files must be built with any user project that uses this module:
* - LUFA/Drivers/USB/Class/Device/Audio.c <i>(Makefile source module name: LUFA_SRC_USBCLASS)</i>
*
* \section Module Description
* Audio Class Driver module. This module contains an internal implementation of the USB Audio Class, for Device
* USB mode only. User applications can use this class driver instead of implementing the Audio class manually via
* the low-level LUFA APIs.
*
* This module is designed to simplify the user code by exposing only the required interface needed to interface with
* Hosts or Devices using the USB Audio Class.
*
* @{
*/
#ifndef _AUDIO_CLASS_H_
#define _AUDIO_CLASS_H_
/* Macros: */
#define __INCLUDE_FROM_AUDIO_DRIVER
#define __INCLUDE_FROM_USB_DRIVER
/* Includes: */
#include "../HighLevel/USBMode.h"
#if defined(NO_STREAM_CALLBACKS)
#error The NO_STREAM_CALLBACKS compile time option cannot be used in projects using the library Class drivers.
#endif
#if defined(USB_CAN_BE_DEVICE)
#include "Device/Audio.h"
#endif
#endif
/** @} */

View File

@ -0,0 +1,83 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Master include file for the library USB CDC-ACM Class driver.
*
* Master include file for the library USB CDC Class driver, for both host and device modes, where available.
*
* This file should be included in all user projects making use of this optional class driver, instead of
* including any headers in the USB/ClassDriver/Device, USB/ClassDriver/Host or USB/ClassDriver/Common subdirectories.
*/
/** \ingroup Group_USBClassDrivers
* @defgroup Group_USBClassCDC CDC-ACM (Virtual Serial) Class Driver - LUFA/Drivers/Class/CDC.h
*
* \section Sec_Dependencies Module Source Dependencies
* The following files must be built with any user project that uses this module:
* - LUFA/Drivers/USB/Class/Device/CDC.c <i>(Makefile source module name: LUFA_SRC_USBCLASS)</i>
* - LUFA/Drivers/USB/Class/Host/CDC.c <i>(Makefile source module name: LUFA_SRC_USBCLASS)</i>
*
* \section Module Description
* CDC Class Driver module. This module contains an internal implementation of the USB CDC-ACM class Virtual Serial
* Ports, for both Device and Host USB modes. User applications can use this class driver instead of implementing the
* CDC class manually via the low-level LUFA APIs.
*
* This module is designed to simplify the user code by exposing only the required interface needed to interface with
* Hosts or Devices using the USB CDC Class.
*
* @{
*/
#ifndef _CDC_CLASS_H_
#define _CDC_CLASS_H_
/* Macros: */
#define __INCLUDE_FROM_CDC_DRIVER
#define __INCLUDE_FROM_USB_DRIVER
/* Includes: */
#include "../HighLevel/USBMode.h"
#if defined(NO_STREAM_CALLBACKS)
#error The NO_STREAM_CALLBACKS compile time option cannot be used in projects using the library Class drivers.
#endif
#if defined(USB_CAN_BE_DEVICE)
#include "Device/CDC.h"
#endif
#if defined(USB_CAN_BE_HOST)
#include "Host/CDC.h"
#endif
#endif
/** @} */

View File

@ -0,0 +1,406 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Common definitions and declarations for the library USB Audio Class driver.
*
* Common definitions and declarations for the library USB Audio Class driver.
*
* \note This file should not be included directly. It is automatically included as needed by the class driver
* dispatch header located in LUFA/Drivers/USB/Class/Audio.h.
*/
/** \ingroup Group_USBClassAudio
* @defgroup Group_USBClassAudioCommon Common Class Definitions
*
* \section Module Description
* Constants, Types and Enum definitions that are common to both Device and Host modes for the USB
* Audio Class.
*
* @{
*/
#ifndef _AUDIO_CLASS_COMMON_H_
#define _AUDIO_CLASS_COMMON_H_
/* Includes: */
#include "../../USB.h"
#include <string.h>
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_AUDIO_DRIVER)
#error Do not include this file directly. Include LUFA/Drivers/Class/Audio.h instead.
#endif
/* Macros: */
#if !defined(AUDIO_TOTAL_SAMPLE_RATES) || defined(__DOXYGEN__)
/** Total number of discrete audio sample rates supported by the device. This value can be overridden by defining this
* token in the project makefile to the desired value, and passing it to the compiler via the -D switch.
*/
#define AUDIO_TOTAL_SAMPLE_RATES 1
#endif
/** Descriptor header constant to indicate a Audio class interface descriptor. */
#define DTYPE_AudioInterface 0x24
/** Descriptor header constant to indicate a Audio class endpoint descriptor. */
#define DTYPE_AudioEndpoint 0x25
/** Audio class descriptor subtype value for a Audio class-specific header descriptor. */
#define DSUBTYPE_Header 0x01
/** Audio class descriptor subtype value for an Output Terminal Audio class-specific descriptor. */
#define DSUBTYPE_InputTerminal 0x02
/** Audio class descriptor subtype value for an Input Terminal Audio class-specific descriptor. */
#define DSUBTYPE_OutputTerminal 0x03
/** Audio class descriptor subtype value for a Feature Unit Audio class-specific descriptor. */
#define DSUBTYPE_FeatureUnit 0x06
/** Audio class descriptor subtype value for a general Audio class-specific descriptor. */
#define DSUBTYPE_General 0x01
/** Audio class descriptor subtype value for an Audio class-specific descriptor indicating the format of an audio stream. */
#define DSUBTYPE_Format 0x02
/** Supported channel mask for an Audio class terminal descriptor. See the Audio class specification for more details. */
#define CHANNEL_LEFT_FRONT (1 << 0)
/** Supported channel mask for an Audio class terminal descriptor. See the Audio class specification for more details. */
#define CHANNEL_RIGHT_FRONT (1 << 1)
/** Supported channel mask for an Audio class terminal descriptor. See the Audio class specification for more details. */
#define CHANNEL_CENTER_FRONT (1 << 2)
/** Supported channel mask for an Audio class terminal descriptor. See the Audio class specification for more details. */
#define CHANNEL_LOW_FREQ_ENHANCE (1 << 3)
/** Supported channel mask for an Audio class terminal descriptor. See the Audio class specification for more details. */
#define CHANNEL_LEFT_SURROUND (1 << 4)
/** Supported channel mask for an Audio class terminal descriptor. See the Audio class specification for more details. */
#define CHANNEL_RIGHT_SURROUND (1 << 5)
/** Supported channel mask for an Audio class terminal descriptor. See the Audio class specification for more details. */
#define CHANNEL_LEFT_OF_CENTER (1 << 6)
/** Supported channel mask for an Audio class terminal descriptor. See the Audio class specification for more details. */
#define CHANNEL_RIGHT_OF_CENTER (1 << 7)
/** Supported channel mask for an Audio class terminal descriptor. See the Audio class specification for more details. */
#define CHANNEL_SURROUND (1 << 8)
/** Supported channel mask for an Audio class terminal descriptor. See the Audio class specification for more details. */
#define CHANNEL_SIDE_LEFT (1 << 9)
/** Supported channel mask for an Audio class terminal descriptor. See the Audio class specification for more details. */
#define CHANNEL_SIDE_RIGHT (1 << 10)
/** Supported channel mask for an Audio class terminal descriptor. See the Audio class specification for more details. */
#define CHANNEL_TOP (1 << 11)
/** Supported feature mask for an Audio class feature unit descriptor. See the Audio class specification for more details. */
#define FEATURE_MUTE (1 << 0)
/** Supported feature mask for an Audio class feature unit descriptor. See the Audio class specification for more details. */
#define FEATURE_VOLUME (1 << 1)
/** Supported feature mask for an Audio class feature unit descriptor. See the Audio class specification for more details. */
#define FEATURE_BASS (1 << 2)
/** Supported feature mask for an Audio class feature unit descriptor. See the Audio class specification for more details. */
#define FEATURE_MID (1 << 3)
/** Supported feature mask for an Audio class feature unit descriptor. See the Audio class specification for more details. */
#define FEATURE_TREBLE (1 << 4)
/** Supported feature mask for an Audio class feature unit descriptor. See the Audio class specification for more details. */
#define FEATURE_GRAPHIC_EQUALIZER (1 << 5)
/** Supported feature mask for an Audio class feature unit descriptor. See the Audio class specification for more details. */
/** Supported feature mask for an Audio class feature unit descriptor. See the Audio class specification for more details. */
#define FEATURE_AUTOMATIC_GAIN (1 << 6)
/** Supported feature mask for an Audio class feature unit descriptor. See the Audio class specification for more details. */
#define FEATURE_DELAY (1 << 7)
/** Supported feature mask for an Audio class feature unit descriptor. See the Audio class specification for more details. */
#define FEATURE_BASS_BOOST (1 << 8)
/** Supported feature mask for an Audio class feature unit descriptor. See the Audio class specification for more details. */
#define FEATURE_BASS_LOUDNESS (1 << 9)
/** Terminal type constant for an Audio class terminal descriptor. See the Audio class specification for more details. */
#define TERMINAL_UNDEFINED 0x0100
/** Terminal type constant for an Audio class terminal descriptor. See the Audio class specification for more details. */
#define TERMINAL_STREAMING 0x0101
/** Terminal type constant for an Audio class terminal descriptor. See the Audio class specification for more details. */
#define TERMINAL_VENDOR 0x01FF
/** Terminal type constant for an Audio class terminal descriptor. See the Audio class specification for more details. */
#define TERMINAL_IN_UNDEFINED 0x0200
/** Terminal type constant for an Audio class terminal descriptor. See the Audio class specification for more details. */
#define TERMINAL_IN_MIC 0x0201
/** Terminal type constant for an Audio class terminal descriptor. See the Audio class specification for more details. */
#define TERMINAL_IN_DESKTOP_MIC 0x0202
/** Terminal type constant for an Audio class terminal descriptor. See the Audio class specification for more details. */
#define TERMINAL_IN_PERSONAL_MIC 0x0203
/** Terminal type constant for an Audio class terminal descriptor. See the Audio class specification for more details. */
#define TERMINAL_IN_OMNIDIR_MIC 0x0204
/** Terminal type constant for an Audio class terminal descriptor. See the Audio class specification for more details. */
#define TERMINAL_IN_MIC_ARRAY 0x0205
/** Terminal type constant for an Audio class terminal descriptor. See the Audio class specification for more details. */
#define TERMINAL_IN_PROCESSING_MIC 0x0206
/** Terminal type constant for an Audio class terminal descriptor. See the Audio class specification for more details. */
#define TERMINAL_IN_OUT_UNDEFINED 0x0300
/** Terminal type constant for an Audio class terminal descriptor. See the Audio class specification for more details. */
#define TERMINAL_OUT_SPEAKER 0x0301
/** Terminal type constant for an Audio class terminal descriptor. See the Audio class specification for more details. */
#define TERMINAL_OUT_HEADPHONES 0x0302
/** Terminal type constant for an Audio class terminal descriptor. See the Audio class specification for more details. */
#define TERMINAL_OUT_HEAD_MOUNTED 0x0303
/** Terminal type constant for an Audio class terminal descriptor. See the Audio class specification for more details. */
#define TERMINAL_OUT_DESKTOP 0x0304
/** Terminal type constant for an Audio class terminal descriptor. See the Audio class specification for more details. */
#define TERMINAL_OUT_ROOM 0x0305
/** Terminal type constant for an Audio class terminal descriptor. See the Audio class specification for more details. */
#define TERMINAL_OUT_COMMUNICATION 0x0306
/** Terminal type constant for an Audio class terminal descriptor. See the Audio class specification for more details. */
#define TERMINAL_OUT_LOWFREQ 0x0307
/** Convenience macro, to fill a 24-bit AudioSampleFreq_t structure with the given sample rate as a 24-bit number.
*
* \param[in] freq Required audio sampling frequency in HZ
*/
#define AUDIO_SAMPLE_FREQ(freq) {LowWord: ((uint32_t)freq & 0x00FFFF), HighByte: (((uint32_t)freq >> 16) & 0x0000FF)}
/** Mask for the attributes parameter of an Audio class-specific Endpoint descriptor, indicating that the endpoint
* accepts only filled endpoint packets of audio samples.
*/
#define EP_ACCEPTS_ONLY_FULL_PACKETS (1 << 7)
/** Mask for the attributes parameter of an Audio class-specific Endpoint descriptor, indicating that the endpoint
* will accept partially filled endpoint packets of audio samples.
*/
#define EP_ACCEPTS_SMALL_PACKETS (0 << 7)
/* Type Defines: */
/** \brief Audio class-specific Interface Descriptor.
*
* Type define for an Audio class-specific interface descriptor. This follows a regular interface descriptor to
* supply extra information about the audio device's layout to the host. See the USB Audio specification for more
* details.
*/
typedef struct
{
USB_Descriptor_Header_t Header; /**< Regular descriptor header containing the descriptor's type and length. */
uint8_t Subtype; /**< Sub type value used to distinguish between audio class-specific descriptors. */
uint16_t ACSpecification; /**< Binary coded decimal value, indicating the supported Audio Class specification version. */
uint16_t TotalLength; /**< Total length of the Audio class-specific descriptors, including this descriptor. */
uint8_t InCollection; /**< Total number of audio class interfaces within this device. */
uint8_t InterfaceNumbers[1]; /**< Interface numbers of each audio interface. */
} USB_Audio_Interface_AC_t;
/** \brief Audio class-specific Feature Unit Descriptor.
*
* Type define for an Audio class-specific Feature Unit descriptor. This indicates to the host what features
* are present in the device's audio stream for basic control, such as per-channel volume. See the USB Audio
* specification for more details.
*/
typedef struct
{
USB_Descriptor_Header_t Header; /**< Regular descriptor header containing the descriptor's type and length. */
uint8_t Subtype; /**< Sub type value used to distinguish between audio class-specific descriptors. */
uint8_t UnitID; /**< ID value of this feature unit - must be a unique value within the device. */
uint8_t SourceID; /**< Source ID value of the audio source input into this feature unit. */
uint8_t ControlSize; /**< Size of each element in the ChanelControlls array. */
uint8_t ChannelControls[3]; /**< Feature masks for the control channel, and each separate audio channel. */
uint8_t FeatureUnitStrIndex; /**< Index of a string descriptor describing this descriptor within the device. */
} USB_Audio_FeatureUnit_t;
/** \brief Audio class-specific Input Terminal Descriptor.
*
* Type define for an Audio class-specific input terminal descriptor. This indicates to the host that the device
* contains an input audio source, either from a physical terminal on the device, or a logical terminal (for example,
* a USB endpoint). See the USB Audio specification for more details.
*/
typedef struct
{
USB_Descriptor_Header_t Header; /**< Regular descriptor header containing the descriptor's type and length. */
uint8_t Subtype; /**< Sub type value used to distinguish between audio class-specific descriptors. */
uint8_t TerminalID; /**< ID value of this terminal unit - must be a unique value within the device. */
uint16_t TerminalType; /**< Type of terminal, a TERMINAL_* mask. */
uint8_t AssociatedOutputTerminal; /**< ID of associated output terminal, for physically grouped terminals
* such as the speaker and microphone of a phone handset.
*/
uint8_t TotalChannels; /**< Total number of separate audio channels within this interface (right, left, etc.) */
uint16_t ChannelConfig; /**< CHANNEL_* masks indicating what channel layout is supported by this terminal. */
uint8_t ChannelStrIndex; /**< Index of a string descriptor describing this channel within the device. */
uint8_t TerminalStrIndex; /**< Index of a string descriptor describing this descriptor within the device. */
} USB_Audio_InputTerminal_t;
/** \brief Audio class-specific Output Terminal Descriptor.
*
* Type define for an Audio class-specific output terminal descriptor. This indicates to the host that the device
* contains an output audio sink, either to a physical terminal on the device, or a logical terminal (for example,
* a USB endpoint). See the USB Audio specification for more details.
*/
typedef struct
{
USB_Descriptor_Header_t Header; /**< Regular descriptor header containing the descriptor's type and length. */
uint8_t Subtype; /**< Sub type value used to distinguish between audio class-specific descriptors. */
uint8_t TerminalID; /**< ID value of this terminal unit - must be a unique value within the device. */
uint16_t TerminalType; /**< Type of terminal, a TERMINAL_* mask. */
uint8_t AssociatedInputTerminal; /**< ID of associated input terminal, for physically grouped terminals
* such as the speaker and microphone of a phone handset.
*/
uint8_t SourceID; /**< ID value of the unit this terminal's audio is sourced from. */
uint8_t TerminalStrIndex; /**< Index of a string descriptor describing this descriptor within the device. */
} USB_Audio_OutputTerminal_t;
/** \brief Audio class-specific Streaming Audio Interface Descriptor.
*
* Type define for an Audio class-specific streaming interface descriptor. This indicates to the host
* how audio streams within the device are formatted. See the USB Audio specification for more details.
*/
typedef struct
{
USB_Descriptor_Header_t Header; /**< Regular descriptor header containing the descriptor's type and length. */
uint8_t Subtype; /**< Sub type value used to distinguish between audio class-specific descriptors. */
uint8_t TerminalLink; /**< ID value of the output terminal this descriptor is describing. */
uint8_t FrameDelay; /**< Delay in frames resulting from the complete sample processing from input to output. */
uint16_t AudioFormat; /**< Format of the audio stream, see Audio Device Formats specification. */
} USB_Audio_Interface_AS_t;
/** \brief 24-Bit Audio Frequency Structure.
*
* Type define for a 24bit audio sample frequency structure. GCC does not contain a built in 24bit datatype,
* this this structure is used to build up the value instead. Fill this structure with the \ref AUDIO_SAMPLE_FREQ() macro.
*/
typedef struct
{
uint16_t LowWord; /**< Low 16 bits of the 24-bit value. */
uint8_t HighByte; /**< Upper 8 bits of the 24-bit value. */
} USB_Audio_SampleFreq_t;
/** \brief Audio class-specific Format Descriptor.
*
* Type define for an Audio class-specific audio format descriptor. This is used to give the host full details
* about the number of channels, the sample resolution, acceptable sample frequencies and encoding method used
* in the device's audio streams. See the USB Audio specification for more details.
*/
typedef struct
{
USB_Descriptor_Header_t Header; /**< Regular descriptor header containing the descriptor's type and length. */
uint8_t Subtype; /**< Sub type value used to distinguish between audio class-specific descriptors. */
uint8_t FormatType; /**< Format of the audio stream, see Audio Device Formats specification. */
uint8_t Channels; /**< Total number of discrete channels in the stream. */
uint8_t SubFrameSize; /**< Size in bytes of each channel's sample data in the stream. */
uint8_t BitResolution; /**< Bits of resolution of each channel's samples in the stream. */
uint8_t SampleFrequencyType; /**< Total number of sample frequencies supported by the device. */
USB_Audio_SampleFreq_t SampleFrequencies[AUDIO_TOTAL_SAMPLE_RATES]; /**< Sample frequencies supported by the device. */
} USB_Audio_Format_t;
/** \brief Audio class-specific Streaming Endpoint Descriptor.
*
* Type define for an Audio class-specific endpoint descriptor. This contains a regular endpoint
* descriptor with a few Audio-class-specific extensions. See the USB Audio specification for more details.
*/
typedef struct
{
USB_Descriptor_Endpoint_t Endpoint; /**< Standard endpoint descriptor describing the audio endpoint. */
uint8_t Refresh; /**< Always set to zero for Audio class devices. */
uint8_t SyncEndpointNumber; /**< Endpoint address to send synchronization information to, if needed (zero otherwise). */
} USB_Audio_StreamEndpoint_Std_t;
/** \brief Audio class-specific Extended Endpoint Descriptor.
*
* Type define for an Audio class-specific extended endpoint descriptor. This contains extra information
* on the usage of endpoints used to stream audio in and out of the USB Audio device, and follows an Audio
* class-specific extended endpoint descriptor. See the USB Audio specification for more details.
*/
typedef struct
{
USB_Descriptor_Header_t Header; /**< Regular descriptor header containing the descriptor's type and length. */
uint8_t Subtype; /**< Sub type value used to distinguish between audio class-specific descriptors. */
uint8_t Attributes; /**< Audio class-specific endpoint attributes, such as ACCEPTS_SMALL_PACKETS. */
uint8_t LockDelayUnits; /**< Units used for the LockDelay field, see Audio class specification. */
uint16_t LockDelay; /**< Time required to internally lock endpoint's internal clock recovery circuitry. */
} USB_Audio_StreamEndpoint_Spc_t;
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,179 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Common definitions and declarations for the library USB CDC Class driver.
*
* Common definitions and declarations for the library USB CDC Class driver.
*
* \note This file should not be included directly. It is automatically included as needed by the class driver
* dispatch header located in LUFA/Drivers/USB/Class/CDC.h.
*/
/** \ingroup Group_USBClassCDC
* @defgroup Group_USBClassCDCCommon Common Class Definitions
*
* \section Module Description
* Constants, Types and Enum definitions that are common to both Device and Host modes for the USB
* CDC Class.
*
* @{
*/
#ifndef _CDC_CLASS_COMMON_H_
#define _CDC_CLASS_COMMON_H_
/* Includes: */
#include "../../USB.h"
#include <string.h>
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_CDC_DRIVER)
#error Do not include this file directly. Include LUFA/Drivers/Class/CDC.h instead.
#endif
/* Macros: */
/** CDC class-specific request to get the current virtual serial port configuration settings. */
#define REQ_GetLineEncoding 0x21
/** CDC class-specific request to set the current virtual serial port configuration settings. */
#define REQ_SetLineEncoding 0x20
/** CDC class-specific request to set the current virtual serial port handshake line states. */
#define REQ_SetControlLineState 0x22
/** CDC class-specific request to send a break to the receiver via the carrier channel. */
#define REQ_SendBreak 0x23
/** CDC class-specific request to send an encapsulated command to the device. */
#define REQ_SendEncapsulatedCommand 0x00
/** CDC class-specific request to retrieve an encapsulated command response from the device. */
#define REQ_GetEncapsulatedResponse 0x01
/** Notification type constant for a change in the virtual serial port handshake line states, for
* use with a USB_Notification_Header_t notification structure when sent to the host via the CDC
* notification endpoint.
*/
#define NOTIF_SerialState 0x20
/** Mask for the DTR handshake line for use with the REQ_SetControlLineState class-specific request
* from the host, to indicate that the DTR line state should be high.
*/
#define CDC_CONTROL_LINE_OUT_DTR (1 << 0)
/** Mask for the RTS handshake line for use with the REQ_SetControlLineState class-specific request
* from the host, to indicate that theRTS line state should be high.
*/
#define CDC_CONTROL_LINE_OUT_RTS (1 << 1)
/** Mask for the DCD handshake line for use with the a NOTIF_SerialState class-specific notification
* from the device to the host, to indicate that the DCD line state is currently high.
*/
#define CDC_CONTROL_LINE_IN_DCD (1 << 0)
/** Mask for the DSR handshake line for use with the a NOTIF_SerialState class-specific notification
* from the device to the host, to indicate that the DSR line state is currently high.
*/
#define CDC_CONTROL_LINE_IN_DSR (1 << 1)
/** Mask for the BREAK handshake line for use with the a NOTIF_SerialState class-specific notification
* from the device to the host, to indicate that the BREAK line state is currently high.
*/
#define CDC_CONTROL_LINE_IN_BREAK (1 << 2)
/** Mask for the RING handshake line for use with the a NOTIF_SerialState class-specific notification
* from the device to the host, to indicate that the RING line state is currently high.
*/
#define CDC_CONTROL_LINE_IN_RING (1 << 3)
/** Mask for use with the a NOTIF_SerialState class-specific notification from the device to the host,
* to indicate that a framing error has occurred on the virtual serial port.
*/
#define CDC_CONTROL_LINE_IN_FRAMEERROR (1 << 4)
/** Mask for use with the a NOTIF_SerialState class-specific notification from the device to the host,
* to indicate that a parity error has occurred on the virtual serial port.
*/
#define CDC_CONTROL_LINE_IN_PARITYERROR (1 << 5)
/** Mask for use with the a NOTIF_SerialState class-specific notification from the device to the host,
* to indicate that a data overrun error has occurred on the virtual serial port.
*/
#define CDC_CONTROL_LINE_IN_OVERRUNERROR (1 << 6)
/** Macro to define a CDC class-specific functional descriptor. CDC functional descriptors have a
* uniform structure but variable sized data payloads, thus cannot be represented accurately by
* a single typedef struct. A macro is used instead so that functional descriptors can be created
* easily by specifying the size of the payload. This allows sizeof() to work correctly.
*
* \param[in] DataSize Size in bytes of the CDC functional descriptor's data payload.
*/
#define CDC_FUNCTIONAL_DESCRIPTOR(DataSize) \
struct \
{ \
USB_Descriptor_Header_t Header; \
uint8_t SubType; \
uint8_t Data[DataSize]; \
}
/* Enums: */
/** Enum for the possible line encoding formats of a virtual serial port. */
enum CDC_LineEncodingFormats_t
{
CDC_LINEENCODING_OneStopBit = 0, /**< Each frame contains one stop bit. */
CDC_LINEENCODING_OneAndAHalfStopBits = 1, /**< Each frame contains one and a half stop bits. */
CDC_LINEENCODING_TwoStopBits = 2, /**< Each frame contains two stop bits. */
};
/** Enum for the possible line encoding parity settings of a virtual serial port. */
enum CDC_LineEncodingParity_t
{
CDC_PARITY_None = 0, /**< No parity bit mode on each frame. */
CDC_PARITY_Odd = 1, /**< Odd parity bit mode on each frame. */
CDC_PARITY_Even = 2, /**< Even parity bit mode on each frame. */
CDC_PARITY_Mark = 3, /**< Mark parity bit mode on each frame. */
CDC_PARITY_Space = 4, /**< Space parity bit mode on each frame. */
};
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,195 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Common definitions and declarations for the library USB HID Class driver.
*
* Common definitions and declarations for the library USB HID Class driver.
*
* \note This file should not be included directly. It is automatically included as needed by the class driver
* dispatch header located in LUFA/Drivers/USB/Class/HID.h.
*/
/** \ingroup Group_USBClassHID
* @defgroup Group_USBClassHIDCommon Common Class Definitions
*
* \section Module Description
* Constants, Types and Enum definitions that are common to both Device and Host modes for the USB
* HID Class.
*
* @{
*/
#ifndef _HID_CLASS_COMMON_H_
#define _HID_CLASS_COMMON_H_
/* Includes: */
#include "../../USB.h"
#include <string.h>
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_HID_DRIVER)
#error Do not include this file directly. Include LUFA/Drivers/Class/HID.h instead.
#endif
/* Macros: */
/** HID class-specific Request to get the current HID report from the device. */
#define REQ_GetReport 0x01
/** HID class-specific Request to get the current device idle count. */
#define REQ_GetIdle 0x02
/** HID class-specific Request to set the current HID report to the device. */
#define REQ_SetReport 0x09
/** HID class-specific Request to set the device's idle count. */
#define REQ_SetIdle 0x0A
/** HID class-specific Request to get the current HID report protocol mode. */
#define REQ_GetProtocol 0x03
/** HID class-specific Request to set the current HID report protocol mode. */
#define REQ_SetProtocol 0x0B
/** Descriptor header type value, to indicate a HID class HID descriptor. */
#define DTYPE_HID 0x21
/** Descriptor header type value, to indicate a HID class HID report descriptor. */
#define DTYPE_Report 0x22
/** Constant for the protocol value of a HID interface descriptor, indicating that the interface does not support
* any HID class boot protocol (see HID Class Specification).
*/
#define HID_NON_BOOT_PROTOCOL 0x00
/** Constant for the protocol value of a HID interface descriptor, indicating that the interface supports the
* HID class Keyboard boot protocol (see HID Class Specification).
*/
#define HID_BOOT_KEYBOARD_PROTOCOL 0x01
/** Constant for the protocol value of a HID interface descriptor, indicating that the interface supports the
* HID class Mouse boot protocol (see HID Class Specification).
*/
#define HID_BOOT_MOUSE_PROTOCOL 0x02
/** Constant for a keyboard report modifier byte, indicating that the keyboard's left control key is currently pressed. */
#define HID_KEYBOARD_MODIFER_LEFTCTRL (1 << 0)
/** Constant for a keyboard report modifier byte, indicating that the keyboard's left shift key is currently pressed. */
#define HID_KEYBOARD_MODIFER_LEFTSHIFT (1 << 1)
/** Constant for a keyboard report modifier byte, indicating that the keyboard's left alt key is currently pressed. */
#define HID_KEYBOARD_MODIFER_LEFTALT (1 << 2)
/** Constant for a keyboard report modifier byte, indicating that the keyboard's left GUI key is currently pressed. */
#define HID_KEYBOARD_MODIFER_LEFTGUI (1 << 3)
/** Constant for a keyboard report modifier byte, indicating that the keyboard's right control key is currently pressed. */
#define HID_KEYBOARD_MODIFER_RIGHTCTRL (1 << 4)
/** Constant for a keyboard report modifier byte, indicating that the keyboard's right shift key is currently pressed. */
#define HID_KEYBOARD_MODIFER_RIGHTSHIFT (1 << 5)
/** Constant for a keyboard report modifier byte, indicating that the keyboard's right alt key is currently pressed. */
#define HID_KEYBOARD_MODIFER_RIGHTALT (1 << 6)
/** Constant for a keyboard report modifier byte, indicating that the keyboard's right GUI key is currently pressed. */
#define HID_KEYBOARD_MODIFER_RIGHTGUI (1 << 7)
/** Constant for a keyboard output report LED byte, indicating that the host's NUM LOCK mode is currently set. */
#define HID_KEYBOARD_LED_NUMLOCK (1 << 0)
/** Constant for a keyboard output report LED byte, indicating that the host's CAPS LOCK mode is currently set. */
#define HID_KEYBOARD_LED_CAPSLOCK (1 << 1)
/** Constant for a keyboard output report LED byte, indicating that the host's SCROLL LOCK mode is currently set. */
#define HID_KEYBOARD_LED_SCROLLLOCK (1 << 2)
/** Constant for a keyboard output report LED byte, indicating that the host's KATANA mode is currently set. */
#define HID_KEYBOARD_LED_KATANA (1 << 3)
/* Type Defines: */
/** Enum for the different types of HID reports. */
enum HID_ReportItemTypes_t
{
REPORT_ITEM_TYPE_In = 0, /**< Indicates that the item is an IN report type. */
REPORT_ITEM_TYPE_Out = 1, /**< Indicates that the item is an OUT report type. */
REPORT_ITEM_TYPE_Feature = 2, /**< Indicates that the item is a FEATURE report type. */
};
/** \brief HID class-specific HID Descriptor.
*
* Type define for the HID class-specific HID descriptor, to describe the HID device's specifications. Refer to the HID
* specification for details on the structure elements.
*/
typedef struct
{
USB_Descriptor_Header_t Header; /**< Regular descriptor header containing the descriptor's type and length. */
uint16_t HIDSpec; /**< BCD encoded version that the HID descriptor and device complies to. */
uint8_t CountryCode; /**< Country code of the localized device, or zero if universal. */
uint8_t TotalReportDescriptors; /**< Total number of HID report descriptors for the interface. */
uint8_t HIDReportType; /**< Type of HID report, set to \ref DTYPE_Report. */
uint16_t HIDReportLength; /**< Length of the associated HID report descriptor, in bytes. */
} USB_HID_Descriptor_t;
/** \brief Standard HID Boot Protocol Mouse Report.
*
* Type define for a standard Boot Protocol Mouse report
*/
typedef struct
{
uint8_t Button; /**< Button mask for currently pressed buttons in the mouse. */
int8_t X; /**< Current delta X movement of the mouse. */
int8_t Y; /**< Current delta Y movement on the mouse. */
} USB_MouseReport_Data_t;
/** \brief Standard HID Boot Protocol Keyboard Report.
*
* Type define for a standard Boot Protocol Keyboard report
*/
typedef struct
{
uint8_t Modifier; /**< Keyboard modifier byte, indicating pressed modifier keys (a combination of
* HID_KEYBOARD_MODIFER_* masks).
*/
uint8_t Reserved; /**< Reserved for OEM use, always set to 0. */
uint8_t KeyCode[6]; /**< Key codes of the currently pressed keys. */
} USB_KeyboardReport_Data_t;
/** Type define for the data type used to store HID report descriptor elements. */
typedef uint8_t USB_Descriptor_HIDReport_Datatype_t;
#endif
/** @} */

View File

@ -0,0 +1,191 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Common definitions and declarations for the library USB MIDI Class driver.
*
* Common definitions and declarations for the library USB MIDI Class driver.
*
* \note This file should not be included directly. It is automatically included as needed by the class driver
* dispatch header located in LUFA/Drivers/USB/Class/MIDI.h.
*/
/** \ingroup Group_USBClassMIDI
* @defgroup Group_USBClassMIDICommon Common Class Definitions
*
* \section Module Description
* Constants, Types and Enum definitions that are common to both Device and Host modes for the USB
* MIDI Class.
*
* @{
*/
#ifndef _MIDI_CLASS_COMMON_H_
#define _MIDI_CLASS_COMMON_H_
/* Macros: */
#define __INCLUDE_FROM_AUDIO_DRIVER
/* Includes: */
#include "../../USB.h"
#include "Audio.h"
#include <string.h>
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_MIDI_DRIVER)
#error Do not include this file directly. Include LUFA/Drivers/Class/MIDI.h instead.
#endif
/* Macros: */
/** Audio class descriptor subtype value for a Audio class-specific MIDI input jack descriptor. */
#define DSUBTYPE_InputJack 0x02
/** Audio class descriptor subtype value for a Audio class-specific MIDI output jack descriptor. */
#define DSUBTYPE_OutputJack 0x03
/** Audio class descriptor jack type value for an embedded (logical) MIDI input or output jack. */
#define MIDI_JACKTYPE_EMBEDDED 0x01
/** Audio class descriptor jack type value for an external (physical) MIDI input or output jack. */
#define MIDI_JACKTYPE_EXTERNAL 0x02
/** MIDI command for a note on (activation) event. */
#define MIDI_COMMAND_NOTE_ON 0x90
/** MIDI command for a note off (deactivation) event. */
#define MIDI_COMMAND_NOTE_OFF 0x80
/** Standard key press velocity value used for all note events. */
#define MIDI_STANDARD_VELOCITY 64
/** Convenience macro. MIDI channels are numbered from 1-10 (natural numbers) however the logical channel
* addresses are zero-indexed. This converts a natural MIDI channel number into the logical channel address.
*
* \param[in] channel MIDI channel number to address.
*/
#define MIDI_CHANNEL(channel) ((channel) - 1)
/* Type Defines: */
/** \brief MIDI class-specific Streaming Interface Descriptor.
*
* Type define for an Audio class-specific MIDI streaming interface descriptor. This indicates to the host
* how MIDI the specification compliance of the device and the total length of the Audio class-specific descriptors.
* See the USB Audio specification for more details.
*/
typedef struct
{
USB_Descriptor_Header_t Header; /**< Regular descriptor header containing the descriptor's type and length. */
uint8_t Subtype; /**< Sub type value used to distinguish between audio class-specific descriptors. */
uint16_t AudioSpecification; /**< Binary coded decimal value, indicating the supported Audio Class
* specification version.
*/
uint16_t TotalLength; /**< Total length of the Audio class-specific descriptors, including this descriptor. */
} USB_MIDI_AudioInterface_AS_t;
/** \brief MIDI class-specific Input Jack Descriptor.
*
* Type define for an Audio class-specific MIDI IN jack. This gives information to the host on a MIDI input, either
* a physical input jack, or a logical jack (receiving input data internally, or from the host via an endpoint).
*/
typedef struct
{
USB_Descriptor_Header_t Header; /**< Regular descriptor header containing the descriptor's type and length. */
uint8_t Subtype; /**< Sub type value used to distinguish between audio class-specific descriptors. */
uint8_t JackType; /**< Type of jack, one of the JACKTYPE_* mask values. */
uint8_t JackID; /**< ID value of this jack - must be a unique value within the device. */
uint8_t JackStrIndex; /**< Index of a string descriptor describing this descriptor within the device. */
} USB_MIDI_In_Jack_t;
/** \brief MIDI class-specific Output Jack Descriptor.
*
* Type define for an Audio class-specific MIDI OUT jack. This gives information to the host on a MIDI output, either
* a physical output jack, or a logical jack (sending output data internally, or to the host via an endpoint).
*/
typedef struct
{
USB_Descriptor_Header_t Header; /**< Regular descriptor header containing the descriptor's type and length. */
uint8_t Subtype; /**< Sub type value used to distinguish between audio class-specific descriptors. */
uint8_t JackType; /**< Type of jack, one of the JACKTYPE_* mask values. */
uint8_t JackID; /**< ID value of this jack - must be a unique value within the device. */
uint8_t NumberOfPins; /**< Number of output channels within the jack, either physical or logical. */
uint8_t SourceJackID[1]; /**< ID of each output pin's source data jack. */
uint8_t SourcePinID[1]; /**< Pin number in the input jack of each output pin's source data. */
uint8_t JackStrIndex; /**< Index of a string descriptor describing this descriptor within the device. */
} USB_MIDI_Out_Jack_t;
/** \brief Audio class-specific Jack Endpoint Descriptor.
*
* Type define for an Audio class-specific extended MIDI jack endpoint descriptor. This contains extra information
* on the usage of MIDI endpoints used to stream MIDI events in and out of the USB Audio device, and follows an Audio
* class-specific extended MIDI endpoint descriptor. See the USB Audio specification for more details.
*/
typedef struct
{
USB_Descriptor_Header_t Header; /**< Regular descriptor header containing the descriptor's type and length. */
uint8_t Subtype; /**< Sub type value used to distinguish between audio class-specific descriptors. */
uint8_t TotalEmbeddedJacks; /**< Total number of jacks inside this endpoint. */
uint8_t AssociatedJackID[1]; /**< IDs of each jack inside the endpoint. */
} USB_MIDI_Jack_Endpoint_t;
/** \brief MIDI Class Driver Event Packet.
*
* Type define for a USB MIDI event packet, used to encapsulate sent and received MIDI messages from a USB MIDI interface.
*/
typedef struct
{
unsigned char Command : 4; /**< Upper nibble of the MIDI command being sent or received in the event packet. */
unsigned char CableNumber : 4; /**< Virtual cable number of the event being sent or received in the given MIDI interface. */
uint8_t Data1; /**< First byte of data in the MIDI event. */
uint8_t Data2; /**< Second byte of data in the MIDI event. */
uint8_t Data3; /**< Third byte of data in the MIDI event. */
} MIDI_EventPacket_t;
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,322 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Common definitions and declarations for the library USB Mass Storage Class driver.
*
* Common definitions and declarations for the library USB Mass Storage Class driver.
*
* \note This file should not be included directly. It is automatically included as needed by the class driver
* dispatch header located in LUFA/Drivers/USB/Class/MassStorage.h.
*/
/** \ingroup Group_USBClassMS
* @defgroup Group_USBClassMSCommon Common Class Definitions
*
* \section Module Description
* Constants, Types and Enum definitions that are common to both Device and Host modes for the USB
* Mass Storage Class.
*
* @{
*/
#ifndef _MS_CLASS_COMMON_H_
#define _MS_CLASS_COMMON_H_
/* Includes: */
#include "../../USB.h"
#include <string.h>
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_MS_DRIVER)
#error Do not include this file directly. Include LUFA/Drivers/Class/MassStorage.h instead.
#endif
/* Macros: */
/** Mass Storage class-specific request to reset the Mass Storage interface, ready for the next command. */
#define REQ_MassStorageReset 0xFF
/** Mass Storage class-specific request to retrieve the total number of Logical Units (drives) in the SCSI device. */
#define REQ_GetMaxLUN 0xFE
/** Magic signature for a Command Block Wrapper used in the Mass Storage Bulk-Only transport protocol. */
#define MS_CBW_SIGNATURE 0x43425355UL
/** Magic signature for a Command Status Wrapper used in the Mass Storage Bulk-Only transport protocol. */
#define MS_CSW_SIGNATURE 0x53425355UL
/** Mask for a Command Block Wrapper's flags attribute to specify a command with data sent from host-to-device. */
#define MS_COMMAND_DIR_DATA_OUT (0 << 7)
/** Mask for a Command Block Wrapper's flags attribute to specify a command with data sent from device-to-host. */
#define MS_COMMAND_DIR_DATA_IN (1 << 7)
/** SCSI Command Code for an INQUIRY command. */
#define SCSI_CMD_INQUIRY 0x12
/** SCSI Command Code for a REQUEST SENSE command. */
#define SCSI_CMD_REQUEST_SENSE 0x03
/** SCSI Command Code for a TEST UNIT READY command. */
#define SCSI_CMD_TEST_UNIT_READY 0x00
/** SCSI Command Code for a READ CAPACITY (10) command. */
#define SCSI_CMD_READ_CAPACITY_10 0x25
/** SCSI Command Code for a SEND DIAGNOSTIC command. */
#define SCSI_CMD_SEND_DIAGNOSTIC 0x1D
/** SCSI Command Code for a PREVENT ALLOW MEDIUM REMOVAL command. */
#define SCSI_CMD_PREVENT_ALLOW_MEDIUM_REMOVAL 0x1E
/** SCSI Command Code for a WRITE (10) command. */
#define SCSI_CMD_WRITE_10 0x2A
/** SCSI Command Code for a READ (10) command. */
#define SCSI_CMD_READ_10 0x28
/** SCSI Command Code for a WRITE (6) command. */
#define SCSI_CMD_WRITE_6 0x0A
/** SCSI Command Code for a READ (6) command. */
#define SCSI_CMD_READ_6 0x08
/** SCSI Command Code for a VERIFY (10) command. */
#define SCSI_CMD_VERIFY_10 0x2F
/** SCSI Command Code for a MODE SENSE (6) command. */
#define SCSI_CMD_MODE_SENSE_6 0x1A
/** SCSI Command Code for a MODE SENSE (10) command. */
#define SCSI_CMD_MODE_SENSE_10 0x5A
/** SCSI Sense Code to indicate no error has occurred. */
#define SCSI_SENSE_KEY_GOOD 0x00
/** SCSI Sense Code to indicate that the device has recovered from an error. */
#define SCSI_SENSE_KEY_RECOVERED_ERROR 0x01
/** SCSI Sense Code to indicate that the device is not ready for a new command. */
#define SCSI_SENSE_KEY_NOT_READY 0x02
/** SCSI Sense Code to indicate an error whilst accessing the medium. */
#define SCSI_SENSE_KEY_MEDIUM_ERROR 0x03
/** SCSI Sense Code to indicate a hardware has occurred. */
#define SCSI_SENSE_KEY_HARDWARE_ERROR 0x04
/** SCSI Sense Code to indicate that an illegal request has been issued. */
#define SCSI_SENSE_KEY_ILLEGAL_REQUEST 0x05
/** SCSI Sense Code to indicate that the unit requires attention from the host to indicate
* a reset event, medium removal or other condition.
*/
#define SCSI_SENSE_KEY_UNIT_ATTENTION 0x06
/** SCSI Sense Code to indicate that a write attempt on a protected block has been made. */
#define SCSI_SENSE_KEY_DATA_PROTECT 0x07
/** SCSI Sense Code to indicate an error while trying to write to a write-once medium. */
#define SCSI_SENSE_KEY_BLANK_CHECK 0x08
/** SCSI Sense Code to indicate a vendor specific error has occurred. */
#define SCSI_SENSE_KEY_VENDOR_SPECIFIC 0x09
/** SCSI Sense Code to indicate that an EXTENDED COPY command has aborted due to an error. */
#define SCSI_SENSE_KEY_COPY_ABORTED 0x0A
/** SCSI Sense Code to indicate that the device has aborted the issued command. */
#define SCSI_SENSE_KEY_ABORTED_COMMAND 0x0B
/** SCSI Sense Code to indicate an attempt to write past the end of a partition has been made. */
#define SCSI_SENSE_KEY_VOLUME_OVERFLOW 0x0D
/** SCSI Sense Code to indicate that the source data did not match the data read from the medium. */
#define SCSI_SENSE_KEY_MISCOMPARE 0x0E
/** SCSI Additional Sense Code to indicate no additional sense information is available. */
#define SCSI_ASENSE_NO_ADDITIONAL_INFORMATION 0x00
/** SCSI Additional Sense Code to indicate that the logical unit (LUN) addressed is not ready. */
#define SCSI_ASENSE_LOGICAL_UNIT_NOT_READY 0x04
/** SCSI Additional Sense Code to indicate an invalid field was encountered while processing the issued command. */
#define SCSI_ASENSE_INVALID_FIELD_IN_CDB 0x24
/** SCSI Additional Sense Code to indicate that an attempt to write to a protected area was made. */
#define SCSI_ASENSE_WRITE_PROTECTED 0x27
/** SCSI Additional Sense Code to indicate an error whilst formatting the device medium. */
#define SCSI_ASENSE_FORMAT_ERROR 0x31
/** SCSI Additional Sense Code to indicate an invalid command was issued. */
#define SCSI_ASENSE_INVALID_COMMAND 0x20
/** SCSI Additional Sense Code to indicate a write to a block out outside of the medium's range was issued. */
#define SCSI_ASENSE_LOGICAL_BLOCK_ADDRESS_OUT_OF_RANGE 0x21
/** SCSI Additional Sense Code to indicate that no removable medium is inserted into the device. */
#define SCSI_ASENSE_MEDIUM_NOT_PRESENT 0x3A
/** SCSI Additional Sense Qualifier Code to indicate no additional sense qualifier information is available. */
#define SCSI_ASENSEQ_NO_QUALIFIER 0x00
/** SCSI Additional Sense Qualifier Code to indicate that a medium format command failed to complete. */
#define SCSI_ASENSEQ_FORMAT_COMMAND_FAILED 0x01
/** SCSI Additional Sense Qualifier Code to indicate that an initializing command must be issued before the issued
* command can be executed.
*/
#define SCSI_ASENSEQ_INITIALIZING_COMMAND_REQUIRED 0x02
/** SCSI Additional Sense Qualifier Code to indicate that an operation is currently in progress. */
#define SCSI_ASENSEQ_OPERATION_IN_PROGRESS 0x07
/* Type defines: */
/** \brief Mass Storage Class Command Block Wrapper.
*
* Type define for a Command Block Wrapper, used in the Mass Storage Bulk-Only Transport protocol. */
typedef struct
{
uint32_t Signature; /**< Command block signature, must be CBW_SIGNATURE to indicate a valid Command Block. */
uint32_t Tag; /**< Unique command ID value, to associate a command block wrapper with its command status wrapper. */
uint32_t DataTransferLength; /**< Length of the optional data portion of the issued command, in bytes. */
uint8_t Flags; /**< Command block flags, indicating command data direction. */
uint8_t LUN; /**< Logical Unit number this command is issued to. */
uint8_t SCSICommandLength; /**< Length of the issued SCSI command within the SCSI command data array. */
uint8_t SCSICommandData[16]; /**< Issued SCSI command in the Command Block. */
} MS_CommandBlockWrapper_t;
/** \brief Mass Storage Class Command Status Wrapper.
*
* Type define for a Command Status Wrapper, used in the Mass Storage Bulk-Only Transport protocol.
*/
typedef struct
{
uint32_t Signature; /**< Status block signature, must be CSW_SIGNATURE to indicate a valid Command Status. */
uint32_t Tag; /**< Unique command ID value, to associate a command block wrapper with its command status wrapper. */
uint32_t DataTransferResidue; /**< Number of bytes of data not processed in the SCSI command. */
uint8_t Status; /**< Status code of the issued command - a value from the MassStorage_CommandStatusCodes_t enum. */
} MS_CommandStatusWrapper_t;
/** \brief Mass Storage Class SCSI Sense Structure
*
* Type define for a SCSI Sense structure. Structures of this type are filled out by the
* device via the \ref MS_Host_RequestSense() function, indicating the current sense data of the
* device (giving explicit error codes for the last issued command). For details of the
* structure contents, refer to the SCSI specifications.
*/
typedef struct
{
uint8_t ResponseCode;
uint8_t SegmentNumber;
unsigned char SenseKey : 4;
unsigned char Reserved : 1;
unsigned char ILI : 1;
unsigned char EOM : 1;
unsigned char FileMark : 1;
uint8_t Information[4];
uint8_t AdditionalLength;
uint8_t CmdSpecificInformation[4];
uint8_t AdditionalSenseCode;
uint8_t AdditionalSenseQualifier;
uint8_t FieldReplaceableUnitCode;
uint8_t SenseKeySpecific[3];
} SCSI_Request_Sense_Response_t;
/** \brief Mass Storage Class SCSI Inquiry Structure.
*
* Type define for a SCSI Inquiry structure. Structures of this type are filled out by the
* device via the \ref MS_Host_GetInquiryData() function, retrieving the attached device's
* information.
*
* For details of the structure contents, refer to the SCSI specifications.
*/
typedef struct
{
unsigned char DeviceType : 5;
unsigned char PeripheralQualifier : 3;
unsigned char Reserved : 7;
unsigned char Removable : 1;
uint8_t Version;
unsigned char ResponseDataFormat : 4;
unsigned char Reserved2 : 1;
unsigned char NormACA : 1;
unsigned char TrmTsk : 1;
unsigned char AERC : 1;
uint8_t AdditionalLength;
uint8_t Reserved3[2];
unsigned char SoftReset : 1;
unsigned char CmdQue : 1;
unsigned char Reserved4 : 1;
unsigned char Linked : 1;
unsigned char Sync : 1;
unsigned char WideBus16Bit : 1;
unsigned char WideBus32Bit : 1;
unsigned char RelAddr : 1;
uint8_t VendorID[8];
uint8_t ProductID[16];
uint8_t RevisionID[4];
} SCSI_Inquiry_Response_t;
/* Enums: */
/** Enum for the possible command status wrapper return status codes. */
enum MassStorage_CommandStatusCodes_t
{
SCSI_Command_Pass = 0, /**< Command completed with no error */
SCSI_Command_Fail = 1, /**< Command failed to complete - host may check the exact error via a
* SCSI REQUEST SENSE command.
*/
SCSI_Phase_Error = 2 /**< Command failed due to being invalid in the current phase. */
};
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,85 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Common definitions and declarations for the library USB Printer Class driver.
*
* Common definitions and declarations for the library USB Printer Class driver.
*
* \note This file should not be included directly. It is automatically included as needed by the class driver
* dispatch header located in LUFA/Drivers/USB/Class/Printer.h.
*/
/** \ingroup Group_USBClassPrinter
* @defgroup Group_USBClassPrinterCommon Common Class Definitions
*
* \section Module Description
* Constants, Types and Enum definitions that are common to both Device and Host modes for the USB
* Printer Class.
*
* @{
*/
#ifndef _PRINTER_CLASS_COMMON_H_
#define _PRINTER_CLASS_COMMON_H_
/* Includes: */
#include "../../USB.h"
#include <string.h>
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_PRINTER_DRIVER)
#error Do not include this file directly. Include LUFA/Drivers/Class/Printer.h instead.
#endif
/* Macros: */
/** Port status mask for a printer device, indicating that an error has *not* occurred. */
#define PRNT_PORTSTATUS_NOTERROR (1 << 3)
/** Port status mask for a printer device, indicating that the device is currently selected. */
#define PRNT_PORTSTATUS_SELECT (1 << 4)
/** Port status mask for a printer device, indicating that the device is currently out of paper. */
#define PRNT_PORTSTATUS_PAPEREMPTY (1 << 5)
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,303 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Common definitions and declarations for the library USB RNDIS Class driver.
*
* Common definitions and declarations for the library USB RNDIS Class driver.
*
* \note This file should not be included directly. It is automatically included as needed by the class driver
* dispatch header located in LUFA/Drivers/USB/Class/RNDIS.h.
*/
/** \ingroup Group_USBClassRNDIS
* @defgroup Group_USBClassRNDISCommon Common Class Definitions
*
* \section Module Description
* Constants, Types and Enum definitions that are common to both Device and Host modes for the USB
* RNDIS Class.
*
* @{
*/
#ifndef _RNDIS_CLASS_COMMON_H_
#define _RNDIS_CLASS_COMMON_H_
/* Macros: */
#define __INCLUDE_FROM_CDC_DRIVER
/* Includes: */
#include "../../USB.h"
#include "RNDISConstants.h"
#include "CDC.h"
#include <string.h>
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_RNDIS_DRIVER)
#error Do not include this file directly. Include LUFA/Drivers/Class/RNDIS.h instead.
#endif
/* Macros: */
/** Implemented RNDIS Version Major. */
#define REMOTE_NDIS_VERSION_MAJOR 0x01
/** Implemented RNDIS Version Minor. */
#define REMOTE_NDIS_VERSION_MINOR 0x00
/** RNDIS request to issue a host-to-device NDIS command. */
#define REQ_SendEncapsulatedCommand 0x00
/** RNDIS request to issue a device-to-host NDIS response. */
#define REQ_GetEncapsulatedResponse 0x01
/** Maximum size in bytes of a RNDIS control message which can be sent or received. */
#define RNDIS_MESSAGE_BUFFER_SIZE 128
/** Maximum size in bytes of an Ethernet frame according to the Ethernet standard. */
#define ETHERNET_FRAME_SIZE_MAX 1500
/** Notification request value for a RNDIS Response Available notification. */
#define NOTIF_ResponseAvailable 1
/* Enums: */
/** Enum for the possible NDIS adapter states. */
enum RNDIS_States_t
{
RNDIS_Uninitialized = 0, /**< Adapter currently uninitialized. */
RNDIS_Initialized = 1, /**< Adapter currently initialized but not ready for data transfers. */
RNDIS_Data_Initialized = 2, /**< Adapter currently initialized and ready for data transfers. */
};
/** Enum for the NDIS hardware states. */
enum NDIS_Hardware_Status_t
{
NDIS_HardwareStatus_Ready, /**< Hardware Ready to accept commands from the host. */
NDIS_HardwareStatus_Initializing, /**< Hardware busy initializing. */
NDIS_HardwareStatus_Reset, /**< Hardware reset. */
NDIS_HardwareStatus_Closing, /**< Hardware currently closing. */
NDIS_HardwareStatus_NotReady /**< Hardware not ready to accept commands from the host. */
};
/* Type Defines: */
/** \brief MAC Address Structure.
*
* Type define for a physical MAC address of a device on a network.
*/
typedef struct
{
uint8_t Octets[6]; /**< Individual bytes of a MAC address */
} MAC_Address_t;
/** \brief RNDIS Ethernet Frame Packet Information Structure.
*
* Type define for an Ethernet frame buffer data and information structure.
*/
typedef struct
{
uint8_t FrameData[ETHERNET_FRAME_SIZE_MAX]; /**< Ethernet frame contents. */
uint16_t FrameLength; /**< Length in bytes of the Ethernet frame stored in the buffer. */
bool FrameInBuffer; /**< Indicates if a frame is currently stored in the buffer. */
} Ethernet_Frame_Info_t;
/** \brief RNDIS Common Message Header Structure.
*
* Type define for a RNDIS message header, sent before RNDIS messages.
*/
typedef struct
{
uint32_t MessageType; /**< RNDIS message type, a REMOTE_NDIS_*_MSG constant */
uint32_t MessageLength; /**< Total length of the RNDIS message, in bytes */
} RNDIS_Message_Header_t;
/** \brief RNDIS Message Structure.
*
* Type define for a RNDIS packet message, used to encapsulate Ethernet packets sent to and from the adapter.
*/
typedef struct
{
uint32_t MessageType;
uint32_t MessageLength;
uint32_t DataOffset;
uint32_t DataLength;
uint32_t OOBDataOffset;
uint32_t OOBDataLength;
uint32_t NumOOBDataElements;
uint32_t PerPacketInfoOffset;
uint32_t PerPacketInfoLength;
uint32_t VcHandle;
uint32_t Reserved;
} RNDIS_Packet_Message_t;
/** \brief RNDIS Initialization Message Structure.
*
* Type define for a RNDIS Initialize command message.
*/
typedef struct
{
uint32_t MessageType;
uint32_t MessageLength;
uint32_t RequestId;
uint32_t MajorVersion;
uint32_t MinorVersion;
uint32_t MaxTransferSize;
} RNDIS_Initialize_Message_t;
/** \brief RNDIS Initialize Complete Message Structure.
*
* Type define for a RNDIS Initialize Complete response message.
*/
typedef struct
{
uint32_t MessageType;
uint32_t MessageLength;
uint32_t RequestId;
uint32_t Status;
uint32_t MajorVersion;
uint32_t MinorVersion;
uint32_t DeviceFlags;
uint32_t Medium;
uint32_t MaxPacketsPerTransfer;
uint32_t MaxTransferSize;
uint32_t PacketAlignmentFactor;
uint32_t AFListOffset;
uint32_t AFListSize;
} RNDIS_Initialize_Complete_t;
/** \brief RNDIS Keep Alive Message Structure.
*
* Type define for a RNDIS Keep Alive command message.
*/
typedef struct
{
uint32_t MessageType;
uint32_t MessageLength;
uint32_t RequestId;
} RNDIS_KeepAlive_Message_t;
/** \brief RNDIS Keep Alive Complete Message Structure.
*
* Type define for a RNDIS Keep Alive Complete response message.
*/
typedef struct
{
uint32_t MessageType;
uint32_t MessageLength;
uint32_t RequestId;
uint32_t Status;
} RNDIS_KeepAlive_Complete_t;
/** \brief RNDIS Reset Complete Message Structure.
*
* Type define for a RNDIS Reset Complete response message.
*/
typedef struct
{
uint32_t MessageType;
uint32_t MessageLength;
uint32_t Status;
uint32_t AddressingReset;
} RNDIS_Reset_Complete_t;
/** \brief RNDIS OID Property Set Message Structure.
*
* Type define for a RNDIS OID Property Set command message.
*/
typedef struct
{
uint32_t MessageType;
uint32_t MessageLength;
uint32_t RequestId;
uint32_t Oid;
uint32_t InformationBufferLength;
uint32_t InformationBufferOffset;
uint32_t DeviceVcHandle;
} RNDIS_Set_Message_t;
/** \brief RNDIS OID Property Set Complete Message Structure.
*
* Type define for a RNDIS OID Property Set Complete response message.
*/
typedef struct
{
uint32_t MessageType;
uint32_t MessageLength;
uint32_t RequestId;
uint32_t Status;
} RNDIS_Set_Complete_t;
/** \brief RNDIS OID Property Query Message Structure.
*
* Type define for a RNDIS OID Property Query command message.
*/
typedef struct
{
uint32_t MessageType;
uint32_t MessageLength;
uint32_t RequestId;
uint32_t Oid;
uint32_t InformationBufferLength;
uint32_t InformationBufferOffset;
uint32_t DeviceVcHandle;
} RNDIS_Query_Message_t;
/** \brief RNDIS OID Property Query Complete Message Structure.
*
* Type define for a RNDIS OID Property Query Complete response message.
*/
typedef struct
{
uint32_t MessageType;
uint32_t MessageLength;
uint32_t RequestId;
uint32_t Status;
uint32_t InformationBufferLength;
uint32_t InformationBufferOffset;
} RNDIS_Query_Complete_t;
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,121 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Common RNDIS class constant definitions.
*
* Common RNDIS class constant definitions.
*
* \note This file should not be included directly. It is automatically included as needed by the class driver
* dispatch header located in LUFA/Drivers/USB/Class/Audio.h.
*/
/** \file
*
* RNDIS specification related constants. For more information on these
* constants, please refer to the Microsoft RNDIS specification.
*/
#ifndef _RNDIS_CONSTANTS_DEVICE_H_
#define _RNDIS_CONSTANTS_DEVICE_H_
/* Macros: */
#define REMOTE_NDIS_PACKET_MSG 0x00000001UL
#define REMOTE_NDIS_INITIALIZE_MSG 0x00000002UL
#define REMOTE_NDIS_HALT_MSG 0x00000003UL
#define REMOTE_NDIS_QUERY_MSG 0x00000004UL
#define REMOTE_NDIS_SET_MSG 0x00000005UL
#define REMOTE_NDIS_RESET_MSG 0x00000006UL
#define REMOTE_NDIS_INDICATE_STATUS_MSG 0x00000007UL
#define REMOTE_NDIS_KEEPALIVE_MSG 0x00000008UL
#define REMOTE_NDIS_INITIALIZE_CMPLT 0x80000002UL
#define REMOTE_NDIS_QUERY_CMPLT 0x80000004UL
#define REMOTE_NDIS_SET_CMPLT 0x80000005UL
#define REMOTE_NDIS_RESET_CMPLT 0x80000006UL
#define REMOTE_NDIS_KEEPALIVE_CMPLT 0x80000008UL
#define REMOTE_NDIS_STATUS_SUCCESS 0x00000000UL
#define REMOTE_NDIS_STATUS_FAILURE 0xC0000001UL
#define REMOTE_NDIS_STATUS_INVALID_DATA 0xC0010015UL
#define REMOTE_NDIS_STATUS_NOT_SUPPORTED 0xC00000BBUL
#define REMOTE_NDIS_STATUS_MEDIA_CONNECT 0x4001000BUL
#define REMOTE_NDIS_STATUS_MEDIA_DISCONNECT 0x4001000CUL
#define REMOTE_NDIS_MEDIA_STATE_CONNECTED 0x00000000UL
#define REMOTE_NDIS_MEDIA_STATE_DISCONNECTED 0x00000001UL
#define REMOTE_NDIS_MEDIUM_802_3 0x00000000UL
#define REMOTE_NDIS_DF_CONNECTIONLESS 0x00000001UL
#define REMOTE_NDIS_DF_CONNECTION_ORIENTED 0x00000002UL
#define REMOTE_NDIS_PACKET_DIRECTED 0x00000001UL
#define REMOTE_NDIS_PACKET_MULTICAST 0x00000002UL
#define REMOTE_NDIS_PACKET_ALL_MULTICAST 0x00000004UL
#define REMOTE_NDIS_PACKET_BROADCAST 0x00000008UL
#define REMOTE_NDIS_PACKET_SOURCE_ROUTING 0x00000010UL
#define REMOTE_NDIS_PACKET_PROMISCUOUS 0x00000020UL
#define REMOTE_NDIS_PACKET_SMT 0x00000040UL
#define REMOTE_NDIS_PACKET_ALL_LOCAL 0x00000080UL
#define REMOTE_NDIS_PACKET_GROUP 0x00001000UL
#define REMOTE_NDIS_PACKET_ALL_FUNCTIONAL 0x00002000UL
#define REMOTE_NDIS_PACKET_FUNCTIONAL 0x00004000UL
#define REMOTE_NDIS_PACKET_MAC_FRAME 0x00008000UL
#define OID_GEN_SUPPORTED_LIST 0x00010101UL
#define OID_GEN_HARDWARE_STATUS 0x00010102UL
#define OID_GEN_MEDIA_SUPPORTED 0x00010103UL
#define OID_GEN_MEDIA_IN_USE 0x00010104UL
#define OID_GEN_MAXIMUM_FRAME_SIZE 0x00010106UL
#define OID_GEN_MAXIMUM_TOTAL_SIZE 0x00010111UL
#define OID_GEN_LINK_SPEED 0x00010107UL
#define OID_GEN_TRANSMIT_BLOCK_SIZE 0x0001010AUL
#define OID_GEN_RECEIVE_BLOCK_SIZE 0x0001010BUL
#define OID_GEN_VENDOR_ID 0x0001010CUL
#define OID_GEN_VENDOR_DESCRIPTION 0x0001010DUL
#define OID_GEN_CURRENT_PACKET_FILTER 0x0001010EUL
#define OID_GEN_MAXIMUM_TOTAL_SIZE 0x00010111UL
#define OID_GEN_MEDIA_CONNECT_STATUS 0x00010114UL
#define OID_GEN_PHYSICAL_MEDIUM 0x00010202UL
#define OID_GEN_XMIT_OK 0x00020101UL
#define OID_GEN_RCV_OK 0x00020102UL
#define OID_GEN_XMIT_ERROR 0x00020103UL
#define OID_GEN_RCV_ERROR 0x00020104UL
#define OID_GEN_RCV_NO_BUFFER 0x00020105UL
#define OID_802_3_PERMANENT_ADDRESS 0x01010101UL
#define OID_802_3_CURRENT_ADDRESS 0x01010102UL
#define OID_802_3_MULTICAST_LIST 0x01010103UL
#define OID_802_3_MAXIMUM_LIST_SIZE 0x01010104UL
#define OID_802_3_RCV_ERROR_ALIGNMENT 0x01020101UL
#define OID_802_3_XMIT_ONE_COLLISION 0x01020102UL
#define OID_802_3_XMIT_MORE_COLLISIONS 0x01020103UL
#endif

View File

@ -0,0 +1,146 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Common definitions and declarations for the library USB Still Image Class driver.
*
* Common definitions and declarations for the library USB Still Image Class driver.
*
* \note This file should not be included directly. It is automatically included as needed by the class driver
* dispatch header located in LUFA/Drivers/USB/Class/StillImage.h.
*/
/** \ingroup Group_USBClassSI
* @defgroup Group_USBClassSICommon Common Class Definitions
*
* \section Module Description
* Constants, Types and Enum definitions that are common to both Device and Host modes for the USB
* Still Image Class.
*
* @{
*/
#ifndef _SI_CLASS_COMMON_H_
#define _SI_CLASS_COMMON_H_
/* Includes: */
#include "../../USB.h"
#include <string.h>
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_SI_DRIVER)
#error Do not include this file directly. Include LUFA/Drivers/Class/StillImage.h instead.
#endif
/* Macros: */
/** Length in bytes of a given Unicode string's character length.
*
* \param[in] Chars Total number of Unicode characters in the string.
*
* \return Number of bytes of the given unicode string.
*/
#define UNICODE_STRING_LENGTH(Chars) ((Chars) << 1)
/** Used in the DataLength field of a PIMA container, to give the total container size in bytes for
* a command container.
*
* \param[in] Params Number of parameters which are to be sent in the Param field of the container.
*/
#define PIMA_COMMAND_SIZE(Params) ((sizeof(SI_PIMA_Container_t) - 12) + \
((Params) * sizeof(uint32_t)))
/** Used in the DataLength field of a PIMA container, to give the total container size in bytes for
* a data container.
*
* \param[in] DataLen Length in bytes of the data in the container.
*/
#define PIMA_DATA_SIZE(DataLen) ((sizeof(SI_PIMA_Container_t) - 12) + \
(DataLen))
/* Enums: */
/** Enum for the possible PIMA contains types. */
enum SI_PIMA_Container_Types_t
{
CType_Undefined = 0, /**< Undefined container type. */
CType_CommandBlock = 1, /**< Command Block container type. */
CType_DataBlock = 2, /**< Data Block container type. */
CType_ResponseBlock = 3, /**< Response container type. */
CType_EventBlock = 4, /**< Event Block container type. */
};
/* Enums: */
/** Enums for the possible status codes of a returned Response Block from an attached PIMA compliant Still Image device. */
enum SI_PIMA_ResponseCodes_t
{
PIMA_RESPONSE_OK = 1, /**< Response code indicating no error in the issued command. */
PIMA_RESPONSE_GeneralError = 2, /**< Response code indicating a general error while processing the
* issued command.
*/
PIMA_RESPONSE_SessionNotOpen = 3, /**< Response code indicating that the sent command requires an open
* session before being issued.
*/
PIMA_RESPONSE_InvalidTransaction = 4, /**< Response code indicating an invalid transaction occurred. */
PIMA_RESPONSE_OperationNotSupported = 5, /**< Response code indicating that the issued command is not supported
* by the attached device.
*/
PIMA_RESPONSE_ParameterNotSupported = 6, /**< Response code indicating that one or more of the issued command's
* parameters are not supported by the device.
*/
};
/* Type Defines: */
/** \brief PIMA Still Image Device Command/Response Container.
*
* Type define for a PIMA container, use to send commands and receive responses to and from an
* attached Still Image device.
*/
typedef struct
{
uint32_t DataLength; /**< Length of the container and data, in bytes. */
uint16_t Type; /**< Container type, a value from the \ref SI_PIMA_Container_Types_t enum. */
uint16_t Code; /**< Command, event or response code of the container. */
uint32_t TransactionID; /**< Unique container ID to link blocks together. */
uint32_t Params[3]; /**< Block parameters to be issued along with the block code (command blocks only). */
} SI_PIMA_Container_t;
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,89 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
#define __INCLUDE_FROM_USB_DRIVER
#include "../../HighLevel/USBMode.h"
#if defined(USB_CAN_BE_DEVICE)
#define __INCLUDE_FROM_AUDIO_DRIVER
#include "Audio.h"
void Audio_Device_ProcessControlRequest(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo)
{
if (!(Endpoint_IsSETUPReceived()))
return;
if (USB_ControlRequest.wIndex != AudioInterfaceInfo->Config.StreamingInterfaceNumber)
return;
switch (USB_ControlRequest.bRequest)
{
case REQ_SetInterface:
if (USB_ControlRequest.bmRequestType == (REQDIR_HOSTTODEVICE | REQTYPE_STANDARD | REQREC_INTERFACE))
{
Endpoint_ClearSETUP();
AudioInterfaceInfo->State.InterfaceEnabled = ((USB_ControlRequest.wValue & 0xFF) != 0);
Endpoint_ClearStatusStage();
}
break;
}
}
bool Audio_Device_ConfigureEndpoints(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo)
{
memset(&AudioInterfaceInfo->State, 0x00, sizeof(AudioInterfaceInfo->State));
if (AudioInterfaceInfo->Config.DataINEndpointNumber)
{
if (!(Endpoint_ConfigureEndpoint(AudioInterfaceInfo->Config.DataINEndpointNumber, EP_TYPE_ISOCHRONOUS,
ENDPOINT_DIR_IN, AudioInterfaceInfo->Config.DataINEndpointSize,
ENDPOINT_BANK_DOUBLE)))
{
return false;
}
}
if (AudioInterfaceInfo->Config.DataOUTEndpointNumber)
{
if (!(Endpoint_ConfigureEndpoint(AudioInterfaceInfo->Config.DataOUTEndpointNumber, EP_TYPE_ISOCHRONOUS,
ENDPOINT_DIR_OUT, AudioInterfaceInfo->Config.DataOUTEndpointSize,
ENDPOINT_BANK_DOUBLE)))
{
return false;
}
}
return true;
}
#endif

View File

@ -0,0 +1,327 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Device mode driver for the library USB Audio Class driver.
*
* Device mode driver for the library USB Audio Class driver.
*
* \note This file should not be included directly. It is automatically included as needed by the class driver
* dispatch header located in LUFA/Drivers/USB/Class/Audio.h.
*/
/** \ingroup Group_USBClassAudio
* @defgroup Group_USBClassAudioDevice Audio Class Device Mode Driver
*
* \section Sec_Dependencies Module Source Dependencies
* The following files must be built with any user project that uses this module:
* - LUFA/Drivers/USB/Class/Device/Audio.c <i>(Makefile source module name: LUFA_SRC_USBCLASS)</i>
*
* \section Module Description
* Device Mode USB Class driver framework interface, for the Audio USB Class driver.
*
* @{
*/
#ifndef _AUDIO_CLASS_DEVICE_H_
#define _AUDIO_CLASS_DEVICE_H_
/* Includes: */
#include "../../USB.h"
#include "../Common/Audio.h"
#include <string.h>
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_AUDIO_DRIVER)
#error Do not include this file directly. Include LUFA/Drivers/Class/Audio.h instead.
#endif
/* Public Interface - May be used in end-application: */
/* Type Defines: */
/** \brief Audio Class Device Mode Configuration and State Structure.
*
* Class state structure. An instance of this structure should be made for each Audio interface
* within the user application, and passed to each of the Audio class driver functions as the
* AudioInterfaceInfo parameter. This stores each Audio interface's configuration and state information.
*/
typedef struct
{
const struct
{
uint8_t StreamingInterfaceNumber; /**< Index of the Audio Streaming interface within the device this
* structure controls.
*/
uint8_t DataINEndpointNumber; /**< Endpoint number of the incoming Audio Streaming data, if available
* (zero if unused).
*/
uint16_t DataINEndpointSize; /**< Size in bytes of the incoming Audio Streaming data endpoint, if available
* (zero if unused).
*/
uint8_t DataOUTEndpointNumber; /**< Endpoint number of the outgoing Audio Streaming data, if available
* (zero if unused).
*/
uint16_t DataOUTEndpointSize; /**< Size in bytes of the outgoing Audio Streaming data endpoint, if available
* (zero if unused).
*/
} Config; /**< Config data for the USB class interface within the device. All elements in this section
* <b>must</b> be set or the interface will fail to enumerate and operate correctly.
*/
struct
{
bool InterfaceEnabled; /**< Set and cleared by the class driver to indicate if the host has enabled the streaming endpoints
* of the Audio Streaming interface.
*/
} State; /**< State data for the USB class interface within the device. All elements in this section
* are reset to their defaults when the interface is enumerated.
*/
} USB_ClassInfo_Audio_Device_t;
/* Function Prototypes: */
/** Configures the endpoints of a given Audio interface, ready for use. This should be linked to the library
* \ref EVENT_USB_Device_ConfigurationChanged() event so that the endpoints are configured when the configuration containing the
* given Audio interface is selected.
*
* \param[in,out] AudioInterfaceInfo Pointer to a structure containing an Audio Class configuration and state.
*
* \return Boolean true if the endpoints were successfully configured, false otherwise.
*/
bool Audio_Device_ConfigureEndpoints(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1);
/** Processes incoming control requests from the host, that are directed to the given Audio class interface. This should be
* linked to the library \ref EVENT_USB_Device_UnhandledControlRequest() event.
*
* \param[in,out] AudioInterfaceInfo Pointer to a structure containing an Audio Class configuration and state.
*/
void Audio_Device_ProcessControlRequest(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1);
/* Inline Functions: */
/** General management task for a given Audio class interface, required for the correct operation of the interface. This should
* be called frequently in the main program loop, before the master USB management task \ref USB_USBTask().
*
* \param[in,out] AudioInterfaceInfo Pointer to a structure containing an Audio Class configuration and state.
*/
static inline void Audio_Device_USBTask(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo)
ATTR_NON_NULL_PTR_ARG(1) ATTR_ALWAYS_INLINE;
static inline void Audio_Device_USBTask(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo)
{
(void)AudioInterfaceInfo;
}
/** Determines if the given audio interface is ready for a sample to be read from it, and selects the streaming
* OUT endpoint ready for reading.
*
* \pre This function must only be called when the Device state machine is in the DEVICE_STATE_Configured state or
* the call will fail.
*
* \param[in,out] AudioInterfaceInfo Pointer to a structure containing an Audio Class configuration and state.
*
* \return Boolean true if the given Audio interface has a sample to be read, false otherwise.
*/
static inline bool Audio_Device_IsSampleReceived(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo)
ATTR_NON_NULL_PTR_ARG(1) ATTR_ALWAYS_INLINE;
static inline bool Audio_Device_IsSampleReceived(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo)
{
if ((USB_DeviceState != DEVICE_STATE_Configured) || !(AudioInterfaceInfo->State.InterfaceEnabled))
return false;
Endpoint_SelectEndpoint(AudioInterfaceInfo->Config.DataOUTEndpointNumber);
return Endpoint_IsOUTReceived();
}
/** Determines if the given audio interface is ready to accept the next sample to be written to it, and selects
* the streaming IN endpoint ready for writing.
*
* \pre This function must only be called when the Device state machine is in the DEVICE_STATE_Configured state or
* the call will fail.
*
* \param[in,out] AudioInterfaceInfo Pointer to a structure containing an Audio Class configuration and state.
*
* \return Boolean true if the given Audio interface is ready to accept the next sample, false otherwise.
*/
static inline bool Audio_Device_IsReadyForNextSample(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo)
ATTR_NON_NULL_PTR_ARG(1) ATTR_ALWAYS_INLINE;
static inline bool Audio_Device_IsReadyForNextSample(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo)
{
if ((USB_DeviceState != DEVICE_STATE_Configured) || !(AudioInterfaceInfo->State.InterfaceEnabled))
return false;
Endpoint_SelectEndpoint(AudioInterfaceInfo->Config.DataINEndpointNumber);
return Endpoint_IsINReady();
}
/** Reads the next 8-bit audio sample from the current audio interface.
*
* \pre This should be preceded immediately by a call to the \ref Audio_Device_IsSampleReceived() function to ensure
* ensure the correct endpoint is selected and ready for data.
*
* \param[in,out] AudioInterfaceInfo Pointer to a structure containing an Audio Class configuration and state.
*
* \return Signed 8-bit audio sample from the audio interface.
*/
static inline int8_t Audio_Device_ReadSample8(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo)
ATTR_NON_NULL_PTR_ARG(1) ATTR_ALWAYS_INLINE;
static inline int8_t Audio_Device_ReadSample8(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo)
{
int8_t Sample;
(void)AudioInterfaceInfo;
Sample = Endpoint_Read_Byte();
if (!(Endpoint_BytesInEndpoint()))
Endpoint_ClearOUT();
return Sample;
}
/** Reads the next 16-bit audio sample from the current audio interface.
*
* \pre This should be preceded immediately by a call to the \ref Audio_Device_IsSampleReceived() function to ensure
* that the correct endpoint is selected and ready for data.
*
* \param[in,out] AudioInterfaceInfo Pointer to a structure containing an Audio Class configuration and state.
*
* \return Signed 16-bit audio sample from the audio interface.
*/
static inline int16_t Audio_Device_ReadSample16(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo)
ATTR_NON_NULL_PTR_ARG(1) ATTR_ALWAYS_INLINE;
static inline int16_t Audio_Device_ReadSample16(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo)
{
int16_t Sample;
(void)AudioInterfaceInfo;
Sample = (int16_t)Endpoint_Read_Word_LE();
if (!(Endpoint_BytesInEndpoint()))
Endpoint_ClearOUT();
return Sample;
}
/** Reads the next 24-bit audio sample from the current audio interface.
*
* \pre This should be preceded immediately by a call to the \ref Audio_Device_IsSampleReceived() function to ensure
* that the correct endpoint is selected and ready for data.
*
* \param[in,out] AudioInterfaceInfo Pointer to a structure containing an Audio Class configuration and state.
*
* \return Signed 24-bit audio sample from the audio interface.
*/
static inline int32_t Audio_Device_ReadSample24(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo)
ATTR_NON_NULL_PTR_ARG(1) ATTR_ALWAYS_INLINE;
static inline int32_t Audio_Device_ReadSample24(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo)
{
int32_t Sample;
(void)AudioInterfaceInfo;
Sample = (((uint32_t)Endpoint_Read_Byte() << 16) | Endpoint_Read_Word_LE());
if (!(Endpoint_BytesInEndpoint()))
Endpoint_ClearOUT();
return Sample;
}
/** Writes the next 8-bit audio sample to the current audio interface.
*
* \pre This should be preceded immediately by a call to the \ref Audio_Device_IsReadyForNextSample() function to
* ensure that the correct endpoint is selected and ready for data.
*
* \param[in,out] AudioInterfaceInfo Pointer to a structure containing an Audio Class configuration and state.
* \param[in] Sample Signed 8-bit audio sample.
*/
static inline void Audio_Device_WriteSample8(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo,
const int8_t Sample) ATTR_NON_NULL_PTR_ARG(1) ATTR_ALWAYS_INLINE;
static inline void Audio_Device_WriteSample8(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo,
const int8_t Sample)
{
Endpoint_Write_Byte(Sample);
if (Endpoint_BytesInEndpoint() == AudioInterfaceInfo->Config.DataINEndpointSize)
Endpoint_ClearIN();
}
/** Writes the next 16-bit audio sample to the current audio interface.
*
* \pre This should be preceded immediately by a call to the \ref Audio_Device_IsReadyForNextSample() function to
* ensure that the correct endpoint is selected and ready for data.
*
* \param[in,out] AudioInterfaceInfo Pointer to a structure containing an Audio Class configuration and state.
* \param[in] Sample Signed 16-bit audio sample.
*/
static inline void Audio_Device_WriteSample16(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo,
const int16_t Sample) ATTR_NON_NULL_PTR_ARG(1) ATTR_ALWAYS_INLINE;
static inline void Audio_Device_WriteSample16(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo,
const int16_t Sample)
{
Endpoint_Write_Word_LE(Sample);
if (Endpoint_BytesInEndpoint() == AudioInterfaceInfo->Config.DataINEndpointSize)
Endpoint_ClearIN();
}
/** Writes the next 24-bit audio sample to the current audio interface.
*
* \pre This should be preceded immediately by a call to the \ref Audio_Device_IsReadyForNextSample() function to
* ensure that the correct endpoint is selected and ready for data.
*
* \param[in,out] AudioInterfaceInfo Pointer to a structure containing an Audio Class configuration and state.
* \param[in] Sample Signed 24-bit audio sample.
*/
static inline void Audio_Device_WriteSample24(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo,
const int32_t Sample) ATTR_NON_NULL_PTR_ARG(1) ATTR_ALWAYS_INLINE;
static inline void Audio_Device_WriteSample24(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo,
const int32_t Sample)
{
Endpoint_Write_Byte(Sample >> 16);
Endpoint_Write_Word_LE(Sample);
if (Endpoint_BytesInEndpoint() == AudioInterfaceInfo->Config.DataINEndpointSize)
Endpoint_ClearIN();
}
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,310 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
#define __INCLUDE_FROM_USB_DRIVER
#include "../../HighLevel/USBMode.h"
#if defined(USB_CAN_BE_DEVICE)
#define __INCLUDE_FROM_CDC_CLASS_DEVICE_C
#define __INCLUDE_FROM_CDC_DRIVER
#include "CDC.h"
void CDC_Device_Event_Stub(void)
{
}
void CDC_Device_ProcessControlRequest(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo)
{
if (!(Endpoint_IsSETUPReceived()))
return;
if (USB_ControlRequest.wIndex != CDCInterfaceInfo->Config.ControlInterfaceNumber)
return;
switch (USB_ControlRequest.bRequest)
{
case REQ_GetLineEncoding:
if (USB_ControlRequest.bmRequestType == (REQDIR_DEVICETOHOST | REQTYPE_CLASS | REQREC_INTERFACE))
{
Endpoint_ClearSETUP();
Endpoint_Write_Control_Stream_LE(&CDCInterfaceInfo->State.LineEncoding, sizeof(CDCInterfaceInfo->State.LineEncoding));
Endpoint_ClearOUT();
}
break;
case REQ_SetLineEncoding:
if (USB_ControlRequest.bmRequestType == (REQDIR_HOSTTODEVICE | REQTYPE_CLASS | REQREC_INTERFACE))
{
Endpoint_ClearSETUP();
Endpoint_Read_Control_Stream_LE(&CDCInterfaceInfo->State.LineEncoding, sizeof(CDCInterfaceInfo->State.LineEncoding));
EVENT_CDC_Device_LineEncodingChanged(CDCInterfaceInfo);
Endpoint_ClearIN();
}
break;
case REQ_SetControlLineState:
if (USB_ControlRequest.bmRequestType == (REQDIR_HOSTTODEVICE | REQTYPE_CLASS | REQREC_INTERFACE))
{
Endpoint_ClearSETUP();
CDCInterfaceInfo->State.ControlLineStates.HostToDevice = USB_ControlRequest.wValue;
EVENT_CDC_Device_ControLineStateChanged(CDCInterfaceInfo);
Endpoint_ClearStatusStage();
}
break;
case REQ_SendBreak:
if (USB_ControlRequest.bmRequestType == (REQDIR_HOSTTODEVICE | REQTYPE_CLASS | REQREC_INTERFACE))
{
Endpoint_ClearSETUP();
EVENT_CDC_Device_BreakSent(CDCInterfaceInfo, (uint8_t)USB_ControlRequest.wValue);
Endpoint_ClearStatusStage();
}
break;
}
}
bool CDC_Device_ConfigureEndpoints(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo)
{
memset(&CDCInterfaceInfo->State, 0x00, sizeof(CDCInterfaceInfo->State));
if (!(Endpoint_ConfigureEndpoint(CDCInterfaceInfo->Config.DataINEndpointNumber, EP_TYPE_BULK,
ENDPOINT_DIR_IN, CDCInterfaceInfo->Config.DataINEndpointSize,
CDCInterfaceInfo->Config.DataINEndpointDoubleBank ? ENDPOINT_BANK_DOUBLE : ENDPOINT_BANK_SINGLE)))
{
return false;
}
if (!(Endpoint_ConfigureEndpoint(CDCInterfaceInfo->Config.DataOUTEndpointNumber, EP_TYPE_BULK,
ENDPOINT_DIR_OUT, CDCInterfaceInfo->Config.DataOUTEndpointSize,
CDCInterfaceInfo->Config.DataOUTEndpointDoubleBank ? ENDPOINT_BANK_DOUBLE : ENDPOINT_BANK_SINGLE)))
{
return false;
}
if (!(Endpoint_ConfigureEndpoint(CDCInterfaceInfo->Config.NotificationEndpointNumber, EP_TYPE_INTERRUPT,
ENDPOINT_DIR_IN, CDCInterfaceInfo->Config.NotificationEndpointSize,
CDCInterfaceInfo->Config.NotificationEndpointDoubleBank ? ENDPOINT_BANK_DOUBLE : ENDPOINT_BANK_SINGLE)))
{
return false;
}
return true;
}
void CDC_Device_USBTask(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo)
{
if ((USB_DeviceState != DEVICE_STATE_Configured) || !(CDCInterfaceInfo->State.LineEncoding.BaudRateBPS))
return;
CDC_Device_Flush(CDCInterfaceInfo);
}
uint8_t CDC_Device_SendString(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo,
const char* const Data,
const uint16_t Length)
{
if ((USB_DeviceState != DEVICE_STATE_Configured) || !(CDCInterfaceInfo->State.LineEncoding.BaudRateBPS))
return ENDPOINT_RWSTREAM_DeviceDisconnected;
Endpoint_SelectEndpoint(CDCInterfaceInfo->Config.DataINEndpointNumber);
return Endpoint_Write_Stream_LE(Data, Length, NO_STREAM_CALLBACK);
}
uint8_t CDC_Device_SendByte(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo,
const uint8_t Data)
{
if ((USB_DeviceState != DEVICE_STATE_Configured) || !(CDCInterfaceInfo->State.LineEncoding.BaudRateBPS))
return ENDPOINT_RWSTREAM_DeviceDisconnected;
Endpoint_SelectEndpoint(CDCInterfaceInfo->Config.DataINEndpointNumber);
if (!(Endpoint_IsReadWriteAllowed()))
{
Endpoint_ClearIN();
uint8_t ErrorCode;
if ((ErrorCode = Endpoint_WaitUntilReady()) != ENDPOINT_READYWAIT_NoError)
return ErrorCode;
}
Endpoint_Write_Byte(Data);
return ENDPOINT_READYWAIT_NoError;
}
uint8_t CDC_Device_Flush(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo)
{
if ((USB_DeviceState != DEVICE_STATE_Configured) || !(CDCInterfaceInfo->State.LineEncoding.BaudRateBPS))
return ENDPOINT_RWSTREAM_DeviceDisconnected;
uint8_t ErrorCode;
Endpoint_SelectEndpoint(CDCInterfaceInfo->Config.DataINEndpointNumber);
if (!(Endpoint_BytesInEndpoint()))
return ENDPOINT_READYWAIT_NoError;
bool BankFull = !(Endpoint_IsReadWriteAllowed());
Endpoint_ClearIN();
if (BankFull)
{
if ((ErrorCode = Endpoint_WaitUntilReady()) != ENDPOINT_READYWAIT_NoError)
return ErrorCode;
Endpoint_ClearIN();
}
return ENDPOINT_READYWAIT_NoError;
}
uint16_t CDC_Device_BytesReceived(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo)
{
if ((USB_DeviceState != DEVICE_STATE_Configured) || !(CDCInterfaceInfo->State.LineEncoding.BaudRateBPS))
return 0;
Endpoint_SelectEndpoint(CDCInterfaceInfo->Config.DataOUTEndpointNumber);
if (Endpoint_IsOUTReceived())
{
if (!(Endpoint_BytesInEndpoint()))
{
Endpoint_ClearOUT();
return 0;
}
else
{
return Endpoint_BytesInEndpoint();
}
}
else
{
return 0;
}
}
int16_t CDC_Device_ReceiveByte(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo)
{
if ((USB_DeviceState != DEVICE_STATE_Configured) || !(CDCInterfaceInfo->State.LineEncoding.BaudRateBPS))
return -1;
int16_t ReceivedByte = -1;
Endpoint_SelectEndpoint(CDCInterfaceInfo->Config.DataOUTEndpointNumber);
if (Endpoint_IsOUTReceived())
{
if (Endpoint_BytesInEndpoint())
ReceivedByte = Endpoint_Read_Byte();
if (!(Endpoint_BytesInEndpoint()))
Endpoint_ClearOUT();
}
return ReceivedByte;
}
void CDC_Device_SendControlLineStateChange(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo)
{
if ((USB_DeviceState != DEVICE_STATE_Configured) || !(CDCInterfaceInfo->State.LineEncoding.BaudRateBPS))
return;
Endpoint_SelectEndpoint(CDCInterfaceInfo->Config.NotificationEndpointNumber);
USB_Request_Header_t Notification = (USB_Request_Header_t)
{
.bmRequestType = (REQDIR_DEVICETOHOST | REQTYPE_CLASS | REQREC_INTERFACE),
.bRequest = NOTIF_SerialState,
.wValue = 0,
.wIndex = 0,
.wLength = sizeof(CDCInterfaceInfo->State.ControlLineStates.DeviceToHost),
};
Endpoint_Write_Stream_LE(&Notification, sizeof(USB_Request_Header_t), NO_STREAM_CALLBACK);
Endpoint_Write_Stream_LE(&CDCInterfaceInfo->State.ControlLineStates.DeviceToHost,
sizeof(CDCInterfaceInfo->State.ControlLineStates.DeviceToHost),
NO_STREAM_CALLBACK);
Endpoint_ClearIN();
}
void CDC_Device_CreateStream(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo,
FILE* const Stream)
{
*Stream = (FILE)FDEV_SETUP_STREAM(CDC_Device_putchar, CDC_Device_getchar, _FDEV_SETUP_RW);
fdev_set_udata(Stream, CDCInterfaceInfo);
}
void CDC_Device_CreateBlockingStream(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo,
FILE* const Stream)
{
*Stream = (FILE)FDEV_SETUP_STREAM(CDC_Device_putchar, CDC_Device_getchar_Blocking, _FDEV_SETUP_RW);
fdev_set_udata(Stream, CDCInterfaceInfo);
}
static int CDC_Device_putchar(char c,
FILE* Stream)
{
return CDC_Device_SendByte((USB_ClassInfo_CDC_Device_t*)fdev_get_udata(Stream), c) ? _FDEV_ERR : 0;
}
static int CDC_Device_getchar(FILE* Stream)
{
int16_t ReceivedByte = CDC_Device_ReceiveByte((USB_ClassInfo_CDC_Device_t*)fdev_get_udata(Stream));
if (ReceivedByte < 0)
return _FDEV_EOF;
return ReceivedByte;
}
static int CDC_Device_getchar_Blocking(FILE* Stream)
{
int16_t ReceivedByte;
while ((ReceivedByte = CDC_Device_ReceiveByte((USB_ClassInfo_CDC_Device_t*)fdev_get_udata(Stream))) < 0)
{
if (USB_DeviceState == DEVICE_STATE_Unattached)
return _FDEV_EOF;
CDC_Device_USBTask((USB_ClassInfo_CDC_Device_t*)fdev_get_udata(Stream));
USB_USBTask();
}
return ReceivedByte;
}
#endif

View File

@ -0,0 +1,342 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Device mode driver for the library USB CDC Class driver.
*
* Device mode driver for the library USB CDC Class driver.
*
* \note This file should not be included directly. It is automatically included as needed by the class driver
* dispatch header located in LUFA/Drivers/USB/Class/CDC.h.
*/
/** \ingroup Group_USBClassCDC
* @defgroup Group_USBClassCDCDevice CDC Class Device Mode Driver
*
* \section Sec_Dependencies Module Source Dependencies
* The following files must be built with any user project that uses this module:
* - LUFA/Drivers/USB/Class/Device/CDC.c <i>(Makefile source module name: LUFA_SRC_USBCLASS)</i>
*
* \section Module Description
* Device Mode USB Class driver framework interface, for the CDC USB Class driver.
*
* \note There are several major drawbacks to the CDC-ACM standard USB class, however
* it is very standardized and thus usually available as a built-in driver on
* most platforms, and so is a better choice than a proprietary serial class.
*
* One major issue with CDC-ACM is that it requires two Interface descriptors,
* which will upset most hosts when part of a multi-function "Composite" USB
* device, as each interface will be loaded into a separate driver instance. To
* combat this, you should use the "Interface Association Descriptor" addendum to
* the USB standard which is available on most OSes when creating Composite devices.
*
* Another major oversight is that there is no mechanism for the host to notify the
* device that there is a data sink on the host side ready to accept data. This
* means that the device may try to send data while the host isn't listening, causing
* lengthy blocking timeouts in the transmission routines. To combat this, it is
* recommended that the virtual serial line DTR (Data Terminal Ready) be used where
* possible to determine if a host application is ready for data.
*
* @{
*/
#ifndef _CDC_CLASS_DEVICE_H_
#define _CDC_CLASS_DEVICE_H_
/* Includes: */
#include "../../USB.h"
#include "../Common/CDC.h"
#include <stdio.h>
#include <string.h>
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_CDC_DRIVER)
#error Do not include this file directly. Include LUFA/Drivers/Class/CDC.h instead.
#endif
/* Public Interface - May be used in end-application: */
/* Type Defines: */
/** \brief CDC Class Device Mode Configuration and State Structure.
*
* Class state structure. An instance of this structure should be made for each CDC interface
* within the user application, and passed to each of the CDC class driver functions as the
* CDCInterfaceInfo parameter. This stores each CDC interface's configuration and state information.
*/
typedef struct
{
const struct
{
uint8_t ControlInterfaceNumber; /**< Interface number of the CDC control interface within the device. */
uint8_t DataINEndpointNumber; /**< Endpoint number of the CDC interface's IN data endpoint. */
uint16_t DataINEndpointSize; /**< Size in bytes of the CDC interface's IN data endpoint. */
bool DataINEndpointDoubleBank; /**< Indicates if the CDC interface's IN data endpoint should use double banking. */
uint8_t DataOUTEndpointNumber; /**< Endpoint number of the CDC interface's OUT data endpoint. */
uint16_t DataOUTEndpointSize; /**< Size in bytes of the CDC interface's OUT data endpoint. */
bool DataOUTEndpointDoubleBank; /**< Indicates if the CDC interface's OUT data endpoint should use double banking. */
uint8_t NotificationEndpointNumber; /**< Endpoint number of the CDC interface's IN notification endpoint, if used. */
uint16_t NotificationEndpointSize; /**< Size in bytes of the CDC interface's IN notification endpoint, if used. */
bool NotificationEndpointDoubleBank; /**< Indicates if the CDC interface's notification endpoint should use double banking. */
} Config; /**< Config data for the USB class interface within the device. All elements in this section
* <b>must</b> be set or the interface will fail to enumerate and operate correctly.
*/
struct
{
struct
{
uint8_t HostToDevice; /**< Control line states from the host to device, as a set of CDC_CONTROL_LINE_OUT_*
* masks. This value is updated each time \ref CDC_Device_USBTask() is called.
*/
uint8_t DeviceToHost; /**< Control line states from the device to host, as a set of CDC_CONTROL_LINE_IN_*
* masks - to notify the host of changes to these values, call the
* \ref CDC_Device_SendControlLineStateChange() function.
*/
} ControlLineStates; /**< Current states of the virtual serial port's control lines between the device and host. */
struct
{
uint32_t BaudRateBPS; /**< Baud rate of the virtual serial port, in bits per second. */
uint8_t CharFormat; /**< Character format of the virtual serial port, a value from the
* \ref CDC_LineEncodingFormats_t enum.
*/
uint8_t ParityType; /**< Parity setting of the virtual serial port, a value from the
* \ref CDC_LineEncodingParity_t enum.
*/
uint8_t DataBits; /**< Bits of data per character of the virtual serial port. */
} LineEncoding; /** Line encoding used in the virtual serial port, for the device's information. This is generally
* only used if the virtual serial port data is to be reconstructed on a physical UART.
*/
} State; /**< State data for the USB class interface within the device. All elements in this section
* are reset to their defaults when the interface is enumerated.
*/
} USB_ClassInfo_CDC_Device_t;
/* Function Prototypes: */
/** Configures the endpoints of a given CDC interface, ready for use. This should be linked to the library
* \ref EVENT_USB_Device_ConfigurationChanged() event so that the endpoints are configured when the configuration containing
* the given CDC interface is selected.
*
* \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class configuration and state.
*
* \return Boolean true if the endpoints were successfully configured, false otherwise.
*/
bool CDC_Device_ConfigureEndpoints(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1);
/** Processes incoming control requests from the host, that are directed to the given CDC class interface. This should be
* linked to the library \ref EVENT_USB_Device_UnhandledControlRequest() event.
*
* \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class configuration and state.
*/
void CDC_Device_ProcessControlRequest(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1);
/** General management task for a given CDC class interface, required for the correct operation of the interface. This should
* be called frequently in the main program loop, before the master USB management task \ref USB_USBTask().
*
* \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class configuration and state.
*/
void CDC_Device_USBTask(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1);
/** CDC class driver event for a line encoding change on a CDC interface. This event fires each time the host requests a
* line encoding change (containing the serial parity, baud and other configuration information) and may be hooked in the
* user program by declaring a handler function with the same name and parameters listed here. The new line encoding
* settings are available in the LineEncoding structure inside the CDC interface structure passed as a parameter.
*
* \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class configuration and state.
*/
void EVENT_CDC_Device_LineEncodingChanged(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1);
/** CDC class driver event for a control line state change on a CDC interface. This event fires each time the host requests a
* control line state change (containing the virtual serial control line states, such as DTR) and may be hooked in the
* user program by declaring a handler function with the same name and parameters listed here. The new control line states
* are available in the ControlLineStates.HostToDevice value inside the CDC interface structure passed as a parameter, set as
* a mask of CDC_CONTROL_LINE_OUT_* masks.
*
* \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class configuration and state.
*/
void EVENT_CDC_Device_ControLineStateChanged(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1);
/** CDC class driver event for a send break request sent to the device from the host. This is generally used to separate
* data or to indicate a special condition to the receiving device.
*
* \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class configuration and state.
* \param[in] Duration Duration of the break that has been sent by the host, in milliseconds.
*/
void EVENT_CDC_Device_BreakSent(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo,
const uint8_t Duration) ATTR_NON_NULL_PTR_ARG(1);
/** Sends a given string to the attached USB host, if connected. If a host is not connected when the function is called, the
* string is discarded. Bytes will be queued for transmission to the host until either the endpoint bank becomes full, or the
* \ref CDC_Device_Flush() function is called to flush the pending data to the host. This allows for multiple bytes to be
* packed into a single endpoint packet, increasing data throughput.
*
* \pre This function must only be called when the Device state machine is in the DEVICE_STATE_Configured state or
* the call will fail.
*
* \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class configuration and state.
* \param[in] Data Pointer to the string to send to the host.
* \param[in] Length Size in bytes of the string to send to the host.
*
* \return A value from the \ref Endpoint_Stream_RW_ErrorCodes_t enum.
*/
uint8_t CDC_Device_SendString(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo,
const char* const Data,
const uint16_t Length) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(2);
/** Sends a given byte to the attached USB host, if connected. If a host is not connected when the function is called, the
* byte is discarded. Bytes will be queued for transmission to the host until either the endpoint bank becomes full, or the
* \ref CDC_Device_Flush() function is called to flush the pending data to the host. This allows for multiple bytes to be
* packed into a single endpoint packet, increasing data throughput.
*
* \pre This function must only be called when the Device state machine is in the DEVICE_STATE_Configured state or
* the call will fail.
*
* \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class configuration and state.
* \param[in] Data Byte of data to send to the host.
*
* \return A value from the \ref Endpoint_WaitUntilReady_ErrorCodes_t enum.
*/
uint8_t CDC_Device_SendByte(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo,
const uint8_t Data) ATTR_NON_NULL_PTR_ARG(1);
/** Determines the number of bytes received by the CDC interface from the host, waiting to be read. This indicates the number
* of bytes in the OUT endpoint bank only, and thus the number of calls to \ref CDC_Device_ReceiveByte() which are guaranteed to
* succeed immediately. If multiple bytes are to be received, they should be buffered by the user application, as the endpoint
* bank will not be released back to the USB controller until all bytes are read.
*
* \pre This function must only be called when the Device state machine is in the DEVICE_STATE_Configured state or
* the call will fail.
*
* \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class configuration and state.
*
* \return Total number of buffered bytes received from the host.
*/
uint16_t CDC_Device_BytesReceived(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1);
/** Reads a byte of data from the host. If no data is waiting to be read of if a USB host is not connected, the function
* returns a negative value. The \ref CDC_Device_BytesReceived() function may be queried in advance to determine how many
* bytes are currently buffered in the CDC interface's data receive endpoint bank, and thus how many repeated calls to this
* function which are guaranteed to succeed.
*
* \pre This function must only be called when the Device state machine is in the DEVICE_STATE_Configured state or
* the call will fail.
*
* \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class configuration and state.
*
* \return Next received byte from the host, or a negative value if no data received.
*/
int16_t CDC_Device_ReceiveByte(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1);
/** Flushes any data waiting to be sent, ensuring that the send buffer is cleared.
*
* \pre This function must only be called when the Device state machine is in the DEVICE_STATE_Configured state or
* the call will fail.
*
* \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class configuration and state.
*
* \return A value from the \ref Endpoint_WaitUntilReady_ErrorCodes_t enum.
*/
uint8_t CDC_Device_Flush(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1);
/** Sends a Serial Control Line State Change notification to the host. This should be called when the virtual serial
* control lines (DCD, DSR, etc.) have changed states, or to give BREAK notifications to the host. Line states persist
* until they are cleared via a second notification. This should be called each time the CDC class driver's
* ControlLineStates.DeviceToHost value is updated to push the new states to the USB host.
*
* \pre This function must only be called when the Device state machine is in the DEVICE_STATE_Configured state or
* the call will fail.
*
* \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class configuration and state.
*/
void CDC_Device_SendControlLineStateChange(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1);
/** Creates a standard character stream for the given CDC Device instance so that it can be used with all the regular
* functions in the avr-libc <stdio.h> library that accept a FILE stream as a destination (e.g. fprintf). The created
* stream is bidirectional and can be used for both input and output functions.
*
* Reading data from this stream is non-blocking, i.e. in most instances, complete strings cannot be read in by a single
* fetch, as the endpoint will not be ready at some point in the transmission, aborting the transfer. However, this may
* be used when the read data is processed byte-per-bye (via getc()) or when the user application will implement its own
* line buffering.
*
* \note The created stream can be given as stdout if desired to direct the standard output from all <stdio.h> functions
* to the given CDC interface.
*
* \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class configuration and state.
* \param[in,out] Stream Pointer to a FILE structure where the created stream should be placed.
*/
void CDC_Device_CreateStream(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo,
FILE* const Stream) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(2);
/** Identical to CDC_Device_CreateStream(), except that reads are blocking until the calling stream function terminates
* the transfer. While blocking, the USB and CDC service tasks are called repeatedly to maintain USB communications.
*
* \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class configuration and state.
* \param[in,out] Stream Pointer to a FILE structure where the created stream should be placed.
*/
void CDC_Device_CreateBlockingStream(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo,
FILE* const Stream) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(2);
/* Private Interface - For use in library only: */
#if !defined(__DOXYGEN__)
/* Function Prototypes: */
#if defined(__INCLUDE_FROM_CDC_CLASS_DEVICE_C)
static int CDC_Device_putchar(char c,
FILE* Stream) ATTR_NON_NULL_PTR_ARG(2);
static int CDC_Device_getchar(FILE* Stream) ATTR_NON_NULL_PTR_ARG(1);
static int CDC_Device_getchar_Blocking(FILE* Stream) ATTR_NON_NULL_PTR_ARG(1);
void CDC_Device_Event_Stub(void);
void EVENT_CDC_Device_LineEncodingChanged(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo)
ATTR_WEAK ATTR_NON_NULL_PTR_ARG(1) ATTR_ALIAS(CDC_Device_Event_Stub);
void EVENT_CDC_Device_ControLineStateChanged(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo)
ATTR_WEAK ATTR_NON_NULL_PTR_ARG(1) ATTR_ALIAS(CDC_Device_Event_Stub);
void EVENT_CDC_Device_BreakSent(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo,
const uint8_t Duration) ATTR_WEAK ATTR_NON_NULL_PTR_ARG(1)
ATTR_ALIAS(CDC_Device_Event_Stub);
#endif
#endif
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,194 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
#define __INCLUDE_FROM_USB_DRIVER
#include "../../HighLevel/USBMode.h"
#if defined(USB_CAN_BE_DEVICE)
#define __INCLUDE_FROM_HID_DRIVER
#include "HID.h"
void HID_Device_ProcessControlRequest(USB_ClassInfo_HID_Device_t* const HIDInterfaceInfo)
{
if (!(Endpoint_IsSETUPReceived()))
return;
if (USB_ControlRequest.wIndex != HIDInterfaceInfo->Config.InterfaceNumber)
return;
switch (USB_ControlRequest.bRequest)
{
case REQ_GetReport:
if (USB_ControlRequest.bmRequestType == (REQDIR_DEVICETOHOST | REQTYPE_CLASS | REQREC_INTERFACE))
{
Endpoint_ClearSETUP();
uint16_t ReportSize = 0;
uint8_t ReportID = (USB_ControlRequest.wValue & 0xFF);
uint8_t ReportType = (USB_ControlRequest.wValue >> 8) - 1;
uint8_t ReportData[HIDInterfaceInfo->Config.PrevReportINBufferSize];
memset(ReportData, 0, sizeof(ReportData));
CALLBACK_HID_Device_CreateHIDReport(HIDInterfaceInfo, &ReportID, ReportType, ReportData, &ReportSize);
if (HIDInterfaceInfo->Config.PrevReportINBuffer != NULL)
memcpy(HIDInterfaceInfo->Config.PrevReportINBuffer, ReportData, HIDInterfaceInfo->Config.PrevReportINBufferSize);
Endpoint_SelectEndpoint(ENDPOINT_CONTROLEP);
Endpoint_Write_Control_Stream_LE(ReportData, ReportSize);
Endpoint_ClearOUT();
}
break;
case REQ_SetReport:
if (USB_ControlRequest.bmRequestType == (REQDIR_HOSTTODEVICE | REQTYPE_CLASS | REQREC_INTERFACE))
{
Endpoint_ClearSETUP();
uint16_t ReportSize = USB_ControlRequest.wLength;
uint8_t ReportID = (USB_ControlRequest.wValue & 0xFF);
uint8_t ReportType = (USB_ControlRequest.wValue >> 8) - 1;
uint8_t ReportData[ReportSize];
Endpoint_Read_Control_Stream_LE(ReportData, ReportSize);
CALLBACK_HID_Device_ProcessHIDReport(HIDInterfaceInfo, ReportID, ReportType, ReportData, ReportSize);
Endpoint_ClearIN();
}
break;
case REQ_GetProtocol:
if (USB_ControlRequest.bmRequestType == (REQDIR_DEVICETOHOST | REQTYPE_CLASS | REQREC_INTERFACE))
{
Endpoint_ClearSETUP();
Endpoint_Write_Byte(HIDInterfaceInfo->State.UsingReportProtocol);
Endpoint_ClearIN();
Endpoint_ClearStatusStage();
}
break;
case REQ_SetProtocol:
if (USB_ControlRequest.bmRequestType == (REQDIR_HOSTTODEVICE | REQTYPE_CLASS | REQREC_INTERFACE))
{
Endpoint_ClearSETUP();
HIDInterfaceInfo->State.UsingReportProtocol = ((USB_ControlRequest.wValue & 0xFF) != 0x00);
Endpoint_ClearStatusStage();
}
break;
case REQ_SetIdle:
if (USB_ControlRequest.bmRequestType == (REQDIR_HOSTTODEVICE | REQTYPE_CLASS | REQREC_INTERFACE))
{
Endpoint_ClearSETUP();
HIDInterfaceInfo->State.IdleCount = ((USB_ControlRequest.wValue & 0xFF00) >> 6);
Endpoint_ClearStatusStage();
}
break;
case REQ_GetIdle:
if (USB_ControlRequest.bmRequestType == (REQDIR_DEVICETOHOST | REQTYPE_CLASS | REQREC_INTERFACE))
{
Endpoint_ClearSETUP();
Endpoint_Write_Byte(HIDInterfaceInfo->State.IdleCount >> 2);
Endpoint_ClearIN();
Endpoint_ClearStatusStage();
}
break;
}
}
bool HID_Device_ConfigureEndpoints(USB_ClassInfo_HID_Device_t* const HIDInterfaceInfo)
{
memset(&HIDInterfaceInfo->State, 0x00, sizeof(HIDInterfaceInfo->State));
HIDInterfaceInfo->State.UsingReportProtocol = true;
HIDInterfaceInfo->State.IdleCount = 500;
if (!(Endpoint_ConfigureEndpoint(HIDInterfaceInfo->Config.ReportINEndpointNumber, EP_TYPE_INTERRUPT,
ENDPOINT_DIR_IN, HIDInterfaceInfo->Config.ReportINEndpointSize,
HIDInterfaceInfo->Config.ReportINEndpointDoubleBank ? ENDPOINT_BANK_DOUBLE : ENDPOINT_BANK_SINGLE)))
{
return false;
}
return true;
}
void HID_Device_USBTask(USB_ClassInfo_HID_Device_t* const HIDInterfaceInfo)
{
if (USB_DeviceState != DEVICE_STATE_Configured)
return;
Endpoint_SelectEndpoint(HIDInterfaceInfo->Config.ReportINEndpointNumber);
if (Endpoint_IsReadWriteAllowed())
{
uint8_t ReportINData[HIDInterfaceInfo->Config.PrevReportINBufferSize];
uint8_t ReportID = 0;
uint16_t ReportINSize = 0;
memset(ReportINData, 0, sizeof(ReportINData));
bool ForceSend = CALLBACK_HID_Device_CreateHIDReport(HIDInterfaceInfo, &ReportID, REPORT_ITEM_TYPE_In,
ReportINData, &ReportINSize);
bool StatesChanged = false;
bool IdlePeriodElapsed = (HIDInterfaceInfo->State.IdleCount && !(HIDInterfaceInfo->State.IdleMSRemaining));
if (HIDInterfaceInfo->Config.PrevReportINBuffer != NULL)
{
StatesChanged = (memcmp(ReportINData, HIDInterfaceInfo->Config.PrevReportINBuffer, ReportINSize) != 0);
memcpy(HIDInterfaceInfo->Config.PrevReportINBuffer, ReportINData, HIDInterfaceInfo->Config.PrevReportINBufferSize);
}
if (ReportINSize && (ForceSend || StatesChanged || IdlePeriodElapsed))
{
HIDInterfaceInfo->State.IdleMSRemaining = HIDInterfaceInfo->State.IdleCount;
Endpoint_SelectEndpoint(HIDInterfaceInfo->Config.ReportINEndpointNumber);
if (ReportID)
Endpoint_Write_Byte(ReportID);
Endpoint_Write_Stream_LE(ReportINData, ReportINSize, NO_STREAM_CALLBACK);
Endpoint_ClearIN();
}
}
}
#endif

View File

@ -0,0 +1,212 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Device mode driver for the library USB HID Class driver.
*
* Device mode driver for the library USB HID Class driver.
*
* \note This file should not be included directly. It is automatically included as needed by the class driver
* dispatch header located in LUFA/Drivers/USB/Class/HID.h.
*/
/** \ingroup Group_USBClassHID
* @defgroup Group_USBClassHIDDevice HID Class Device Mode Driver
*
* \section Sec_Dependencies Module Source Dependencies
* The following files must be built with any user project that uses this module:
* - LUFA/Drivers/USB/Class/Device/HID.c <i>(Makefile source module name: LUFA_SRC_USBCLASS)</i>
*
* \section Module Description
* Device Mode USB Class driver framework interface, for the HID USB Class driver.
*
* @{
*/
#ifndef _HID_CLASS_DEVICE_H_
#define _HID_CLASS_DEVICE_H_
/* Includes: */
#include "../../USB.h"
#include "../Common/HID.h"
#include <string.h>
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_HID_DRIVER)
#error Do not include this file directly. Include LUFA/Drivers/Class/HID.h instead.
#endif
/* Public Interface - May be used in end-application: */
/* Type Defines: */
/** \brief HID Class Device Mode Configuration and State Structure.
*
* Class state structure. An instance of this structure should be made for each HID interface
* within the user application, and passed to each of the HID class driver functions as the
* HIDInterfaceInfo parameter. This stores each HID interface's configuration and state information.
*
* \note Due to technical limitations, the HID device class driver does not utilize a separate OUT
* endpoint for host->device communications. Instead, the host->device data (if any) is sent to
* the device via the control endpoint.
*/
typedef struct
{
const struct
{
uint8_t InterfaceNumber; /**< Interface number of the HID interface within the device. */
uint8_t ReportINEndpointNumber; /**< Endpoint number of the HID interface's IN report endpoint. */
uint16_t ReportINEndpointSize; /**< Size in bytes of the HID interface's IN report endpoint. */
bool ReportINEndpointDoubleBank; /**< Indicates if the HID interface's IN report endpoint should use double banking. */
void* PrevReportINBuffer; /**< Pointer to a buffer where the previously created HID input report can be
* stored by the driver, for comparison purposes to detect report changes that
* must be sent immediately to the host. This should point to a buffer big enough
* to hold the largest HID input report sent from the HID interface. If this is set
* to NULL, it is up to the user to force transfers when needed in the
* \ref CALLBACK_HID_Device_CreateHIDReport() callback function.
*
* \note Due to the single buffer, the internal driver can only correctly compare
* subsequent reports with identical report IDs. In multiple report devices,
* this buffer should be set to NULL and the decision to send reports made
* by the user application instead.
*/
uint8_t PrevReportINBufferSize; /**< Size in bytes of the given input report buffer. This is used to create a
* second buffer of the same size within the driver so that subsequent reports
* can be compared. If the user app is to determine when reports are to be sent
* exclusively (i.e. \ref PrevReportINBuffer is NULL) this value must still be
* set to the size of the largest report the device can issue to the host.
*/
} Config; /**< Config data for the USB class interface within the device. All elements in this section
* <b>must</b> be set or the interface will fail to enumerate and operate correctly.
*/
struct
{
bool UsingReportProtocol; /**< Indicates if the HID interface is set to Boot or Report protocol mode. */
uint16_t IdleCount; /**< Report idle period, in milliseconds, set by the host. */
uint16_t IdleMSRemaining; /**< Total number of milliseconds remaining before the idle period elapsed - this
* should be decremented by the user application if non-zero each millisecond. */
} State; /**< State data for the USB class interface within the device. All elements in this section
* are reset to their defaults when the interface is enumerated.
*/
} USB_ClassInfo_HID_Device_t;
/* Function Prototypes: */
/** Configures the endpoints of a given HID interface, ready for use. This should be linked to the library
* \ref EVENT_USB_Device_ConfigurationChanged() event so that the endpoints are configured when the configuration
* containing the given HID interface is selected.
*
* \param[in,out] HIDInterfaceInfo Pointer to a structure containing a HID Class configuration and state.
*
* \return Boolean true if the endpoints were successfully configured, false otherwise.
*/
bool HID_Device_ConfigureEndpoints(USB_ClassInfo_HID_Device_t* const HIDInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1);
/** Processes incoming control requests from the host, that are directed to the given HID class interface. This should be
* linked to the library \ref EVENT_USB_Device_UnhandledControlRequest() event.
*
* \param[in,out] HIDInterfaceInfo Pointer to a structure containing a HID Class configuration and state.
*/
void HID_Device_ProcessControlRequest(USB_ClassInfo_HID_Device_t* const HIDInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1);
/** General management task for a given HID class interface, required for the correct operation of the interface. This should
* be called frequently in the main program loop, before the master USB management task \ref USB_USBTask().
*
* \param[in,out] HIDInterfaceInfo Pointer to a structure containing a HID Class configuration and state.
*/
void HID_Device_USBTask(USB_ClassInfo_HID_Device_t* const HIDInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1);
/** HID class driver callback for the user creation of a HID IN report. This callback may fire in response to either
* HID class control requests from the host, or by the normal HID endpoint polling procedure. Inside this callback the
* user is responsible for the creation of the next HID input report to be sent to the host.
*
* \param[in,out] HIDInterfaceInfo Pointer to a structure containing a HID Class configuration and state.
* \param[in,out] ReportID If preset to a non-zero value, this is the report ID being requested by the host. If zero,
* this should be set to the report ID of the generated HID input report (if any). If multiple
* reports are not sent via the given HID interface, this parameter should be ignored.
* \param[in] ReportType Type of HID report to generate, either \ref REPORT_ITEM_TYPE_In or \ref REPORT_ITEM_TYPE_Feature.
* \param[out] ReportData Pointer to a buffer where the generated HID report should be stored.
* \param[out] ReportSize Number of bytes in the generated input report, or zero if no report is to be sent.
*
* \return Boolean true to force the sending of the report even if it is identical to the previous report and still within
* the idle period (useful for devices which report relative movement), false otherwise.
*/
bool CALLBACK_HID_Device_CreateHIDReport(USB_ClassInfo_HID_Device_t* const HIDInterfaceInfo,
uint8_t* const ReportID,
const uint8_t ReportType,
void* ReportData,
uint16_t* const ReportSize) ATTR_NON_NULL_PTR_ARG(1)
ATTR_NON_NULL_PTR_ARG(2) ATTR_NON_NULL_PTR_ARG(4) ATTR_NON_NULL_PTR_ARG(5);
/** HID class driver callback for the user processing of a received HID OUT report. This callback may fire in response to
* either HID class control requests from the host, or by the normal HID endpoint polling procedure. Inside this callback
* the user is responsible for the processing of the received HID output report from the host.
*
* \param[in,out] HIDInterfaceInfo Pointer to a structure containing a HID Class configuration and state.
* \param[in] ReportID Report ID of the received output report. If multiple reports are not received via the given HID
* interface, this parameter should be ignored.
* \param[in] ReportType Type of received HID report, either \ref REPORT_ITEM_TYPE_Out or \ref REPORT_ITEM_TYPE_Feature.
* \param[in] ReportData Pointer to a buffer where the received HID report is stored.
* \param[in] ReportSize Size in bytes of the received report from the host.
*/
void CALLBACK_HID_Device_ProcessHIDReport(USB_ClassInfo_HID_Device_t* const HIDInterfaceInfo,
const uint8_t ReportID,
const uint8_t ReportType,
const void* ReportData,
const uint16_t ReportSize) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(4);
/* Inline Functions: */
/** Indicates that a millisecond of idle time has elapsed on the given HID interface, and the interface's idle count should be
* decremented. This should be called once per millisecond so that hardware key-repeats function correctly. It is recommended
* that this be called by the \ref EVENT_USB_Device_StartOfFrame() event, once SOF events have been enabled via
* \ref USB_Device_EnableSOFEvents().
*
* \param[in,out] HIDInterfaceInfo Pointer to a structure containing a HID Class configuration and state.
*/
static inline void HID_Device_MillisecondElapsed(USB_ClassInfo_HID_Device_t* const HIDInterfaceInfo) ATTR_ALWAYS_INLINE ATTR_NON_NULL_PTR_ARG(1);
static inline void HID_Device_MillisecondElapsed(USB_ClassInfo_HID_Device_t* const HIDInterfaceInfo)
{
if (HIDInterfaceInfo->State.IdleMSRemaining)
HIDInterfaceInfo->State.IdleMSRemaining--;
}
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,126 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
#define __INCLUDE_FROM_USB_DRIVER
#include "../../HighLevel/USBMode.h"
#if defined(USB_CAN_BE_DEVICE)
#define __INCLUDE_FROM_MIDI_DRIVER
#include "MIDI.h"
bool MIDI_Device_ConfigureEndpoints(USB_ClassInfo_MIDI_Device_t* const MIDIInterfaceInfo)
{
memset(&MIDIInterfaceInfo->State, 0x00, sizeof(MIDIInterfaceInfo->State));
if (MIDIInterfaceInfo->Config.DataINEndpointNumber)
{
if (!(Endpoint_ConfigureEndpoint(MIDIInterfaceInfo->Config.DataINEndpointNumber, EP_TYPE_BULK,
ENDPOINT_DIR_IN, MIDIInterfaceInfo->Config.DataINEndpointSize,
MIDIInterfaceInfo->Config.DataINEndpointDoubleBank ? ENDPOINT_BANK_DOUBLE : ENDPOINT_BANK_SINGLE)))
{
return false;
}
}
if (MIDIInterfaceInfo->Config.DataOUTEndpointNumber)
{
if (!(Endpoint_ConfigureEndpoint(MIDIInterfaceInfo->Config.DataOUTEndpointNumber, EP_TYPE_BULK,
ENDPOINT_DIR_OUT, MIDIInterfaceInfo->Config.DataOUTEndpointSize,
MIDIInterfaceInfo->Config.DataOUTEndpointDoubleBank ? ENDPOINT_BANK_DOUBLE : ENDPOINT_BANK_SINGLE)))
{
return false;
}
}
return true;
}
uint8_t MIDI_Device_SendEventPacket(USB_ClassInfo_MIDI_Device_t* const MIDIInterfaceInfo,
const MIDI_EventPacket_t* const Event)
{
if (USB_DeviceState != DEVICE_STATE_Configured)
return ENDPOINT_RWSTREAM_DeviceDisconnected;
Endpoint_SelectEndpoint(MIDIInterfaceInfo->Config.DataINEndpointNumber);
if (Endpoint_IsReadWriteAllowed())
{
uint8_t ErrorCode;
if ((ErrorCode = Endpoint_Write_Stream_LE(Event, sizeof(MIDI_EventPacket_t), NO_STREAM_CALLBACK)) != ENDPOINT_RWSTREAM_NoError)
return ErrorCode;
if (!(Endpoint_IsReadWriteAllowed()))
Endpoint_ClearIN();
}
return ENDPOINT_RWSTREAM_NoError;
}
uint8_t MIDI_Device_Flush(USB_ClassInfo_MIDI_Device_t* const MIDIInterfaceInfo)
{
if (USB_DeviceState != DEVICE_STATE_Configured)
return ENDPOINT_RWSTREAM_DeviceDisconnected;
uint8_t ErrorCode;
Endpoint_SelectEndpoint(MIDIInterfaceInfo->Config.DataINEndpointNumber);
if (Endpoint_BytesInEndpoint())
{
Endpoint_ClearIN();
if ((ErrorCode = Endpoint_WaitUntilReady()) != ENDPOINT_READYWAIT_NoError)
return ErrorCode;
}
return ENDPOINT_READYWAIT_NoError;
}
bool MIDI_Device_ReceiveEventPacket(USB_ClassInfo_MIDI_Device_t* const MIDIInterfaceInfo,
MIDI_EventPacket_t* const Event)
{
if (USB_DeviceState != DEVICE_STATE_Configured)
return false;
Endpoint_SelectEndpoint(MIDIInterfaceInfo->Config.DataOUTEndpointNumber);
if (!(Endpoint_IsReadWriteAllowed()))
return false;
Endpoint_Read_Stream_LE(Event, sizeof(MIDI_EventPacket_t), NO_STREAM_CALLBACK);
if (!(Endpoint_IsReadWriteAllowed()))
Endpoint_ClearOUT();
return true;
}
#endif

View File

@ -0,0 +1,184 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Device mode driver for the library USB MIDI Class driver.
*
* Device mode driver for the library USB MIDI Class driver.
*
* \note This file should not be included directly. It is automatically included as needed by the class driver
* dispatch header located in LUFA/Drivers/USB/Class/MIDI.h.
*/
/** \ingroup Group_USBClassMIDI
* @defgroup Group_USBClassMIDIDevice MIDI Class Device Mode Driver
*
* \section Sec_Dependencies Module Source Dependencies
* The following files must be built with any user project that uses this module:
* - LUFA/Drivers/USB/Class/Device/MIDI.c <i>(Makefile source module name: LUFA_SRC_USBCLASS)</i>
*
* \section Module Description
* Device Mode USB Class driver framework interface, for the MIDI USB Class driver.
*
* @{
*/
#ifndef _MIDI_CLASS_DEVICE_H_
#define _MIDI_CLASS_DEVICE_H_
/* Includes: */
#include "../../USB.h"
#include "../Common/MIDI.h"
#include <string.h>
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_MIDI_DRIVER)
#error Do not include this file directly. Include LUFA/Drivers/Class/MIDI.h instead.
#endif
/* Public Interface - May be used in end-application: */
/* Type Define: */
/** \brief MIDI Class Device Mode Configuration and State Structure.
*
* Class state structure. An instance of this structure should be made for each MIDI interface
* within the user application, and passed to each of the MIDI class driver functions as the
* MIDIInterfaceInfo parameter. This stores each MIDI interface's configuration and state information.
*/
typedef struct
{
const struct
{
uint8_t StreamingInterfaceNumber; /**< Index of the Audio Streaming interface within the device this structure controls. */
uint8_t DataINEndpointNumber; /**< Endpoint number of the incoming MIDI data, if available (zero if unused). */
uint16_t DataINEndpointSize; /**< Size in bytes of the incoming MIDI data endpoint, if available (zero if unused). */
bool DataINEndpointDoubleBank; /**< Indicates if the MIDI interface's IN data endpoint should use double banking. */
uint8_t DataOUTEndpointNumber; /**< Endpoint number of the outgoing MIDI data, if available (zero if unused). */
uint16_t DataOUTEndpointSize; /**< Size in bytes of the outgoing MIDI data endpoint, if available (zero if unused). */
bool DataOUTEndpointDoubleBank; /**< Indicates if the MIDI interface's IN data endpoint should use double banking. */
} Config; /**< Config data for the USB class interface within the device. All elements in this section
* <b>must</b> be set or the interface will fail to enumerate and operate correctly.
*/
struct
{
// No state information for this class yet
} State; /**< State data for the USB class interface within the device. All elements in this section
* are reset to their defaults when the interface is enumerated.
*/
} USB_ClassInfo_MIDI_Device_t;
/* Function Prototypes: */
/** Configures the endpoints of a given MIDI interface, ready for use. This should be linked to the library
* \ref EVENT_USB_Device_ConfigurationChanged() event so that the endpoints are configured when the configuration
* containing the given MIDI interface is selected.
*
* \param[in,out] MIDIInterfaceInfo Pointer to a structure containing a MIDI Class configuration and state.
*
* \return Boolean true if the endpoints were successfully configured, false otherwise.
*/
bool MIDI_Device_ConfigureEndpoints(USB_ClassInfo_MIDI_Device_t* const MIDIInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1);
/** Sends a MIDI event packet to the host. If no host is connected, the event packet is discarded. Events are queued into the
* endpoint bank until either the endpoint bank is full, or \ref MIDI_Device_Flush() is called. This allows for multiple
* MIDI events to be packed into a single endpoint packet, increasing data throughput.
*
* \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the
* call will fail.
*
* \param[in,out] MIDIInterfaceInfo Pointer to a structure containing a MIDI Class configuration and state.
* \param[in] Event Pointer to a populated USB_MIDI_EventPacket_t structure containing the MIDI event to send.
*
* \return A value from the \ref Endpoint_Stream_RW_ErrorCodes_t enum.
*/
uint8_t MIDI_Device_SendEventPacket(USB_ClassInfo_MIDI_Device_t* const MIDIInterfaceInfo,
const MIDI_EventPacket_t* const Event) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(2);
/** Flushes the MIDI send buffer, sending any queued MIDI events to the host. This should be called to override the
* \ref MIDI_Device_SendEventPacket() function's packing behaviour, to flush queued events.
*
* \param[in,out] MIDIInterfaceInfo Pointer to a structure containing a MIDI Class configuration and state.
*
* \return A value from the \ref Endpoint_WaitUntilReady_ErrorCodes_t enum.
*/
uint8_t MIDI_Device_Flush(USB_ClassInfo_MIDI_Device_t* const MIDIInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1);
/** Receives a MIDI event packet from the host. Events are unpacked from the endpoint, thus if the endpoint bank contains
* multiple MIDI events from the host in the one packet, multiple calls to this function will return each individual event.
*
* \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the
* call will fail.
*
* \param[in,out] MIDIInterfaceInfo Pointer to a structure containing a MIDI Class configuration and state.
* \param[out] Event Pointer to a USB_MIDI_EventPacket_t structure where the received MIDI event is to be placed.
*
* \return Boolean true if a MIDI event packet was received, false otherwise.
*/
bool MIDI_Device_ReceiveEventPacket(USB_ClassInfo_MIDI_Device_t* const MIDIInterfaceInfo,
MIDI_EventPacket_t* const Event) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(2);
/* Inline Functions: */
/** General management task for a given MIDI class interface, required for the correct operation of the interface. This should
* be called frequently in the main program loop, before the master USB management task \ref USB_USBTask().
*
* \param[in,out] MIDIInterfaceInfo Pointer to a structure containing a MIDI Class configuration and state.
*/
static inline void MIDI_Device_USBTask(USB_ClassInfo_MIDI_Device_t* const MIDIInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1);
static inline void MIDI_Device_USBTask(USB_ClassInfo_MIDI_Device_t* const MIDIInterfaceInfo)
{
(void)MIDIInterfaceInfo;
}
/** Processes incoming control requests from the host, that are directed to the given MIDI class interface. This should be
* linked to the library \ref EVENT_USB_Device_UnhandledControlRequest() event.
*
* \param[in,out] MIDIInterfaceInfo Pointer to a structure containing a MIDI Class configuration and state.
*/
static inline void MIDI_Device_ProcessControlRequest(USB_ClassInfo_MIDI_Device_t* const MIDIInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1);
static inline void MIDI_Device_ProcessControlRequest(USB_ClassInfo_MIDI_Device_t* const MIDIInterfaceInfo)
{
(void)MIDIInterfaceInfo;
}
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,230 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
#define __INCLUDE_FROM_USB_DRIVER
#include "../../HighLevel/USBMode.h"
#if defined(USB_CAN_BE_DEVICE)
#define __INCLUDE_FROM_MS_CLASS_DEVICE_C
#define __INCLUDE_FROM_MS_DRIVER
#include "MassStorage.h"
static volatile bool* CallbackIsResetSource;
void MS_Device_ProcessControlRequest(USB_ClassInfo_MS_Device_t* const MSInterfaceInfo)
{
if (!(Endpoint_IsSETUPReceived()))
return;
if (USB_ControlRequest.wIndex != MSInterfaceInfo->Config.InterfaceNumber)
return;
switch (USB_ControlRequest.bRequest)
{
case REQ_MassStorageReset:
if (USB_ControlRequest.bmRequestType == (REQDIR_HOSTTODEVICE | REQTYPE_CLASS | REQREC_INTERFACE))
{
Endpoint_ClearSETUP();
MSInterfaceInfo->State.IsMassStoreReset = true;
Endpoint_ClearStatusStage();
}
break;
case REQ_GetMaxLUN:
if (USB_ControlRequest.bmRequestType == (REQDIR_DEVICETOHOST | REQTYPE_CLASS | REQREC_INTERFACE))
{
Endpoint_ClearSETUP();
Endpoint_Write_Byte(MSInterfaceInfo->Config.TotalLUNs - 1);
Endpoint_ClearIN();
Endpoint_ClearStatusStage();
}
break;
}
}
bool MS_Device_ConfigureEndpoints(USB_ClassInfo_MS_Device_t* const MSInterfaceInfo)
{
memset(&MSInterfaceInfo->State, 0x00, sizeof(MSInterfaceInfo->State));
if (!(Endpoint_ConfigureEndpoint(MSInterfaceInfo->Config.DataINEndpointNumber, EP_TYPE_BULK,
ENDPOINT_DIR_IN, MSInterfaceInfo->Config.DataINEndpointSize,
MSInterfaceInfo->Config.DataINEndpointDoubleBank ? ENDPOINT_BANK_DOUBLE : ENDPOINT_BANK_SINGLE)))
{
return false;
}
if (!(Endpoint_ConfigureEndpoint(MSInterfaceInfo->Config.DataOUTEndpointNumber, EP_TYPE_BULK,
ENDPOINT_DIR_OUT, MSInterfaceInfo->Config.DataOUTEndpointSize,
MSInterfaceInfo->Config.DataOUTEndpointDoubleBank ? ENDPOINT_BANK_DOUBLE : ENDPOINT_BANK_SINGLE)))
{
return false;
}
return true;
}
void MS_Device_USBTask(USB_ClassInfo_MS_Device_t* const MSInterfaceInfo)
{
if (USB_DeviceState != DEVICE_STATE_Configured)
return;
Endpoint_SelectEndpoint(MSInterfaceInfo->Config.DataOUTEndpointNumber);
if (Endpoint_IsReadWriteAllowed())
{
if (MS_Device_ReadInCommandBlock(MSInterfaceInfo))
{
if (MSInterfaceInfo->State.CommandBlock.Flags & MS_COMMAND_DIR_DATA_IN)
Endpoint_SelectEndpoint(MSInterfaceInfo->Config.DataINEndpointNumber);
MSInterfaceInfo->State.CommandStatus.Status = CALLBACK_MS_Device_SCSICommandReceived(MSInterfaceInfo) ?
SCSI_Command_Pass : SCSI_Command_Fail;
MSInterfaceInfo->State.CommandStatus.Signature = MS_CSW_SIGNATURE;
MSInterfaceInfo->State.CommandStatus.Tag = MSInterfaceInfo->State.CommandBlock.Tag;
MSInterfaceInfo->State.CommandStatus.DataTransferResidue = MSInterfaceInfo->State.CommandBlock.DataTransferLength;
if ((MSInterfaceInfo->State.CommandStatus.Status == SCSI_Command_Fail) &&
(MSInterfaceInfo->State.CommandStatus.DataTransferResidue))
{
Endpoint_StallTransaction();
}
MS_Device_ReturnCommandStatus(MSInterfaceInfo);
}
}
if (MSInterfaceInfo->State.IsMassStoreReset)
{
Endpoint_ResetFIFO(MSInterfaceInfo->Config.DataOUTEndpointNumber);
Endpoint_ResetFIFO(MSInterfaceInfo->Config.DataINEndpointNumber);
Endpoint_SelectEndpoint(MSInterfaceInfo->Config.DataOUTEndpointNumber);
Endpoint_ClearStall();
Endpoint_ResetDataToggle();
Endpoint_SelectEndpoint(MSInterfaceInfo->Config.DataINEndpointNumber);
Endpoint_ClearStall();
Endpoint_ResetDataToggle();
MSInterfaceInfo->State.IsMassStoreReset = false;
}
}
static bool MS_Device_ReadInCommandBlock(USB_ClassInfo_MS_Device_t* const MSInterfaceInfo)
{
Endpoint_SelectEndpoint(MSInterfaceInfo->Config.DataOUTEndpointNumber);
CallbackIsResetSource = &MSInterfaceInfo->State.IsMassStoreReset;
if (Endpoint_Read_Stream_LE(&MSInterfaceInfo->State.CommandBlock,
(sizeof(MS_CommandBlockWrapper_t) - 16),
StreamCallback_MS_Device_AbortOnMassStoreReset))
{
return false;
}
if ((MSInterfaceInfo->State.CommandBlock.Signature != MS_CBW_SIGNATURE) ||
(MSInterfaceInfo->State.CommandBlock.LUN >= MSInterfaceInfo->Config.TotalLUNs) ||
(MSInterfaceInfo->State.CommandBlock.Flags & 0x1F) ||
(MSInterfaceInfo->State.CommandBlock.SCSICommandLength == 0) ||
(MSInterfaceInfo->State.CommandBlock.SCSICommandLength > 16))
{
Endpoint_StallTransaction();
Endpoint_SelectEndpoint(MSInterfaceInfo->Config.DataINEndpointNumber);
Endpoint_StallTransaction();
return false;
}
CallbackIsResetSource = &MSInterfaceInfo->State.IsMassStoreReset;
if (Endpoint_Read_Stream_LE(&MSInterfaceInfo->State.CommandBlock.SCSICommandData,
MSInterfaceInfo->State.CommandBlock.SCSICommandLength,
StreamCallback_MS_Device_AbortOnMassStoreReset))
{
return false;
}
Endpoint_ClearOUT();
return true;
}
static void MS_Device_ReturnCommandStatus(USB_ClassInfo_MS_Device_t* const MSInterfaceInfo)
{
Endpoint_SelectEndpoint(MSInterfaceInfo->Config.DataOUTEndpointNumber);
while (Endpoint_IsStalled())
{
#if !defined(INTERRUPT_CONTROL_ENDPOINT)
USB_USBTask();
#endif
if (MSInterfaceInfo->State.IsMassStoreReset)
return;
}
Endpoint_SelectEndpoint(MSInterfaceInfo->Config.DataINEndpointNumber);
while (Endpoint_IsStalled())
{
#if !defined(INTERRUPT_CONTROL_ENDPOINT)
USB_USBTask();
#endif
if (MSInterfaceInfo->State.IsMassStoreReset)
return;
}
CallbackIsResetSource = &MSInterfaceInfo->State.IsMassStoreReset;
if (Endpoint_Write_Stream_LE(&MSInterfaceInfo->State.CommandStatus, sizeof(MS_CommandStatusWrapper_t),
StreamCallback_MS_Device_AbortOnMassStoreReset))
{
return;
}
Endpoint_ClearIN();
}
static uint8_t StreamCallback_MS_Device_AbortOnMassStoreReset(void)
{
#if !defined(INTERRUPT_CONTROL_ENDPOINT)
USB_USBTask();
#endif
if (*CallbackIsResetSource)
return STREAMCALLBACK_Abort;
else
return STREAMCALLBACK_Continue;
}
#endif

View File

@ -0,0 +1,168 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Device mode driver for the library USB Mass Storage Class driver.
*
* Device mode driver for the library USB Mass Storage Class driver.
*
* \note This file should not be included directly. It is automatically included as needed by the class driver
* dispatch header located in LUFA/Drivers/USB/Class/MassStorage.h.
*/
/** \ingroup Group_USBClassMS
* @defgroup Group_USBClassMSDevice Mass Storage Class Device Mode Driver
*
* \section Sec_Dependencies Module Source Dependencies
* The following files must be built with any user project that uses this module:
* - LUFA/Drivers/USB/Class/Device/MassStorage.c <i>(Makefile source module name: LUFA_SRC_USBCLASS)</i>
*
* \section Module Description
* Device Mode USB Class driver framework interface, for the Mass Storage USB Class driver.
*
* @{
*/
#ifndef _MS_CLASS_DEVICE_H_
#define _MS_CLASS_DEVICE_H_
/* Includes: */
#include "../../USB.h"
#include "../Common/MassStorage.h"
#include <string.h>
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_MS_DRIVER)
#error Do not include this file directly. Include LUFA/Drivers/Class/MassStorage.h instead.
#endif
/* Public Interface - May be used in end-application: */
/* Type Defines: */
/** \brief Mass Storage Class Device Mode Configuration and State Structure.
*
* Class state structure. An instance of this structure should be made for each Mass Storage interface
* within the user application, and passed to each of the Mass Storage class driver functions as the
* MSInterfaceInfo parameter. This stores each Mass Storage interface's configuration and state information.
*/
typedef struct
{
const struct
{
uint8_t InterfaceNumber; /**< Interface number of the Mass Storage interface within the device. */
uint8_t DataINEndpointNumber; /**< Endpoint number of the Mass Storage interface's IN data endpoint. */
uint16_t DataINEndpointSize; /**< Size in bytes of the Mass Storage interface's IN data endpoint. */
bool DataINEndpointDoubleBank; /**< Indicates if the Mass Storage interface's IN data endpoint should use double banking. */
uint8_t DataOUTEndpointNumber; /**< Endpoint number of the Mass Storage interface's OUT data endpoint. */
uint16_t DataOUTEndpointSize; /**< Size in bytes of the Mass Storage interface's OUT data endpoint. */
bool DataOUTEndpointDoubleBank; /**< Indicates if the Mass Storage interface's OUT data endpoint should use double banking. */
uint8_t TotalLUNs; /**< Total number of logical drives in the Mass Storage interface. */
} Config; /**< Config data for the USB class interface within the device. All elements in this section
* <b>must</b> be set or the interface will fail to enumerate and operate correctly.
*/
struct
{
MS_CommandBlockWrapper_t CommandBlock; /**< Mass Storage class command block structure, stores the received SCSI
* command from the host which is to be processed.
*/
MS_CommandStatusWrapper_t CommandStatus; /**< Mass Storage class command status structure, set elements to indicate
* the issued command's success or failure to the host.
*/
volatile bool IsMassStoreReset; /**< Flag indicating that the host has requested that the Mass Storage interface be reset
* and that all current Mass Storage operations should immediately abort.
*/
} State; /**< State data for the USB class interface within the device. All elements in this section
* are reset to their defaults when the interface is enumerated.
*/
} USB_ClassInfo_MS_Device_t;
/* Function Prototypes: */
/** Configures the endpoints of a given Mass Storage interface, ready for use. This should be linked to the library
* \ref EVENT_USB_Device_ConfigurationChanged() event so that the endpoints are configured when the configuration
* containing the given Mass Storage interface is selected.
*
* \param[in,out] MSInterfaceInfo Pointer to a structure containing a Mass Storage Class configuration and state.
*
* \return Boolean true if the endpoints were successfully configured, false otherwise.
*/
bool MS_Device_ConfigureEndpoints(USB_ClassInfo_MS_Device_t* const MSInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1);
/** Processes incoming control requests from the host, that are directed to the given Mass Storage class interface. This should be
* linked to the library \ref EVENT_USB_Device_UnhandledControlRequest() event.
*
* \param[in,out] MSInterfaceInfo Pointer to a structure containing a Mass Storage Class configuration and state.
*/
void MS_Device_ProcessControlRequest(USB_ClassInfo_MS_Device_t* const MSInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1);
/** General management task for a given Mass Storage class interface, required for the correct operation of the interface. This should
* be called frequently in the main program loop, before the master USB management task \ref USB_USBTask().
*
* \param[in,out] MSInterfaceInfo Pointer to a structure containing a Mass Storage configuration and state.
*/
void MS_Device_USBTask(USB_ClassInfo_MS_Device_t* const MSInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1);
/** Mass Storage class driver callback for the user processing of a received SCSI command. This callback will fire each time the
* host sends a SCSI command which requires processing by the user application. Inside this callback the user is responsible
* for the processing of the received SCSI command from the host. The SCSI command is available in the CommandBlock structure
* inside the Mass Storage class state structure passed as a parameter to the callback function.
*
* \param[in,out] MSInterfaceInfo Pointer to a structure containing a Mass Storage Class configuration and state.
*
* \return Boolean true if the SCSI command was successfully processed, false otherwise.
*/
bool CALLBACK_MS_Device_SCSICommandReceived(USB_ClassInfo_MS_Device_t* const MSInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1);
/* Private Interface - For use in library only: */
#if !defined(__DOXYGEN__)
/* Function Prototypes: */
#if defined(__INCLUDE_FROM_MS_CLASS_DEVICE_C)
static void MS_Device_ReturnCommandStatus(USB_ClassInfo_MS_Device_t* const MSInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1);
static bool MS_Device_ReadInCommandBlock(USB_ClassInfo_MS_Device_t* const MSInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1);
static uint8_t StreamCallback_MS_Device_AbortOnMassStoreReset(void);
#endif
#endif
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,477 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
#define __INCLUDE_FROM_USB_DRIVER
#include "../../HighLevel/USBMode.h"
#if defined(USB_CAN_BE_DEVICE)
#define __INCLUDE_FROM_RNDIS_CLASS_DEVICE_C
#define __INCLUDE_FROM_RNDIS_DRIVER
#include "RNDIS.h"
static const uint32_t PROGMEM AdapterSupportedOIDList[] =
{
OID_GEN_SUPPORTED_LIST,
OID_GEN_PHYSICAL_MEDIUM,
OID_GEN_HARDWARE_STATUS,
OID_GEN_MEDIA_SUPPORTED,
OID_GEN_MEDIA_IN_USE,
OID_GEN_MAXIMUM_FRAME_SIZE,
OID_GEN_MAXIMUM_TOTAL_SIZE,
OID_GEN_LINK_SPEED,
OID_GEN_TRANSMIT_BLOCK_SIZE,
OID_GEN_RECEIVE_BLOCK_SIZE,
OID_GEN_VENDOR_ID,
OID_GEN_VENDOR_DESCRIPTION,
OID_GEN_CURRENT_PACKET_FILTER,
OID_GEN_MAXIMUM_TOTAL_SIZE,
OID_GEN_MEDIA_CONNECT_STATUS,
OID_GEN_XMIT_OK,
OID_GEN_RCV_OK,
OID_GEN_XMIT_ERROR,
OID_GEN_RCV_ERROR,
OID_GEN_RCV_NO_BUFFER,
OID_802_3_PERMANENT_ADDRESS,
OID_802_3_CURRENT_ADDRESS,
OID_802_3_MULTICAST_LIST,
OID_802_3_MAXIMUM_LIST_SIZE,
OID_802_3_RCV_ERROR_ALIGNMENT,
OID_802_3_XMIT_ONE_COLLISION,
OID_802_3_XMIT_MORE_COLLISIONS,
};
void RNDIS_Device_ProcessControlRequest(USB_ClassInfo_RNDIS_Device_t* const RNDISInterfaceInfo)
{
if (!(Endpoint_IsSETUPReceived()))
return;
if (USB_ControlRequest.wIndex != RNDISInterfaceInfo->Config.ControlInterfaceNumber)
return;
switch (USB_ControlRequest.bRequest)
{
case REQ_SendEncapsulatedCommand:
if (USB_ControlRequest.bmRequestType == (REQDIR_HOSTTODEVICE | REQTYPE_CLASS | REQREC_INTERFACE))
{
Endpoint_ClearSETUP();
Endpoint_Read_Control_Stream_LE(RNDISInterfaceInfo->State.RNDISMessageBuffer, USB_ControlRequest.wLength);
RNDIS_Device_ProcessRNDISControlMessage(RNDISInterfaceInfo);
Endpoint_ClearIN();
}
break;
case REQ_GetEncapsulatedResponse:
if (USB_ControlRequest.bmRequestType == (REQDIR_DEVICETOHOST | REQTYPE_CLASS | REQREC_INTERFACE))
{
Endpoint_ClearSETUP();
RNDIS_Message_Header_t* MessageHeader = (RNDIS_Message_Header_t*)&RNDISInterfaceInfo->State.RNDISMessageBuffer;
if (!(MessageHeader->MessageLength))
{
RNDISInterfaceInfo->State.RNDISMessageBuffer[0] = 0;
MessageHeader->MessageLength = 1;
}
Endpoint_Write_Control_Stream_LE(RNDISInterfaceInfo->State.RNDISMessageBuffer, MessageHeader->MessageLength);
Endpoint_ClearOUT();
MessageHeader->MessageLength = 0;
}
break;
}
}
bool RNDIS_Device_ConfigureEndpoints(USB_ClassInfo_RNDIS_Device_t* const RNDISInterfaceInfo)
{
memset(&RNDISInterfaceInfo->State, 0x00, sizeof(RNDISInterfaceInfo->State));
if (!(Endpoint_ConfigureEndpoint(RNDISInterfaceInfo->Config.DataINEndpointNumber, EP_TYPE_BULK,
ENDPOINT_DIR_IN, RNDISInterfaceInfo->Config.DataINEndpointSize,
RNDISInterfaceInfo->Config.DataINEndpointDoubleBank ? ENDPOINT_BANK_DOUBLE : ENDPOINT_BANK_SINGLE)))
{
return false;
}
if (!(Endpoint_ConfigureEndpoint(RNDISInterfaceInfo->Config.DataOUTEndpointNumber, EP_TYPE_BULK,
ENDPOINT_DIR_OUT, RNDISInterfaceInfo->Config.DataOUTEndpointSize,
RNDISInterfaceInfo->Config.DataOUTEndpointDoubleBank ? ENDPOINT_BANK_DOUBLE : ENDPOINT_BANK_SINGLE)))
{
return false;
}
if (!(Endpoint_ConfigureEndpoint(RNDISInterfaceInfo->Config.NotificationEndpointNumber, EP_TYPE_INTERRUPT,
ENDPOINT_DIR_IN, RNDISInterfaceInfo->Config.NotificationEndpointSize,
RNDISInterfaceInfo->Config.NotificationEndpointDoubleBank ? ENDPOINT_BANK_DOUBLE : ENDPOINT_BANK_SINGLE)))
{
return false;
}
return true;
}
void RNDIS_Device_USBTask(USB_ClassInfo_RNDIS_Device_t* const RNDISInterfaceInfo)
{
if (USB_DeviceState != DEVICE_STATE_Configured)
return;
RNDIS_Message_Header_t* MessageHeader = (RNDIS_Message_Header_t*)&RNDISInterfaceInfo->State.RNDISMessageBuffer;
Endpoint_SelectEndpoint(RNDISInterfaceInfo->Config.NotificationEndpointNumber);
if (Endpoint_IsINReady() && RNDISInterfaceInfo->State.ResponseReady)
{
USB_Request_Header_t Notification = (USB_Request_Header_t)
{
.bmRequestType = (REQDIR_DEVICETOHOST | REQTYPE_CLASS | REQREC_INTERFACE),
.bRequest = NOTIF_ResponseAvailable,
.wValue = 0,
.wIndex = 0,
.wLength = 0,
};
Endpoint_Write_Stream_LE(&Notification, sizeof(USB_Request_Header_t), NO_STREAM_CALLBACK);
Endpoint_ClearIN();
RNDISInterfaceInfo->State.ResponseReady = false;
}
if ((RNDISInterfaceInfo->State.CurrRNDISState == RNDIS_Data_Initialized) && !(MessageHeader->MessageLength))
{
RNDIS_Packet_Message_t RNDISPacketHeader;
Endpoint_SelectEndpoint(RNDISInterfaceInfo->Config.DataOUTEndpointNumber);
if (Endpoint_IsOUTReceived() && !(RNDISInterfaceInfo->State.FrameIN.FrameInBuffer))
{
Endpoint_Read_Stream_LE(&RNDISPacketHeader, sizeof(RNDIS_Packet_Message_t), NO_STREAM_CALLBACK);
if (RNDISPacketHeader.DataLength > ETHERNET_FRAME_SIZE_MAX)
{
Endpoint_StallTransaction();
return;
}
Endpoint_Read_Stream_LE(RNDISInterfaceInfo->State.FrameIN.FrameData, RNDISPacketHeader.DataLength, NO_STREAM_CALLBACK);
Endpoint_ClearOUT();
RNDISInterfaceInfo->State.FrameIN.FrameLength = RNDISPacketHeader.DataLength;
RNDISInterfaceInfo->State.FrameIN.FrameInBuffer = true;
}
Endpoint_SelectEndpoint(RNDISInterfaceInfo->Config.DataINEndpointNumber);
if (Endpoint_IsINReady() && RNDISInterfaceInfo->State.FrameOUT.FrameInBuffer)
{
memset(&RNDISPacketHeader, 0, sizeof(RNDIS_Packet_Message_t));
RNDISPacketHeader.MessageType = REMOTE_NDIS_PACKET_MSG;
RNDISPacketHeader.MessageLength = (sizeof(RNDIS_Packet_Message_t) + RNDISInterfaceInfo->State.FrameOUT.FrameLength);
RNDISPacketHeader.DataOffset = (sizeof(RNDIS_Packet_Message_t) - sizeof(RNDIS_Message_Header_t));
RNDISPacketHeader.DataLength = RNDISInterfaceInfo->State.FrameOUT.FrameLength;
Endpoint_Write_Stream_LE(&RNDISPacketHeader, sizeof(RNDIS_Packet_Message_t), NO_STREAM_CALLBACK);
Endpoint_Write_Stream_LE(RNDISInterfaceInfo->State.FrameOUT.FrameData, RNDISPacketHeader.DataLength, NO_STREAM_CALLBACK);
Endpoint_ClearIN();
RNDISInterfaceInfo->State.FrameOUT.FrameInBuffer = false;
}
}
}
void RNDIS_Device_ProcessRNDISControlMessage(USB_ClassInfo_RNDIS_Device_t* const RNDISInterfaceInfo)
{
/* Note: Only a single buffer is used for both the received message and its response to save SRAM. Because of
this, response bytes should be filled in order so that they do not clobber unread data in the buffer. */
RNDIS_Message_Header_t* MessageHeader = (RNDIS_Message_Header_t*)&RNDISInterfaceInfo->State.RNDISMessageBuffer;
switch (MessageHeader->MessageType)
{
case REMOTE_NDIS_INITIALIZE_MSG:
RNDISInterfaceInfo->State.ResponseReady = true;
RNDIS_Initialize_Message_t* INITIALIZE_Message =
(RNDIS_Initialize_Message_t*)&RNDISInterfaceInfo->State.RNDISMessageBuffer;
RNDIS_Initialize_Complete_t* INITIALIZE_Response =
(RNDIS_Initialize_Complete_t*)&RNDISInterfaceInfo->State.RNDISMessageBuffer;
INITIALIZE_Response->MessageType = REMOTE_NDIS_INITIALIZE_CMPLT;
INITIALIZE_Response->MessageLength = sizeof(RNDIS_Initialize_Complete_t);
INITIALIZE_Response->RequestId = INITIALIZE_Message->RequestId;
INITIALIZE_Response->Status = REMOTE_NDIS_STATUS_SUCCESS;
INITIALIZE_Response->MajorVersion = REMOTE_NDIS_VERSION_MAJOR;
INITIALIZE_Response->MinorVersion = REMOTE_NDIS_VERSION_MINOR;
INITIALIZE_Response->DeviceFlags = REMOTE_NDIS_DF_CONNECTIONLESS;
INITIALIZE_Response->Medium = REMOTE_NDIS_MEDIUM_802_3;
INITIALIZE_Response->MaxPacketsPerTransfer = 1;
INITIALIZE_Response->MaxTransferSize = (sizeof(RNDIS_Packet_Message_t) + ETHERNET_FRAME_SIZE_MAX);
INITIALIZE_Response->PacketAlignmentFactor = 0;
INITIALIZE_Response->AFListOffset = 0;
INITIALIZE_Response->AFListSize = 0;
RNDISInterfaceInfo->State.CurrRNDISState = RNDIS_Initialized;
break;
case REMOTE_NDIS_HALT_MSG:
RNDISInterfaceInfo->State.ResponseReady = false;
MessageHeader->MessageLength = 0;
RNDISInterfaceInfo->State.CurrRNDISState = RNDIS_Uninitialized;
break;
case REMOTE_NDIS_QUERY_MSG:
RNDISInterfaceInfo->State.ResponseReady = true;
RNDIS_Query_Message_t* QUERY_Message = (RNDIS_Query_Message_t*)&RNDISInterfaceInfo->State.RNDISMessageBuffer;
RNDIS_Query_Complete_t* QUERY_Response = (RNDIS_Query_Complete_t*)&RNDISInterfaceInfo->State.RNDISMessageBuffer;
uint32_t Query_Oid = QUERY_Message->Oid;
void* QueryData = &RNDISInterfaceInfo->State.RNDISMessageBuffer[sizeof(RNDIS_Message_Header_t) +
QUERY_Message->InformationBufferOffset];
void* ResponseData = &RNDISInterfaceInfo->State.RNDISMessageBuffer[sizeof(RNDIS_Query_Complete_t)];
uint16_t ResponseSize;
QUERY_Response->MessageType = REMOTE_NDIS_QUERY_CMPLT;
QUERY_Response->MessageLength = sizeof(RNDIS_Query_Complete_t);
if (RNDIS_Device_ProcessNDISQuery(RNDISInterfaceInfo, Query_Oid, QueryData, QUERY_Message->InformationBufferLength,
ResponseData, &ResponseSize))
{
QUERY_Response->Status = REMOTE_NDIS_STATUS_SUCCESS;
QUERY_Response->MessageLength += ResponseSize;
QUERY_Response->InformationBufferLength = ResponseSize;
QUERY_Response->InformationBufferOffset = (sizeof(RNDIS_Query_Complete_t) - sizeof(RNDIS_Message_Header_t));
}
else
{
QUERY_Response->Status = REMOTE_NDIS_STATUS_NOT_SUPPORTED;
QUERY_Response->InformationBufferLength = 0;
QUERY_Response->InformationBufferOffset = 0;
}
break;
case REMOTE_NDIS_SET_MSG:
RNDISInterfaceInfo->State.ResponseReady = true;
RNDIS_Set_Message_t* SET_Message = (RNDIS_Set_Message_t*)&RNDISInterfaceInfo->State.RNDISMessageBuffer;
RNDIS_Set_Complete_t* SET_Response = (RNDIS_Set_Complete_t*)&RNDISInterfaceInfo->State.RNDISMessageBuffer;
uint32_t SET_Oid = SET_Message->Oid;
SET_Response->MessageType = REMOTE_NDIS_SET_CMPLT;
SET_Response->MessageLength = sizeof(RNDIS_Set_Complete_t);
SET_Response->RequestId = SET_Message->RequestId;
void* SetData = &RNDISInterfaceInfo->State.RNDISMessageBuffer[sizeof(RNDIS_Message_Header_t) +
SET_Message->InformationBufferOffset];
SET_Response->Status = RNDIS_Device_ProcessNDISSet(RNDISInterfaceInfo, SET_Oid, SetData,
SET_Message->InformationBufferLength) ?
REMOTE_NDIS_STATUS_SUCCESS : REMOTE_NDIS_STATUS_NOT_SUPPORTED;
break;
case REMOTE_NDIS_RESET_MSG:
RNDISInterfaceInfo->State.ResponseReady = true;
RNDIS_Reset_Complete_t* RESET_Response = (RNDIS_Reset_Complete_t*)&RNDISInterfaceInfo->State.RNDISMessageBuffer;
RESET_Response->MessageType = REMOTE_NDIS_RESET_CMPLT;
RESET_Response->MessageLength = sizeof(RNDIS_Reset_Complete_t);
RESET_Response->Status = REMOTE_NDIS_STATUS_SUCCESS;
RESET_Response->AddressingReset = 0;
break;
case REMOTE_NDIS_KEEPALIVE_MSG:
RNDISInterfaceInfo->State.ResponseReady = true;
RNDIS_KeepAlive_Message_t* KEEPALIVE_Message =
(RNDIS_KeepAlive_Message_t*)&RNDISInterfaceInfo->State.RNDISMessageBuffer;
RNDIS_KeepAlive_Complete_t* KEEPALIVE_Response =
(RNDIS_KeepAlive_Complete_t*)&RNDISInterfaceInfo->State.RNDISMessageBuffer;
KEEPALIVE_Response->MessageType = REMOTE_NDIS_KEEPALIVE_CMPLT;
KEEPALIVE_Response->MessageLength = sizeof(RNDIS_KeepAlive_Complete_t);
KEEPALIVE_Response->RequestId = KEEPALIVE_Message->RequestId;
KEEPALIVE_Response->Status = REMOTE_NDIS_STATUS_SUCCESS;
break;
}
}
static bool RNDIS_Device_ProcessNDISQuery(USB_ClassInfo_RNDIS_Device_t* const RNDISInterfaceInfo,
const uint32_t OId,
void* const QueryData,
const uint16_t QuerySize,
void* ResponseData,
uint16_t* const ResponseSize)
{
(void)QueryData;
(void)QuerySize;
switch (OId)
{
case OID_GEN_SUPPORTED_LIST:
*ResponseSize = sizeof(AdapterSupportedOIDList);
memcpy_P(ResponseData, AdapterSupportedOIDList, sizeof(AdapterSupportedOIDList));
return true;
case OID_GEN_PHYSICAL_MEDIUM:
*ResponseSize = sizeof(uint32_t);
/* Indicate that the device is a true ethernet link */
*((uint32_t*)ResponseData) = 0;
return true;
case OID_GEN_HARDWARE_STATUS:
*ResponseSize = sizeof(uint32_t);
*((uint32_t*)ResponseData) = NDIS_HardwareStatus_Ready;
return true;
case OID_GEN_MEDIA_SUPPORTED:
case OID_GEN_MEDIA_IN_USE:
*ResponseSize = sizeof(uint32_t);
*((uint32_t*)ResponseData) = REMOTE_NDIS_MEDIUM_802_3;
return true;
case OID_GEN_VENDOR_ID:
*ResponseSize = sizeof(uint32_t);
/* Vendor ID 0x0xFFFFFF is reserved for vendors who have not purchased a NDIS VID */
*((uint32_t*)ResponseData) = 0x00FFFFFF;
return true;
case OID_GEN_MAXIMUM_FRAME_SIZE:
case OID_GEN_TRANSMIT_BLOCK_SIZE:
case OID_GEN_RECEIVE_BLOCK_SIZE:
*ResponseSize = sizeof(uint32_t);
*((uint32_t*)ResponseData) = ETHERNET_FRAME_SIZE_MAX;
return true;
case OID_GEN_VENDOR_DESCRIPTION:
*ResponseSize = (strlen(RNDISInterfaceInfo->Config.AdapterVendorDescription) + 1);
memcpy(ResponseData, RNDISInterfaceInfo->Config.AdapterVendorDescription, *ResponseSize);
return true;
case OID_GEN_MEDIA_CONNECT_STATUS:
*ResponseSize = sizeof(uint32_t);
*((uint32_t*)ResponseData) = REMOTE_NDIS_MEDIA_STATE_CONNECTED;
return true;
case OID_GEN_LINK_SPEED:
*ResponseSize = sizeof(uint32_t);
/* Indicate 10Mb/s link speed */
*((uint32_t*)ResponseData) = 100000;
return true;
case OID_802_3_PERMANENT_ADDRESS:
case OID_802_3_CURRENT_ADDRESS:
*ResponseSize = sizeof(MAC_Address_t);
memcpy(ResponseData, &RNDISInterfaceInfo->Config.AdapterMACAddress, sizeof(MAC_Address_t));
return true;
case OID_802_3_MAXIMUM_LIST_SIZE:
*ResponseSize = sizeof(uint32_t);
/* Indicate only one multicast address supported */
*((uint32_t*)ResponseData) = 1;
return true;
case OID_GEN_CURRENT_PACKET_FILTER:
*ResponseSize = sizeof(uint32_t);
*((uint32_t*)ResponseData) = RNDISInterfaceInfo->State.CurrPacketFilter;
return true;
case OID_GEN_XMIT_OK:
case OID_GEN_RCV_OK:
case OID_GEN_XMIT_ERROR:
case OID_GEN_RCV_ERROR:
case OID_GEN_RCV_NO_BUFFER:
case OID_802_3_RCV_ERROR_ALIGNMENT:
case OID_802_3_XMIT_ONE_COLLISION:
case OID_802_3_XMIT_MORE_COLLISIONS:
*ResponseSize = sizeof(uint32_t);
/* Unused statistic OIDs - always return 0 for each */
*((uint32_t*)ResponseData) = 0;
return true;
case OID_GEN_MAXIMUM_TOTAL_SIZE:
*ResponseSize = sizeof(uint32_t);
/* Indicate maximum overall buffer (Ethernet frame and RNDIS header) the adapter can handle */
*((uint32_t*)ResponseData) = (RNDIS_MESSAGE_BUFFER_SIZE + ETHERNET_FRAME_SIZE_MAX);
return true;
default:
return false;
}
}
static bool RNDIS_Device_ProcessNDISSet(USB_ClassInfo_RNDIS_Device_t* const RNDISInterfaceInfo,
const uint32_t OId,
const void* SetData,
const uint16_t SetSize)
{
(void)SetSize;
switch (OId)
{
case OID_GEN_CURRENT_PACKET_FILTER:
RNDISInterfaceInfo->State.CurrPacketFilter = *((uint32_t*)SetData);
RNDISInterfaceInfo->State.CurrRNDISState = ((RNDISInterfaceInfo->State.CurrPacketFilter) ?
RNDIS_Data_Initialized : RNDIS_Data_Initialized);
return true;
case OID_802_3_MULTICAST_LIST:
/* Do nothing - throw away the value from the host as it is unused */
return true;
default:
return false;
}
}
#endif

View File

@ -0,0 +1,176 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Device mode driver for the library USB RNDIS Class driver.
*
* Device mode driver for the library USB RNDIS Class driver.
*
* \note This file should not be included directly. It is automatically included as needed by the class driver
* dispatch header located in LUFA/Drivers/USB/Class/RNDIS.h.
*/
/** \ingroup Group_USBClassRNDIS
* @defgroup Group_USBClassRNDISDevice RNDIS Class Device Mode Driver
*
* \section Sec_Dependencies Module Source Dependencies
* The following files must be built with any user project that uses this module:
* - LUFA/Drivers/USB/Class/Device/RNDIS.c <i>(Makefile source module name: LUFA_SRC_USBCLASS)</i>
*
* \section Module Description
* Device Mode USB Class driver framework interface, for the RNDIS USB Class driver.
*
* @{
*/
#ifndef _RNDIS_CLASS_DEVICE_H_
#define _RNDIS_CLASS_DEVICE_H_
/* Includes: */
#include "../../USB.h"
#include "../Common/RNDIS.h"
#include <string.h>
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_RNDIS_DRIVER)
#error Do not include this file directly. Include LUFA/Drivers/Class/RNDIS.h instead.
#endif
/* Public Interface - May be used in end-application: */
/* Type Defines: */
/** \brief RNDIS Class Device Mode Configuration and State Structure.
*
* Class state structure. An instance of this structure should be made for each RNDIS interface
* within the user application, and passed to each of the RNDIS class driver functions as the
* RNDISInterfaceInfo parameter. This stores each RNDIS interface's configuration and state information.
*/
typedef struct
{
const struct
{
uint8_t ControlInterfaceNumber; /**< Interface number of the CDC control interface within the device. */
uint8_t DataINEndpointNumber; /**< Endpoint number of the CDC interface's IN data endpoint. */
uint16_t DataINEndpointSize; /**< Size in bytes of the CDC interface's IN data endpoint. */
bool DataINEndpointDoubleBank; /**< Indicates if the RNDIS interface's IN data endpoint should use double banking. */
uint8_t DataOUTEndpointNumber; /**< Endpoint number of the CDC interface's OUT data endpoint. */
uint16_t DataOUTEndpointSize; /**< Size in bytes of the CDC interface's OUT data endpoint. */
bool DataOUTEndpointDoubleBank; /**< Indicates if the RNDIS interface's OUT data endpoint should use double banking. */
uint8_t NotificationEndpointNumber; /**< Endpoint number of the CDC interface's IN notification endpoint, if used. */
uint16_t NotificationEndpointSize; /**< Size in bytes of the CDC interface's IN notification endpoint, if used. */
bool NotificationEndpointDoubleBank; /**< Indicates if the RNDIS interface's notification endpoint should use double banking. */
char* AdapterVendorDescription; /**< String description of the adapter vendor. */
MAC_Address_t AdapterMACAddress; /**< MAC address of the adapter. */
} Config; /**< Config data for the USB class interface within the device. All elements in this section.
* <b>must</b> be set or the interface will fail to enumerate and operate correctly.
*/
struct
{
uint8_t RNDISMessageBuffer[RNDIS_MESSAGE_BUFFER_SIZE]; /**< Buffer to hold RNDIS messages to and from the host,
* managed by the class driver.
*/
bool ResponseReady; /**< Internal flag indicating if a RNDIS message is waiting to be returned to the host. */
uint8_t CurrRNDISState; /**< Current RNDIS state of the adapter, a value from the RNDIS_States_t enum. */
uint32_t CurrPacketFilter; /**< Current packet filter mode, used internally by the class driver. */
Ethernet_Frame_Info_t FrameIN; /**< Structure holding the last received Ethernet frame from the host, for user
* processing.
*/
Ethernet_Frame_Info_t FrameOUT; /**< Structure holding the next Ethernet frame to send to the host, populated by the
* user application.
*/
} State; /**< State data for the USB class interface within the device. All elements in this section
* are reset to their defaults when the interface is enumerated.
*/
} USB_ClassInfo_RNDIS_Device_t;
/* Function Prototypes: */
/** Configures the endpoints of a given RNDIS interface, ready for use. This should be linked to the library
* \ref EVENT_USB_Device_ConfigurationChanged() event so that the endpoints are configured when the configuration
* containing the given HID interface is selected.
*
* \param[in,out] RNDISInterfaceInfo Pointer to a structure containing a RNDIS Class configuration and state.
*
* \return Boolean true if the endpoints were successfully configured, false otherwise.
*/
bool RNDIS_Device_ConfigureEndpoints(USB_ClassInfo_RNDIS_Device_t* const RNDISInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1);
/** Processes incoming control requests from the host, that are directed to the given RNDIS class interface. This should be
* linked to the library \ref EVENT_USB_Device_UnhandledControlRequest() event.
*
* \param[in,out] RNDISInterfaceInfo Pointer to a structure containing a RNDIS Class configuration and state.
*/
void RNDIS_Device_ProcessControlRequest(USB_ClassInfo_RNDIS_Device_t* const RNDISInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1);
/** General management task for a given HID class interface, required for the correct operation of the interface. This should
* be called frequently in the main program loop, before the master USB management task \ref USB_USBTask().
*
* \param[in,out] RNDISInterfaceInfo Pointer to a structure containing a RNDIS Class configuration and state.
*/
void RNDIS_Device_USBTask(USB_ClassInfo_RNDIS_Device_t* const RNDISInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1);
/* Private Interface - For use in library only: */
#if !defined(__DOXYGEN__)
/* Function Prototypes: */
#if defined(__INCLUDE_FROM_RNDIS_CLASS_DEVICE_C)
static void RNDIS_Device_ProcessRNDISControlMessage(USB_ClassInfo_RNDIS_Device_t* const RNDISInterfaceInfo)
ATTR_NON_NULL_PTR_ARG(1);
static bool RNDIS_Device_ProcessNDISQuery(USB_ClassInfo_RNDIS_Device_t* const RNDISInterfaceInfo,
const uint32_t OId,
void* const QueryData,
const uint16_t QuerySize,
void* ResponseData,
uint16_t* const ResponseSize) ATTR_NON_NULL_PTR_ARG(1)
ATTR_NON_NULL_PTR_ARG(5) ATTR_NON_NULL_PTR_ARG(6);
static bool RNDIS_Device_ProcessNDISSet(USB_ClassInfo_RNDIS_Device_t* const RNDISInterfaceInfo,
const uint32_t OId,
const void* SetData,
const uint16_t SetSize) ATTR_NON_NULL_PTR_ARG(1)
ATTR_NON_NULL_PTR_ARG(3);
#endif
#endif
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,84 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Master include file for the library USB HID Class driver.
*
* Master include file for the library USB HID Class driver, for both host and device modes, where available.
*
* This file should be included in all user projects making use of this optional class driver, instead of
* including any headers in the USB/ClassDriver/Device, USB/ClassDriver/Host or USB/ClassDriver/Common subdirectories.
*/
/** \ingroup Group_USBClassDrivers
* @defgroup Group_USBClassHID HID Class Driver - LUFA/Drivers/Class/HID.h
*
* \section Sec_Dependencies Module Source Dependencies
* The following files must be built with any user project that uses this module:
* - LUFA/Drivers/USB/Class/Device/HID.c <i>(Makefile source module name: LUFA_SRC_USBCLASS)</i>
* - LUFA/Drivers/USB/Class/Host/HID.c <i>(Makefile source module name: LUFA_SRC_USBCLASS)</i>
* - LUFA/Drivers/USB/Class/Host/HIDParser.c <i>(Makefile source module name: LUFA_SRC_USB)</i>
*
* \section Module Description
* HID Class Driver module. This module contains an internal implementation of the USB HID Class, for both Device
* and Host USB modes. User applications can use this class driver instead of implementing the HID class manually
* via the low-level LUFA APIs.
*
* This module is designed to simplify the user code by exposing only the required interface needed to interface with
* Hosts or Devices using the USB HID Class.
*
* @{
*/
#ifndef _HID_CLASS_H_
#define _HID_CLASS_H_
/* Macros: */
#define __INCLUDE_FROM_HID_DRIVER
#define __INCLUDE_FROM_USB_DRIVER
/* Includes: */
#include "../HighLevel/USBMode.h"
#if defined(NO_STREAM_CALLBACKS)
#error The NO_STREAM_CALLBACKS compile time option cannot be used in projects using the library Class drivers.
#endif
#if defined(USB_CAN_BE_DEVICE)
#include "Device/HID.h"
#endif
#if defined(USB_CAN_BE_HOST)
#include "Host/HID.h"
#endif
#endif
/** @} */

View File

@ -0,0 +1,464 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
#define __INCLUDE_FROM_USB_DRIVER
#include "../../HighLevel/USBMode.h"
#if defined(USB_CAN_BE_HOST)
#define __INCLUDE_FROM_CDC_CLASS_HOST_C
#define __INCLUDE_FROM_CDC_DRIVER
#include "CDC.h"
uint8_t CDC_Host_ConfigurePipes(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo,
uint16_t ConfigDescriptorSize,
void* ConfigDescriptorData)
{
uint8_t FoundEndpoints = 0;
memset(&CDCInterfaceInfo->State, 0x00, sizeof(CDCInterfaceInfo->State));
if (DESCRIPTOR_TYPE(ConfigDescriptorData) != DTYPE_Configuration)
return CDC_ENUMERROR_InvalidConfigDescriptor;
if (USB_GetNextDescriptorComp(&ConfigDescriptorSize, &ConfigDescriptorData,
DCOMP_CDC_Host_NextCDCControlInterface) != DESCRIPTOR_SEARCH_COMP_Found)
{
return CDC_ENUMERROR_NoCDCInterfaceFound;
}
CDCInterfaceInfo->State.ControlInterfaceNumber = DESCRIPTOR_CAST(ConfigDescriptorData, USB_Descriptor_Interface_t).InterfaceNumber;
while (FoundEndpoints != (CDC_FOUND_NOTIFICATION_IN | CDC_FOUND_DATAPIPE_IN | CDC_FOUND_DATAPIPE_OUT))
{
if (USB_GetNextDescriptorComp(&ConfigDescriptorSize, &ConfigDescriptorData,
DCOMP_CDC_Host_NextCDCInterfaceEndpoint) != DESCRIPTOR_SEARCH_COMP_Found)
{
if (FoundEndpoints & CDC_FOUND_NOTIFICATION_IN)
{
if (USB_GetNextDescriptorComp(&ConfigDescriptorSize, &ConfigDescriptorData,
DCOMP_CDC_Host_NextCDCDataInterface) != DESCRIPTOR_SEARCH_COMP_Found)
{
return CDC_ENUMERROR_NoCDCInterfaceFound;
}
}
else
{
FoundEndpoints = 0;
Pipe_SelectPipe(CDCInterfaceInfo->Config.DataINPipeNumber);
Pipe_DisablePipe();
Pipe_SelectPipe(CDCInterfaceInfo->Config.DataOUTPipeNumber);
Pipe_DisablePipe();
Pipe_SelectPipe(CDCInterfaceInfo->Config.NotificationPipeNumber);
Pipe_DisablePipe();
if (USB_GetNextDescriptorComp(&ConfigDescriptorSize, &ConfigDescriptorData,
DCOMP_CDC_Host_NextCDCControlInterface) != DESCRIPTOR_SEARCH_COMP_Found)
{
return CDC_ENUMERROR_NoCDCInterfaceFound;
}
}
if (USB_GetNextDescriptorComp(&ConfigDescriptorSize, &ConfigDescriptorData,
DCOMP_CDC_Host_NextCDCInterfaceEndpoint) != DESCRIPTOR_SEARCH_COMP_Found)
{
return CDC_ENUMERROR_EndpointsNotFound;
}
}
USB_Descriptor_Endpoint_t* EndpointData = DESCRIPTOR_PCAST(ConfigDescriptorData, USB_Descriptor_Endpoint_t);
if ((EndpointData->Attributes & EP_TYPE_MASK) == EP_TYPE_INTERRUPT)
{
if (EndpointData->EndpointAddress & ENDPOINT_DESCRIPTOR_DIR_IN)
{
Pipe_ConfigurePipe(CDCInterfaceInfo->Config.NotificationPipeNumber, EP_TYPE_INTERRUPT, PIPE_TOKEN_IN,
EndpointData->EndpointAddress, EndpointData->EndpointSize,
CDCInterfaceInfo->Config.NotificationPipeDoubleBank ? PIPE_BANK_DOUBLE : PIPE_BANK_SINGLE);
CDCInterfaceInfo->State.NotificationPipeSize = EndpointData->EndpointSize;
Pipe_SetInterruptPeriod(EndpointData->PollingIntervalMS);
FoundEndpoints |= CDC_FOUND_NOTIFICATION_IN;
}
}
else
{
if (EndpointData->EndpointAddress & ENDPOINT_DESCRIPTOR_DIR_IN)
{
Pipe_ConfigurePipe(CDCInterfaceInfo->Config.DataINPipeNumber, EP_TYPE_BULK, PIPE_TOKEN_IN,
EndpointData->EndpointAddress, EndpointData->EndpointSize,
CDCInterfaceInfo->Config.DataINPipeDoubleBank ? PIPE_BANK_DOUBLE : PIPE_BANK_SINGLE);
CDCInterfaceInfo->State.DataINPipeSize = EndpointData->EndpointSize;
FoundEndpoints |= CDC_FOUND_DATAPIPE_IN;
}
else
{
Pipe_ConfigurePipe(CDCInterfaceInfo->Config.DataOUTPipeNumber, EP_TYPE_BULK, PIPE_TOKEN_OUT,
EndpointData->EndpointAddress, EndpointData->EndpointSize,
CDCInterfaceInfo->Config.DataOUTPipeDoubleBank ? PIPE_BANK_DOUBLE : PIPE_BANK_SINGLE);
CDCInterfaceInfo->State.DataOUTPipeSize = EndpointData->EndpointSize;
FoundEndpoints |= CDC_FOUND_DATAPIPE_OUT;
}
}
}
CDCInterfaceInfo->State.ControlLineStates.HostToDevice = (CDC_CONTROL_LINE_OUT_RTS | CDC_CONTROL_LINE_OUT_DTR);
CDCInterfaceInfo->State.ControlLineStates.DeviceToHost = (CDC_CONTROL_LINE_IN_DCD | CDC_CONTROL_LINE_IN_DSR);
CDCInterfaceInfo->State.IsActive = true;
return CDC_ENUMERROR_NoError;
}
static uint8_t DCOMP_CDC_Host_NextCDCControlInterface(void* const CurrentDescriptor)
{
if (DESCRIPTOR_TYPE(CurrentDescriptor) == DTYPE_Interface)
{
USB_Descriptor_Interface_t* CurrentInterface = DESCRIPTOR_PCAST(CurrentDescriptor,
USB_Descriptor_Interface_t);
if ((CurrentInterface->Class == CDC_CONTROL_CLASS) &&
(CurrentInterface->SubClass == CDC_CONTROL_SUBCLASS) &&
(CurrentInterface->Protocol == CDC_CONTROL_PROTOCOL))
{
return DESCRIPTOR_SEARCH_Found;
}
}
return DESCRIPTOR_SEARCH_NotFound;
}
static uint8_t DCOMP_CDC_Host_NextCDCDataInterface(void* const CurrentDescriptor)
{
if (DESCRIPTOR_TYPE(CurrentDescriptor) == DTYPE_Interface)
{
USB_Descriptor_Interface_t* CurrentInterface = DESCRIPTOR_PCAST(CurrentDescriptor,
USB_Descriptor_Interface_t);
if ((CurrentInterface->Class == CDC_DATA_CLASS) &&
(CurrentInterface->SubClass == CDC_DATA_SUBCLASS) &&
(CurrentInterface->Protocol == CDC_DATA_PROTOCOL))
{
return DESCRIPTOR_SEARCH_Found;
}
}
return DESCRIPTOR_SEARCH_NotFound;
}
static uint8_t DCOMP_CDC_Host_NextCDCInterfaceEndpoint(void* const CurrentDescriptor)
{
if (DESCRIPTOR_TYPE(CurrentDescriptor) == DTYPE_Endpoint)
{
USB_Descriptor_Endpoint_t* CurrentEndpoint = DESCRIPTOR_PCAST(CurrentDescriptor,
USB_Descriptor_Endpoint_t);
uint8_t EndpointType = (CurrentEndpoint->Attributes & EP_TYPE_MASK);
if (((EndpointType == EP_TYPE_BULK) || (EndpointType == EP_TYPE_INTERRUPT)) &&
!(Pipe_IsEndpointBound(CurrentEndpoint->EndpointAddress)))
{
return DESCRIPTOR_SEARCH_Found;
}
}
else if (DESCRIPTOR_TYPE(CurrentDescriptor) == DTYPE_Interface)
{
return DESCRIPTOR_SEARCH_Fail;
}
return DESCRIPTOR_SEARCH_NotFound;
}
void CDC_Host_USBTask(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo)
{
if ((USB_HostState != HOST_STATE_Configured) || !(CDCInterfaceInfo->State.IsActive))
return;
Pipe_SelectPipe(CDCInterfaceInfo->Config.NotificationPipeNumber);
Pipe_Unfreeze();
if (Pipe_IsINReceived())
{
USB_Request_Header_t Notification;
Pipe_Read_Stream_LE(&Notification, sizeof(USB_Request_Header_t), NO_STREAM_CALLBACK);
if ((Notification.bRequest == NOTIF_SerialState) &&
(Notification.bmRequestType == (REQDIR_DEVICETOHOST | REQTYPE_CLASS | REQREC_INTERFACE)))
{
Pipe_Read_Stream_LE(&CDCInterfaceInfo->State.ControlLineStates.DeviceToHost,
sizeof(CDCInterfaceInfo->State.ControlLineStates.DeviceToHost),
NO_STREAM_CALLBACK);
Pipe_ClearIN();
EVENT_CDC_Host_ControLineStateChanged(CDCInterfaceInfo);
}
else
{
Pipe_ClearIN();
}
}
Pipe_Freeze();
CDC_Host_Flush(CDCInterfaceInfo);
}
uint8_t CDC_Host_SetLineEncoding(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo)
{
USB_ControlRequest = (USB_Request_Header_t)
{
.bmRequestType = (REQDIR_HOSTTODEVICE | REQTYPE_CLASS | REQREC_INTERFACE),
.bRequest = REQ_SetLineEncoding,
.wValue = 0,
.wIndex = CDCInterfaceInfo->State.ControlInterfaceNumber,
.wLength = sizeof(CDCInterfaceInfo->State.LineEncoding),
};
Pipe_SelectPipe(PIPE_CONTROLPIPE);
return USB_Host_SendControlRequest(&CDCInterfaceInfo->State.LineEncoding);
}
uint8_t CDC_Host_SendControlLineStateChange(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo)
{
USB_ControlRequest = (USB_Request_Header_t)
{
.bmRequestType = (REQDIR_HOSTTODEVICE | REQTYPE_CLASS | REQREC_INTERFACE),
.bRequest = REQ_SetControlLineState,
.wValue = CDCInterfaceInfo->State.ControlLineStates.HostToDevice,
.wIndex = CDCInterfaceInfo->State.ControlInterfaceNumber,
.wLength = 0,
};
Pipe_SelectPipe(PIPE_CONTROLPIPE);
return USB_Host_SendControlRequest(NULL);
}
uint8_t CDC_Host_SendBreak(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo,
const uint8_t Duration)
{
USB_ControlRequest = (USB_Request_Header_t)
{
.bmRequestType = (REQDIR_HOSTTODEVICE | REQTYPE_CLASS | REQREC_INTERFACE),
.bRequest = REQ_SendBreak,
.wValue = Duration,
.wIndex = CDCInterfaceInfo->State.ControlInterfaceNumber,
.wLength = 0,
};
Pipe_SelectPipe(PIPE_CONTROLPIPE);
return USB_Host_SendControlRequest(NULL);
}
uint8_t CDC_Host_SendString(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo,
const char* const Data,
const uint16_t Length)
{
if ((USB_HostState != HOST_STATE_Configured) || !(CDCInterfaceInfo->State.IsActive))
return PIPE_READYWAIT_DeviceDisconnected;
uint8_t ErrorCode;
Pipe_SelectPipe(CDCInterfaceInfo->Config.DataOUTPipeNumber);
Pipe_Unfreeze();
ErrorCode = Pipe_Write_Stream_LE(Data, Length, NO_STREAM_CALLBACK);
Pipe_Freeze();
return ErrorCode;
}
uint8_t CDC_Host_SendByte(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo,
const uint8_t Data)
{
if ((USB_HostState != HOST_STATE_Configured) || !(CDCInterfaceInfo->State.IsActive))
return PIPE_READYWAIT_DeviceDisconnected;
uint8_t ErrorCode;
Pipe_SelectPipe(CDCInterfaceInfo->Config.DataOUTPipeNumber);
Pipe_Unfreeze();
if (!(Pipe_IsReadWriteAllowed()))
{
Pipe_ClearOUT();
if ((ErrorCode = Pipe_WaitUntilReady()) != PIPE_READYWAIT_NoError)
return ErrorCode;
}
Pipe_Write_Byte(Data);
Pipe_Freeze();
return PIPE_READYWAIT_NoError;
}
uint16_t CDC_Host_BytesReceived(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo)
{
if ((USB_HostState != HOST_STATE_Configured) || !(CDCInterfaceInfo->State.IsActive))
return 0;
Pipe_SelectPipe(CDCInterfaceInfo->Config.DataINPipeNumber);
Pipe_Unfreeze();
if (Pipe_IsINReceived())
{
if (!(Pipe_BytesInPipe()))
{
Pipe_ClearIN();
Pipe_Freeze();
return 0;
}
else
{
Pipe_Freeze();
return Pipe_BytesInPipe();
}
}
else
{
Pipe_Freeze();
return 0;
}
}
int16_t CDC_Host_ReceiveByte(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo)
{
if ((USB_HostState != HOST_STATE_Configured) || !(CDCInterfaceInfo->State.IsActive))
return -1;
int16_t ReceivedByte = -1;
Pipe_SelectPipe(CDCInterfaceInfo->Config.DataINPipeNumber);
Pipe_Unfreeze();
if (Pipe_IsINReceived())
{
if (Pipe_BytesInPipe())
ReceivedByte = Pipe_Read_Byte();
if (!(Pipe_BytesInPipe()))
Pipe_ClearIN();
}
Pipe_Freeze();
return ReceivedByte;
}
uint8_t CDC_Host_Flush(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo)
{
if ((USB_HostState != HOST_STATE_Configured) || !(CDCInterfaceInfo->State.IsActive))
return PIPE_READYWAIT_DeviceDisconnected;
uint8_t ErrorCode;
Pipe_SelectPipe(CDCInterfaceInfo->Config.DataOUTPipeNumber);
Pipe_Unfreeze();
if (!(Pipe_BytesInPipe()))
return PIPE_READYWAIT_NoError;
bool BankFull = !(Pipe_IsReadWriteAllowed());
Pipe_ClearOUT();
if (BankFull)
{
if ((ErrorCode = Pipe_WaitUntilReady()) != PIPE_READYWAIT_NoError)
return ErrorCode;
Pipe_ClearOUT();
}
Pipe_Freeze();
return PIPE_READYWAIT_NoError;
}
void CDC_Host_CreateStream(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo,
FILE* const Stream)
{
*Stream = (FILE)FDEV_SETUP_STREAM(CDC_Host_putchar, CDC_Host_getchar, _FDEV_SETUP_RW);
fdev_set_udata(Stream, CDCInterfaceInfo);
}
void CDC_Host_CreateBlockingStream(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo,
FILE* const Stream)
{
*Stream = (FILE)FDEV_SETUP_STREAM(CDC_Host_putchar, CDC_Host_getchar_Blocking, _FDEV_SETUP_RW);
fdev_set_udata(Stream, CDCInterfaceInfo);
}
static int CDC_Host_putchar(char c,
FILE* Stream)
{
return CDC_Host_SendByte((USB_ClassInfo_CDC_Host_t*)fdev_get_udata(Stream), c) ? _FDEV_ERR : 0;
}
static int CDC_Host_getchar(FILE* Stream)
{
int16_t ReceivedByte = CDC_Host_ReceiveByte((USB_ClassInfo_CDC_Host_t*)fdev_get_udata(Stream));
if (ReceivedByte < 0)
return _FDEV_EOF;
return ReceivedByte;
}
static int CDC_Host_getchar_Blocking(FILE* Stream)
{
int16_t ReceivedByte;
while ((ReceivedByte = CDC_Host_ReceiveByte((USB_ClassInfo_CDC_Host_t*)fdev_get_udata(Stream))) < 0)
{
if (USB_HostState == HOST_STATE_Unattached)
return _FDEV_EOF;
CDC_Host_USBTask((USB_ClassInfo_CDC_Host_t*)fdev_get_udata(Stream));
USB_USBTask();
}
return ReceivedByte;
}
void CDC_Host_Event_Stub(void)
{
}
#endif

View File

@ -0,0 +1,347 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
/** \file
* \brief Host mode driver for the library USB CDC Class driver.
*
* Host mode driver for the library USB CDC Class driver.
*
* \note This file should not be included directly. It is automatically included as needed by the class driver
* dispatch header located in LUFA/Drivers/USB/Class/CDC.h.
*/
/** \ingroup Group_USBClassCDC
* @defgroup Group_USBClassCDCHost CDC Class Host Mode Driver
*
* \section Sec_Dependencies Module Source Dependencies
* The following files must be built with any user project that uses this module:
* - LUFA/Drivers/USB/Class/Host/CDC.c <i>(Makefile source module name: LUFA_SRC_USBCLASS)</i>
*
* \section Module Description
* Host Mode USB Class driver framework interface, for the CDC USB Class driver.
*
* @{
*/
#ifndef __CDC_CLASS_HOST_H__
#define __CDC_CLASS_HOST_H__
/* Includes: */
#include "../../USB.h"
#include "../Common/CDC.h"
#include <stdio.h>
#include <string.h>
/* Enable C linkage for C++ Compilers: */
#if defined(__cplusplus)
extern "C" {
#endif
/* Preprocessor Checks: */
#if !defined(__INCLUDE_FROM_CDC_DRIVER)
#error Do not include this file directly. Include LUFA/Drivers/Class/CDC.h instead.
#endif
/* Public Interface - May be used in end-application: */
/* Type Defines: */
/** \brief CDC Class Host Mode Configuration and State Structure.
*
* Class state structure. An instance of this structure should be made within the user application,
* and passed to each of the CDC class driver functions as the CDCInterfaceInfo parameter. This
* stores each CDC interface's configuration and state information.
*/
typedef struct
{
const struct
{
uint8_t DataINPipeNumber; /**< Pipe number of the CDC interface's IN data pipe. */
bool DataINPipeDoubleBank; /**< Indicates if the CDC interface's IN data pipe should use double banking. */
uint8_t DataOUTPipeNumber; /**< Pipe number of the CDC interface's OUT data pipe. */
bool DataOUTPipeDoubleBank; /**< Indicates if the CDC interface's OUT data pipe should use double banking. */
uint8_t NotificationPipeNumber; /**< Pipe number of the CDC interface's IN notification endpoint, if used. */
bool NotificationPipeDoubleBank; /**< Indicates if the CDC interface's notification pipe should use double banking. */
} Config; /**< Config data for the USB class interface within the device. All elements in this section
* <b>must</b> be set or the interface will fail to enumerate and operate correctly.
*/
struct
{
bool IsActive; /**< Indicates if the current interface instance is connected to an attached device, valid
* after \ref CDC_Host_ConfigurePipes() is called and the Host state machine is in the
* Configured state.
*/
uint8_t ControlInterfaceNumber; /**< Interface index of the CDC-ACM control interface within the attached device. */
uint16_t DataINPipeSize; /**< Size in bytes of the CDC interface's IN data pipe. */
uint16_t DataOUTPipeSize; /**< Size in bytes of the CDC interface's OUT data pipe. */
uint16_t NotificationPipeSize; /**< Size in bytes of the CDC interface's IN notification pipe, if used. */
struct
{
uint8_t HostToDevice; /**< Control line states from the host to device, as a set of CDC_CONTROL_LINE_OUT_*
* masks - to notify the device of changes to these values, call the
* \ref CDC_Host_SendControlLineStateChange() function.
*/
uint8_t DeviceToHost; /**< Control line states from the device to host, as a set of CDC_CONTROL_LINE_IN_*
* masks. This value is updated each time \ref CDC_Host_USBTask() is called.
*/
} ControlLineStates; /**< Current states of the virtual serial port's control lines between the device and host. */
struct
{
uint32_t BaudRateBPS; /**< Baud rate of the virtual serial port, in bits per second. */
uint8_t CharFormat; /**< Character format of the virtual serial port, a value from the
* \ref CDC_LineEncodingFormats_t enum.
*/
uint8_t ParityType; /**< Parity setting of the virtual serial port, a value from the
* \ref CDC_LineEncodingParity_t enum.
*/
uint8_t DataBits; /**< Bits of data per character of the virtual serial port. */
} LineEncoding; /**< Line encoding used in the virtual serial port, for the device's information. This is generally
* only used if the virtual serial port data is to be reconstructed on a physical UART. When set
* by the host application, the \ref CDC_Host_SetLineEncoding() function must be called to push
* the changes to the device.
*/
} State; /**< State data for the USB class interface within the device. All elements in this section
* <b>may</b> be set to initial values, but may also be ignored to default to sane values when
* the interface is enumerated.
*/
} USB_ClassInfo_CDC_Host_t;
/* Enums: */
/** Enum for the possible error codes returned by the \ref CDC_Host_ConfigurePipes() function. */
enum CDCHost_EnumerationFailure_ErrorCodes_t
{
CDC_ENUMERROR_NoError = 0, /**< Configuration Descriptor was processed successfully. */
CDC_ENUMERROR_InvalidConfigDescriptor = 1, /**< The device returned an invalid Configuration Descriptor. */
CDC_ENUMERROR_NoCDCInterfaceFound = 2, /**< A compatible CDC interface was not found in the device's Configuration Descriptor. */
CDC_ENUMERROR_EndpointsNotFound = 3, /**< Compatible CDC endpoints were not found in the device's CDC interface. */
};
/* Function Prototypes: */
/** General management task for a given CDC host class interface, required for the correct operation of the interface. This should
* be called frequently in the main program loop, before the master USB management task \ref USB_USBTask().
*
* \param[in,out] CDCInterfaceInfo Pointer to a structure containing an CDC Class host configuration and state.
*/
void CDC_Host_USBTask(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1);
/** Host interface configuration routine, to configure a given CDC host interface instance using the Configuration
* Descriptor read from an attached USB device. This function automatically updates the given CDC Host instance's
* state values and configures the pipes required to communicate with the interface if it is found within the device.
* This should be called once after the stack has enumerated the attached device, while the host state machine is in
* the Addressed state.
*
* \param[in,out] CDCInterfaceInfo Pointer to a structure containing an CDC Class host configuration and state.
* \param[in] ConfigDescriptorSize Length of the attached device's Configuration Descriptor.
* \param[in] DeviceConfigDescriptor Pointer to a buffer containing the attached device's Configuration Descriptor.
*
* \return A value from the \ref CDCHost_EnumerationFailure_ErrorCodes_t enum.
*/
uint8_t CDC_Host_ConfigurePipes(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo,
uint16_t ConfigDescriptorSize,
void* DeviceConfigDescriptor) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(3);
/** Sets the line encoding for the attached device's virtual serial port. This should be called when the LineEncoding
* values of the interface have been changed to push the new settings to the USB device.
*
* \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class host configuration and state.
*
* \return A value from the \ref USB_Host_SendControlErrorCodes_t enum.
*/
uint8_t CDC_Host_SetLineEncoding(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1);
/** Sends a Serial Control Line State Change notification to the device. This should be called when the virtual serial
* control lines (DTR, RTS, etc.) have changed states. Line states persist until they are cleared via a second
* notification. This should be called each time the CDC class driver's ControlLineStates.HostToDevice value is updated
* to push the new states to the USB device.
*
* \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class host configuration and state.
*
* \return A value from the \ref USB_Host_SendControlErrorCodes_t enum.
*/
uint8_t CDC_Host_SendControlLineStateChange(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1);
/** Sends a Send Break request to the device. This is generally used to separate data data or to indicate a special condition
* to the receiving device.
*
* \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class host configuration and state.
* \param[in] Duration Duration of the break, in milliseconds.
*
* \return A value from the \ref USB_Host_SendControlErrorCodes_t enum.
*/
uint8_t CDC_Host_SendBreak(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo,
const uint8_t Duration) ATTR_NON_NULL_PTR_ARG(1);
/** Sends a given string to the attached USB device, if connected. If a device is not connected when the function is called, the
* string is discarded. Bytes will be queued for transmission to the device until either the pipe bank becomes full, or the
* \ref CDC_Host_Flush() function is called to flush the pending data to the host. This allows for multiple bytes to be
* packed into a single pipe packet, increasing data throughput.
*
* \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the
* call will fail.
*
* \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class host configuration and state.
* \param[in] Data Pointer to the string to send to the device.
* \param[in] Length Size in bytes of the string to send to the device.
*
* \return A value from the \ref Pipe_Stream_RW_ErrorCodes_t enum.
*/
uint8_t CDC_Host_SendString(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo,
const char* const Data,
const uint16_t Length) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(2);
/** Sends a given byte to the attached USB device, if connected. If a device is not connected when the function is called, the
* byte is discarded. Bytes will be queued for transmission to the device until either the pipe bank becomes full, or the
* \ref CDC_Host_Flush() function is called to flush the pending data to the host. This allows for multiple bytes to be
* packed into a single pipe packet, increasing data throughput.
*
* \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the
* call will fail.
*
* \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class host configuration and state.
* \param[in] Data Byte of data to send to the device.
*
* \return A value from the \ref Pipe_WaitUntilReady_ErrorCodes_t enum.
*/
uint8_t CDC_Host_SendByte(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo,
const uint8_t Data) ATTR_NON_NULL_PTR_ARG(1);
/** Determines the number of bytes received by the CDC interface from the device, waiting to be read. This indicates the number
* of bytes in the IN pipe bank only, and thus the number of calls to \ref CDC_Host_ReceiveByte() which are guaranteed to succeed
* immediately. If multiple bytes are to be received, they should be buffered by the user application, as the pipe bank will not be
* released back to the USB controller until all bytes are read.
*
* \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the
* call will fail.
*
* \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class host configuration and state.
*
* \return Total number of buffered bytes received from the device.
*/
uint16_t CDC_Host_BytesReceived(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1);
/** Reads a byte of data from the device. If no data is waiting to be read of if a USB device is not connected, the function
* returns a negative value. The \ref CDC_Host_BytesReceived() function may be queried in advance to determine how many bytes
* are currently buffered in the CDC interface's data receive pipe.
*
* \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the
* call will fail.
*
* \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class host configuration and state.
*
* \return Next received byte from the device, or a negative value if no data received.
*/
int16_t CDC_Host_ReceiveByte(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1);
/** Flushes any data waiting to be sent, ensuring that the send buffer is cleared.
*
* \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the
* call will fail.
*
* \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class host configuration and state.
*
* \return A value from the \ref Pipe_WaitUntilReady_ErrorCodes_t enum.
*/
uint8_t CDC_Host_Flush(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1);
/** Creates a standard character stream for the given CDC Device instance so that it can be used with all the regular
* functions in the avr-libc <stdio.h> library that accept a FILE stream as a destination (e.g. fprintf). The created
* stream is bidirectional and can be used for both input and output functions.
*
* \note The created stream can be given as stdout if desired to direct the standard output from all <stdio.h> functions
* to the given CDC interface.
*
* \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class configuration and state.
* \param[in,out] Stream Pointer to a FILE structure where the created stream should be placed.
*/
void CDC_Host_CreateStream(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo,
FILE* const Stream);
/** Identical to CDC_Host_CreateStream(), except that reads are blocking until the calling stream function terminates
* the transfer. While blocking, the USB and CDC service tasks are called repeatedly to maintain USB communications.
*
* \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class configuration and state.
* \param[in,out] Stream Pointer to a FILE structure where the created stream should be placed.
*/
void CDC_Host_CreateBlockingStream(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo,
FILE* const Stream);
/** CDC class driver event for a control line state change on a CDC host interface. This event fires each time the device notifies
* the host of a control line state change (containing the virtual serial control line states, such as DCD) and may be hooked in the
* user program by declaring a handler function with the same name and parameters listed here. The new control line states
* are available in the ControlLineStates.DeviceToHost value inside the CDC host interface structure passed as a parameter, set as
* a mask of CDC_CONTROL_LINE_IN_* masks.
*
* \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class host configuration and state.
*/
void EVENT_CDC_Host_ControLineStateChanged(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1);
/* Private Interface - For use in library only: */
#if !defined(__DOXYGEN__)
/* Macros: */
#define CDC_CONTROL_CLASS 0x02
#define CDC_CONTROL_SUBCLASS 0x02
#define CDC_CONTROL_PROTOCOL 0x01
#define CDC_DATA_CLASS 0x0A
#define CDC_DATA_SUBCLASS 0x00
#define CDC_DATA_PROTOCOL 0x00
#define CDC_FOUND_DATAPIPE_IN (1 << 0)
#define CDC_FOUND_DATAPIPE_OUT (1 << 1)
#define CDC_FOUND_NOTIFICATION_IN (1 << 2)
/* Function Prototypes: */
#if defined(__INCLUDE_FROM_CDC_CLASS_HOST_C)
static int CDC_Host_putchar(char c,
FILE* Stream) ATTR_NON_NULL_PTR_ARG(2);
static int CDC_Host_getchar(FILE* Stream) ATTR_NON_NULL_PTR_ARG(1);
static int CDC_Host_getchar_Blocking(FILE* Stream) ATTR_NON_NULL_PTR_ARG(1);
void CDC_Host_Event_Stub(void);
void EVENT_CDC_Host_ControLineStateChanged(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo)
ATTR_WEAK ATTR_NON_NULL_PTR_ARG(1) ATTR_ALIAS(CDC_Host_Event_Stub);
static uint8_t DCOMP_CDC_Host_NextCDCControlInterface(void* const CurrentDescriptor) ATTR_NON_NULL_PTR_ARG(1);
static uint8_t DCOMP_CDC_Host_NextCDCDataInterface(void* const CurrentDescriptor) ATTR_NON_NULL_PTR_ARG(1);
static uint8_t DCOMP_CDC_Host_NextCDCInterfaceEndpoint(void* const CurrentDescriptor) ATTR_NON_NULL_PTR_ARG(1);
#endif
#endif
/* Disable C linkage for C++ Compilers: */
#if defined(__cplusplus)
}
#endif
#endif
/** @} */

View File

@ -0,0 +1,368 @@
/*
LUFA Library
Copyright (C) Dean Camera, 2010.
dean [at] fourwalledcubicle [dot] com
www.fourwalledcubicle.com
*/
/*
Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com)
Permission to use, copy, modify, distribute, and sell this
software and its documentation for any purpose is hereby granted
without fee, provided that the above copyright notice appear in
all copies and that both that the copyright notice and this
permission notice and warranty disclaimer appear in supporting
documentation, and that the name of the author not be used in
advertising or publicity pertaining to distribution of the
software without specific, written prior permission.
The author disclaim all warranties with regard to this
software, including all implied warranties of merchantability
and fitness. In no event shall the author be liable for any
special, indirect or consequential damages or any damages
whatsoever resulting from loss of use, data or profits, whether
in an action of contract, negligence or other tortious action,
arising out of or in connection with the use or performance of
this software.
*/
#define __INCLUDE_FROM_USB_DRIVER
#include "../../HighLevel/USBMode.h"
#if defined(USB_CAN_BE_HOST)
#define __INCLUDE_FROM_HID_CLASS_HOST_C
#define __INCLUDE_FROM_HID_DRIVER
#include "HID.h"
uint8_t HID_Host_ConfigurePipes(USB_ClassInfo_HID_Host_t* const HIDInterfaceInfo,
uint16_t ConfigDescriptorSize,
void* ConfigDescriptorData)
{
uint8_t FoundEndpoints = 0;
memset(&HIDInterfaceInfo->State, 0x00, sizeof(HIDInterfaceInfo->State));
if (DESCRIPTOR_TYPE(ConfigDescriptorData) != DTYPE_Configuration)
return HID_ENUMERROR_InvalidConfigDescriptor;
USB_Descriptor_Interface_t* CurrentHIDInterface;
do
{
if (USB_GetNextDescriptorComp(&ConfigDescriptorSize, &ConfigDescriptorData,
DCOMP_HID_Host_NextHIDInterface) != DESCRIPTOR_SEARCH_COMP_Found)
{
return HID_ENUMERROR_NoHIDInterfaceFound;
}
CurrentHIDInterface = DESCRIPTOR_PCAST(ConfigDescriptorData, USB_Descriptor_Interface_t);
} while (HIDInterfaceInfo->Config.HIDInterfaceProtocol &&
(CurrentHIDInterface->Protocol != HIDInterfaceInfo->Config.HIDInterfaceProtocol));
HIDInterfaceInfo->State.InterfaceNumber = CurrentHIDInterface->InterfaceNumber;
HIDInterfaceInfo->State.SupportsBootProtocol = (CurrentHIDInterface->SubClass != HID_NON_BOOT_PROTOCOL);
if (USB_GetNextDescriptorComp(&ConfigDescriptorSize, &ConfigDescriptorData, DCOMP_HID_NextHID) != DESCRIPTOR_SEARCH_COMP_Found)
{
return HID_ENUMERROR_NoHIDDescriptorFound;
}
HIDInterfaceInfo->State.HIDReportSize = DESCRIPTOR_CAST(ConfigDescriptorData, USB_HID_Descriptor_t).HIDReportLength;
while (FoundEndpoints != (HID_FOUND_DATAPIPE_IN | HID_FOUND_DATAPIPE_OUT))
{
if (USB_GetNextDescriptorComp(&ConfigDescriptorSize, &ConfigDescriptorData,
DCOMP_HID_Host_NextHIDInterfaceEndpoint) != DESCRIPTOR_SEARCH_COMP_Found)
{
if (FoundEndpoints & HID_FOUND_DATAPIPE_IN)
break;
return HID_ENUMERROR_EndpointsNotFound;
}
USB_Descriptor_Endpoint_t* EndpointData = DESCRIPTOR_PCAST(ConfigDescriptorData, USB_Descriptor_Endpoint_t);
if (EndpointData->EndpointAddress & ENDPOINT_DESCRIPTOR_DIR_IN)
{
Pipe_ConfigurePipe(HIDInterfaceInfo->Config.DataINPipeNumber, EP_TYPE_INTERRUPT, PIPE_TOKEN_IN,
EndpointData->EndpointAddress, EndpointData->EndpointSize,
HIDInterfaceInfo->Config.DataINPipeDoubleBank ? PIPE_BANK_DOUBLE : PIPE_BANK_SINGLE);
HIDInterfaceInfo->State.DataINPipeSize = EndpointData->EndpointSize;
FoundEndpoints |= HID_FOUND_DATAPIPE_IN;
}
else
{
Pipe_ConfigurePipe(HIDInterfaceInfo->Config.DataOUTPipeNumber, EP_TYPE_INTERRUPT, PIPE_TOKEN_OUT,
EndpointData->EndpointAddress, EndpointData->EndpointSize,
HIDInterfaceInfo->Config.DataOUTPipeDoubleBank ? PIPE_BANK_DOUBLE : PIPE_BANK_SINGLE);
HIDInterfaceInfo->State.DataOUTPipeSize = EndpointData->EndpointSize;
HIDInterfaceInfo->State.DeviceUsesOUTPipe = true;
FoundEndpoints |= HID_FOUND_DATAPIPE_OUT;
}
}
HIDInterfaceInfo->State.LargestReportSize = 8;
HIDInterfaceInfo->State.IsActive = true;
return HID_ENUMERROR_NoError;
}
static uint8_t DCOMP_HID_Host_NextHIDInterface(void* const CurrentDescriptor)
{
if (DESCRIPTOR_TYPE(CurrentDescriptor) == DTYPE_Interface)
{
USB_Descriptor_Interface_t* CurrentInterface = DESCRIPTOR_PCAST(CurrentDescriptor,
USB_Descriptor_Interface_t);
if (CurrentInterface->Class == HID_INTERFACE_CLASS)
return DESCRIPTOR_SEARCH_Found;
}
return DESCRIPTOR_SEARCH_NotFound;
}
static uint8_t DCOMP_HID_NextHID(void* const CurrentDescriptor)
{
if (DESCRIPTOR_TYPE(CurrentDescriptor) == DTYPE_HID)
return DESCRIPTOR_SEARCH_Found;
else if (DESCRIPTOR_TYPE(CurrentDescriptor) == DTYPE_Interface)
return DESCRIPTOR_SEARCH_Fail;
else
return DESCRIPTOR_SEARCH_NotFound;
}
static uint8_t DCOMP_HID_Host_NextHIDInterfaceEndpoint(void* const CurrentDescriptor)
{
if (DESCRIPTOR_TYPE(CurrentDescriptor) == DTYPE_Endpoint)
{
USB_Descriptor_Endpoint_t* CurrentEndpoint = DESCRIPTOR_PCAST(CurrentDescriptor,
USB_Descriptor_Endpoint_t);
if (!(Pipe_IsEndpointBound(CurrentEndpoint->EndpointAddress)))
return DESCRIPTOR_SEARCH_Found;
}
else if (DESCRIPTOR_TYPE(CurrentDescriptor) == DTYPE_Interface)
{
return DESCRIPTOR_SEARCH_Fail;
}
return DESCRIPTOR_SEARCH_NotFound;
}
#if !defined(HID_HOST_BOOT_PROTOCOL_ONLY)
uint8_t HID_Host_ReceiveReportByID(USB_ClassInfo_HID_Host_t* const HIDInterfaceInfo,
const uint8_t ReportID,
void* Buffer)
{
USB_ControlRequest = (USB_Request_Header_t)
{
.bmRequestType = (REQDIR_HOSTTODEVICE | REQTYPE_CLASS | REQREC_INTERFACE),
.bRequest = REQ_SetReport,
.wValue = ((REPORT_ITEM_TYPE_In + 1) << 8) | ReportID,
.wIndex = HIDInterfaceInfo->State.InterfaceNumber,
.wLength = USB_GetHIDReportSize(HIDInterfaceInfo->Config.HIDParserData, ReportID, REPORT_ITEM_TYPE_In),
};
Pipe_SelectPipe(PIPE_CONTROLPIPE);
return USB_Host_SendControlRequest(Buffer);
}
#endif
uint8_t HID_Host_ReceiveReport(USB_ClassInfo_HID_Host_t* const HIDInterfaceInfo,
void* Buffer)
{
if ((USB_HostState != HOST_STATE_Configured) || !(HIDInterfaceInfo->State.IsActive))
return PIPE_READYWAIT_DeviceDisconnected;
uint8_t ErrorCode;
Pipe_SelectPipe(HIDInterfaceInfo->Config.DataINPipeNumber);
Pipe_Unfreeze();
uint16_t ReportSize;
uint8_t* BufferPos = Buffer;
#if !defined(HID_HOST_BOOT_PROTOCOL_ONLY)
if (!(HIDInterfaceInfo->State.UsingBootProtocol))
{
uint8_t ReportID = 0;
if (HIDInterfaceInfo->Config.HIDParserData->UsingReportIDs)
{
ReportID = Pipe_Read_Byte();
*(BufferPos++) = ReportID;
}
ReportSize = USB_GetHIDReportSize(HIDInterfaceInfo->Config.HIDParserData, ReportID, REPORT_ITEM_TYPE_In);
}
else
#endif
{
ReportSize = Pipe_BytesInPipe();
}
if ((ErrorCode = Pipe_Read_Stream_LE(BufferPos, ReportSize, NO_STREAM_CALLBACK)) != PIPE_RWSTREAM_NoError)
return ErrorCode;
Pipe_ClearIN();
Pipe_Freeze();
return PIPE_RWSTREAM_NoError;
}
uint8_t HID_Host_SendReportByID(USB_ClassInfo_HID_Host_t* const HIDInterfaceInfo,
#if !defined(HID_HOST_BOOT_PROTOCOL_ONLY)
const uint8_t ReportID,
#endif
const uint8_t ReportType,
void* Buffer,
const uint16_t ReportSize)
{
#if !defined(HID_HOST_BOOT_PROTOCOL_ONLY)
if ((USB_HostState != HOST_STATE_Configured) || !(HIDInterfaceInfo->State.IsActive))
return false;
if (HIDInterfaceInfo->State.DeviceUsesOUTPipe && (ReportType == REPORT_ITEM_TYPE_Out))
{
uint8_t ErrorCode;
Pipe_SelectPipe(HIDInterfaceInfo->Config.DataOUTPipeNumber);
Pipe_Unfreeze();
if (ReportID)
Pipe_Write_Stream_LE(&ReportID, sizeof(ReportID), NO_STREAM_CALLBACK);
if ((ErrorCode = Pipe_Write_Stream_LE(Buffer, ReportSize, NO_STREAM_CALLBACK)) != PIPE_RWSTREAM_NoError)
return ErrorCode;
Pipe_ClearOUT();
Pipe_Freeze();
return PIPE_RWSTREAM_NoError;
}
else
#endif
{
USB_ControlRequest = (USB_Request_Header_t)
{
.bmRequestType = (REQDIR_HOSTTODEVICE | REQTYPE_CLASS | REQREC_INTERFACE),
.bRequest = REQ_SetReport,
#if !defined(HID_HOST_BOOT_PROTOCOL_ONLY)
.wValue = ((ReportType + 1) << 8) | ReportID,
#else
.wValue = ((ReportType + 1) << 8),
#endif
.wIndex = HIDInterfaceInfo->State.InterfaceNumber,
.wLength = ReportSize,
};
Pipe_SelectPipe(PIPE_CONTROLPIPE);
return USB_Host_SendControlRequest(Buffer);
}
}
bool HID_Host_IsReportReceived(USB_ClassInfo_HID_Host_t* const HIDInterfaceInfo)
{
if ((USB_HostState != HOST_STATE_Configured) || !(HIDInterfaceInfo->State.IsActive))
return false;
bool ReportReceived;
Pipe_SelectPipe(HIDInterfaceInfo->Config.DataINPipeNumber);
Pipe_Unfreeze();
ReportReceived = Pipe_IsINReceived();
Pipe_Freeze();
return ReportReceived;
}
uint8_t HID_Host_SetBootProtocol(USB_ClassInfo_HID_Host_t* const HIDInterfaceInfo)
{
uint8_t ErrorCode;
USB_ControlRequest = (USB_Request_Header_t)
{
.bmRequestType = (REQDIR_HOSTTODEVICE | REQTYPE_CLASS | REQREC_INTERFACE),
.bRequest = REQ_SetProtocol,
.wValue = 0,
.wIndex = HIDInterfaceInfo->State.InterfaceNumber,
.wLength = 0,
};
Pipe_SelectPipe(PIPE_CONTROLPIPE);
if (!(HIDInterfaceInfo->State.SupportsBootProtocol))
return HID_ERROR_LOGICAL;
if ((ErrorCode = USB_Host_SendControlRequest(NULL)) != HOST_SENDCONTROL_Successful)
return ErrorCode;
HIDInterfaceInfo->State.LargestReportSize = 8;
HIDInterfaceInfo->State.UsingBootProtocol = true;
return HOST_SENDCONTROL_Successful;
}
#if !defined(HID_HOST_BOOT_PROTOCOL_ONLY)
uint8_t HID_Host_SetReportProtocol(USB_ClassInfo_HID_Host_t* const HIDInterfaceInfo)
{
uint8_t ErrorCode;
uint8_t HIDReportData[HIDInterfaceInfo->State.HIDReportSize];
USB_ControlRequest = (USB_Request_Header_t)
{
.bmRequestType = (REQDIR_DEVICETOHOST | REQTYPE_STANDARD | REQREC_INTERFACE),
.bRequest = REQ_GetDescriptor,
.wValue = (DTYPE_Report << 8),
.wIndex = HIDInterfaceInfo->State.InterfaceNumber,
.wLength = HIDInterfaceInfo->State.HIDReportSize,
};
Pipe_SelectPipe(PIPE_CONTROLPIPE);
if ((ErrorCode = USB_Host_SendControlRequest(HIDReportData)) != HOST_SENDCONTROL_Successful)
return ErrorCode;
if (HIDInterfaceInfo->State.UsingBootProtocol)
{
USB_ControlRequest = (USB_Request_Header_t)
{
.bmRequestType = (REQDIR_HOSTTODEVICE | REQTYPE_CLASS | REQREC_INTERFACE),
.bRequest = REQ_SetProtocol,
.wValue = 1,
.wIndex = HIDInterfaceInfo->State.InterfaceNumber,
.wLength = 0,
};
if ((ErrorCode = USB_Host_SendControlRequest(NULL)) != HOST_SENDCONTROL_Successful)
return ErrorCode;
HIDInterfaceInfo->State.UsingBootProtocol = false;
}
if (HIDInterfaceInfo->Config.HIDParserData == NULL)
return HID_ERROR_LOGICAL;
if ((ErrorCode = USB_ProcessHIDReport(HIDReportData, HIDInterfaceInfo->State.HIDReportSize,
HIDInterfaceInfo->Config.HIDParserData)) != HID_PARSE_Successful)
{
return HID_ERROR_LOGICAL | ErrorCode;
}
uint8_t LargestReportSizeBits = HIDInterfaceInfo->Config.HIDParserData->LargestReportSizeBits;
HIDInterfaceInfo->State.LargestReportSize = (LargestReportSizeBits >> 3) + ((LargestReportSizeBits & 0x07) != 0);
return 0;
}
#endif
#endif

Some files were not shown because too many files have changed in this diff Show More