Merge remote-tracking branch 'origin/master'

This commit is contained in:
rmackay9 2011-10-01 21:56:29 +09:00
commit 12e8e27af1
307 changed files with 46483 additions and 1146 deletions

4
.gitignore vendored
View File

@ -3,3 +3,7 @@ Tools/ArdupilotMegaPlanner/bin/Release/logs/
ArduCopter/Debug/
config.mk
serialsent.raw
CMakeFiles
CMakeCache.txt
cmake_install.cmake
build

24
ArduBoat/ArduBoat.cpp Normal file
View File

@ -0,0 +1,24 @@
// Libraries
#include <FastSerial.h>
#include <AP_Common.h>
#include <APM_RC.h>
#include <AP_RangeFinder.h>
#include <GCS_MAVLink.h>
#include <AP_ADC.h>
#include <AP_DCM.h>
#include <AP_Compass.h>
#include <Wire.h>
#include <AP_GPS.h>
#include <AP_IMU.h>
#include <APM_BMP085.h>
#include <ModeFilter.h>
#include <APO.h>
#include <WProgram.h>
// Vehicle Configuration
#include "BoatGeneric.h"
// ArduPilotOne Default Setup
#include "APO_DefaultSetup.h"
#include <WProgram.h>; int main(void) {init();setup();for(;;) loop(); return 0; }

22
ArduBoat/ArduBoat.pde Normal file
View File

@ -0,0 +1,22 @@
// Libraries
#include <FastSerial.h>
#include <AP_Common.h>
#include <APM_RC.h>
#include <AP_RangeFinder.h>
#include <GCS_MAVLink.h>
#include <AP_ADC.h>
#include <AP_DCM.h>
#include <AP_Compass.h>
#include <Wire.h>
#include <AP_GPS.h>
#include <AP_IMU.h>
#include <APM_BMP085.h>
#include <ModeFilter.h>
#include <APO.h>
#include <WProgram.h>
// Vehicle Configuration
#include "BoatGeneric.h"
// ArduPilotOne Default Setup
#include "APO_DefaultSetup.h"

68
ArduBoat/BoatGeneric.h Normal file
View File

@ -0,0 +1,68 @@
/*
* BoatGeneric.h
*
* Created on: May 1, 2011
* Author: jgoppert
*/
#ifndef BOATGENERIC_H_
#define BOATGENERIC_H_
// vehicle options
static const apo::vehicle_t vehicle = apo::VEHICLE_BOAT;
static const apo::halMode_t halMode = apo::MODE_LIVE;
static const apo::board_t board = apo::BOARD_ARDUPILOTMEGA_2560;
static const uint8_t heartBeatTimeout = 3;
// algorithm selection
#define CONTROLLER_CLASS ControllerBoat
#define GUIDE_CLASS MavlinkGuide
#define NAVIGATOR_CLASS DcmNavigator
#define COMMLINK_CLASS MavlinkComm
// hardware selection
#define ADC_CLASS AP_ADC_ADS7844
#define COMPASS_CLASS AP_Compass_HMC5843
#define BARO_CLASS APM_BMP085_Class
#define RANGE_FINDER_CLASS AP_RangeFinder_MaxsonarXL
#define DEBUG_BAUD 57600
#define TELEM_BAUD 57600
#define GPS_BAUD 38400
#define HIL_BAUD 57600
// optional sensors
static bool gpsEnabled = false;
static bool baroEnabled = true;
static bool compassEnabled = true;
static bool rangeFinderFrontEnabled = true;
static bool rangeFinderBackEnabled = true;
static bool rangeFinderLeftEnabled = true;
static bool rangeFinderRightEnabled = true;
static bool rangeFinderUpEnabled = true;
static bool rangeFinderDownEnabled = true;
// loop rates
static const float loop0Rate = 150;
static const float loop1Rate = 100;
static const float loop2Rate = 10;
static const float loop3Rate = 1;
static const float loop4Rate = 0.1;
// gains
const float steeringP = 1.0;
const float steeringI = 0.0;
const float steeringD = 0.0;
const float steeringIMax = 0.0;
const float steeringYMax = 3.0;
const float throttleP = 0.0;
const float throttleI = 0.0;
const float throttleD = 0.0;
const float throttleIMax = 0.0;
const float throttleYMax = 0.0;
const float throttleDFCut = 3.0;
#include "ControllerBoat.h"
#endif /* BOATGENERIC_H_ */

125
ArduBoat/ControllerBoat.h Normal file
View File

@ -0,0 +1,125 @@
/*
* ControllerBoat.h
*
* Created on: Jun 30, 2011
* Author: jgoppert
*/
#ifndef CONTROLLERBOAT_H_
#define CONTROLLERBOAT_H_
#include "../APO/AP_Controller.h"
namespace apo {
class ControllerBoat: public AP_Controller {
private:
AP_Var_group _group;
AP_Uint8 _mode;
enum {
k_chMode = k_radioChannelsStart, k_chStr, k_chThr
};
enum {
k_pidStr = k_controllersStart, k_pidThr
};
enum {
CH_MODE = 0, CH_STR, CH_THR
};
BlockPIDDfb pidStr;
BlockPID pidThr;
public:
ControllerBoat(AP_Navigator * nav, AP_Guide * guide,
AP_HardwareAbstractionLayer * hal) :
AP_Controller(nav, guide, hal),
_group(k_cntrl, PSTR("CNTRL_")),
_mode(&_group, 1, MAV_MODE_UNINIT, PSTR("MODE")),
pidStr(new AP_Var_group(k_pidStr, PSTR("STR_")), 1, steeringP,
steeringI, steeringD, steeringIMax, steeringYMax),
pidThr(new AP_Var_group(k_pidThr, PSTR("THR_")), 1, throttleP,
throttleI, throttleD, throttleIMax, throttleYMax,
throttleDFCut) {
_hal->debug->println_P(PSTR("initializing boat controller"));
_hal->rc.push_back(
new AP_RcChannel(k_chMode, PSTR("MODE_"), APM_RC, 7, 1100,
1500, 1900));
_hal->rc.push_back(
new AP_RcChannel(k_chStr, PSTR("STR_"), APM_RC, 0, 1100, 1540,
1900));
_hal->rc.push_back(
new AP_RcChannel(k_chThr, PSTR("THR_"), APM_RC, 1, 1100, 1500,
1900));
}
virtual MAV_MODE getMode() {
return (MAV_MODE) _mode.get();
}
virtual void update(const float & dt) {
// check for heartbeat
if (_hal->heartBeatLost()) {
_mode = MAV_MODE_FAILSAFE;
setAllRadioChannelsToNeutral();
_hal->setState(MAV_STATE_EMERGENCY);
_hal->debug->printf_P(PSTR("comm lost, send heartbeat from gcs\n"));
return;
// if throttle less than 5% cut motor power
} else if (_hal->rc[CH_THR]->getRadioPosition() < 0.05) {
_mode = MAV_MODE_LOCKED;
setAllRadioChannelsToNeutral();
_hal->setState(MAV_STATE_STANDBY);
return;
// if in live mode then set state to active
} else if (_hal->getMode() == MODE_LIVE) {
_hal->setState(MAV_STATE_ACTIVE);
// if in hardware in the loop (control) mode, set to hilsim
} else if (_hal->getMode() == MODE_HIL_CNTL) {
_hal->setState(MAV_STATE_HILSIM);
}
// read switch to set mode
if (_hal->rc[CH_MODE]->getRadioPosition() > 0) {
_mode = MAV_MODE_MANUAL;
} else {
_mode = MAV_MODE_AUTO;
}
// manual mode
switch (_mode) {
case MAV_MODE_MANUAL: {
setAllRadioChannelsManually();
//_hal->debug->println("manual");
break;
}
case MAV_MODE_AUTO: {
float headingError = _guide->getHeadingCommand()
- _nav->getYaw();
if (headingError > 180 * deg2Rad)
headingError -= 360 * deg2Rad;
if (headingError < -180 * deg2Rad)
headingError += 360 * deg2Rad;
_hal->rc[CH_STR]->setPosition(
pidStr.update(headingError, _nav->getYawRate(), dt));
_hal->rc[CH_THR]->setPosition(
pidThr.update(
_guide->getGroundSpeedCommand()
- _nav->getGroundSpeed(), dt));
//_hal->debug->println("automode");
break;
}
default: {
setAllRadioChannelsToNeutral();
_mode = MAV_MODE_FAILSAFE;
_hal->setState(MAV_STATE_EMERGENCY);
_hal->debug->printf_P(PSTR("unknown controller mode\n"));
break;
}
}
}
};
} // namespace apo
#endif /* CONTROLLERBOAT_H_ */

1
ArduBoat/Makefile Normal file
View File

@ -0,0 +1 @@
include ../libraries/AP_Common/Arduino.mk

1
ArduCopter/.gitignore vendored Normal file
View File

@ -0,0 +1 @@
arducopter.cpp

View File

@ -37,8 +37,13 @@
CH7_SIMPLE_MODE
CH7_RTL
CH7_AUTO_TRIM
CH7_ADC_FILTER (experimental)
*/
#define ACCEL_ALT_HOLD 0
#define ACCEL_ALT_HOLD_GAIN 12.0
// ACCEL_ALT_HOLD 1 to enable experimental alt_hold_mode
// See the config.h and defines.h files for how to set this up!
//

View File

@ -1,6 +1,6 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#define THISFIRMWARE "ArduCopter V2.0.45 Beta"
#define THISFIRMWARE "ArduCopter V2.0.46 Beta"
/*
ArduCopter Version 2.0 Beta
Authors: Jason Short
@ -129,6 +129,9 @@ static AP_Int8 *flight_modes = &g.flight_mode1;
APM_BMP085_Class barometer;
AP_Compass_HMC5843 compass(Parameters::k_param_compass);
#ifdef OPTFLOW_ENABLED
AP_OpticalFlow_ADNS3080 optflow;
#endif
// real GPS selection
#if GPS_PROTOCOL == GPS_PROTOCOL_AUTO
@ -200,10 +203,6 @@ static AP_Int8 *flight_modes = &g.flight_mode1;
#endif
// normal dcm
AP_DCM dcm(&imu, g_gps);
#ifdef OPTFLOW_ENABLED
AP_OpticalFlow_ADNS3080 optflow;
#endif
#endif
////////////////////////////////////////////////////////////////////////////////
@ -245,7 +244,8 @@ static const char* flight_mode_strings[] = {
"GUIDED",
"LOITER",
"RTL",
"CIRCLE"};
"CIRCLE",
"POSITION"};
/* Radio values
Channel assignments
@ -260,8 +260,8 @@ static const char* flight_mode_strings[] = {
*/
// test
//Vector3f accels_rot;
//float accel_gain = 20;
Vector3f accels_rot;
//float accel_gain = 12;
// temp
int y_actual_speed;
@ -483,7 +483,6 @@ static byte gps_watchdog;
// --------------
static unsigned long fast_loopTimer; // Time in miliseconds of main control loop
static byte medium_loopCounter; // Counters for branching from main control loop to slower loops
static unsigned long throttle_timer;
static unsigned long fiftyhz_loopTimer;
@ -497,7 +496,6 @@ static unsigned long nav_loopTimer; // used to track the elapsed ime for GPS
static byte counter_one_herz;
static bool GPS_enabled = false;
static byte loop_step;
static bool new_radio_frame;
////////////////////////////////////////////////////////////////////////////////
@ -585,6 +583,9 @@ static void fast_loop()
// write out the servo PWM values
// ------------------------------
set_servos_4();
//if(motor_armed)
// Log_Write_Attitude();
}
static void medium_loop()
@ -596,8 +597,6 @@ static void medium_loop()
// This case deals with the GPS and Compass
//-----------------------------------------
case 0:
loop_step = 1;
medium_loopCounter++;
#ifdef OPTFLOW_ENABLED
@ -637,12 +636,10 @@ static void medium_loop()
// This case performs some navigation computations
//------------------------------------------------
case 1:
loop_step = 2;
medium_loopCounter++;
// Auto control modes:
if(g_gps->new_data && g_gps->fix){
loop_step = 11;
// invalidate GPS data
g_gps->new_data = false;
@ -665,13 +662,14 @@ static void medium_loop()
if (g.log_bitmask & MASK_LOG_NTUN)
Log_Write_Nav_Tuning();
}
}else{
g_gps->new_data = false;
}
break;
// command processing
//-------------------
case 2:
loop_step = 3;
medium_loopCounter++;
// Read altitude from sensors
@ -687,7 +685,6 @@ static void medium_loop()
// This case deals with sending high rate telemetry
//-------------------------------------------------
case 3:
loop_step = 4;
medium_loopCounter++;
// perform next command
@ -726,7 +723,6 @@ static void medium_loop()
// This case controls the slow loop
//---------------------------------
case 4:
loop_step = 5;
medium_loopCounter = 0;
if (g.battery_monitoring != 0){
@ -820,7 +816,6 @@ static void slow_loop()
//----------------------------------------
switch (slow_loopCounter){
case 0:
loop_step = 6;
slow_loopCounter++;
superslow_loopCounter++;
@ -835,7 +830,6 @@ static void slow_loop()
break;
case 1:
loop_step = 7;
slow_loopCounter++;
// Read 3-position switch on radio
@ -860,7 +854,6 @@ static void slow_loop()
break;
case 2:
loop_step = 8;
slow_loopCounter = 0;
update_events();
@ -899,7 +892,6 @@ static void slow_loop()
// 1Hz loop
static void super_slow_loop()
{
loop_step = 9;
if (g.log_bitmask & MASK_LOG_CUR)
Log_Write_Current();
@ -912,7 +904,6 @@ static void super_slow_loop()
static void update_GPS(void)
{
loop_step = 10;
g_gps->update();
update_GPS_light();
@ -920,12 +911,13 @@ static void update_GPS(void)
//current_loc.lat = -1224318000; // Lat * 10 * *7
//current_loc.alt = 100; // alt * 10 * *7
//return;
if(gps_watchdog < 10){
if(gps_watchdog < 12){
gps_watchdog++;
}else{
// we have lost GPS signal for a moment. Reduce our error to avoid flyaways
nav_roll >>= 1;
nav_pitch >>= 1;
// commented temporarily
//nav_roll >>= 1;
//nav_pitch >>= 1;
}
if (g_gps->new_data && g_gps->fix) {
@ -950,19 +942,10 @@ static void update_GPS(void)
// so that the altitude is more accurate
// -------------------------------------
if (current_loc.lat == 0) {
//SendDebugln("!! bad loc");
ground_start_count = 5;
}else{
//Serial.printf("init Home!");
// reset our nav loop timer
//nav_loopTimer = millis();
init_home();
// init altitude
// commented out because we aren't using absolute altitude
// current_loc.alt = home.alt;
ground_start_count = 0;
}
}
@ -1048,10 +1031,7 @@ void update_roll_pitch_mode(void)
switch(roll_pitch_mode){
case ROLL_PITCH_ACRO:
// Roll control
g.rc_1.servo_out = get_rate_roll(g.rc_1.control_in);
// Pitch control
g.rc_2.servo_out = get_rate_pitch(g.rc_2.control_in);
break;
@ -1070,7 +1050,6 @@ void update_roll_pitch_mode(void)
}
}
// 50 hz update rate, not 250
void update_throttle_mode(void)
{
@ -1084,8 +1063,6 @@ void update_throttle_mode(void)
g.pi_rate_pitch.reset_I();
g.rc_3.servo_out = 0;
}
// reset the timer to throttle so that we never get fast I term run-ups
throttle_timer = 0;
break;
case THROTTLE_HOLD:
@ -1109,7 +1086,7 @@ void update_throttle_mode(void)
}
// apply throttle control at 200 hz
g.rc_3.servo_out = g.throttle_cruise + nav_throttle + get_angle_boost();
g.rc_3.servo_out = g.throttle_cruise + nav_throttle + get_angle_boost() + alt_hold_velocity();
break;
}
}
@ -1158,6 +1135,7 @@ static void update_navigation()
// switch passthrough to LOITER
case LOITER:
case POSITION:
wp_control = LOITER_MODE;
// calculates the desired Roll and Pitch
@ -1223,8 +1201,8 @@ static void update_trig(void){
// 270 = cos_yaw: -1.00, sin_yaw: 0.00,
//Vector3f accel_filt = imu.get_accel_filtered();
//accels_rot = dcm.get_dcm_matrix() * imu.get_accel_filtered();
Vector3f accel_filt = imu.get_accel_filtered();
accels_rot = dcm.get_dcm_matrix() * imu.get_accel_filtered();
}
// updated at 10hz
@ -1276,11 +1254,11 @@ adjust_altitude()
{
if(g.rc_3.control_in <= 200){
next_WP.alt -= 1; // 1 meter per second
next_WP.alt = max(next_WP.alt, (current_loc.alt - 400)); // don't go less than 4 meters below current location
next_WP.alt = max(next_WP.alt, (current_loc.alt - 500)); // don't go less than 4 meters below current location
next_WP.alt = max(next_WP.alt, 100); // don't go less than 1 meter
}else if (g.rc_3.control_in > 700){
next_WP.alt += 1; // 1 meter per second
next_WP.alt = min(next_WP.alt, (current_loc.alt + 400)); // don't go more than 4 meters below current location
next_WP.alt = min(next_WP.alt, (current_loc.alt + 500)); // don't go more than 4 meters below current location
}
}
@ -1344,6 +1322,12 @@ static void tuning(){
g.waypoint_speed_max = g.rc_6.control_in;
break;
case CH6_LOITER_P:
g.rc_6.set_range(0,1000);
g.pi_loiter_lat.kP(tuning_value);
g.pi_loiter_lon.kP(tuning_value);
break;
case CH6_NAV_P:
g.rc_6.set_range(0,6000);
g.pi_nav_lat.kP(tuning_value);
@ -1360,10 +1344,10 @@ static void update_nav_wp()
calc_location_error(&next_WP);
// use error as the desired rate towards the target
calc_nav_rate(long_error, lat_error, g.waypoint_speed_max, 0);
calc_loiter(long_error, lat_error);
// rotate pitch and roll to the copter frame of reference
calc_nav_pitch_roll();
calc_loiter_pitch_roll();
}else if(wp_control == CIRCLE_MODE){
@ -1393,18 +1377,18 @@ static void update_nav_wp()
// use error as the desired rate towards the target
// nav_lon, nav_lat is calculated
calc_nav_rate(long_error, lat_error, 200, 0);
calc_loiter(long_error, lat_error);
// rotate pitch and roll to the copter frame of reference
calc_nav_pitch_roll();
calc_loiter_pitch_roll();
} else {
// for long journey's reset the wind resopnse
// it assumes we are standing still.
// use error as the desired rate towards the target
calc_nav_rate2(g.waypoint_speed_max);
calc_nav_rate(g.waypoint_speed_max);
// rotate pitch and roll to the copter frame of reference
calc_nav_pitch_roll2();
calc_nav_pitch_roll();
}
}

View File

@ -1,6 +1,4 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
// XXX TODO: convert these PI rate controlers to a Class
static int
get_stabilize_roll(long target_angle)
{
@ -85,7 +83,7 @@ get_stabilize_yaw(long target_angle)
return (int)constrain(rate, -2500, 2500);
}
#define ALT_ERROR_MAX 350
#define ALT_ERROR_MAX 300
static int
get_nav_throttle(long z_error, int target_speed)
{
@ -95,9 +93,8 @@ get_nav_throttle(long z_error, int target_speed)
// limit error to prevent I term run up
z_error = constrain(z_error, -ALT_ERROR_MAX, ALT_ERROR_MAX);
target_speed = z_error * scaler;
rate_error = target_speed - altitude_rate;
rate_error = constrain(rate_error, -120, 140);
rate_error = constrain(rate_error, -110, 110);
return (int)g.pi_throttle.get_pi(rate_error, .1);
}
@ -106,10 +103,9 @@ static int
get_rate_roll(long target_rate)
{
long error;
target_rate = constrain(target_rate, -2500, 2500);
error = (target_rate * 4.5) - (long)(degrees(omega.x) * 100.0);
target_rate = g.pi_rate_roll.get_pi(error, G_Dt);
target_rate = constrain(target_rate, -2500, 2500);
error = (target_rate * 4.5) - (long)(degrees(omega.x) * 100.0);
target_rate = g.pi_rate_roll.get_pi(error, G_Dt);
// output control:
return (int)constrain(target_rate, -2500, 2500);
@ -119,10 +115,9 @@ static int
get_rate_pitch(long target_rate)
{
long error;
target_rate = constrain(target_rate, -2500, 2500);
error = (target_rate * 4.5) - (long)(degrees(omega.y) * 100.0);
target_rate = g.pi_rate_pitch.get_pi(error, G_Dt);
target_rate = constrain(target_rate, -2500, 2500);
error = (target_rate * 4.5) - (long)(degrees(omega.y) * 100.0);
target_rate = g.pi_rate_pitch.get_pi(error, G_Dt);
// output control:
return (int)constrain(target_rate, -2500, 2500);
@ -132,7 +127,6 @@ static int
get_rate_yaw(long target_rate)
{
long error;
error = (target_rate * 4.5) - (long)(degrees(omega.z) * 100.0);
target_rate = g.pi_rate_yaw.get_pi(error, G_Dt);
@ -193,16 +187,20 @@ get_nav_yaw_offset(int yaw_input, int reset)
}
}
/*
///*
static int alt_hold_velocity()
{
// subtract filtered Accel
float error = abs(next_WP.alt - current_loc.alt);
error = min(error, 200);
error = 1 - (error/ 200.0);
return (accels_rot.z + 9.81) * accel_gain * error;
#if ACCEL_ALT_HOLD == 1
// subtract filtered Accel
float error = abs(next_WP.alt - current_loc.alt);
error = min(error, 200.0);
error = 1 - (error/ 200.0);
return (accels_rot.z + 9.81) * ACCEL_ALT_HOLD_GAIN * error;
#else
return 0;
#endif
}
*/
//*/
static int get_angle_boost()
{

View File

@ -22,12 +22,18 @@ project(ArduCopter C CXX)
find_package(Arduino 22 REQUIRED)
if (NOT DEFINED BOARD)
message(STATUS "board not defined, assuming mega, use cmake -DBOARD=mega2560 , etc. to specify")
set(BOARD "mega")
endif()
message(STATUS "Board configured as: ${BOARD}")
add_subdirectory(../libraries "${CMAKE_CURRENT_BINARY_DIR}/libs")
#add_subdirectory(${CMAKE_SOURCE_DIR}/ArduCopter)
#add_subdirectory(testtool)
PRINT_BOARD_SETTINGS(mega2560)
PRINT_BOARD_SETTINGS(${BOARD})
@ -42,7 +48,7 @@ PRINT_BOARD_SETTINGS(mega2560)
#====================================================================#
set(FIRMWARE_NAME arducopter)
set(${FIRMWARE_NAME}_BOARD mega2560) # Arduino Target board
set(${FIRMWARE_NAME}_BOARD ${BOARD}) # Arduino Target board
set(${FIRMWARE_NAME}_SKETCHES
ArduCopter.pde
@ -126,8 +132,6 @@ set(${FIRMWARE_NAME}_LIBS
c
m
)
SET_TARGET_PROPERTIES(AP_Math PROPERTIES LINKER_LANGUAGE CXX)
#${CONSOLE_PORT}
set(${FIRMWARE_NAME}_PORT COM2) # Serial upload port

View File

@ -1,10 +1 @@
#
# Trivial makefile for building APM
#
#
# Select 'mega' for the original APM, or 'mega2560' for the V2 APM.
#
BOARD = mega
include ../libraries/AP_Common/Arduino.mk

View File

@ -221,8 +221,6 @@
//#define OPTFLOW_ENABLED
#endif
//#define OPTFLOW_ENABLED
#ifndef OPTFLOW // sets global enabled/disabled flag for optflow (as seen in CLI)
# define OPTFLOW DISABLED
#endif
@ -317,19 +315,6 @@
// Attitude Control
//
// SIMPLE Mode
#ifndef SIMPLE_YAW
# define SIMPLE_YAW YAW_HOLD
#endif
#ifndef SIMPLE_RP
# define SIMPLE_RP ROLL_PITCH_STABLE
#endif
#ifndef SIMPLE_THR
# define SIMPLE_THR THROTTLE_MANUAL
#endif
// Alt Hold Mode
#ifndef ALT_HOLD_YAW
# define ALT_HOLD_YAW YAW_HOLD
@ -403,40 +388,40 @@
// Attitude Control
//
#ifndef STABILIZE_ROLL_P
# define STABILIZE_ROLL_P 4.2
# define STABILIZE_ROLL_P 4.0
#endif
#ifndef STABILIZE_ROLL_I
# define STABILIZE_ROLL_I 0.001
#endif
#ifndef STABILIZE_ROLL_IMAX
# define STABILIZE_ROLL_IMAX 0 // degrees
# define STABILIZE_ROLL_IMAX 1.5 // degrees
#endif
#ifndef STABILIZE_PITCH_P
# define STABILIZE_PITCH_P 4.2
# define STABILIZE_PITCH_P 4.0
#endif
#ifndef STABILIZE_PITCH_I
# define STABILIZE_PITCH_I 0.001
#endif
#ifndef STABILIZE_PITCH_IMAX
# define STABILIZE_PITCH_IMAX 0 // degrees
# define STABILIZE_PITCH_IMAX 1.5 // degrees
#endif
//////////////////////////////////////////////////////////////////////////////
// Rate Control
//
#ifndef RATE_ROLL_P
# define RATE_ROLL_P 0.14
# define RATE_ROLL_P .13
#endif
#ifndef RATE_ROLL_I
# define RATE_ROLL_I 0 //0.18
# define RATE_ROLL_I 0.0
#endif
#ifndef RATE_ROLL_IMAX
# define RATE_ROLL_IMAX 15 // degrees
#endif
#ifndef RATE_PITCH_P
# define RATE_PITCH_P 0.14
# define RATE_PITCH_P 0.13
#endif
#ifndef RATE_PITCH_I
# define RATE_PITCH_I 0 //0.18
@ -482,7 +467,7 @@
// Navigation control gains
//
#ifndef LOITER_P
# define LOITER_P .4 //
# define LOITER_P 1.0 //
#endif
#ifndef LOITER_I
# define LOITER_I 0.01 //
@ -495,14 +480,14 @@
# define NAV_P 2.0 // for 4.5 ms error = 13.5 pitch
#endif
#ifndef NAV_I
# define NAV_I 0.15 // this
# define NAV_I 0.10 // this feels really low, 4s to move 1 degree pitch...
#endif
#ifndef NAV_IMAX
# define NAV_IMAX 20 // degrees
# define NAV_IMAX 16 // degrees
#endif
#ifndef WAYPOINT_SPEED_MAX
# define WAYPOINT_SPEED_MAX 400 // for 6m/s error = 13mph
# define WAYPOINT_SPEED_MAX 450 // for 6m/s error = 13mph
#endif
@ -519,7 +504,7 @@
# define THROTTLE_P 0.6 //
#endif
#ifndef THROTTLE_I
# define THROTTLE_I 0.02 // with 4m error, 8 PWM gain/s
# define THROTTLE_I 0.10 // with 4m error, 12.5s windup
#endif
#ifndef THROTTLE_IMAX
# define THROTTLE_IMAX 300
@ -671,7 +656,7 @@
#endif
#ifndef ALT_HOLD_HOME
# define ALT_HOLD_HOME -1
# define ALT_HOLD_HOME 10
#endif
#ifndef USE_CURRENT_ALT

View File

@ -18,10 +18,7 @@ static void read_control_switch()
// setup Simple mode
// do we enable simple mode?
do_simple = (g.simple_modes & (1 << switchPosition));
//Serial.printf("do simple: %d \n", (int)do_simple);
#endif
}else{
switch_debouncer = true;
}
@ -93,6 +90,12 @@ static void read_trim_switch()
trim_flag = false;
}
}
#elif CH7_OPTION == CH7_ADC_FILTER
if (g.rc_7.control_in > 800){
adc.filter_result = true;
}else{
adc.filter_result = false;
}
#elif CH7_OPTION == CH7_AUTO_TRIM
if (g.rc_7.control_in > 800){
auto_level_counter = 10;

View File

@ -33,6 +33,7 @@
#define CH7_SIMPLE_MODE 3
#define CH7_RTL 4
#define CH7_AUTO_TRIM 5
#define CH7_ADC_FILTER 6
// Frame types
#define QUAD_FRAME 0
@ -123,7 +124,8 @@
#define LOITER 5 // Hold a single location
#define RTL 6 // AUTO control
#define CIRCLE 7 // AUTO control
#define NUM_MODES 8
#define POSITION 8 // AUTO control
#define NUM_MODES 9
#define SIMPLE_1 1
#define SIMPLE_2 2
@ -151,6 +153,7 @@
#define CH6_TRAVERSE_SPEED 10
#define CH6_NAV_P 11
#define CH6_LOITER_P 12
// nav byte mask
// -------------

View File

@ -55,39 +55,15 @@ static void calc_location_error(struct Location *next_loc)
lat_error = next_loc->lat - current_loc.lat; // 0 - 500 = -500 pitch NORTH
}
// nav_roll = g.pid_of_roll.get_pid(-optflow.x_cm * 10, dTnav, 1.0);
#define NAV_ERR_MAX 400
static void calc_nav_rate(int x_error, int y_error, int max_speed, int min_speed)
static void calc_loiter(int x_error, int y_error)
{
// moved to globals for logging
//int x_actual_speed, y_actual_speed;
//int x_rate_error, y_rate_error;
x_error = constrain(x_error, -NAV_ERR_MAX, NAV_ERR_MAX);
y_error = constrain(y_error, -NAV_ERR_MAX, NAV_ERR_MAX);
float scaler = (float)max_speed/(float)NAV_ERR_MAX;
g.pi_loiter_lat.kP(scaler);
g.pi_loiter_lon.kP(scaler);
int x_target_speed = g.pi_loiter_lon.get_pi(x_error, dTnav);
int y_target_speed = g.pi_loiter_lat.get_pi(y_error, dTnav);
//Serial.printf("scaler: %1.3f, y_target_speed %d",scaler,y_target_speed);
if(x_target_speed > 0){
x_target_speed = max(x_target_speed, min_speed);
}else{
x_target_speed = min(x_target_speed, -min_speed);
}
if(y_target_speed > 0){
y_target_speed = max(y_target_speed, min_speed);
}else{
y_target_speed = min(y_target_speed, -min_speed);
}
// find the rates:
float temp = radians((float)g_gps->ground_course/100.0);
@ -106,17 +82,28 @@ static void calc_nav_rate(int x_error, int y_error, int max_speed, int min_speed
#endif
y_rate_error = y_target_speed - y_actual_speed; // 413
y_rate_error = constrain(y_rate_error, -600, 600); // added a rate error limit to keep pitching down to a minimum
nav_lat = constrain(g.pi_nav_lat.get_pi(y_rate_error, dTnav), -3500, 3500);
//Serial.printf("yr: %d, nav_lat: %d, int:%d \n",y_rate_error, nav_lat, g.pi_nav_lat.get_integrator());
y_rate_error = constrain(y_rate_error, -250, 250); // added a rate error limit to keep pitching down to a minimum
nav_lat = g.pi_nav_lat.get_pi(y_rate_error, dTnav);
nav_lat = constrain(nav_lat, -3500, 3500);
x_rate_error = x_target_speed - x_actual_speed;
x_rate_error = constrain(x_rate_error, -600, 600);
nav_lon = constrain(g.pi_nav_lon.get_pi(x_rate_error, dTnav), -3500, 3500);
x_rate_error = constrain(x_rate_error, -250, 250);
nav_lon = g.pi_nav_lon.get_pi(x_rate_error, dTnav);
nav_lon = constrain(nav_lon, -3500, 3500);
}
static void calc_nav_rate2(int max_speed)
// nav_roll, nav_pitch
static void calc_loiter_pitch_roll()
{
// rotate the vector
nav_roll = (float)nav_lon * sin_yaw_y - (float)nav_lat * cos_yaw_x;
nav_pitch = (float)nav_lon * cos_yaw_x + (float)nav_lat * sin_yaw_y;
// flip pitch because forward is negative
nav_pitch = -nav_pitch;
}
static void calc_nav_rate(int max_speed)
{
/*
0 1 2 3 4 5 6 7 8
@ -151,7 +138,7 @@ static void calc_nav_rate2(int max_speed)
}
// nav_roll, nav_pitch
static void calc_nav_pitch_roll2()
static void calc_nav_pitch_roll()
{
float temp = radians((float)(9000 - (dcm.yaw_sensor - original_target_bearing))/100.0);
float _cos_yaw_x = cos(temp);
@ -171,40 +158,11 @@ static void calc_nav_pitch_roll2()
nav_pitch);*/
}
// nav_roll, nav_pitch
static void calc_nav_pitch_roll()
{
// rotate the vector
nav_roll = (float)nav_lon * sin_yaw_y - (float)nav_lat * cos_yaw_x;
nav_pitch = (float)nav_lon * cos_yaw_x + (float)nav_lat * sin_yaw_y;
// flip pitch because forward is negative
nav_pitch = -nav_pitch;
}
static long get_altitude_error()
{
return next_WP.alt - current_loc.alt;
}
/*
static void calc_altitude_smoothing_error()
{
// limit climb rates - we draw a straight line between first location and edge of waypoint_radius
target_altitude = next_WP.alt - ((float)(wp_distance * (next_WP.alt - prev_WP.alt)) / (float)(wp_totalDistance - g.waypoint_radius));
// stay within a certain range
if(prev_WP.alt > next_WP.alt){
target_altitude = constrain(target_altitude, next_WP.alt, prev_WP.alt);
}else{
target_altitude = constrain(target_altitude, prev_WP.alt, next_WP.alt);
}
altitude_error = target_altitude - current_loc.alt;
}
*/
static int get_loiter_angle()
{
float power;
@ -223,7 +181,6 @@ static int get_loiter_angle()
return angle;
}
static long wrap_360(long error)
{
if (error > 36000) error -= 36000;

View File

@ -23,10 +23,16 @@ static void init_rc_in()
g.rc_4.set_type(RC_CHANNEL_ANGLE_RAW);
// set rc dead zones
g.rc_1.dead_zone = 60; // 60 = .6 degrees
/*g.rc_1.dead_zone = 60;
g.rc_2.dead_zone = 60;
g.rc_3.dead_zone = 60;
g.rc_4.dead_zone = 600;// 0 = hybrid rate approach
g.rc_4.dead_zone = 300;
*/
g.rc_1.set_dead_zone(60);
g.rc_2.set_dead_zone(60);
g.rc_3.set_dead_zone(60);
g.rc_4.set_dead_zone(200);
//set auxiliary ranges
g.rc_5.set_range(0,1000);
@ -117,14 +123,6 @@ static void read_radio()
#endif
//throttle_failsafe(g.rc_3.radio_in);
/*
Serial.printf_P(PSTR("OUT 1: %d\t2: %d\t3: %d\t4: %d \n"),
g.rc_1.control_in,
g.rc_2.control_in,
g.rc_3.control_in,
g.rc_4.control_in);
*/
}
}

View File

@ -169,6 +169,9 @@ static void init_ardupilot()
heli_init_swash(); // heli initialisation
#endif
// begin filtering the ADC Gyros
adc.filter_result = true;
init_rc_in(); // sets up rc channels from radio
init_rc_out(); // sets up the timer libs
init_camera();
@ -414,6 +417,14 @@ static void set_mode(byte mode)
next_WP = current_loc;
break;
case POSITION:
yaw_mode = YAW_HOLD;
roll_pitch_mode = ROLL_PITCH_AUTO;
throttle_mode = THROTTLE_MANUAL;
next_WP = current_loc;
break;
case GUIDED:
yaw_mode = YAW_AUTO;
roll_pitch_mode = ROLL_PITCH_AUTO;

View File

@ -430,9 +430,6 @@ test_imu(uint8_t argc, const Menu::arg *argv)
while(1){
//delay(20);
if (millis() - fast_loopTimer >= 5) {
//delta_ms_fast_loop = millis() - fast_loopTimer;
//G_Dt = (float)delta_ms_fast_loop / 1000.f; // used by DCM integrator
//fast_loopTimer = millis();
// IMU
// ---
@ -451,7 +448,7 @@ test_imu(uint8_t argc, const Menu::arg *argv)
}
if(medium_loopCounter == 20){
read_radio();
//read_radio();
medium_loopCounter = 0;
//tuning();
//dcm.kp_roll_pitch((float)g.rc_6.control_in / 2000.0);

1
ArduPlane/.gitignore vendored Normal file
View File

@ -0,0 +1 @@
ArduPlane.cpp

View File

@ -273,6 +273,7 @@ static byte command_may_ID; // current command ID
static int airspeed; // m/s * 100
static int airspeed_nudge; // m/s * 100 : additional airspeed based on throttle stick position in top 1/2 of range
static float airspeed_error; // m/s * 100
static float airspeed_fbwB; // m/s * 100
static long energy_error; // energy state error (kinetic + potential) for altitude hold
static long airspeed_energy_error; // kinetic portion of energy error
@ -792,7 +793,7 @@ static void update_current_flight_mode(void)
break;
case FLY_BY_WIRE_A:
// fake Navigation output using sticks
// set nav_roll and nav_pitch using sticks
nav_roll = g.channel_roll.norm_input() * g.roll_limit;
nav_pitch = g.channel_pitch.norm_input() * (-1) * g.pitch_limit_min;
// We use pitch_min above because it is usually greater magnitude then pitch_max. -1 is to compensate for its sign.
@ -809,15 +810,13 @@ static void update_current_flight_mode(void)
if (g.airspeed_enabled == true)
{
airspeed_error = ((int)(g.flybywire_airspeed_max -
airspeed_fbwB = ((int)(g.flybywire_airspeed_max -
g.flybywire_airspeed_min) *
g.channel_throttle.servo_out) +
((int)g.flybywire_airspeed_min * 100);
// Intermediate calculation - airspeed_error is just desired airspeed at this point
airspeed_energy_error = (long)(((long)airspeed_error *
(long)airspeed_error) -
airspeed_energy_error = (long)(((long)airspeed_fbwB *
(long)airspeed_fbwB) -
((long)airspeed * (long)airspeed))/20000;
//Changed 0.00005f * to / 20000 to avoid floating point calculation
airspeed_error = (airspeed_error - airspeed);
}

View File

@ -302,6 +302,27 @@ static void set_servos(void)
#else
// convert 0 to 100% into PWM
g.channel_throttle.servo_out = constrain(g.channel_throttle.servo_out, g.throttle_min.get(), g.throttle_max.get());
// We want to supress the throttle if we think we are on the ground and in an autopilot controlled throttle mode.
/* Disable throttle if following conditions are met:
1 - We are in Circle mode (which we use for short term failsafe), or in FBW-B or higher
AND
2 - Our reported altitude is within 10 meters of the home altitude.
3 - Our reported speed is under 5 meters per second.
4 - We are not performing a takeoff in Auto mode
OR
5 - Home location is not set
*/
if (
(control_mode == CIRCLE || control_mode >= FLY_BY_WIRE_B) &&
(abs(home.alt - current_loc.alt) < 1000) &&
((g.airspeed_enabled ? airspeed : g_gps->ground_speed) < 500 ) &&
!(control_mode==AUTO && takeoff_complete == false)
) {
g.channel_throttle.servo_out = 0;
g.channel_throttle.calc_pwm();
}
#endif
g.channel_throttle.calc_pwm();
@ -318,7 +339,9 @@ static void set_servos(void)
if(control_mode < FLY_BY_WIRE_B) {
G_RC_AUX(k_flap_auto)->radio_out = g_rc_function[RC_Channel_aux::k_flap_auto]->radio_in;
} else if (control_mode >= FLY_BY_WIRE_B) {
if (g.airspeed_enabled == true) {
if (control_mode == FLY_BY_WIRE_B) {
flapSpeedSource = airspeed_fbwB/100;
} else if (g.airspeed_enabled == true) {
flapSpeedSource = g.airspeed_cruise/100;
} else {
flapSpeedSource = g.throttle_cruise;

View File

@ -22,12 +22,18 @@ project(ArduPlane C CXX)
find_package(Arduino 22 REQUIRED)
if (NOT DEFINED BOARD)
message(STATUS "board not defined, assuming mega, use cmake -DBOARD=mega2560 , etc. to specify")
set(BOARD "mega")
endif()
message(STATUS "Board configured as: ${BOARD}")
add_subdirectory(../libraries "${CMAKE_CURRENT_BINARY_DIR}/libs")
#add_subdirectory(${CMAKE_SOURCE_DIR}/ArduCopter)
#add_subdirectory(testtool)
PRINT_BOARD_SETTINGS(mega2560)
PRINT_BOARD_SETTINGS(${BOARD})
@ -42,7 +48,7 @@ PRINT_BOARD_SETTINGS(mega2560)
#====================================================================#
set(FIRMWARE_NAME ArduPlane)
set(${FIRMWARE_NAME}_BOARD mega2560) # Arduino Target board
set(${FIRMWARE_NAME}_BOARD ${BOARD}) # Arduino Target board
set(${FIRMWARE_NAME}_SKETCHES
ArduPlane.pde
@ -62,7 +68,7 @@ set(${FIRMWARE_NAME}_SKETCHES
#GCS_Standard.pde
#GCS_Xplane.pde
#heli.pde
HIL_Xplane.pde
#HIL_Xplane.pde
#leds.pde
Log.pde
#motors_hexa.pde
@ -92,12 +98,12 @@ set(${FIRMWARE_NAME}_SRCS
set(${FIRMWARE_NAME}_HDRS
APM_Config.h
APM_Config_mavlink_hil.h
APM_Config_xplane.h
#APM_Config_xplane.h
config.h
defines.h
GCS.h
HIL.h
Mavlink_Common.h
#HIL.h
#Mavlink_Common.h
Parameters.h
) # Firmware sources
@ -126,8 +132,6 @@ set(${FIRMWARE_NAME}_LIBS
c
m
)
SET_TARGET_PROPERTIES(AP_Math PROPERTIES LINKER_LANGUAGE CXX)
#${CONSOLE_PORT}
set(${FIRMWARE_NAME}_PORT COM2) # Serial upload port

View File

@ -1,10 +1 @@
#
# Trivial makefile for building APM
#
#
# Select 'mega' for the original APM, or 'mega2560' for the V2 APM.
#
BOARD = mega
include ../libraries/AP_Common/Arduino.mk

View File

@ -222,6 +222,7 @@ static void do_takeoff()
next_WP.lat = home.lat + 1000; // so we don't have bad calcs
next_WP.lng = home.lng + 1000; // so we don't have bad calcs
takeoff_complete = false; // set flag to use gps ground course during TO. IMU will be doing yaw drift correction
// Flag also used to override "on the ground" throttle disable
}
static void do_nav_wp()

View File

@ -17,10 +17,15 @@ static void init_rc_in()
g.channel_throttle.set_range(0, 100);
// set rc dead zones
g.channel_roll.dead_zone = 60;
g.channel_pitch.dead_zone = 60;
g.channel_rudder.dead_zone = 60;
g.channel_throttle.dead_zone = 6;
g.channel_roll.set_dead_zone(60);
g.channel_pitch.set_dead_zone(60);
g.channel_rudder.set_dead_zone(60);
g.channel_throttle.set_dead_zone(6);
//g.channel_roll.dead_zone = 60;
//g.channel_pitch.dead_zone = 60;
//g.channel_rudder.dead_zone = 60;
//g.channel_throttle.dead_zone = 6;
//set auxiliary ranges
update_aux_servo_function(&g.rc_5, &g.rc_6, &g.rc_7, &g.rc_8);
@ -112,7 +117,7 @@ static void control_failsafe(uint16_t pwm)
} else {
ch3_failsafe = false;
}
//Check for failsafe and debounce funky reads
} else if (g.throttle_fs_enabled) {
if (pwm < (unsigned)g.throttle_fs_value){
@ -155,7 +160,7 @@ static void trim_control_surfaces()
g.channel_pitch.radio_trim = g.channel_pitch.radio_in;
g.channel_rudder.radio_trim = g.channel_rudder.radio_in;
G_RC_AUX(k_aileron)->radio_trim = g_rc_function[RC_Channel_aux::k_aileron]->radio_in; // Second aileron channel
}else{
elevon1_trim = ch1_temp;
elevon2_trim = ch2_temp;

23
ArduRover/ArduRover.cpp Normal file
View File

@ -0,0 +1,23 @@
// Libraries
#include <FastSerial.h>
#include <AP_Common.h>
#include <APM_RC.h>
#include <AP_RangeFinder.h>
#include <GCS_MAVLink.h>
#include <AP_ADC.h>
#include <AP_DCM.h>
#include <AP_Compass.h>
#include <Wire.h>
#include <AP_GPS.h>
#include <AP_IMU.h>
#include <APM_BMP085.h>
#include <ModeFilter.h>
#include <APO.h>
// Vehicle Configuration
#include "CarStampede.h"
// ArduPilotOne Default Setup
#include "APO_DefaultSetup.h"
#include <WProgram.h>; int main(void) {init();setup();for(;;) loop(); return 0; }

21
ArduRover/ArduRover.pde Normal file
View File

@ -0,0 +1,21 @@
// Libraries
#include <FastSerial.h>
#include <AP_Common.h>
#include <APM_RC.h>
#include <AP_RangeFinder.h>
#include <GCS_MAVLink.h>
#include <AP_ADC.h>
#include <AP_DCM.h>
#include <AP_Compass.h>
#include <Wire.h>
#include <AP_GPS.h>
#include <AP_IMU.h>
#include <APM_BMP085.h>
#include <ModeFilter.h>
#include <APO.h>
// Vehicle Configuration
#include "CarStampede.h"
// ArduPilotOne Default Setup
#include "APO_DefaultSetup.h"

69
ArduRover/CarStampede.h Normal file
View File

@ -0,0 +1,69 @@
/*
* CarStampede.h
*
* Created on: May 1, 2011
* Author: jgoppert
*
*/
#ifndef CARSTAMPEDE_H_
#define CARSTAMPEDE_H_
// vehicle options
static const apo::vehicle_t vehicle = apo::VEHICLE_CAR;
static const apo::halMode_t halMode = apo::MODE_LIVE;
static const apo::board_t board = apo::BOARD_ARDUPILOTMEGA_2560;
static const uint8_t heartBeatTimeout = 3;
// algorithm selection
#define CONTROLLER_CLASS ControllerCar
#define GUIDE_CLASS MavlinkGuide
#define NAVIGATOR_CLASS DcmNavigator
#define COMMLINK_CLASS MavlinkComm
// hardware selection
#define ADC_CLASS AP_ADC_ADS7844
#define COMPASS_CLASS AP_Compass_HMC5843
#define BARO_CLASS APM_BMP085_Class
#define RANGE_FINDER_CLASS AP_RangeFinder_MaxsonarXL
#define DEBUG_BAUD 57600
#define TELEM_BAUD 57600
#define GPS_BAUD 38400
#define HIL_BAUD 57600
// optional sensors
static bool gpsEnabled = false;
static bool baroEnabled = true;
static bool compassEnabled = true;
static bool rangeFinderFrontEnabled = true;
static bool rangeFinderBackEnabled = true;
static bool rangeFinderLeftEnabled = true;
static bool rangeFinderRightEnabled = true;
static bool rangeFinderUpEnabled = true;
static bool rangeFinderDownEnabled = true;
// loop rates
static const float loop0Rate = 150;
static const float loop1Rate = 100;
static const float loop2Rate = 10;
static const float loop3Rate = 1;
static const float loop4Rate = 0.1;
// gains
static const float steeringP = 1.0;
static const float steeringI = 0.0;
static const float steeringD = 0.0;
static const float steeringIMax = 0.0;
static const float steeringYMax = 3.0;
static const float throttleP = 0.0;
static const float throttleI = 0.0;
static const float throttleD = 0.0;
static const float throttleIMax = 0.0;
static const float throttleYMax = 0.0;
static const float throttleDFCut = 3.0;
#include "ControllerCar.h"
#endif /* CARSTAMPEDE_H_ */

125
ArduRover/ControllerCar.h Normal file
View File

@ -0,0 +1,125 @@
/*
* ControllerCar.h
*
* Created on: Jun 30, 2011
* Author: jgoppert
*/
#ifndef CONTROLLERCAR_H_
#define CONTROLLERCAR_H_
#include "../APO/AP_Controller.h"
namespace apo {
class ControllerCar: public AP_Controller {
private:
AP_Var_group _group;
AP_Uint8 _mode;
enum {
k_chMode = k_radioChannelsStart, k_chStr, k_chThr
};
enum {
k_pidStr = k_controllersStart, k_pidThr
};
enum {
CH_MODE = 0, CH_STR, CH_THR
};
BlockPIDDfb pidStr;
BlockPID pidThr;
public:
ControllerCar(AP_Navigator * nav, AP_Guide * guide,
AP_HardwareAbstractionLayer * hal) :
AP_Controller(nav, guide, hal),
_group(k_cntrl, PSTR("CNTRL_")),
_mode(&_group, 1, MAV_MODE_UNINIT, PSTR("MODE")),
pidStr(new AP_Var_group(k_pidStr, PSTR("STR_")), 1, steeringP,
steeringI, steeringD, steeringIMax, steeringYMax),
pidThr(new AP_Var_group(k_pidThr, PSTR("THR_")), 1, throttleP,
throttleI, throttleD, throttleIMax, throttleYMax,
throttleDFCut) {
_hal->debug->println_P(PSTR("initializing car controller"));
_hal->rc.push_back(
new AP_RcChannel(k_chMode, PSTR("MODE_"), APM_RC, 7, 1100,
1500, 1900));
_hal->rc.push_back(
new AP_RcChannel(k_chStr, PSTR("STR_"), APM_RC, 0, 1100, 1540,
1900));
_hal->rc.push_back(
new AP_RcChannel(k_chThr, PSTR("THR_"), APM_RC, 1, 1100, 1500,
1900));
}
virtual MAV_MODE getMode() {
return (MAV_MODE) _mode.get();
}
virtual void update(const float & dt) {
// check for heartbeat
if (_hal->heartBeatLost()) {
_mode = MAV_MODE_FAILSAFE;
setAllRadioChannelsToNeutral();
_hal->setState(MAV_STATE_EMERGENCY);
_hal->debug->printf_P(PSTR("comm lost, send heartbeat from gcs\n"));
return;
// if throttle less than 5% cut motor power
} else if (_hal->rc[CH_THR]->getRadioPosition() < 0.05) {
_mode = MAV_MODE_LOCKED;
setAllRadioChannelsToNeutral();
_hal->setState(MAV_STATE_STANDBY);
return;
// if in live mode then set state to active
} else if (_hal->getMode() == MODE_LIVE) {
_hal->setState(MAV_STATE_ACTIVE);
// if in hardware in the loop (control) mode, set to hilsim
} else if (_hal->getMode() == MODE_HIL_CNTL) {
_hal->setState(MAV_STATE_HILSIM);
}
// read switch to set mode
if (_hal->rc[CH_MODE]->getRadioPosition() > 0) {
_mode = MAV_MODE_MANUAL;
} else {
_mode = MAV_MODE_AUTO;
}
// manual mode
switch (_mode) {
case MAV_MODE_MANUAL: {
setAllRadioChannelsManually();
//_hal->debug->println("manual");
break;
}
case MAV_MODE_AUTO: {
float headingError = _guide->getHeadingCommand()
- _nav->getYaw();
if (headingError > 180 * deg2Rad)
headingError -= 360 * deg2Rad;
if (headingError < -180 * deg2Rad)
headingError += 360 * deg2Rad;
_hal->rc[CH_STR]->setPosition(
pidStr.update(headingError, _nav->getYawRate(), dt));
_hal->rc[CH_THR]->setPosition(
pidThr.update(
_guide->getGroundSpeedCommand()
- _nav->getGroundSpeed(), dt));
//_hal->debug->println("automode");
break;
}
default: {
setAllRadioChannelsToNeutral();
_mode = MAV_MODE_FAILSAFE;
_hal->setState(MAV_STATE_EMERGENCY);
_hal->debug->printf_P(PSTR("unknown controller mode\n"));
break;
}
}
}
};
} // namespace apo
#endif /* CONTROLLERCAR_H_ */

133
ArduRover/ControllerTank.h Normal file
View File

@ -0,0 +1,133 @@
/*
* ControllerTank.h
*
* Created on: Jun 30, 2011
* Author: jgoppert
*/
#ifndef CONTROLLERTANK_H_
#define CONTROLLERTANK_H_
#include "../APO/AP_Controller.h"
namespace apo {
class ControllerTank: public AP_Controller {
private:
AP_Var_group _group;
AP_Uint8 _mode;
enum {
k_chMode = k_radioChannelsStart, k_chLeft, k_chRight, k_chStr, k_chThr
};
enum {
k_pidStr = k_controllersStart, k_pidThr
};
enum {
CH_MODE = 0, CH_LEFT, CH_RIGHT, CH_STR, CH_THR
};
BlockPIDDfb pidStr;
BlockPID pidThr;
public:
ControllerTank(AP_Navigator * nav, AP_Guide * guide,
AP_HardwareAbstractionLayer * hal) :
AP_Controller(nav, guide, hal),
_group(k_cntrl, PSTR("CNTRL_")),
_mode(&_group, 1, MAV_MODE_UNINIT, PSTR("MODE")),
pidStr(new AP_Var_group(k_pidStr, PSTR("STR_")), 1, steeringP,
steeringI, steeringD, steeringIMax, steeringYMax),
pidThr(new AP_Var_group(k_pidThr, PSTR("THR_")), 1, throttleP,
throttleI, throttleD, throttleIMax, throttleYMax,
throttleDFCut) {
_hal->debug->println_P(PSTR("initializing tank controller"));
_hal->rc.push_back(
new AP_RcChannel(k_chMode, PSTR("MODE_"), APM_RC, 5, 1100,
1500, 1900, RC_MODE_IN));
_hal->rc.push_back(
new AP_RcChannel(k_chLeft, PSTR("LEFT_"), APM_RC, 0, 1100, 1500,
1900, RC_MODE_OUT));
_hal->rc.push_back(
new AP_RcChannel(k_chRight, PSTR("RIGHT_"), APM_RC, 1, 1100, 1500,
1900, RC_MODE_OUT));
_hal->rc.push_back(
new AP_RcChannel(k_chStr, PSTR("STR_"), APM_RC, 0, 1100, 1500,
1900, RC_MODE_IN));
_hal->rc.push_back(
new AP_RcChannel(k_chThr, PSTR("THR_"), APM_RC, 1, 1100, 1500,
1900, RC_MODE_IN));
}
virtual MAV_MODE getMode() {
return (MAV_MODE) _mode.get();
}
void mix(float headingOutput, float throttleOutput) {
_hal->rc[CH_LEFT]->setPosition(throttleOutput + headingOutput);
_hal->rc[CH_RIGHT]->setPosition(throttleOutput - headingOutput);
}
virtual void update(const float & dt) {
// check for heartbeat
if (_hal->heartBeatLost()) {
_mode = MAV_MODE_FAILSAFE;
setAllRadioChannelsToNeutral();
_hal->setState(MAV_STATE_EMERGENCY);
_hal->debug->printf_P(PSTR("comm lost, send heartbeat from gcs\n"));
return;
// if throttle less than 5% cut motor power
} else if (_hal->rc[CH_THR]->getRadioPosition() < 0.05) {
_mode = MAV_MODE_LOCKED;
setAllRadioChannelsToNeutral();
_hal->setState(MAV_STATE_STANDBY);
return;
// if in live mode then set state to active
} else if (_hal->getMode() == MODE_LIVE) {
_hal->setState(MAV_STATE_ACTIVE);
// if in hardware in the loop (control) mode, set to hilsim
} else if (_hal->getMode() == MODE_HIL_CNTL) {
_hal->setState(MAV_STATE_HILSIM);
}
// read switch to set mode
if (_hal->rc[CH_MODE]->getRadioPosition() > 0) {
_mode = MAV_MODE_MANUAL;
} else {
_mode = MAV_MODE_AUTO;
}
// manual mode
switch (_mode) {
case MAV_MODE_MANUAL: {
setAllRadioChannelsManually();
mix(_hal->rc[CH_STR]->getPosition(),
_hal->rc[CH_THR]->getPosition());
break;
}
case MAV_MODE_AUTO: {
float headingError = _guide->getHeadingCommand()
- _nav->getYaw();
if (headingError > 180 * deg2Rad)
headingError -= 360 * deg2Rad;
if (headingError < -180 * deg2Rad)
headingError += 360 * deg2Rad;
mix(pidStr.update(headingError, _nav->getYawRate(), dt),
pidThr.update(_guide->getGroundSpeedCommand()
- _nav->getGroundSpeed(), dt));
//_hal->debug->println("automode");
break;
}
default: {
setAllRadioChannelsToNeutral();
_mode = MAV_MODE_FAILSAFE;
_hal->setState(MAV_STATE_EMERGENCY);
_hal->debug->printf_P(PSTR("unknown controller mode\n"));
break;
}
}
}
};
} // namespace apo
#endif /* CONTROLLERTANK_H_ */

1
ArduRover/Makefile Normal file
View File

@ -0,0 +1 @@
include ../libraries/AP_Common/Arduino.mk

68
ArduRover/TankGeneric.h Normal file
View File

@ -0,0 +1,68 @@
/*
* TankGeneric.h
*
* Created on: Sep 26, 2011
* Author: jgoppert
*/
#ifndef TANKGENERIC_H_
#define TANKGENERIC_H_
// vehicle options
static const apo::vehicle_t vehicle = apo::VEHICLE_TANK;
static const apo::halMode_t halMode = apo::MODE_LIVE;
static const apo::board_t board = apo::BOARD_ARDUPILOTMEGA_2560;
static const uint8_t heartBeatTimeout = 3;
// algorithm selection
#define CONTROLLER_CLASS ControllerTank
#define GUIDE_CLASS MavlinkGuide
#define NAVIGATOR_CLASS DcmNavigator
#define COMMLINK_CLASS MavlinkComm
// hardware selection
#define ADC_CLASS AP_ADC_ADS7844
#define COMPASS_CLASS AP_Compass_HMC5843
#define BARO_CLASS APM_BMP085_Class
#define RANGE_FINDER_CLASS AP_RangeFinder_MaxsonarXL
#define DEBUG_BAUD 57600
#define TELEM_BAUD 57600
#define GPS_BAUD 38400
#define HIL_BAUD 57600
// optional sensors
static bool gpsEnabled = false;
static bool baroEnabled = true;
static bool compassEnabled = true;
static bool rangeFinderFrontEnabled = true;
static bool rangeFinderBackEnabled = true;
static bool rangeFinderLeftEnabled = true;
static bool rangeFinderRightEnabled = true;
static bool rangeFinderUpEnabled = true;
static bool rangeFinderDownEnabled = true;
// loop rates
static const float loop0Rate = 150;
static const float loop1Rate = 100;
static const float loop2Rate = 10;
static const float loop3Rate = 1;
static const float loop4Rate = 0.1;
// gains
const float steeringP = 1.0;
const float steeringI = 0.0;
const float steeringD = 0.0;
const float steeringIMax = 0.0;
const float steeringYMax = 3.0;
const float throttleP = 0.0;
const float throttleI = 0.0;
const float throttleD = 0.0;
const float throttleIMax = 0.0;
const float throttleYMax = 0.0;
const float throttleDFCut = 3.0;
#include "ControllerTank.h"
#endif /* TANKGENERIC_H_ */

102
CMakeLists.txt Normal file
View File

@ -0,0 +1,102 @@
cmake_minimum_required(VERSION 2.8)
set(CMAKE_MODULE_PATH ${CMAKE_SOURCE_DIR}/cmake/modules)
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Arduino.cmake)
# modify flags from default toolchain flags
set(APM_OPT_FLAGS "-Wformat -Wall -Wshadow -Wpointer-arith -Wcast-align -Wwrite-strings -Wformat=2")
set(ARDUINO_C_FLAGS "${APM_OPT_FLAGS} -mcall-prologues -ffunction-sections -fdata-sections")
set(ARDUINO_CXX_FLAGS "${APM_OPT_FLAGS} -mcall-prologues -ffunction-sections -fdata-sections -fno-exceptions -Wno-reorder")
set(ARDUINO_LINKER_FLAGS "-lc -lm ${APM_OPT_FLAGS} -Wl,--gc-sections")
project(ArduPilotMega C CXX)
# set default cmake build type to RelWithDebInfo (None Debug Release RelWithDebInfo MinSizeRel)
if( NOT DEFINED CMAKE_BUILD_TYPE )
set( CMAKE_BUILD_TYPE "RelWithDebInfo" )
endif()
# set these for release
set(APPLICATION_VERSION_MAJOR "1")
set(APPLICATION_VERSION_MINOR "2")
set(APPLICATION_VERSION_PATCH "0")
# dependencies
find_package(Arduino 22 REQUIRED)
# cmake settigns
set(APPLICATION_NAME ${PROJECT_NAME})
set(APPLICATION_VERSION "${APPLICATION_VERSION_MAJOR}.${APPLICATION_VERSION_MINOR}.${APPLICATION_VERSION_PATCH}")
# macros
include(MacroEnsureOutOfSourceBuild)
# disallow in-source build
macro_ensure_out_of_source_build("${PROJECT_NAME} requires an out of source build.
Please create a separate build directory and run 'cmake /path/to/${PROJECT_NAME} [options]' there.")
# options
if (NOT DEFINED BOARD)
message(STATUS "please define the board type (for example: cmake -DBOARD=mega, assuming mega")
set(BOARD "mega")
endif()
# cpack settings
set(CPACK_PACKAGE_DESCRIPTION_SUMMARY "A universal autopilot system for the ArduPilotMega board.")
set(CPACK_PACKAGE_VENDOR "DIYDRONES")
set(CPACK_DEBIAN_PACKAGE_MAINTAINER "james.goppert@gmail.com")
set(CPACK_PACKAGE_CONTACT "james.goppert@gmail.com")
set(CPACK_PACKAGE_DESCRIPTION_FILE "${CMAKE_SOURCE_DIR}/README.txt")
set(CPACK_RESOURCE_FILE_LICENSE "${CMAKE_SOURCE_DIR}/COPYING.txt")
set(CPACK_RESOURCE_FILE_README "${CMAKE_SOURCE_DIR}/README.txt")
set(CPACK_PACKAGE_VERSION_MAJOR "${APPLICATION_VERSION_MAJOR}")
set(CPACK_PACKAGE_VERSION_MINOR "${APPLICATION_VERSION_MINOR}")
set(CPACK_PACKAGE_VERSION_PATCH "${APPLICATION_VERSION_PATCH}")
set(CPACK_PACKAGE_INSTALL_DIRECTORY "CMake ${CMake_VERSION_MAJOR}.${CMake_VERSION_MINOR}")
set(CPACK_SET_DESTDIR TRUE)
set(CPACK_SOURCE_IGNORE_FILES ${CPACK_SOURCE_IGNORE_FILES}
/.git/;/build/;~$;.*\\\\.bin$;.*\\\\.swp$)
set(CPACK_INSTALL_PREFIX "${CMAKE_INSTALL_PREFIX}")
set(CPACK_SOURCE_GENERATOR "ZIP")
set(CPACK_GENERATOR "ZIP")
set(CPACK_PACKAGE_NAME "${APPLICATION_NAME}_${BOARD}")
include(CPack)
find_package(Arduino 22 REQUIRED)
# determine board being used
if (NOT DEFINED BOARD)
message(STATUS "board not defined, assuming mega, use cmake -DBOARD=mega2560 , etc. to specify")
set(BOARD "mega")
endif()
message(STATUS "Board configured as: ${BOARD}")
set (CMAKE_CXX_SOURCE_FILE_EXTENSIONS pde)
# standard apm project setup
macro(apm_project PROJECT_NAME BOARD SRCS)
message(STATUS "creating apo project ${PROJECT_NAME}")
set(${PROJECT_NAME}_BOARD ${BOARD})
set(${PROJECT_NAME}_AFLAGS "-assembler-with-cpp")
file(GLOB HDRS ${PROJECT_NAME}/*.h)
file(GLOB PDE ${PROJECT_NAME}/*.pde)
set(${PROJECT_NAME}_SRCS ${SRCS} ${HDRS} ${PDE})
set(${PROJECT_NAME}_LIBS c)
message(STATUS "sources: ${SRCS}")
message(STATUS "headers: ${HDRS}")
message(STATUS "pde: ${PDE}")
generate_arduino_firmware(${PROJECT_NAME})
set_target_properties(${PROJECT_NAME} PROPERTIES LINKER_LANGUAGE CXX)
install(FILES
${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}.hex
DESTINATION bin
)
endmacro()
# projects
apm_project(apo ${BOARD} apo/apo.cpp)
apm_project(ArduRover ${BOARD} ArduRover/ArduRover.cpp)
apm_project(ArduBoat ${BOARD} ArduBoat/ArduBoat.cpp)
#apm_project(ArduPlane ${BOARD} ArduPlane/ArduPlane.cpp)
#apm_project(ArduCopter ${BOARD} ArduCopter/ArduCopter.cpp)

674
COPYING.txt Normal file
View File

@ -0,0 +1,674 @@
GNU GENERAL PUBLIC LICENSE
Version 3, 29 June 2007
Copyright (C) 2007 Free Software Foundation, Inc. <http://fsf.org/>
Everyone is permitted to copy and distribute verbatim copies
of this license document, but changing it is not allowed.
Preamble
The GNU General Public License is a free, copyleft license for
software and other kinds of works.
The licenses for most software and other practical works are designed
to take away your freedom to share and change the works. By contrast,
the GNU General Public License is intended to guarantee your freedom to
share and change all versions of a program--to make sure it remains free
software for all its users. We, the Free Software Foundation, use the
GNU General Public License for most of our software; it applies also to
any other work released this way by its authors. You can apply it to
your programs, too.
When we speak of free software, we are referring to freedom, not
price. Our General Public Licenses are designed to make sure that you
have the freedom to distribute copies of free software (and charge for
them if you wish), that you receive source code or can get it if you
want it, that you can change the software or use pieces of it in new
free programs, and that you know you can do these things.
To protect your rights, we need to prevent others from denying you
these rights or asking you to surrender the rights. Therefore, you have
certain responsibilities if you distribute copies of the software, or if
you modify it: responsibilities to respect the freedom of others.
For example, if you distribute copies of such a program, whether
gratis or for a fee, you must pass on to the recipients the same
freedoms that you received. You must make sure that they, too, receive
or can get the source code. And you must show them these terms so they
know their rights.
Developers that use the GNU GPL protect your rights with two steps:
(1) assert copyright on the software, and (2) offer you this License
giving you legal permission to copy, distribute and/or modify it.
For the developers' and authors' protection, the GPL clearly explains
that there is no warranty for this free software. For both users' and
authors' sake, the GPL requires that modified versions be marked as
changed, so that their problems will not be attributed erroneously to
authors of previous versions.
Some devices are designed to deny users access to install or run
modified versions of the software inside them, although the manufacturer
can do so. This is fundamentally incompatible with the aim of
protecting users' freedom to change the software. The systematic
pattern of such abuse occurs in the area of products for individuals to
use, which is precisely where it is most unacceptable. Therefore, we
have designed this version of the GPL to prohibit the practice for those
products. If such problems arise substantially in other domains, we
stand ready to extend this provision to those domains in future versions
of the GPL, as needed to protect the freedom of users.
Finally, every program is threatened constantly by software patents.
States should not allow patents to restrict development and use of
software on general-purpose computers, but in those that do, we wish to
avoid the special danger that patents applied to a free program could
make it effectively proprietary. To prevent this, the GPL assures that
patents cannot be used to render the program non-free.
The precise terms and conditions for copying, distribution and
modification follow.
TERMS AND CONDITIONS
0. Definitions.
"This License" refers to version 3 of the GNU General Public License.
"Copyright" also means copyright-like laws that apply to other kinds of
works, such as semiconductor masks.
"The Program" refers to any copyrightable work licensed under this
License. Each licensee is addressed as "you". "Licensees" and
"recipients" may be individuals or organizations.
To "modify" a work means to copy from or adapt all or part of the work
in a fashion requiring copyright permission, other than the making of an
exact copy. The resulting work is called a "modified version" of the
earlier work or a work "based on" the earlier work.
A "covered work" means either the unmodified Program or a work based
on the Program.
To "propagate" a work means to do anything with it that, without
permission, would make you directly or secondarily liable for
infringement under applicable copyright law, except executing it on a
computer or modifying a private copy. Propagation includes copying,
distribution (with or without modification), making available to the
public, and in some countries other activities as well.
To "convey" a work means any kind of propagation that enables other
parties to make or receive copies. Mere interaction with a user through
a computer network, with no transfer of a copy, is not conveying.
An interactive user interface displays "Appropriate Legal Notices"
to the extent that it includes a convenient and prominently visible
feature that (1) displays an appropriate copyright notice, and (2)
tells the user that there is no warranty for the work (except to the
extent that warranties are provided), that licensees may convey the
work under this License, and how to view a copy of this License. If
the interface presents a list of user commands or options, such as a
menu, a prominent item in the list meets this criterion.
1. Source Code.
The "source code" for a work means the preferred form of the work
for making modifications to it. "Object code" means any non-source
form of a work.
A "Standard Interface" means an interface that either is an official
standard defined by a recognized standards body, or, in the case of
interfaces specified for a particular programming language, one that
is widely used among developers working in that language.
The "System Libraries" of an executable work include anything, other
than the work as a whole, that (a) is included in the normal form of
packaging a Major Component, but which is not part of that Major
Component, and (b) serves only to enable use of the work with that
Major Component, or to implement a Standard Interface for which an
implementation is available to the public in source code form. A
"Major Component", in this context, means a major essential component
(kernel, window system, and so on) of the specific operating system
(if any) on which the executable work runs, or a compiler used to
produce the work, or an object code interpreter used to run it.
The "Corresponding Source" for a work in object code form means all
the source code needed to generate, install, and (for an executable
work) run the object code and to modify the work, including scripts to
control those activities. However, it does not include the work's
System Libraries, or general-purpose tools or generally available free
programs which are used unmodified in performing those activities but
which are not part of the work. For example, Corresponding Source
includes interface definition files associated with source files for
the work, and the source code for shared libraries and dynamically
linked subprograms that the work is specifically designed to require,
such as by intimate data communication or control flow between those
subprograms and other parts of the work.
The Corresponding Source need not include anything that users
can regenerate automatically from other parts of the Corresponding
Source.
The Corresponding Source for a work in source code form is that
same work.
2. Basic Permissions.
All rights granted under this License are granted for the term of
copyright on the Program, and are irrevocable provided the stated
conditions are met. This License explicitly affirms your unlimited
permission to run the unmodified Program. The output from running a
covered work is covered by this License only if the output, given its
content, constitutes a covered work. This License acknowledges your
rights of fair use or other equivalent, as provided by copyright law.
You may make, run and propagate covered works that you do not
convey, without conditions so long as your license otherwise remains
in force. You may convey covered works to others for the sole purpose
of having them make modifications exclusively for you, or provide you
with facilities for running those works, provided that you comply with
the terms of this License in conveying all material for which you do
not control copyright. Those thus making or running the covered works
for you must do so exclusively on your behalf, under your direction
and control, on terms that prohibit them from making any copies of
your copyrighted material outside their relationship with you.
Conveying under any other circumstances is permitted solely under
the conditions stated below. Sublicensing is not allowed; section 10
makes it unnecessary.
3. Protecting Users' Legal Rights From Anti-Circumvention Law.
No covered work shall be deemed part of an effective technological
measure under any applicable law fulfilling obligations under article
11 of the WIPO copyright treaty adopted on 20 December 1996, or
similar laws prohibiting or restricting circumvention of such
measures.
When you convey a covered work, you waive any legal power to forbid
circumvention of technological measures to the extent such circumvention
is effected by exercising rights under this License with respect to
the covered work, and you disclaim any intention to limit operation or
modification of the work as a means of enforcing, against the work's
users, your or third parties' legal rights to forbid circumvention of
technological measures.
4. Conveying Verbatim Copies.
You may convey verbatim copies of the Program's source code as you
receive it, in any medium, provided that you conspicuously and
appropriately publish on each copy an appropriate copyright notice;
keep intact all notices stating that this License and any
non-permissive terms added in accord with section 7 apply to the code;
keep intact all notices of the absence of any warranty; and give all
recipients a copy of this License along with the Program.
You may charge any price or no price for each copy that you convey,
and you may offer support or warranty protection for a fee.
5. Conveying Modified Source Versions.
You may convey a work based on the Program, or the modifications to
produce it from the Program, in the form of source code under the
terms of section 4, provided that you also meet all of these conditions:
a) The work must carry prominent notices stating that you modified
it, and giving a relevant date.
b) The work must carry prominent notices stating that it is
released under this License and any conditions added under section
7. This requirement modifies the requirement in section 4 to
"keep intact all notices".
c) You must license the entire work, as a whole, under this
License to anyone who comes into possession of a copy. This
License will therefore apply, along with any applicable section 7
additional terms, to the whole of the work, and all its parts,
regardless of how they are packaged. This License gives no
permission to license the work in any other way, but it does not
invalidate such permission if you have separately received it.
d) If the work has interactive user interfaces, each must display
Appropriate Legal Notices; however, if the Program has interactive
interfaces that do not display Appropriate Legal Notices, your
work need not make them do so.
A compilation of a covered work with other separate and independent
works, which are not by their nature extensions of the covered work,
and which are not combined with it such as to form a larger program,
in or on a volume of a storage or distribution medium, is called an
"aggregate" if the compilation and its resulting copyright are not
used to limit the access or legal rights of the compilation's users
beyond what the individual works permit. Inclusion of a covered work
in an aggregate does not cause this License to apply to the other
parts of the aggregate.
6. Conveying Non-Source Forms.
You may convey a covered work in object code form under the terms
of sections 4 and 5, provided that you also convey the
machine-readable Corresponding Source under the terms of this License,
in one of these ways:
a) Convey the object code in, or embodied in, a physical product
(including a physical distribution medium), accompanied by the
Corresponding Source fixed on a durable physical medium
customarily used for software interchange.
b) Convey the object code in, or embodied in, a physical product
(including a physical distribution medium), accompanied by a
written offer, valid for at least three years and valid for as
long as you offer spare parts or customer support for that product
model, to give anyone who possesses the object code either (1) a
copy of the Corresponding Source for all the software in the
product that is covered by this License, on a durable physical
medium customarily used for software interchange, for a price no
more than your reasonable cost of physically performing this
conveying of source, or (2) access to copy the
Corresponding Source from a network server at no charge.
c) Convey individual copies of the object code with a copy of the
written offer to provide the Corresponding Source. This
alternative is allowed only occasionally and noncommercially, and
only if you received the object code with such an offer, in accord
with subsection 6b.
d) Convey the object code by offering access from a designated
place (gratis or for a charge), and offer equivalent access to the
Corresponding Source in the same way through the same place at no
further charge. You need not require recipients to copy the
Corresponding Source along with the object code. If the place to
copy the object code is a network server, the Corresponding Source
may be on a different server (operated by you or a third party)
that supports equivalent copying facilities, provided you maintain
clear directions next to the object code saying where to find the
Corresponding Source. Regardless of what server hosts the
Corresponding Source, you remain obligated to ensure that it is
available for as long as needed to satisfy these requirements.
e) Convey the object code using peer-to-peer transmission, provided
you inform other peers where the object code and Corresponding
Source of the work are being offered to the general public at no
charge under subsection 6d.
A separable portion of the object code, whose source code is excluded
from the Corresponding Source as a System Library, need not be
included in conveying the object code work.
A "User Product" is either (1) a "consumer product", which means any
tangible personal property which is normally used for personal, family,
or household purposes, or (2) anything designed or sold for incorporation
into a dwelling. In determining whether a product is a consumer product,
doubtful cases shall be resolved in favor of coverage. For a particular
product received by a particular user, "normally used" refers to a
typical or common use of that class of product, regardless of the status
of the particular user or of the way in which the particular user
actually uses, or expects or is expected to use, the product. A product
is a consumer product regardless of whether the product has substantial
commercial, industrial or non-consumer uses, unless such uses represent
the only significant mode of use of the product.
"Installation Information" for a User Product means any methods,
procedures, authorization keys, or other information required to install
and execute modified versions of a covered work in that User Product from
a modified version of its Corresponding Source. The information must
suffice to ensure that the continued functioning of the modified object
code is in no case prevented or interfered with solely because
modification has been made.
If you convey an object code work under this section in, or with, or
specifically for use in, a User Product, and the conveying occurs as
part of a transaction in which the right of possession and use of the
User Product is transferred to the recipient in perpetuity or for a
fixed term (regardless of how the transaction is characterized), the
Corresponding Source conveyed under this section must be accompanied
by the Installation Information. But this requirement does not apply
if neither you nor any third party retains the ability to install
modified object code on the User Product (for example, the work has
been installed in ROM).
The requirement to provide Installation Information does not include a
requirement to continue to provide support service, warranty, or updates
for a work that has been modified or installed by the recipient, or for
the User Product in which it has been modified or installed. Access to a
network may be denied when the modification itself materially and
adversely affects the operation of the network or violates the rules and
protocols for communication across the network.
Corresponding Source conveyed, and Installation Information provided,
in accord with this section must be in a format that is publicly
documented (and with an implementation available to the public in
source code form), and must require no special password or key for
unpacking, reading or copying.
7. Additional Terms.
"Additional permissions" are terms that supplement the terms of this
License by making exceptions from one or more of its conditions.
Additional permissions that are applicable to the entire Program shall
be treated as though they were included in this License, to the extent
that they are valid under applicable law. If additional permissions
apply only to part of the Program, that part may be used separately
under those permissions, but the entire Program remains governed by
this License without regard to the additional permissions.
When you convey a copy of a covered work, you may at your option
remove any additional permissions from that copy, or from any part of
it. (Additional permissions may be written to require their own
removal in certain cases when you modify the work.) You may place
additional permissions on material, added by you to a covered work,
for which you have or can give appropriate copyright permission.
Notwithstanding any other provision of this License, for material you
add to a covered work, you may (if authorized by the copyright holders of
that material) supplement the terms of this License with terms:
a) Disclaiming warranty or limiting liability differently from the
terms of sections 15 and 16 of this License; or
b) Requiring preservation of specified reasonable legal notices or
author attributions in that material or in the Appropriate Legal
Notices displayed by works containing it; or
c) Prohibiting misrepresentation of the origin of that material, or
requiring that modified versions of such material be marked in
reasonable ways as different from the original version; or
d) Limiting the use for publicity purposes of names of licensors or
authors of the material; or
e) Declining to grant rights under trademark law for use of some
trade names, trademarks, or service marks; or
f) Requiring indemnification of licensors and authors of that
material by anyone who conveys the material (or modified versions of
it) with contractual assumptions of liability to the recipient, for
any liability that these contractual assumptions directly impose on
those licensors and authors.
All other non-permissive additional terms are considered "further
restrictions" within the meaning of section 10. If the Program as you
received it, or any part of it, contains a notice stating that it is
governed by this License along with a term that is a further
restriction, you may remove that term. If a license document contains
a further restriction but permits relicensing or conveying under this
License, you may add to a covered work material governed by the terms
of that license document, provided that the further restriction does
not survive such relicensing or conveying.
If you add terms to a covered work in accord with this section, you
must place, in the relevant source files, a statement of the
additional terms that apply to those files, or a notice indicating
where to find the applicable terms.
Additional terms, permissive or non-permissive, may be stated in the
form of a separately written license, or stated as exceptions;
the above requirements apply either way.
8. Termination.
You may not propagate or modify a covered work except as expressly
provided under this License. Any attempt otherwise to propagate or
modify it is void, and will automatically terminate your rights under
this License (including any patent licenses granted under the third
paragraph of section 11).
However, if you cease all violation of this License, then your
license from a particular copyright holder is reinstated (a)
provisionally, unless and until the copyright holder explicitly and
finally terminates your license, and (b) permanently, if the copyright
holder fails to notify you of the violation by some reasonable means
prior to 60 days after the cessation.
Moreover, your license from a particular copyright holder is
reinstated permanently if the copyright holder notifies you of the
violation by some reasonable means, this is the first time you have
received notice of violation of this License (for any work) from that
copyright holder, and you cure the violation prior to 30 days after
your receipt of the notice.
Termination of your rights under this section does not terminate the
licenses of parties who have received copies or rights from you under
this License. If your rights have been terminated and not permanently
reinstated, you do not qualify to receive new licenses for the same
material under section 10.
9. Acceptance Not Required for Having Copies.
You are not required to accept this License in order to receive or
run a copy of the Program. Ancillary propagation of a covered work
occurring solely as a consequence of using peer-to-peer transmission
to receive a copy likewise does not require acceptance. However,
nothing other than this License grants you permission to propagate or
modify any covered work. These actions infringe copyright if you do
not accept this License. Therefore, by modifying or propagating a
covered work, you indicate your acceptance of this License to do so.
10. Automatic Licensing of Downstream Recipients.
Each time you convey a covered work, the recipient automatically
receives a license from the original licensors, to run, modify and
propagate that work, subject to this License. You are not responsible
for enforcing compliance by third parties with this License.
An "entity transaction" is a transaction transferring control of an
organization, or substantially all assets of one, or subdividing an
organization, or merging organizations. If propagation of a covered
work results from an entity transaction, each party to that
transaction who receives a copy of the work also receives whatever
licenses to the work the party's predecessor in interest had or could
give under the previous paragraph, plus a right to possession of the
Corresponding Source of the work from the predecessor in interest, if
the predecessor has it or can get it with reasonable efforts.
You may not impose any further restrictions on the exercise of the
rights granted or affirmed under this License. For example, you may
not impose a license fee, royalty, or other charge for exercise of
rights granted under this License, and you may not initiate litigation
(including a cross-claim or counterclaim in a lawsuit) alleging that
any patent claim is infringed by making, using, selling, offering for
sale, or importing the Program or any portion of it.
11. Patents.
A "contributor" is a copyright holder who authorizes use under this
License of the Program or a work on which the Program is based. The
work thus licensed is called the contributor's "contributor version".
A contributor's "essential patent claims" are all patent claims
owned or controlled by the contributor, whether already acquired or
hereafter acquired, that would be infringed by some manner, permitted
by this License, of making, using, or selling its contributor version,
but do not include claims that would be infringed only as a
consequence of further modification of the contributor version. For
purposes of this definition, "control" includes the right to grant
patent sublicenses in a manner consistent with the requirements of
this License.
Each contributor grants you a non-exclusive, worldwide, royalty-free
patent license under the contributor's essential patent claims, to
make, use, sell, offer for sale, import and otherwise run, modify and
propagate the contents of its contributor version.
In the following three paragraphs, a "patent license" is any express
agreement or commitment, however denominated, not to enforce a patent
(such as an express permission to practice a patent or covenant not to
sue for patent infringement). To "grant" such a patent license to a
party means to make such an agreement or commitment not to enforce a
patent against the party.
If you convey a covered work, knowingly relying on a patent license,
and the Corresponding Source of the work is not available for anyone
to copy, free of charge and under the terms of this License, through a
publicly available network server or other readily accessible means,
then you must either (1) cause the Corresponding Source to be so
available, or (2) arrange to deprive yourself of the benefit of the
patent license for this particular work, or (3) arrange, in a manner
consistent with the requirements of this License, to extend the patent
license to downstream recipients. "Knowingly relying" means you have
actual knowledge that, but for the patent license, your conveying the
covered work in a country, or your recipient's use of the covered work
in a country, would infringe one or more identifiable patents in that
country that you have reason to believe are valid.
If, pursuant to or in connection with a single transaction or
arrangement, you convey, or propagate by procuring conveyance of, a
covered work, and grant a patent license to some of the parties
receiving the covered work authorizing them to use, propagate, modify
or convey a specific copy of the covered work, then the patent license
you grant is automatically extended to all recipients of the covered
work and works based on it.
A patent license is "discriminatory" if it does not include within
the scope of its coverage, prohibits the exercise of, or is
conditioned on the non-exercise of one or more of the rights that are
specifically granted under this License. You may not convey a covered
work if you are a party to an arrangement with a third party that is
in the business of distributing software, under which you make payment
to the third party based on the extent of your activity of conveying
the work, and under which the third party grants, to any of the
parties who would receive the covered work from you, a discriminatory
patent license (a) in connection with copies of the covered work
conveyed by you (or copies made from those copies), or (b) primarily
for and in connection with specific products or compilations that
contain the covered work, unless you entered into that arrangement,
or that patent license was granted, prior to 28 March 2007.
Nothing in this License shall be construed as excluding or limiting
any implied license or other defenses to infringement that may
otherwise be available to you under applicable patent law.
12. No Surrender of Others' Freedom.
If conditions are imposed on you (whether by court order, agreement or
otherwise) that contradict the conditions of this License, they do not
excuse you from the conditions of this License. If you cannot convey a
covered work so as to satisfy simultaneously your obligations under this
License and any other pertinent obligations, then as a consequence you may
not convey it at all. For example, if you agree to terms that obligate you
to collect a royalty for further conveying from those to whom you convey
the Program, the only way you could satisfy both those terms and this
License would be to refrain entirely from conveying the Program.
13. Use with the GNU Affero General Public License.
Notwithstanding any other provision of this License, you have
permission to link or combine any covered work with a work licensed
under version 3 of the GNU Affero General Public License into a single
combined work, and to convey the resulting work. The terms of this
License will continue to apply to the part which is the covered work,
but the special requirements of the GNU Affero General Public License,
section 13, concerning interaction through a network will apply to the
combination as such.
14. Revised Versions of this License.
The Free Software Foundation may publish revised and/or new versions of
the GNU General Public License from time to time. Such new versions will
be similar in spirit to the present version, but may differ in detail to
address new problems or concerns.
Each version is given a distinguishing version number. If the
Program specifies that a certain numbered version of the GNU General
Public License "or any later version" applies to it, you have the
option of following the terms and conditions either of that numbered
version or of any later version published by the Free Software
Foundation. If the Program does not specify a version number of the
GNU General Public License, you may choose any version ever published
by the Free Software Foundation.
If the Program specifies that a proxy can decide which future
versions of the GNU General Public License can be used, that proxy's
public statement of acceptance of a version permanently authorizes you
to choose that version for the Program.
Later license versions may give you additional or different
permissions. However, no additional obligations are imposed on any
author or copyright holder as a result of your choosing to follow a
later version.
15. Disclaimer of Warranty.
THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY
APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT
HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY
OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO,
THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM
IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF
ALL NECESSARY SERVICING, REPAIR OR CORRECTION.
16. Limitation of Liability.
IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING
WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS
THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY
GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE
USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF
DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD
PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS),
EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF
SUCH DAMAGES.
17. Interpretation of Sections 15 and 16.
If the disclaimer of warranty and limitation of liability provided
above cannot be given local legal effect according to their terms,
reviewing courts shall apply local law that most closely approximates
an absolute waiver of all civil liability in connection with the
Program, unless a warranty or assumption of liability accompanies a
copy of the Program in return for a fee.
END OF TERMS AND CONDITIONS
How to Apply These Terms to Your New Programs
If you develop a new program, and you want it to be of the greatest
possible use to the public, the best way to achieve this is to make it
free software which everyone can redistribute and change under these terms.
To do so, attach the following notices to the program. It is safest
to attach them to the start of each source file to most effectively
state the exclusion of warranty; and each file should have at least
the "copyright" line and a pointer to where the full notice is found.
<one line to give the program's name and a brief idea of what it does.>
Copyright (C) <year> <name of author>
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
Also add information on how to contact you by electronic and paper mail.
If the program does terminal interaction, make it output a short
notice like this when it starts in an interactive mode:
<program> Copyright (C) <year> <name of author>
This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'.
This is free software, and you are welcome to redistribute it
under certain conditions; type `show c' for details.
The hypothetical commands `show w' and `show c' should show the appropriate
parts of the General Public License. Of course, your program's commands
might be different; for a GUI interface, you would use an "about box".
You should also get your employer (if you work as a programmer) or school,
if any, to sign a "copyright disclaimer" for the program, if necessary.
For more information on this, and how to apply and follow the GNU GPL, see
<http://www.gnu.org/licenses/>.
The GNU General Public License does not permit incorporating your program
into proprietary programs. If your program is a subroutine library, you
may consider it more useful to permit linking proprietary applications with
the library. If this is what you want to do, use the GNU Lesser General
Public License instead of this License. But first, please read
<http://www.gnu.org/philosophy/why-not-lgpl.html>.

26
README.txt Normal file
View File

@ -0,0 +1,26 @@
Building using arduino
--------------------------
To install the libraries:
- copy Library Directories to your \arduino\hardware\libraries\ or arduino\libraries directory
- Restart arduino IDE
* Each library comes with a simple example. You can find the examples in menu File->Examples
Building using make
-----------------------------------------------
- go to directory of sketch and type make.
Building using cmake
-----------------------------------------------
- mkdir build
- cd build
- cmake ..
- make (will build every sketch)
- make ArduPlane (will build just ArduPlane etc.)
Build a package using cpack
-----------------------------------------------
- cd build
- cmake ..
- make package
- make package_source

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

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