diff --git a/.gitignore b/.gitignore index 99b43f7898..e282838e79 100644 --- a/.gitignore +++ b/.gitignore @@ -3,3 +3,8 @@ Tools/ArdupilotMegaPlanner/bin/Release/logs/ ArduCopter/Debug/ config.mk serialsent.raw +CMakeFiles +CMakeCache.txt +cmake_install.cmake +build +/Tools/ArdupilotMegaPlanner/bin/Release/gmapcache \ No newline at end of file diff --git a/ArduBoat/.cproject b/ArduBoat/.cproject new file mode 100644 index 0000000000..adf5adc365 --- /dev/null +++ b/ArduBoat/.cproject @@ -0,0 +1,46 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ArduBoat/.project b/ArduBoat/.project new file mode 100644 index 0000000000..969ff0d90c --- /dev/null +++ b/ArduBoat/.project @@ -0,0 +1,79 @@ + + + ArduBoat + + + + + + org.eclipse.cdt.managedbuilder.core.genmakebuilder + clean,full,incremental, + + + ?name? + + + + org.eclipse.cdt.make.core.append_environment + true + + + org.eclipse.cdt.make.core.autoBuildTarget + all + + + org.eclipse.cdt.make.core.buildArguments + + + + org.eclipse.cdt.make.core.buildCommand + make + + + org.eclipse.cdt.make.core.cleanBuildTarget + clean + + + org.eclipse.cdt.make.core.contents + org.eclipse.cdt.make.core.activeConfigSettings + + + org.eclipse.cdt.make.core.enableAutoBuild + false + + + org.eclipse.cdt.make.core.enableCleanBuild + true + + + org.eclipse.cdt.make.core.enableFullBuild + true + + + org.eclipse.cdt.make.core.fullBuildTarget + all + + + org.eclipse.cdt.make.core.stopOnError + true + + + org.eclipse.cdt.make.core.useDefaultBuildCmd + true + + + + + org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder + full,incremental, + + + + + + org.eclipse.cdt.core.cnature + org.eclipse.cdt.core.ccnature + org.eclipse.cdt.managedbuilder.core.managedBuildNature + org.eclipse.cdt.managedbuilder.core.ScannerConfigNature + + diff --git a/ArduBoat/ArduBoat.cpp b/ArduBoat/ArduBoat.cpp new file mode 100644 index 0000000000..9841cf6c17 --- /dev/null +++ b/ArduBoat/ArduBoat.cpp @@ -0,0 +1,24 @@ +// Libraries +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +// Vehicle Configuration +#include "BoatGeneric.h" + +// ArduPilotOne Default Setup +#include "APO_DefaultSetup.h" + +#include ; int main(void) {init();setup();for(;;) loop(); return 0; } diff --git a/ArduBoat/ArduBoat.pde b/ArduBoat/ArduBoat.pde new file mode 100644 index 0000000000..cbe9a99c66 --- /dev/null +++ b/ArduBoat/ArduBoat.pde @@ -0,0 +1,22 @@ +// Libraries +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +// Vehicle Configuration +#include "BoatGeneric.h" + +// ArduPilotOne Default Setup +#include "APO_DefaultSetup.h" diff --git a/ArduBoat/BoatGeneric.h b/ArduBoat/BoatGeneric.h new file mode 100644 index 0000000000..5e47672847 --- /dev/null +++ b/ArduBoat/BoatGeneric.h @@ -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_ */ diff --git a/ArduBoat/ControllerBoat.h b/ArduBoat/ControllerBoat.h new file mode 100644 index 0000000000..4999569acb --- /dev/null +++ b/ArduBoat/ControllerBoat.h @@ -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, RC_MODE_IN, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chStr, PSTR("STR_"), APM_RC, 0, 1100, 1540, + 1900, RC_MODE_INOUT, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chThr, PSTR("THR_"), APM_RC, 1, 1100, 1500, + 1900, RC_MODE_INOUT, false)); + } + 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_ */ diff --git a/ArduBoat/Makefile b/ArduBoat/Makefile new file mode 100644 index 0000000000..1d9b6a022d --- /dev/null +++ b/ArduBoat/Makefile @@ -0,0 +1 @@ +include ../libraries/AP_Common/Arduino.mk diff --git a/ArduCopter/.gitignore b/ArduCopter/.gitignore new file mode 100644 index 0000000000..05fd67446c --- /dev/null +++ b/ArduCopter/.gitignore @@ -0,0 +1 @@ +arducopter.cpp diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h index ccd7e5c548..802c4c0881 100644 --- a/ArduCopter/APM_Config.h +++ b/ArduCopter/APM_Config.h @@ -37,8 +37,13 @@ CH7_SIMPLE_MODE CH7_RTL CH7_AUTO_TRIM + CH7_ADC_FILTER (experimental) */ +#define ACCEL_ALT_HOLD 0 // disabled by default, work in progress +#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! // diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 6f4d76e752..49e0fc3f46 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -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.47 Beta" /* ArduCopter Version 2.0 Beta Authors: Jason Short @@ -65,6 +65,7 @@ And much more so PLEASE PM me on DIYDRONES to add your contribution to the List #include // Range finder library #include // Optical Flow library #include +#include // APM relay #include // MAVLink GCS definitions #include @@ -129,6 +130,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 +204,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 +245,8 @@ static const char* flight_mode_strings[] = { "GUIDED", "LOITER", "RTL", - "CIRCLE"}; + "CIRCLE", + "POSITION"}; /* Radio values Channel assignments @@ -260,16 +261,20 @@ static const char* flight_mode_strings[] = { */ // test -//Vector3f accels_rot; -//float accel_gain = 20; +#if ACCEL_ALT_HOLD == 1 +Vector3f accels_rot; +static int accels_rot_count; +static float accels_rot_sum; +static float alt_hold_gain = ACCEL_ALT_HOLD_GAIN; +#endif // temp -int y_actual_speed; -int y_rate_error; +static int y_actual_speed; +static int y_rate_error; // calc the -int x_actual_speed; -int x_rate_error; +static int x_actual_speed; +static int x_rate_error; // Radio // ----- @@ -336,6 +341,7 @@ static float sin_pitch_y, sin_yaw_y, sin_roll_y; static long initial_simple_bearing; // used for Simple mode static float simple_sin_y, simple_cos_x; static byte jump = -10; // used to track loops in jump command +static int waypoint_speed_gov; // Acro #if CH7_OPTION == CH7_FLIP @@ -483,7 +489,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,9 +502,10 @@ 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; +AP_Relay relay; + //////////////////////////////////////////////////////////////////////////////// // Top-level logic //////////////////////////////////////////////////////////////////////////////// @@ -585,6 +591,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 +605,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 +644,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 +670,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 +693,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 +731,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 +824,6 @@ static void slow_loop() //---------------------------------------- switch (slow_loopCounter){ case 0: - loop_step = 6; slow_loopCounter++; superslow_loopCounter++; @@ -835,7 +838,6 @@ static void slow_loop() break; case 1: - loop_step = 7; slow_loopCounter++; // Read 3-position switch on radio @@ -860,7 +862,6 @@ static void slow_loop() break; case 2: - loop_step = 8; slow_loopCounter = 0; update_events(); @@ -899,7 +900,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 +912,6 @@ static void super_slow_loop() static void update_GPS(void) { - loop_step = 10; g_gps->update(); update_GPS_light(); @@ -920,12 +919,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 +950,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 +1039,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 +1058,6 @@ void update_roll_pitch_mode(void) } } - // 50 hz update rate, not 250 void update_throttle_mode(void) { @@ -1084,8 +1071,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: @@ -1101,7 +1086,7 @@ void update_throttle_mode(void) altitude_error = get_altitude_error(); // get the AP throttle - nav_throttle = get_nav_throttle(altitude_error, 250); //150 = target speed of 1.5m/s + nav_throttle = get_nav_throttle(altitude_error);//, 250); //150 = target speed of 1.5m/s //Serial.printf("in:%d, cr:%d, NT:%d, I:%1.4f\n", g.rc_3.control_in,altitude_error, nav_throttle, g.pi_throttle.get_integrator()); // clear the new data flag @@ -1109,7 +1094,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; } } @@ -1139,7 +1124,10 @@ static void update_navigation() break; case RTL: - if(wp_distance > 4){ + if((wp_distance <= g.waypoint_radius) || check_missed_wp()){ + // lets just jump to Loiter Mode after RTL + set_mode(LOITER); + }else{ // calculates desired Yaw // XXX this is an experiment #if FRAME_CONFIG == HELI_FRAME @@ -1147,9 +1135,6 @@ static void update_navigation() #endif wp_control = WP_MODE; - }else{ - // lets just jump to Loiter Mode after RTL - set_mode(LOITER); } // calculates the desired Roll and Pitch @@ -1158,6 +1143,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 +1209,12 @@ 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(); + #if ACCEL_ALT_HOLD == 1 + Vector3f accel_filt = imu.get_accel_filtered(); + accels_rot = dcm.get_dcm_matrix() * imu.get_accel_filtered(); + accels_rot_sum += accels_rot.z; + accels_rot_count++; + #endif } // updated at 10hz @@ -1276,11 +1266,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 } } @@ -1288,6 +1278,13 @@ static void tuning(){ tuning_value = (float)g.rc_6.control_in / 1000.0; switch(g.radio_tuning){ + + /*case CH6_STABILIZE_KP: + g.rc_6.set_range(0,2000); // 0 to 8 + tuning_value = (float)g.rc_6.control_in / 100.0; + alt_hold_gain = tuning_value; + break;*/ + case CH6_STABILIZE_KP: g.rc_6.set_range(0,8000); // 0 to 8 g.pi_stabilize_roll.kP(tuning_value); @@ -1335,8 +1332,8 @@ static void tuning(){ case CH6_RELAY: g.rc_6.set_range(0,1000); - if (g.rc_6.control_in > 525) relay_on(); - if (g.rc_6.control_in < 475) relay_off(); + if (g.rc_6.control_in > 525) relay.on(); + if (g.rc_6.control_in < 475) relay.off(); break; case CH6_TRAVERSE_SPEED: @@ -1344,6 +1341,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 +1363,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 +1396,16 @@ 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(); } } diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde index c834a487d4..ccbd382dde 100644 --- a/ArduCopter/Attitude.pde +++ b/ArduCopter/Attitude.pde @@ -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,20 +83,18 @@ get_stabilize_yaw(long target_angle) return (int)constrain(rate, -2500, 2500); } -#define ALT_ERROR_MAX 350 +#define ALT_ERROR_MAX 400 static int -get_nav_throttle(long z_error, int target_speed) +get_nav_throttle(long z_error) { - int rate_error; - float scaler = (float)target_speed/(float)ALT_ERROR_MAX; - // limit error to prevent I term run up z_error = constrain(z_error, -ALT_ERROR_MAX, ALT_ERROR_MAX); - target_speed = z_error * scaler; + int rate_error = g.pi_alt_hold.get_pi(z_error, .1); //_p = .85 - rate_error = target_speed - altitude_rate; - rate_error = constrain(rate_error, -120, 140); + rate_error = rate_error - altitude_rate; + // limit the rate + rate_error = constrain(rate_error, -100, 120); return (int)g.pi_throttle.get_pi(rate_error, .1); } @@ -106,10 +102,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 +114,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 +126,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 +186,35 @@ 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 -= 100; + error = min(error, 200.0); + error = max(error, 0.0); + error = 1 - (error/ 200.0); + float sum = accels_rot_sum / (float)accels_rot_count; + + accels_rot_sum = 0; + accels_rot_count = 0; + + int output = (sum + 9.81) * alt_hold_gain * error; + +// fast rise +//s: -17.6241, g:0.0000, e:1.0000, o:0 +//s: -18.4990, g:0.0000, e:1.0000, o:0 +//s: -19.3193, g:0.0000, e:1.0000, o:0 +//s: -13.1310, g:47.8700, e:1.0000, o:-158 + + //Serial.printf("s: %1.4f, g:%1.4f, e:%1.4f, o:%d\n",sum, alt_hold_gain, error, output); + return output; + #else + return 0; + #endif } -*/ static int get_angle_boost() { diff --git a/ArduCopter/CMakeLists.txt b/ArduCopter/CMakeLists.txt index 4e282df19b..ba540e183c 100644 --- a/ArduCopter/CMakeLists.txt +++ b/ArduCopter/CMakeLists.txt @@ -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 diff --git a/ArduCopter/Makefile b/ArduCopter/Makefile index 34f8baffd9..1d9b6a022d 100644 --- a/ArduCopter/Makefile +++ b/ArduCopter/Makefile @@ -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 diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index b520c6871e..8b1ce7fff3 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -164,6 +164,7 @@ public: k_param_pi_loiter_lon, k_param_pi_nav_lat, k_param_pi_nav_lon, + k_param_pi_alt_hold, k_param_pi_throttle, k_param_pi_crosstrack, @@ -277,6 +278,7 @@ public: APM_PI pi_nav_lat; APM_PI pi_nav_lon; + APM_PI pi_alt_hold; APM_PI pi_throttle; APM_PI pi_crosstrack; @@ -381,7 +383,8 @@ public: pi_nav_lat (k_param_pi_nav_lat, PSTR("NAV_LAT_"), NAV_P, NAV_I, NAV_IMAX * 100), pi_nav_lon (k_param_pi_nav_lon, PSTR("NAV_LON_"), NAV_P, NAV_I, NAV_IMAX * 100), - pi_throttle (k_param_pi_throttle, PSTR("THR_HOLD_"), THROTTLE_P, THROTTLE_I, THROTTLE_IMAX), + pi_alt_hold (k_param_pi_alt_hold, PSTR("THR_ALT_"), THR_HOLD_P, THR_HOLD_I, THR_HOLD_IMAX), + pi_throttle (k_param_pi_throttle, PSTR("THR_RATE_"), THROTTLE_P, THROTTLE_I, THROTTLE_IMAX), pi_crosstrack (k_param_pi_crosstrack, PSTR("XTRACK_"), XTRACK_P, XTRACK_I, XTRACK_IMAX), junk(0) // XXX just so that we can add things without worrying about the trailing comma diff --git a/ArduCopter/commands.pde b/ArduCopter/commands.pde index 31faf10d3c..01b60c22bb 100644 --- a/ArduCopter/commands.pde +++ b/ArduCopter/commands.pde @@ -170,14 +170,19 @@ static void set_next_WP(struct Location *wp) scaleLongUp = 1.0f/cos(rads); // this is handy for the groundstation + // ----------------------------------- wp_totalDistance = get_distance(¤t_loc, &next_WP); wp_distance = wp_totalDistance; target_bearing = get_bearing(¤t_loc, &next_WP); // to check if we have missed the WP - // ---------------------------- + // --------------------------------- original_target_bearing = target_bearing; + // reset speed governer + // -------------------- + waypoint_speed_gov = 0; + gcs.print_current_waypoints(); } diff --git a/ArduCopter/commands_logic.pde b/ArduCopter/commands_logic.pde index 49c6bb941c..c8a0cb1628 100644 --- a/ArduCopter/commands_logic.pde +++ b/ArduCopter/commands_logic.pde @@ -247,6 +247,7 @@ static void do_nav_wp() } set_next_WP(&next_command); + // this is our bitmask to verify we have met all conditions to move on wp_verify_byte = 0; @@ -482,7 +483,7 @@ static void do_wait_delay() //Serial.print("dwd "); condition_start = millis(); condition_value = next_command.lat * 1000; // convert to milliseconds - Serial.println(condition_value,DEC); + //Serial.println(condition_value,DEC); } static void do_change_alt() @@ -693,11 +694,11 @@ static void do_set_servo() static void do_set_relay() { if (next_command.p1 == 1) { - relay_on(); + relay.on(); } else if (next_command.p1 == 0) { - relay_off(); + relay.off(); }else{ - relay_toggle(); + relay.toggle(); } } diff --git a/ArduCopter/config.h b/ArduCopter/config.h index e550721548..67585a6bfc 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -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.6 #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.6 #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 0.145 #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.145 #endif #ifndef RATE_PITCH_I # define RATE_PITCH_I 0 //0.18 @@ -482,27 +467,27 @@ // Navigation control gains // #ifndef LOITER_P -# define LOITER_P .4 // +# define LOITER_P .5 // #endif #ifndef LOITER_I -# define LOITER_I 0.01 // +# define LOITER_I 0.0 // #endif #ifndef LOITER_IMAX # define LOITER_IMAX 12 // degrees° #endif #ifndef NAV_P -# define NAV_P 2.0 // for 4.5 ms error = 13.5 pitch +# define NAV_P 4.0 // #endif #ifndef NAV_I -# define NAV_I 0.15 // this +# define NAV_I 0.25 // this feels really low, 4s to move 1 degree pitch... #endif #ifndef NAV_IMAX # define NAV_IMAX 20 // 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 @@ -515,14 +500,24 @@ # define THROTTLE_CRUISE 350 // #endif +#ifndef THR_HOLD_P +# define THR_HOLD_P 0.80 // +#endif +#ifndef THR_HOLD_I +# define THR_HOLD_I 0.00 // with 4m error, 12.5s windup +#endif +#ifndef THR_HOLD_IMAX +# define THR_HOLD_IMAX 00 +#endif + #ifndef THROTTLE_P # 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 +# define THROTTLE_IMAX 300 #endif @@ -671,7 +666,7 @@ #endif #ifndef ALT_HOLD_HOME -# define ALT_HOLD_HOME -1 +# define ALT_HOLD_HOME 10 #endif #ifndef USE_CURRENT_ALT diff --git a/ArduCopter/control_modes.pde b/ArduCopter/control_modes.pde index 8d958b476e..ba03570201 100644 --- a/ArduCopter/control_modes.pde +++ b/ArduCopter/control_modes.pde @@ -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; @@ -117,7 +120,7 @@ static void auto_trim() led_mode = NORMAL_LEDS; clear_leds(); imu.save(); - Serial.println("Done"); + //Serial.println("Done"); auto_level_counter = 0; } } diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index 269fcef3a8..9408dea354 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -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 // ------------- diff --git a/ArduCopter/events.pde b/ArduCopter/events.pde index 08357e60ad..d6ae523c54 100644 --- a/ArduCopter/events.pde +++ b/ArduCopter/events.pde @@ -75,26 +75,11 @@ static void update_events() // Used for MAV_CMD_DO_REPEAT_SERVO and MAV_CMD_DO_R } if (event_id == RELAY_TOGGLE) { - relay_toggle(); + relay.toggle(); } } } -static void relay_on() -{ - PORTL |= B00000100; -} - -static void relay_off() -{ - PORTL &= ~B00000100; -} - -static void relay_toggle() -{ - PORTL ^= B00000100; -} - #if PIEZO == ENABLED void piezo_on() { diff --git a/ArduCopter/navigation.pde b/ArduCopter/navigation.pde index bc5c35e2e5..9b83625e8e 100644 --- a/ArduCopter/navigation.pde +++ b/ArduCopter/navigation.pde @@ -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 @@ -124,9 +111,14 @@ static void calc_nav_rate2(int max_speed) 100 200 300 400 +|+ */ - max_speed = min(max_speed, (wp_distance * 50)); + // limit the ramp up of the speed + if(waypoint_speed_gov < max_speed){ + waypoint_speed_gov += 40; + max_speed = min(max_speed, waypoint_speed_gov); + } + // XXX target_angle should be the original desired target angle! float temp = radians((original_target_bearing - g_gps->ground_course)/100.0); @@ -151,7 +143,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 +163,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 +186,6 @@ static int get_loiter_angle() return angle; } - static long wrap_360(long error) { if (error > 36000) error -= 36000; diff --git a/ArduCopter/radio.pde b/ArduCopter/radio.pde index 86b30c9de7..309ea91274 100644 --- a/ArduCopter/radio.pde +++ b/ArduCopter/radio.pde @@ -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); - */ } } diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index 8812079962..848713b396 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -174,6 +174,9 @@ static void init_ardupilot() init_camera(); #if HIL_MODE != HIL_MODE_ATTITUDE + // begin filtering the ADC Gyros + adc.filter_result = true; + adc.Init(); // APM ADC library initialization barometer.Init(); // APM Abs Pressure sensor initialization #endif @@ -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; diff --git a/ArduCopter/test.pde b/ArduCopter/test.pde index 2533c08565..7b2884a9f7 100644 --- a/ArduCopter/test.pde +++ b/ArduCopter/test.pde @@ -24,7 +24,7 @@ static int8_t test_current(uint8_t argc, const Menu::arg *argv); static int8_t test_relay(uint8_t argc, const Menu::arg *argv); static int8_t test_wp(uint8_t argc, const Menu::arg *argv); static int8_t test_baro(uint8_t argc, const Menu::arg *argv); -static int8_t test_mag(uint8_t argc, const Menu::arg *argv); +//static int8_t test_mag(uint8_t argc, const Menu::arg *argv); static int8_t test_sonar(uint8_t argc, const Menu::arg *argv); #ifdef OPTFLOW_ENABLED static int8_t test_optflow(uint8_t argc, const Menu::arg *argv); @@ -76,11 +76,11 @@ const struct Menu::command test_menu_commands[] PROGMEM = { {"altitude", test_baro}, #endif {"sonar", test_sonar}, - {"compass", test_mag}, + //{"compass", test_mag}, #ifdef OPTFLOW_ENABLED {"optflow", test_optflow}, #endif - {"xbee", test_xbee}, + //{"xbee", test_xbee}, {"eedump", test_eedump}, {"rawgps", test_rawgps}, // {"mission", test_mission}, @@ -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); @@ -715,14 +712,14 @@ test_relay(uint8_t argc, const Menu::arg *argv) while(1){ Serial.printf_P(PSTR("Relay on\n")); - relay_on(); + relay.on(); delay(3000); if(Serial.available() > 0){ return (0); } Serial.printf_P(PSTR("Relay off\n")); - relay_off(); + relay.off(); delay(3000); if(Serial.available() > 0){ return (0); @@ -772,7 +769,7 @@ static int8_t test_rawgps(uint8_t argc, const Menu::arg *argv) { } } -static int8_t +/*static int8_t test_xbee(uint8_t argc, const Menu::arg *argv) { print_hit_enter(); @@ -788,6 +785,7 @@ test_xbee(uint8_t argc, const Menu::arg *argv) } } } +*/ #if HIL_MODE != HIL_MODE_ATTITUDE static int8_t @@ -808,6 +806,7 @@ test_baro(uint8_t argc, const Menu::arg *argv) } #endif +/* static int8_t test_mag(uint8_t argc, const Menu::arg *argv) { @@ -837,6 +836,7 @@ test_mag(uint8_t argc, const Menu::arg *argv) return (0); } } +*/ /* static int8_t test_reverse(uint8_t argc, const Menu::arg *argv) diff --git a/ArduPlane/.gitignore b/ArduPlane/.gitignore new file mode 100644 index 0000000000..733b1fe2ff --- /dev/null +++ b/ArduPlane/.gitignore @@ -0,0 +1 @@ +ArduPlane.cpp diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde index 7766f57305..9bb147ce3e 100644 --- a/ArduPlane/ArduPlane.pde +++ b/ArduPlane/ArduPlane.pde @@ -41,6 +41,7 @@ version 2.1 of the License, or (at your option) any later version. #include // RC Channel Library #include // Range finder library #include +#include // APM relay #include // MAVLink GCS definitions #include @@ -215,10 +216,12 @@ static const char* flight_mode_strings[] = { 2 Elevator 3 Throttle 4 Rudder (if we have ailerons) - 5 Mode - 6 TBD - 7 TBD - 8 TBD + 5 Aux5 + 6 Aux6 + 7 Aux7 + 8 Aux8/Mode + Each Aux channel can be configured to have any of the available auxiliary functions assigned to it. + See libraries/RC_Channel/RC_Channel_aux.h for more information */ // Failsafe @@ -273,6 +276,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 @@ -397,6 +401,7 @@ static unsigned long dTnav; // Delta Time in milliseconds for navigation c static float load; // % MCU cycles used RC_Channel_aux* g_rc_function[RC_Channel_aux::k_nr_aux_servo_functions]; // the aux. servo ch. assigned to each function +AP_Relay relay; //////////////////////////////////////////////////////////////////////////////// // Top-level logic @@ -792,7 +797,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 +814,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); } diff --git a/ArduPlane/Attitude.pde b/ArduPlane/Attitude.pde index ccc20a4fb6..bb066d67a5 100644 --- a/ArduPlane/Attitude.pde +++ b/ArduPlane/Attitude.pde @@ -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; diff --git a/ArduPlane/CMakeLists.txt b/ArduPlane/CMakeLists.txt index d2c7506d88..9b53e492be 100644 --- a/ArduPlane/CMakeLists.txt +++ b/ArduPlane/CMakeLists.txt @@ -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 diff --git a/ArduPlane/Makefile b/ArduPlane/Makefile index 34f8baffd9..1d9b6a022d 100644 --- a/ArduPlane/Makefile +++ b/ArduPlane/Makefile @@ -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 diff --git a/ArduPlane/commands_logic.pde b/ArduPlane/commands_logic.pde index 296b238c19..8f73520e31 100644 --- a/ArduPlane/commands_logic.pde +++ b/ArduPlane/commands_logic.pde @@ -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() @@ -482,11 +483,11 @@ static void do_set_servo() static void do_set_relay() { if (next_command.p1 == 1) { - relay_on(); + relay.on(); } else if (next_command.p1 == 0) { - relay_off(); + relay.off(); }else{ - relay_toggle(); + relay.toggle(); } } diff --git a/ArduPlane/events.pde b/ArduPlane/events.pde index d5eb2ae9fe..0dd7435406 100644 --- a/ArduPlane/events.pde +++ b/ArduPlane/events.pde @@ -104,23 +104,7 @@ static void update_events(void) // Used for MAV_CMD_DO_REPEAT_SERVO and MAV_CMD_ } if (event_id == RELAY_TOGGLE) { - relay_toggle(); + relay.toggle(); } } } - -static void relay_on() -{ - PORTL |= B00000100; -} - -static void relay_off() -{ - PORTL &= ~B00000100; -} - -static void relay_toggle() -{ - PORTL ^= B00000100; -} - diff --git a/ArduPlane/radio.pde b/ArduPlane/radio.pde index 6c8967d542..af2c38bd88 100644 --- a/ArduPlane/radio.pde +++ b/ArduPlane/radio.pde @@ -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; diff --git a/ArduPlane/test.pde b/ArduPlane/test.pde index 3b95d9c6c0..9c0adbd26d 100644 --- a/ArduPlane/test.pde +++ b/ArduPlane/test.pde @@ -279,14 +279,14 @@ test_relay(uint8_t argc, const Menu::arg *argv) while(1){ Serial.printf_P(PSTR("Relay on\n")); - relay_on(); + relay.on(); delay(3000); if(Serial.available() > 0){ return (0); } Serial.printf_P(PSTR("Relay off\n")); - relay_off(); + relay.off(); delay(3000); if(Serial.available() > 0){ return (0); diff --git a/ArduRover/.cproject b/ArduRover/.cproject new file mode 100644 index 0000000000..7a4dd5232b --- /dev/null +++ b/ArduRover/.cproject @@ -0,0 +1,46 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ArduRover/.project b/ArduRover/.project new file mode 100644 index 0000000000..4494bc9869 --- /dev/null +++ b/ArduRover/.project @@ -0,0 +1,79 @@ + + + ArduRover + + + + + + org.eclipse.cdt.managedbuilder.core.genmakebuilder + clean,full,incremental, + + + ?name? + + + + org.eclipse.cdt.make.core.append_environment + true + + + org.eclipse.cdt.make.core.autoBuildTarget + all + + + org.eclipse.cdt.make.core.buildArguments + + + + org.eclipse.cdt.make.core.buildCommand + make + + + org.eclipse.cdt.make.core.cleanBuildTarget + clean + + + org.eclipse.cdt.make.core.contents + org.eclipse.cdt.make.core.activeConfigSettings + + + org.eclipse.cdt.make.core.enableAutoBuild + false + + + org.eclipse.cdt.make.core.enableCleanBuild + true + + + org.eclipse.cdt.make.core.enableFullBuild + true + + + org.eclipse.cdt.make.core.fullBuildTarget + all + + + org.eclipse.cdt.make.core.stopOnError + true + + + org.eclipse.cdt.make.core.useDefaultBuildCmd + true + + + + + org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder + full,incremental, + + + + + + org.eclipse.cdt.core.cnature + org.eclipse.cdt.core.ccnature + org.eclipse.cdt.managedbuilder.core.managedBuildNature + org.eclipse.cdt.managedbuilder.core.ScannerConfigNature + + diff --git a/ArduRover/ArduRover.cpp b/ArduRover/ArduRover.cpp new file mode 100644 index 0000000000..57f0903250 --- /dev/null +++ b/ArduRover/ArduRover.cpp @@ -0,0 +1,23 @@ +// Libraries +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +// Vehicle Configuration +#include "CarStampede.h" + +// ArduPilotOne Default Setup +#include "APO_DefaultSetup.h" + +#include ; int main(void) {init();setup();for(;;) loop(); return 0; } diff --git a/ArduRover/ArduRover.pde b/ArduRover/ArduRover.pde new file mode 100644 index 0000000000..cc1a79aa0c --- /dev/null +++ b/ArduRover/ArduRover.pde @@ -0,0 +1,21 @@ +// Libraries +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +// Vehicle Configuration +#include "TankGeneric.h" + +// ArduPilotOne Default Setup +#include "APO_DefaultSetup.h" diff --git a/ArduRover/CarStampede.h b/ArduRover/CarStampede.h new file mode 100644 index 0000000000..07a4fe20e4 --- /dev/null +++ b/ArduRover/CarStampede.h @@ -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_1280; +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_ */ diff --git a/ArduRover/ControllerCar.h b/ArduRover/ControllerCar.h new file mode 100644 index 0000000000..8bb7e9afb5 --- /dev/null +++ b/ArduRover/ControllerCar.h @@ -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, RC_MODE_IN, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chStr, PSTR("STR_"), APM_RC, 0, 1100, 1540, + 1900, RC_MODE_INOUT, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chThr, PSTR("THR_"), APM_RC, 1, 1100, 1500, + 1900, RC_MODE_INOUT, false)); + } + 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_ */ diff --git a/ArduRover/ControllerTank.h b/ArduRover/ControllerTank.h new file mode 100644 index 0000000000..ad8a294a2c --- /dev/null +++ b/ArduRover/ControllerTank.h @@ -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, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chLeft, PSTR("LEFT_"), APM_RC, 0, 1100, 1500, + 1900, RC_MODE_OUT, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chRight, PSTR("RIGHT_"), APM_RC, 1, 1100, 1500, + 1900, RC_MODE_OUT, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chStr, PSTR("STR_"), APM_RC, 0, 1100, 1500, + 1900, RC_MODE_IN, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chThr, PSTR("THR_"), APM_RC, 1, 1100, 1500, + 1900, RC_MODE_IN, false)); + } + 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_ */ diff --git a/ArduRover/Makefile b/ArduRover/Makefile new file mode 100644 index 0000000000..1d9b6a022d --- /dev/null +++ b/ArduRover/Makefile @@ -0,0 +1 @@ +include ../libraries/AP_Common/Arduino.mk diff --git a/ArduRover/TankGeneric.h b/ArduRover/TankGeneric.h new file mode 100644 index 0000000000..9af4f9b1d4 --- /dev/null +++ b/ArduRover/TankGeneric.h @@ -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_1280; +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 = false; +static bool compassEnabled = false; + +static bool rangeFinderFrontEnabled = false; +static bool rangeFinderBackEnabled = false; +static bool rangeFinderLeftEnabled = false; +static bool rangeFinderRightEnabled = false; +static bool rangeFinderUpEnabled = false; +static bool rangeFinderDownEnabled = false; + +// 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_ */ diff --git a/CMakeLists.txt b/CMakeLists.txt new file mode 100644 index 0000000000..fc36d92527 --- /dev/null +++ b/CMakeLists.txt @@ -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) diff --git a/COPYING.txt b/COPYING.txt new file mode 100644 index 0000000000..94a9ed024d --- /dev/null +++ b/COPYING.txt @@ -0,0 +1,674 @@ + GNU GENERAL PUBLIC LICENSE + Version 3, 29 June 2007 + + Copyright (C) 2007 Free Software Foundation, Inc. + 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. + + + Copyright (C) + + 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 . + +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: + + Copyright (C) + 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 +. + + 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 +. diff --git a/Install.txt b/Install.txt deleted file mode 100644 index 5c129d6b64..0000000000 --- a/Install.txt +++ /dev/null @@ -1,11 +0,0 @@ - -Install notes -------------- - -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 - -test svn diff --git a/README.txt b/README.txt new file mode 100644 index 0000000000..b8f91718d6 --- /dev/null +++ b/README.txt @@ -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 diff --git a/Tools/ArduPPM/ATMega328p/Encoder-PPM.c b/Tools/ArduPPM/ATMega328p/Encoder-PPM.c new file mode 100644 index 0000000000..fa4aefc454 --- /dev/null +++ b/Tools/ArduPPM/ATMega328p/Encoder-PPM.c @@ -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 "..\Libraries\ppm_encoder.h" +#include + + +#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 + + diff --git a/Tools/ArduPPM/ATMega328p/Makefile b/Tools/ArduPPM/ATMega328p/Makefile new file mode 100644 index 0000000000..59ae094a40 --- /dev/null +++ b/Tools/ArduPPM/ATMega328p/Makefile @@ -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/*) + diff --git a/Tools/ArduPPM/ATMega328p/manual.txt b/Tools/ArduPPM/ATMega328p/manual.txt new file mode 100644 index 0000000000..b4fb772833 --- /dev/null +++ b/Tools/ArduPPM/ATMega328p/manual.txt @@ -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 + +-------------------------------------------------------------------------------------------------- diff --git a/Tools/ArduPPM/ATMega328p/readme.txt b/Tools/ArduPPM/ATMega328p/readme.txt new file mode 100644 index 0000000000..69b1474710 --- /dev/null +++ b/Tools/ArduPPM/ATMega328p/readme.txt @@ -0,0 +1,3 @@ + +This is the second generation ppm encoder code designed for APM v1.x boards using ATMega328P. + diff --git a/Tools/ArduPPM/ATMega32U2/Bootloaders/arduino-usbdfu/Arduino-usbdfu.c b/Tools/ArduPPM/ATMega32U2/Bootloaders/arduino-usbdfu/Arduino-usbdfu.c new file mode 100644 index 0000000000..18c761f7a9 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/Bootloaders/arduino-usbdfu/Arduino-usbdfu.c @@ -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]; +} diff --git a/Tools/ArduPPM/ATMega32U2/Bootloaders/arduino-usbdfu/Arduino-usbdfu.h b/Tools/ArduPPM/ATMega32U2/Bootloaders/arduino-usbdfu/Arduino-usbdfu.h new file mode 100644 index 0000000000..4adc7e5545 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/Bootloaders/arduino-usbdfu/Arduino-usbdfu.h @@ -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 + #include + #include + #include + #include + #include + #include + #include + + #include "Descriptors.h" + + #include + #include + + /* 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_ */ diff --git a/Tools/ArduPPM/ATMega32U2/Bootloaders/arduino-usbdfu/Board/LEDs.h b/Tools/ArduPPM/ATMega32U2/Bootloaders/arduino-usbdfu/Board/LEDs.h new file mode 100644 index 0000000000..41465f22dd --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/Bootloaders/arduino-usbdfu/Board/LEDs.h @@ -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 + +/* 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 diff --git a/Tools/ArduPPM/ATMega32U2/Bootloaders/arduino-usbdfu/Descriptors.c b/Tools/ArduPPM/ATMega32U2/Bootloaders/arduino-usbdfu/Descriptors.c new file mode 100644 index 0000000000..1ec1cd2235 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/Bootloaders/arduino-usbdfu/Descriptors.c @@ -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; +} diff --git a/Tools/ArduPPM/ATMega32U2/Bootloaders/arduino-usbdfu/Descriptors.h b/Tools/ArduPPM/ATMega32U2/Bootloaders/arduino-usbdfu/Descriptors.h new file mode 100644 index 0000000000..cb3a8ca1dd --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/Bootloaders/arduino-usbdfu/Descriptors.h @@ -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 + + /* 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 diff --git a/Tools/ArduPPM/ATMega32U2/Bootloaders/arduino-usbdfu/makefile b/Tools/ArduPPM/ATMega32U2/Bootloaders/arduino-usbdfu/makefile new file mode 100644 index 0000000000..80160e8095 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/Bootloaders/arduino-usbdfu/makefile @@ -0,0 +1,716 @@ +# Hey Emacs, this is a -*- makefile -*- +#---------------------------------------------------------------------------- +# WinAVR Makefile Template written by Eric B. Weddington, Jrg 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 +# 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 diff --git a/Tools/ArduPPM/ATMega32U2/Bootloaders/arduino-usbdfu/readme.txt b/Tools/ArduPPM/ATMega32U2/Bootloaders/arduino-usbdfu/readme.txt new file mode 100644 index 0000000000..f42ff834d4 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/Bootloaders/arduino-usbdfu/readme.txt @@ -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) + diff --git a/Tools/ArduPPM/ATMega32U2/LUFA.pnproj b/Tools/ArduPPM/ATMega32U2/LUFA.pnproj new file mode 100644 index 0000000000..84e57b4670 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA.pnproj @@ -0,0 +1 @@ + \ No newline at end of file diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Common/Attributes.h b/Tools/ArduPPM/ATMega32U2/LUFA/Common/Attributes.h new file mode 100644 index 0000000000..bcac84c7b3 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Common/Attributes.h @@ -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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Common/BoardTypes.h b/Tools/ArduPPM/ATMega32U2/LUFA/Common/BoardTypes.h new file mode 100644 index 0000000000..4849384fc7 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Common/BoardTypes.h @@ -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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Common/Common.h b/Tools/ArduPPM/ATMega32U2/LUFA/Common/Common.h new file mode 100644 index 0000000000..e939b66f3e --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Common/Common.h @@ -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 + #include + + #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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Doxygen.conf b/Tools/ArduPPM/ATMega32U2/LUFA/Doxygen.conf new file mode 100644 index 0000000000..d69b12d190 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Doxygen.conf @@ -0,0 +1,1563 @@ +# Doxyfile 1.6.2 + +# This file describes the settings to be used by the documentation system +# doxygen (www.doxygen.org) for a project +# +# All text after a hash (#) is considered a comment and will be ignored +# The format is: +# TAG = value [value, ...] +# For lists items can also be appended using: +# TAG += value [value, ...] +# Values that contain spaces should be placed between quotes (" ") + +#--------------------------------------------------------------------------- +# Project related configuration options +#--------------------------------------------------------------------------- + +# This tag specifies the encoding used for all characters in the config file +# that follow. The default is UTF-8 which is also the encoding used for all +# text before the first occurrence of this tag. Doxygen uses libiconv (or the +# iconv built into libc) for the transcoding. See +# http://www.gnu.org/software/libiconv for the list of possible encodings. + +DOXYFILE_ENCODING = UTF-8 + +# The PROJECT_NAME tag is a single word (or a sequence of words surrounded +# by quotes) that should identify the project. + +PROJECT_NAME = "LUFA (Formerly MyUSB) Library" + +# The PROJECT_NUMBER tag can be used to enter a project or revision number. +# This could be handy for archiving the generated documentation or +# if some version control system is used. + +PROJECT_NUMBER = 000000 + +# The OUTPUT_DIRECTORY tag is used to specify the (relative or absolute) +# base path where the generated documentation will be put. +# If a relative path is entered, it will be relative to the location +# where doxygen was started. If left blank the current directory will be used. + +OUTPUT_DIRECTORY = ./Documentation/ + +# If the CREATE_SUBDIRS tag is set to YES, then doxygen will create +# 4096 sub-directories (in 2 levels) under the output directory of each output +# format and will distribute the generated files over these directories. +# Enabling this option can be useful when feeding doxygen a huge amount of +# source files, where putting all generated files in the same directory would +# otherwise cause performance problems for the file system. + +CREATE_SUBDIRS = NO + +# The OUTPUT_LANGUAGE tag is used to specify the language in which all +# documentation generated by doxygen is written. Doxygen will use this +# information to generate all constant output in the proper language. +# The default language is English, other supported languages are: +# Afrikaans, Arabic, Brazilian, Catalan, Chinese, Chinese-Traditional, +# Croatian, Czech, Danish, Dutch, Esperanto, Farsi, Finnish, French, German, +# Greek, Hungarian, Italian, Japanese, Japanese-en (Japanese with English +# messages), Korean, Korean-en, Lithuanian, Norwegian, Macedonian, Persian, +# Polish, Portuguese, Romanian, Russian, Serbian, Serbian-Cyrilic, Slovak, +# Slovene, Spanish, Swedish, Ukrainian, and Vietnamese. + +OUTPUT_LANGUAGE = English + +# If the BRIEF_MEMBER_DESC tag is set to YES (the default) Doxygen will +# include brief member descriptions after the members that are listed in +# the file and class documentation (similar to JavaDoc). +# Set to NO to disable this. + +BRIEF_MEMBER_DESC = YES + +# If the REPEAT_BRIEF tag is set to YES (the default) Doxygen will prepend +# the brief description of a member or function before the detailed description. +# Note: if both HIDE_UNDOC_MEMBERS and BRIEF_MEMBER_DESC are set to NO, the +# brief descriptions will be completely suppressed. + +REPEAT_BRIEF = NO + +# This tag implements a quasi-intelligent brief description abbreviator +# that is used to form the text in various listings. Each string +# in this list, if found as the leading text of the brief description, will be +# stripped from the text and the result after processing the whole list, is +# used as the annotated text. Otherwise, the brief description is used as-is. +# If left blank, the following values are used ("$name" is automatically +# replaced with the name of the entity): "The $name class" "The $name widget" +# "The $name file" "is" "provides" "specifies" "contains" +# "represents" "a" "an" "the" + +ABBREVIATE_BRIEF = "The $name class" \ + "The $name widget" \ + "The $name file" \ + is \ + provides \ + specifies \ + contains \ + represents \ + a \ + an \ + the + +# If the ALWAYS_DETAILED_SEC and REPEAT_BRIEF tags are both set to YES then +# Doxygen will generate a detailed section even if there is only a brief +# description. + +ALWAYS_DETAILED_SEC = NO + +# If the INLINE_INHERITED_MEMB tag is set to YES, doxygen will show all +# inherited members of a class in the documentation of that class as if those +# members were ordinary class members. Constructors, destructors and assignment +# operators of the base classes will not be shown. + +INLINE_INHERITED_MEMB = NO + +# If the FULL_PATH_NAMES tag is set to YES then Doxygen will prepend the full +# path before files name in the file list and in the header files. If set +# to NO the shortest path that makes the file name unique will be used. + +FULL_PATH_NAMES = YES + +# If the FULL_PATH_NAMES tag is set to YES then the STRIP_FROM_PATH tag +# can be used to strip a user-defined part of the path. Stripping is +# only done if one of the specified strings matches the left-hand part of +# the path. The tag can be used to show relative paths in the file list. +# If left blank the directory from which doxygen is run is used as the +# path to strip. + +STRIP_FROM_PATH = + +# The STRIP_FROM_INC_PATH tag can be used to strip a user-defined part of +# the path mentioned in the documentation of a class, which tells +# the reader which header file to include in order to use a class. +# If left blank only the name of the header file containing the class +# definition is used. Otherwise one should specify the include paths that +# are normally passed to the compiler using the -I flag. + +STRIP_FROM_INC_PATH = + +# If the SHORT_NAMES tag is set to YES, doxygen will generate much shorter +# (but less readable) file names. This can be useful is your file systems +# doesn't support long names like on DOS, Mac, or CD-ROM. + +SHORT_NAMES = NO + +# If the JAVADOC_AUTOBRIEF tag is set to YES then Doxygen +# will interpret the first line (until the first dot) of a JavaDoc-style +# comment as the brief description. If set to NO, the JavaDoc +# comments will behave just like regular Qt-style comments +# (thus requiring an explicit @brief command for a brief description.) + +JAVADOC_AUTOBRIEF = NO + +# If the QT_AUTOBRIEF tag is set to YES then Doxygen will +# interpret the first line (until the first dot) of a Qt-style +# comment as the brief description. If set to NO, the comments +# will behave just like regular Qt-style comments (thus requiring +# an explicit \brief command for a brief description.) + +QT_AUTOBRIEF = NO + +# The MULTILINE_CPP_IS_BRIEF tag can be set to YES to make Doxygen +# treat a multi-line C++ special comment block (i.e. a block of //! or /// +# comments) as a brief description. This used to be the default behaviour. +# The new default is to treat a multi-line C++ comment block as a detailed +# description. Set this tag to YES if you prefer the old behaviour instead. + +MULTILINE_CPP_IS_BRIEF = NO + +# If the INHERIT_DOCS tag is set to YES (the default) then an undocumented +# member inherits the documentation from any documented member that it +# re-implements. + +INHERIT_DOCS = YES + +# If the SEPARATE_MEMBER_PAGES tag is set to YES, then doxygen will produce +# a new page for each member. If set to NO, the documentation of a member will +# be part of the file/class/namespace that contains it. + +SEPARATE_MEMBER_PAGES = NO + +# The TAB_SIZE tag can be used to set the number of spaces in a tab. +# Doxygen uses this value to replace tabs by spaces in code fragments. + +TAB_SIZE = 4 + +# This tag can be used to specify a number of aliases that acts +# as commands in the documentation. An alias has the form "name=value". +# For example adding "sideeffect=\par Side Effects:\n" will allow you to +# put the command \sideeffect (or @sideeffect) in the documentation, which +# will result in a user-defined paragraph with heading "Side Effects:". +# You can put \n's in the value part of an alias to insert newlines. + +ALIASES = + +# Set the OPTIMIZE_OUTPUT_FOR_C tag to YES if your project consists of C +# sources only. Doxygen will then generate output that is more tailored for C. +# For instance, some of the names that are used will be different. The list +# of all members will be omitted, etc. + +OPTIMIZE_OUTPUT_FOR_C = YES + +# Set the OPTIMIZE_OUTPUT_JAVA tag to YES if your project consists of Java +# sources only. Doxygen will then generate output that is more tailored for +# Java. For instance, namespaces will be presented as packages, qualified +# scopes will look different, etc. + +OPTIMIZE_OUTPUT_JAVA = NO + +# Set the OPTIMIZE_FOR_FORTRAN tag to YES if your project consists of Fortran +# sources only. Doxygen will then generate output that is more tailored for +# Fortran. + +OPTIMIZE_FOR_FORTRAN = NO + +# Set the OPTIMIZE_OUTPUT_VHDL tag to YES if your project consists of VHDL +# sources. Doxygen will then generate output that is tailored for +# VHDL. + +OPTIMIZE_OUTPUT_VHDL = NO + +# Doxygen selects the parser to use depending on the extension of the files it parses. +# With this tag you can assign which parser to use for a given extension. +# Doxygen has a built-in mapping, but you can override or extend it using this tag. +# The format is ext=language, where ext is a file extension, and language is one of +# the parsers supported by doxygen: IDL, Java, Javascript, C#, C, C++, D, PHP, +# Objective-C, Python, Fortran, VHDL, C, C++. For instance to make doxygen treat +# .inc files as Fortran files (default is PHP), and .f files as C (default is Fortran), +# use: inc=Fortran f=C. Note that for custom extensions you also need to set FILE_PATTERNS otherwise the files are not read by doxygen. + +EXTENSION_MAPPING = + +# If you use STL classes (i.e. std::string, std::vector, etc.) but do not want +# to include (a tag file for) the STL sources as input, then you should +# set this tag to YES in order to let doxygen match functions declarations and +# definitions whose arguments contain STL classes (e.g. func(std::string); v.s. +# func(std::string) {}). This also make the inheritance and collaboration +# diagrams that involve STL classes more complete and accurate. + +BUILTIN_STL_SUPPORT = NO + +# If you use Microsoft's C++/CLI language, you should set this option to YES to +# enable parsing support. + +CPP_CLI_SUPPORT = NO + +# Set the SIP_SUPPORT tag to YES if your project consists of sip sources only. +# Doxygen will parse them like normal C++ but will assume all classes use public +# instead of private inheritance when no explicit protection keyword is present. + +SIP_SUPPORT = NO + +# For Microsoft's IDL there are propget and propput attributes to indicate getter +# and setter methods for a property. Setting this option to YES (the default) +# will make doxygen to replace the get and set methods by a property in the +# documentation. This will only work if the methods are indeed getting or +# setting a simple type. If this is not the case, or you want to show the +# methods anyway, you should set this option to NO. + +IDL_PROPERTY_SUPPORT = YES + +# If member grouping is used in the documentation and the DISTRIBUTE_GROUP_DOC +# tag is set to YES, then doxygen will reuse the documentation of the first +# member in the group (if any) for the other members of the group. By default +# all members of a group must be documented explicitly. + +DISTRIBUTE_GROUP_DOC = NO + +# Set the SUBGROUPING tag to YES (the default) to allow class member groups of +# the same type (for instance a group of public functions) to be put as a +# subgroup of that type (e.g. under the Public Functions section). Set it to +# NO to prevent subgrouping. Alternatively, this can be done per class using +# the \nosubgrouping command. + +SUBGROUPING = YES + +# When TYPEDEF_HIDES_STRUCT is enabled, a typedef of a struct, union, or enum +# is documented as struct, union, or enum with the name of the typedef. So +# typedef struct TypeS {} TypeT, will appear in the documentation as a struct +# with name TypeT. When disabled the typedef will appear as a member of a file, +# namespace, or class. And the struct will be named TypeS. This can typically +# be useful for C code in case the coding convention dictates that all compound +# types are typedef'ed and only the typedef is referenced, never the tag name. + +TYPEDEF_HIDES_STRUCT = YES + +# The SYMBOL_CACHE_SIZE determines the size of the internal cache use to +# determine which symbols to keep in memory and which to flush to disk. +# When the cache is full, less often used symbols will be written to disk. +# For small to medium size projects (<1000 input files) the default value is +# probably good enough. For larger projects a too small cache size can cause +# doxygen to be busy swapping symbols to and from disk most of the time +# causing a significant performance penality. +# If the system has enough physical memory increasing the cache will improve the +# performance by keeping more symbols in memory. Note that the value works on +# a logarithmic scale so increasing the size by one will rougly double the +# memory usage. The cache size is given by this formula: +# 2^(16+SYMBOL_CACHE_SIZE). The valid range is 0..9, the default is 0, +# corresponding to a cache size of 2^16 = 65536 symbols + +SYMBOL_CACHE_SIZE = 1 + +#--------------------------------------------------------------------------- +# Build related configuration options +#--------------------------------------------------------------------------- + +# If the EXTRACT_ALL tag is set to YES doxygen will assume all entities in +# documentation are documented, even if no documentation was available. +# Private class members and static file members will be hidden unless +# the EXTRACT_PRIVATE and EXTRACT_STATIC tags are set to YES + +EXTRACT_ALL = YES + +# If the EXTRACT_PRIVATE tag is set to YES all private members of a class +# will be included in the documentation. + +EXTRACT_PRIVATE = YES + +# If the EXTRACT_STATIC tag is set to YES all static members of a file +# will be included in the documentation. + +EXTRACT_STATIC = YES + +# If the EXTRACT_LOCAL_CLASSES tag is set to YES classes (and structs) +# defined locally in source files will be included in the documentation. +# If set to NO only classes defined in header files are included. + +EXTRACT_LOCAL_CLASSES = YES + +# This flag is only useful for Objective-C code. When set to YES local +# methods, which are defined in the implementation section but not in +# the interface are included in the documentation. +# If set to NO (the default) only methods in the interface are included. + +EXTRACT_LOCAL_METHODS = NO + +# If this flag is set to YES, the members of anonymous namespaces will be +# extracted and appear in the documentation as a namespace called +# 'anonymous_namespace{file}', where file will be replaced with the base +# name of the file that contains the anonymous namespace. By default +# anonymous namespace are hidden. + +EXTRACT_ANON_NSPACES = NO + +# If the HIDE_UNDOC_MEMBERS tag is set to YES, Doxygen will hide all +# undocumented members of documented classes, files or namespaces. +# If set to NO (the default) these members will be included in the +# various overviews, but no documentation section is generated. +# This option has no effect if EXTRACT_ALL is enabled. + +HIDE_UNDOC_MEMBERS = NO + +# If the HIDE_UNDOC_CLASSES tag is set to YES, Doxygen will hide all +# undocumented classes that are normally visible in the class hierarchy. +# If set to NO (the default) these classes will be included in the various +# overviews. This option has no effect if EXTRACT_ALL is enabled. + +HIDE_UNDOC_CLASSES = NO + +# If the HIDE_FRIEND_COMPOUNDS tag is set to YES, Doxygen will hide all +# friend (class|struct|union) declarations. +# If set to NO (the default) these declarations will be included in the +# documentation. + +HIDE_FRIEND_COMPOUNDS = NO + +# If the HIDE_IN_BODY_DOCS tag is set to YES, Doxygen will hide any +# documentation blocks found inside the body of a function. +# If set to NO (the default) these blocks will be appended to the +# function's detailed documentation block. + +HIDE_IN_BODY_DOCS = NO + +# The INTERNAL_DOCS tag determines if documentation +# that is typed after a \internal command is included. If the tag is set +# to NO (the default) then the documentation will be excluded. +# Set it to YES to include the internal documentation. + +INTERNAL_DOCS = NO + +# If the CASE_SENSE_NAMES tag is set to NO then Doxygen will only generate +# file names in lower-case letters. If set to YES upper-case letters are also +# allowed. This is useful if you have classes or files whose names only differ +# in case and if your file system supports case sensitive file names. Windows +# and Mac users are advised to set this option to NO. + +CASE_SENSE_NAMES = NO + +# If the HIDE_SCOPE_NAMES tag is set to NO (the default) then Doxygen +# will show members with their full class and namespace scopes in the +# documentation. If set to YES the scope will be hidden. + +HIDE_SCOPE_NAMES = NO + +# If the SHOW_INCLUDE_FILES tag is set to YES (the default) then Doxygen +# will put a list of the files that are included by a file in the documentation +# of that file. + +SHOW_INCLUDE_FILES = YES + +# If the FORCE_LOCAL_INCLUDES tag is set to YES then Doxygen +# will list include files with double quotes in the documentation +# rather than with sharp brackets. + +FORCE_LOCAL_INCLUDES = NO + +# If the INLINE_INFO tag is set to YES (the default) then a tag [inline] +# is inserted in the documentation for inline members. + +INLINE_INFO = YES + +# If the SORT_MEMBER_DOCS tag is set to YES (the default) then doxygen +# will sort the (detailed) documentation of file and class members +# alphabetically by member name. If set to NO the members will appear in +# declaration order. + +SORT_MEMBER_DOCS = YES + +# If the SORT_BRIEF_DOCS tag is set to YES then doxygen will sort the +# brief documentation of file, namespace and class members alphabetically +# by member name. If set to NO (the default) the members will appear in +# declaration order. + +SORT_BRIEF_DOCS = NO + +# If the SORT_MEMBERS_CTORS_1ST tag is set to YES then doxygen will sort the (brief and detailed) documentation of class members so that constructors and destructors are listed first. If set to NO (the default) the constructors will appear in the respective orders defined by SORT_MEMBER_DOCS and SORT_BRIEF_DOCS. This tag will be ignored for brief docs if SORT_BRIEF_DOCS is set to NO and ignored for detailed docs if SORT_MEMBER_DOCS is set to NO. + +SORT_MEMBERS_CTORS_1ST = NO + +# If the SORT_GROUP_NAMES tag is set to YES then doxygen will sort the +# hierarchy of group names into alphabetical order. If set to NO (the default) +# the group names will appear in their defined order. + +SORT_GROUP_NAMES = YES + +# If the SORT_BY_SCOPE_NAME tag is set to YES, the class list will be +# sorted by fully-qualified names, including namespaces. If set to +# NO (the default), the class list will be sorted only by class name, +# not including the namespace part. +# Note: This option is not very useful if HIDE_SCOPE_NAMES is set to YES. +# Note: This option applies only to the class list, not to the +# alphabetical list. + +SORT_BY_SCOPE_NAME = NO + +# The GENERATE_TODOLIST tag can be used to enable (YES) or +# disable (NO) the todo list. This list is created by putting \todo +# commands in the documentation. + +GENERATE_TODOLIST = NO + +# The GENERATE_TESTLIST tag can be used to enable (YES) or +# disable (NO) the test list. This list is created by putting \test +# commands in the documentation. + +GENERATE_TESTLIST = NO + +# The GENERATE_BUGLIST tag can be used to enable (YES) or +# disable (NO) the bug list. This list is created by putting \bug +# commands in the documentation. + +GENERATE_BUGLIST = NO + +# The GENERATE_DEPRECATEDLIST tag can be used to enable (YES) or +# disable (NO) the deprecated list. This list is created by putting +# \deprecated commands in the documentation. + +GENERATE_DEPRECATEDLIST= YES + +# The ENABLED_SECTIONS tag can be used to enable conditional +# documentation sections, marked by \if sectionname ... \endif. + +ENABLED_SECTIONS = + +# The MAX_INITIALIZER_LINES tag determines the maximum number of lines +# the initial value of a variable or define consists of for it to appear in +# the documentation. If the initializer consists of more lines than specified +# here it will be hidden. Use a value of 0 to hide initializers completely. +# The appearance of the initializer of individual variables and defines in the +# documentation can be controlled using \showinitializer or \hideinitializer +# command in the documentation regardless of this setting. + +MAX_INITIALIZER_LINES = 30 + +# Set the SHOW_USED_FILES tag to NO to disable the list of files generated +# at the bottom of the documentation of classes and structs. If set to YES the +# list will mention the files that were used to generate the documentation. + +SHOW_USED_FILES = YES + +# If the sources in your project are distributed over multiple directories +# then setting the SHOW_DIRECTORIES tag to YES will show the directory hierarchy +# in the documentation. The default is NO. + +SHOW_DIRECTORIES = YES + +# Set the SHOW_FILES tag to NO to disable the generation of the Files page. +# This will remove the Files entry from the Quick Index and from the +# Folder Tree View (if specified). The default is YES. + +SHOW_FILES = YES + +# Set the SHOW_NAMESPACES tag to NO to disable the generation of the +# Namespaces page. +# This will remove the Namespaces entry from the Quick Index +# and from the Folder Tree View (if specified). The default is YES. + +SHOW_NAMESPACES = YES + +# The FILE_VERSION_FILTER tag can be used to specify a program or script that +# doxygen should invoke to get the current version for each file (typically from +# the version control system). Doxygen will invoke the program by executing (via +# popen()) the command , where is the value of +# the FILE_VERSION_FILTER tag, and is the name of an input file +# provided by doxygen. Whatever the program writes to standard output +# is used as the file version. See the manual for examples. + +FILE_VERSION_FILTER = + +# The LAYOUT_FILE tag can be used to specify a layout file which will be parsed by +# doxygen. The layout file controls the global structure of the generated output files +# in an output format independent way. The create the layout file that represents +# doxygen's defaults, run doxygen with the -l option. You can optionally specify a +# file name after the option, if omitted DoxygenLayout.xml will be used as the name +# of the layout file. + +LAYOUT_FILE = + +#--------------------------------------------------------------------------- +# configuration options related to warning and progress messages +#--------------------------------------------------------------------------- + +# The QUIET tag can be used to turn on/off the messages that are generated +# by doxygen. Possible values are YES and NO. If left blank NO is used. + +QUIET = YES + +# The WARNINGS tag can be used to turn on/off the warning messages that are +# generated by doxygen. Possible values are YES and NO. If left blank +# NO is used. + +WARNINGS = YES + +# If WARN_IF_UNDOCUMENTED is set to YES, then doxygen will generate warnings +# for undocumented members. If EXTRACT_ALL is set to YES then this flag will +# automatically be disabled. + +WARN_IF_UNDOCUMENTED = YES + +# If WARN_IF_DOC_ERROR is set to YES, doxygen will generate warnings for +# potential errors in the documentation, such as not documenting some +# parameters in a documented function, or documenting parameters that +# don't exist or using markup commands wrongly. + +WARN_IF_DOC_ERROR = YES + +# This WARN_NO_PARAMDOC option can be abled to get warnings for +# functions that are documented, but have no documentation for their parameters +# or return value. If set to NO (the default) doxygen will only warn about +# wrong or incomplete parameter documentation, but not about the absence of +# documentation. + +WARN_NO_PARAMDOC = YES + +# The WARN_FORMAT tag determines the format of the warning messages that +# doxygen can produce. The string should contain the $file, $line, and $text +# tags, which will be replaced by the file and line number from which the +# warning originated and the warning text. Optionally the format may contain +# $version, which will be replaced by the version of the file (if it could +# be obtained via FILE_VERSION_FILTER) + +WARN_FORMAT = "$file:$line: $text" + +# The WARN_LOGFILE tag can be used to specify a file to which warning +# and error messages should be written. If left blank the output is written +# to stderr. + +WARN_LOGFILE = + +#--------------------------------------------------------------------------- +# configuration options related to the input files +#--------------------------------------------------------------------------- + +# The INPUT tag can be used to specify the files and/or directories that contain +# documented source files. You may enter file names like "myfile.cpp" or +# directories like "/usr/src/myproject". Separate the files or directories +# with spaces. + +INPUT = ./ + +# This tag can be used to specify the character encoding of the source files +# that doxygen parses. Internally doxygen uses the UTF-8 encoding, which is +# also the default input encoding. Doxygen uses libiconv (or the iconv built +# into libc) for the transcoding. See http://www.gnu.org/software/libiconv for +# the list of possible encodings. + +INPUT_ENCODING = UTF-8 + +# If the value of the INPUT tag contains directories, you can use the +# FILE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp +# and *.h) to filter out the source-files in the directories. If left +# blank the following patterns are tested: +# *.c *.cc *.cxx *.cpp *.c++ *.java *.ii *.ixx *.ipp *.i++ *.inl *.h *.hh *.hxx +# *.hpp *.h++ *.idl *.odl *.cs *.php *.php3 *.inc *.m *.mm *.py *.f90 + +FILE_PATTERNS = *.h \ + *.txt + +# The RECURSIVE tag can be used to turn specify whether or not subdirectories +# should be searched for input files as well. Possible values are YES and NO. +# If left blank NO is used. + +RECURSIVE = YES + +# The EXCLUDE tag can be used to specify files and/or directories that should +# excluded from the INPUT source files. This way you can easily exclude a +# subdirectory from a directory tree whose root is specified with the INPUT tag. + +EXCLUDE = Documentation/ License.txt + +# The EXCLUDE_SYMLINKS tag can be used select whether or not files or +# directories that are symbolic links (a Unix filesystem feature) are excluded +# from the input. + +EXCLUDE_SYMLINKS = NO + +# If the value of the INPUT tag contains directories, you can use the +# EXCLUDE_PATTERNS tag to specify one or more wildcard patterns to exclude +# certain files from those directories. Note that the wildcards are matched +# against the file with absolute path, so to exclude all test directories +# for example use the pattern */test/* + +EXCLUDE_PATTERNS = + +# The EXCLUDE_SYMBOLS tag can be used to specify one or more symbol names +# (namespaces, classes, functions, etc.) that should be excluded from the +# output. The symbol name can be a fully qualified name, a word, or if the +# wildcard * is used, a substring. Examples: ANamespace, AClass, +# AClass::ANamespace, ANamespace::*Test + +EXCLUDE_SYMBOLS = _* __* + +# The EXAMPLE_PATH tag can be used to specify one or more files or +# directories that contain example code fragments that are included (see +# the \include command). + +EXAMPLE_PATH = ../ + +# If the value of the EXAMPLE_PATH tag contains directories, you can use the +# EXAMPLE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp +# and *.h) to filter out the source-files in the directories. If left +# blank all files are included. + +EXAMPLE_PATTERNS = * + +# If the EXAMPLE_RECURSIVE tag is set to YES then subdirectories will be +# searched for input files to be used with the \include or \dontinclude +# commands irrespective of the value of the RECURSIVE tag. +# Possible values are YES and NO. If left blank NO is used. + +EXAMPLE_RECURSIVE = NO + +# The IMAGE_PATH tag can be used to specify one or more files or +# directories that contain image that are included in the documentation (see +# the \image command). + +IMAGE_PATH = ./ + +# The INPUT_FILTER tag can be used to specify a program that doxygen should +# invoke to filter for each input file. Doxygen will invoke the filter program +# by executing (via popen()) the command , where +# is the value of the INPUT_FILTER tag, and is the name of an +# input file. Doxygen will then use the output that the filter program writes +# to standard output. +# If FILTER_PATTERNS is specified, this tag will be +# ignored. + +INPUT_FILTER = + +# The FILTER_PATTERNS tag can be used to specify filters on a per file pattern +# basis. +# Doxygen will compare the file name with each pattern and apply the +# filter if there is a match. +# The filters are a list of the form: +# pattern=filter (like *.cpp=my_cpp_filter). See INPUT_FILTER for further +# info on how filters are used. If FILTER_PATTERNS is empty, INPUT_FILTER +# is applied to all files. + +FILTER_PATTERNS = + +# If the FILTER_SOURCE_FILES tag is set to YES, the input filter (if set using +# INPUT_FILTER) will be used to filter the input files when producing source +# files to browse (i.e. when SOURCE_BROWSER is set to YES). + +FILTER_SOURCE_FILES = NO + +#--------------------------------------------------------------------------- +# configuration options related to source browsing +#--------------------------------------------------------------------------- + +# If the SOURCE_BROWSER tag is set to YES then a list of source files will +# be generated. Documented entities will be cross-referenced with these sources. +# Note: To get rid of all source code in the generated output, make sure also +# VERBATIM_HEADERS is set to NO. + +SOURCE_BROWSER = NO + +# Setting the INLINE_SOURCES tag to YES will include the body +# of functions and classes directly in the documentation. + +INLINE_SOURCES = NO + +# Setting the STRIP_CODE_COMMENTS tag to YES (the default) will instruct +# doxygen to hide any special comment blocks from generated source code +# fragments. Normal C and C++ comments will always remain visible. + +STRIP_CODE_COMMENTS = YES + +# If the REFERENCED_BY_RELATION tag is set to YES +# then for each documented function all documented +# functions referencing it will be listed. + +REFERENCED_BY_RELATION = NO + +# If the REFERENCES_RELATION tag is set to YES +# then for each documented function all documented entities +# called/used by that function will be listed. + +REFERENCES_RELATION = NO + +# If the REFERENCES_LINK_SOURCE tag is set to YES (the default) +# and SOURCE_BROWSER tag is set to YES, then the hyperlinks from +# functions in REFERENCES_RELATION and REFERENCED_BY_RELATION lists will +# link to the source code. +# Otherwise they will link to the documentation. + +REFERENCES_LINK_SOURCE = NO + +# If the USE_HTAGS tag is set to YES then the references to source code +# will point to the HTML generated by the htags(1) tool instead of doxygen +# built-in source browser. The htags tool is part of GNU's global source +# tagging system (see http://www.gnu.org/software/global/global.html). You +# will need version 4.8.6 or higher. + +USE_HTAGS = NO + +# If the VERBATIM_HEADERS tag is set to YES (the default) then Doxygen +# will generate a verbatim copy of the header file for each class for +# which an include is specified. Set to NO to disable this. + +VERBATIM_HEADERS = NO + +#--------------------------------------------------------------------------- +# configuration options related to the alphabetical class index +#--------------------------------------------------------------------------- + +# If the ALPHABETICAL_INDEX tag is set to YES, an alphabetical index +# of all compounds will be generated. Enable this if the project +# contains a lot of classes, structs, unions or interfaces. + +ALPHABETICAL_INDEX = YES + +# If the alphabetical index is enabled (see ALPHABETICAL_INDEX) then +# the COLS_IN_ALPHA_INDEX tag can be used to specify the number of columns +# in which this list will be split (can be a number in the range [1..20]) + +COLS_IN_ALPHA_INDEX = 5 + +# In case all classes in a project start with a common prefix, all +# classes will be put under the same header in the alphabetical index. +# The IGNORE_PREFIX tag can be used to specify one or more prefixes that +# should be ignored while generating the index headers. + +IGNORE_PREFIX = + +#--------------------------------------------------------------------------- +# configuration options related to the HTML output +#--------------------------------------------------------------------------- + +# If the GENERATE_HTML tag is set to YES (the default) Doxygen will +# generate HTML output. + +GENERATE_HTML = YES + +# The HTML_OUTPUT tag is used to specify where the HTML docs will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `html' will be used as the default path. + +HTML_OUTPUT = html + +# The HTML_FILE_EXTENSION tag can be used to specify the file extension for +# each generated HTML page (for example: .htm,.php,.asp). If it is left blank +# doxygen will generate files with .html extension. + +HTML_FILE_EXTENSION = .html + +# The HTML_HEADER tag can be used to specify a personal HTML header for +# each generated HTML page. If it is left blank doxygen will generate a +# standard header. + +HTML_HEADER = + +# The HTML_FOOTER tag can be used to specify a personal HTML footer for +# each generated HTML page. If it is left blank doxygen will generate a +# standard footer. + +HTML_FOOTER = + +# The HTML_STYLESHEET tag can be used to specify a user-defined cascading +# style sheet that is used by each HTML page. It can be used to +# fine-tune the look of the HTML output. If the tag is left blank doxygen +# will generate a default style sheet. Note that doxygen will try to copy +# the style sheet file to the HTML output directory, so don't put your own +# stylesheet in the HTML output directory as well, or it will be erased! + +HTML_STYLESHEET = + +# If the HTML_TIMESTAMP tag is set to YES then the footer of each generated HTML +# page will contain the date and time when the page was generated. Setting +# this to NO can help when comparing the output of multiple runs. + +HTML_TIMESTAMP = NO + +# If the HTML_ALIGN_MEMBERS tag is set to YES, the members of classes, +# files or namespaces will be aligned in HTML using tables. If set to +# NO a bullet list will be used. + +HTML_ALIGN_MEMBERS = YES + +# If the HTML_DYNAMIC_SECTIONS tag is set to YES then the generated HTML +# documentation will contain sections that can be hidden and shown after the +# page has loaded. For this to work a browser that supports +# JavaScript and DHTML is required (for instance Mozilla 1.0+, Firefox +# Netscape 6.0+, Internet explorer 5.0+, Konqueror, or Safari). + +HTML_DYNAMIC_SECTIONS = YES + +# If the GENERATE_DOCSET tag is set to YES, additional index files +# will be generated that can be used as input for Apple's Xcode 3 +# integrated development environment, introduced with OSX 10.5 (Leopard). +# To create a documentation set, doxygen will generate a Makefile in the +# HTML output directory. Running make will produce the docset in that +# directory and running "make install" will install the docset in +# ~/Library/Developer/Shared/Documentation/DocSets so that Xcode will find +# it at startup. +# See http://developer.apple.com/tools/creatingdocsetswithdoxygen.html for more information. + +GENERATE_DOCSET = NO + +# When GENERATE_DOCSET tag is set to YES, this tag determines the name of the +# feed. A documentation feed provides an umbrella under which multiple +# documentation sets from a single provider (such as a company or product suite) +# can be grouped. + +DOCSET_FEEDNAME = "Doxygen generated docs" + +# When GENERATE_DOCSET tag is set to YES, this tag specifies a string that +# should uniquely identify the documentation set bundle. This should be a +# reverse domain-name style string, e.g. com.mycompany.MyDocSet. Doxygen +# will append .docset to the name. + +DOCSET_BUNDLE_ID = org.doxygen.Project + +# If the GENERATE_HTMLHELP tag is set to YES, additional index files +# will be generated that can be used as input for tools like the +# Microsoft HTML help workshop to generate a compiled HTML help file (.chm) +# of the generated HTML documentation. + +GENERATE_HTMLHELP = NO + +# If the GENERATE_HTMLHELP tag is set to YES, the CHM_FILE tag can +# be used to specify the file name of the resulting .chm file. You +# can add a path in front of the file if the result should not be +# written to the html output directory. + +CHM_FILE = ../LUFA.chm + +# If the GENERATE_HTMLHELP tag is set to YES, the HHC_LOCATION tag can +# be used to specify the location (absolute path including file name) of +# the HTML help compiler (hhc.exe). If non-empty doxygen will try to run +# the HTML help compiler on the generated index.hhp. + +HHC_LOCATION = + +# If the GENERATE_HTMLHELP tag is set to YES, the GENERATE_CHI flag +# controls if a separate .chi index file is generated (YES) or that +# it should be included in the master .chm file (NO). + +GENERATE_CHI = NO + +# If the GENERATE_HTMLHELP tag is set to YES, the CHM_INDEX_ENCODING +# is used to encode HtmlHelp index (hhk), content (hhc) and project file +# content. + +CHM_INDEX_ENCODING = + +# If the GENERATE_HTMLHELP tag is set to YES, the BINARY_TOC flag +# controls whether a binary table of contents is generated (YES) or a +# normal table of contents (NO) in the .chm file. + +BINARY_TOC = NO + +# The TOC_EXPAND flag can be set to YES to add extra items for group members +# to the contents of the HTML help documentation and to the tree view. + +TOC_EXPAND = YES + +# If the GENERATE_QHP tag is set to YES and both QHP_NAMESPACE and QHP_VIRTUAL_FOLDER +# are set, an additional index file will be generated that can be used as input for +# Qt's qhelpgenerator to generate a Qt Compressed Help (.qch) of the generated +# HTML documentation. + +GENERATE_QHP = NO + +# If the QHG_LOCATION tag is specified, the QCH_FILE tag can +# be used to specify the file name of the resulting .qch file. +# The path specified is relative to the HTML output folder. + +QCH_FILE = + +# The QHP_NAMESPACE tag specifies the namespace to use when generating +# Qt Help Project output. For more information please see +# http://doc.trolltech.com/qthelpproject.html#namespace + +QHP_NAMESPACE = org.doxygen.Project + +# The QHP_VIRTUAL_FOLDER tag specifies the namespace to use when generating +# Qt Help Project output. For more information please see +# http://doc.trolltech.com/qthelpproject.html#virtual-folders + +QHP_VIRTUAL_FOLDER = doc + +# If QHP_CUST_FILTER_NAME is set, it specifies the name of a custom filter to add. +# For more information please see +# http://doc.trolltech.com/qthelpproject.html#custom-filters + +QHP_CUST_FILTER_NAME = + +# The QHP_CUST_FILT_ATTRS tag specifies the list of the attributes of the custom filter to add.For more information please see +# Qt Help Project / Custom Filters. + +QHP_CUST_FILTER_ATTRS = + +# The QHP_SECT_FILTER_ATTRS tag specifies the list of the attributes this project's +# filter section matches. +# Qt Help Project / Filter Attributes. + +QHP_SECT_FILTER_ATTRS = + +# If the GENERATE_QHP tag is set to YES, the QHG_LOCATION tag can +# be used to specify the location of Qt's qhelpgenerator. +# If non-empty doxygen will try to run qhelpgenerator on the generated +# .qhp file. + +QHG_LOCATION = + +# If the GENERATE_ECLIPSEHELP tag is set to YES, additional index files +# will be generated, which together with the HTML files, form an Eclipse help +# plugin. To install this plugin and make it available under the help contents +# menu in Eclipse, the contents of the directory containing the HTML and XML +# files needs to be copied into the plugins directory of eclipse. The name of +# the directory within the plugins directory should be the same as +# the ECLIPSE_DOC_ID value. After copying Eclipse needs to be restarted before the help appears. + +GENERATE_ECLIPSEHELP = NO + +# A unique identifier for the eclipse help plugin. When installing the plugin +# the directory name containing the HTML and XML files should also have +# this name. + +ECLIPSE_DOC_ID = org.doxygen.Project + +# The DISABLE_INDEX tag can be used to turn on/off the condensed index at +# top of each HTML page. The value NO (the default) enables the index and +# the value YES disables it. + +DISABLE_INDEX = NO + +# This tag can be used to set the number of enum values (range [1..20]) +# that doxygen will group on one line in the generated HTML documentation. + +ENUM_VALUES_PER_LINE = 1 + +# The GENERATE_TREEVIEW tag is used to specify whether a tree-like index +# structure should be generated to display hierarchical information. +# If the tag value is set to YES, a side panel will be generated +# containing a tree-like index structure (just like the one that +# is generated for HTML Help). For this to work a browser that supports +# JavaScript, DHTML, CSS and frames is required (i.e. any modern browser). +# Windows users are probably better off using the HTML help feature. + +GENERATE_TREEVIEW = YES + +# By enabling USE_INLINE_TREES, doxygen will generate the Groups, Directories, +# and Class Hierarchy pages using a tree view instead of an ordered list. + +USE_INLINE_TREES = NO + +# If the treeview is enabled (see GENERATE_TREEVIEW) then this tag can be +# used to set the initial width (in pixels) of the frame in which the tree +# is shown. + +TREEVIEW_WIDTH = 300 + +# Use this tag to change the font size of Latex formulas included +# as images in the HTML documentation. The default is 10. Note that +# when you change the font size after a successful doxygen run you need +# to manually remove any form_*.png images from the HTML output directory +# to force them to be regenerated. + +FORMULA_FONTSIZE = 10 + +# When the SEARCHENGINE tag is enabled doxygen will generate a search box for the HTML output. The underlying search engine uses javascript +# and DHTML and should work on any modern browser. Note that when using HTML help (GENERATE_HTMLHELP), Qt help (GENERATE_QHP), or docsets (GENERATE_DOCSET) there is already a search function so this one should +# typically be disabled. For large projects the javascript based search engine +# can be slow, then enabling SERVER_BASED_SEARCH may provide a better solution. + +SEARCHENGINE = YES + +# When the SERVER_BASED_SEARCH tag is enabled the search engine will be implemented using a PHP enabled web server instead of at the web client using Javascript. Doxygen will generate the search PHP script and index +# file to put on the web server. The advantage of the server based approach is that it scales better to large projects and allows full text search. The disadvances is that it is more difficult to setup +# and does not have live searching capabilities. + +SERVER_BASED_SEARCH = NO + +#--------------------------------------------------------------------------- +# configuration options related to the LaTeX output +#--------------------------------------------------------------------------- + +# If the GENERATE_LATEX tag is set to YES (the default) Doxygen will +# generate Latex output. + +GENERATE_LATEX = NO + +# The LATEX_OUTPUT tag is used to specify where the LaTeX docs will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `latex' will be used as the default path. + +LATEX_OUTPUT = latex + +# The LATEX_CMD_NAME tag can be used to specify the LaTeX command name to be +# invoked. If left blank `latex' will be used as the default command name. +# Note that when enabling USE_PDFLATEX this option is only used for +# generating bitmaps for formulas in the HTML output, but not in the +# Makefile that is written to the output directory. + +LATEX_CMD_NAME = latex + +# The MAKEINDEX_CMD_NAME tag can be used to specify the command name to +# generate index for LaTeX. If left blank `makeindex' will be used as the +# default command name. + +MAKEINDEX_CMD_NAME = makeindex + +# If the COMPACT_LATEX tag is set to YES Doxygen generates more compact +# LaTeX documents. This may be useful for small projects and may help to +# save some trees in general. + +COMPACT_LATEX = NO + +# The PAPER_TYPE tag can be used to set the paper type that is used +# by the printer. Possible values are: a4, a4wide, letter, legal and +# executive. If left blank a4wide will be used. + +PAPER_TYPE = a4wide + +# The EXTRA_PACKAGES tag can be to specify one or more names of LaTeX +# packages that should be included in the LaTeX output. + +EXTRA_PACKAGES = + +# The LATEX_HEADER tag can be used to specify a personal LaTeX header for +# the generated latex document. The header should contain everything until +# the first chapter. If it is left blank doxygen will generate a +# standard header. Notice: only use this tag if you know what you are doing! + +LATEX_HEADER = + +# If the PDF_HYPERLINKS tag is set to YES, the LaTeX that is generated +# is prepared for conversion to pdf (using ps2pdf). The pdf file will +# contain links (just like the HTML output) instead of page references +# This makes the output suitable for online browsing using a pdf viewer. + +PDF_HYPERLINKS = YES + +# If the USE_PDFLATEX tag is set to YES, pdflatex will be used instead of +# plain latex in the generated Makefile. Set this option to YES to get a +# higher quality PDF documentation. + +USE_PDFLATEX = YES + +# If the LATEX_BATCHMODE tag is set to YES, doxygen will add the \\batchmode. +# command to the generated LaTeX files. This will instruct LaTeX to keep +# running if errors occur, instead of asking the user for help. +# This option is also used when generating formulas in HTML. + +LATEX_BATCHMODE = NO + +# If LATEX_HIDE_INDICES is set to YES then doxygen will not +# include the index chapters (such as File Index, Compound Index, etc.) +# in the output. + +LATEX_HIDE_INDICES = NO + +# If LATEX_SOURCE_CODE is set to YES then doxygen will include source code with syntax highlighting in the LaTeX output. Note that which sources are shown also depends on other settings such as SOURCE_BROWSER. + +LATEX_SOURCE_CODE = NO + +#--------------------------------------------------------------------------- +# configuration options related to the RTF output +#--------------------------------------------------------------------------- + +# If the GENERATE_RTF tag is set to YES Doxygen will generate RTF output +# The RTF output is optimized for Word 97 and may not look very pretty with +# other RTF readers or editors. + +GENERATE_RTF = NO + +# The RTF_OUTPUT tag is used to specify where the RTF docs will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `rtf' will be used as the default path. + +RTF_OUTPUT = rtf + +# If the COMPACT_RTF tag is set to YES Doxygen generates more compact +# RTF documents. This may be useful for small projects and may help to +# save some trees in general. + +COMPACT_RTF = NO + +# If the RTF_HYPERLINKS tag is set to YES, the RTF that is generated +# will contain hyperlink fields. The RTF file will +# contain links (just like the HTML output) instead of page references. +# This makes the output suitable for online browsing using WORD or other +# programs which support those fields. +# Note: wordpad (write) and others do not support links. + +RTF_HYPERLINKS = NO + +# Load stylesheet definitions from file. Syntax is similar to doxygen's +# config file, i.e. a series of assignments. You only have to provide +# replacements, missing definitions are set to their default value. + +RTF_STYLESHEET_FILE = + +# Set optional variables used in the generation of an rtf document. +# Syntax is similar to doxygen's config file. + +RTF_EXTENSIONS_FILE = + +#--------------------------------------------------------------------------- +# configuration options related to the man page output +#--------------------------------------------------------------------------- + +# If the GENERATE_MAN tag is set to YES (the default) Doxygen will +# generate man pages + +GENERATE_MAN = NO + +# The MAN_OUTPUT tag is used to specify where the man pages will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `man' will be used as the default path. + +MAN_OUTPUT = man + +# The MAN_EXTENSION tag determines the extension that is added to +# the generated man pages (default is the subroutine's section .3) + +MAN_EXTENSION = .3 + +# If the MAN_LINKS tag is set to YES and Doxygen generates man output, +# then it will generate one additional man file for each entity +# documented in the real man page(s). These additional files +# only source the real man page, but without them the man command +# would be unable to find the correct page. The default is NO. + +MAN_LINKS = NO + +#--------------------------------------------------------------------------- +# configuration options related to the XML output +#--------------------------------------------------------------------------- + +# If the GENERATE_XML tag is set to YES Doxygen will +# generate an XML file that captures the structure of +# the code including all documentation. + +GENERATE_XML = NO + +# The XML_OUTPUT tag is used to specify where the XML pages will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `xml' will be used as the default path. + +XML_OUTPUT = xml + +# The XML_SCHEMA tag can be used to specify an XML schema, +# which can be used by a validating XML parser to check the +# syntax of the XML files. + +XML_SCHEMA = + +# The XML_DTD tag can be used to specify an XML DTD, +# which can be used by a validating XML parser to check the +# syntax of the XML files. + +XML_DTD = + +# If the XML_PROGRAMLISTING tag is set to YES Doxygen will +# dump the program listings (including syntax highlighting +# and cross-referencing information) to the XML output. Note that +# enabling this will significantly increase the size of the XML output. + +XML_PROGRAMLISTING = YES + +#--------------------------------------------------------------------------- +# configuration options for the AutoGen Definitions output +#--------------------------------------------------------------------------- + +# If the GENERATE_AUTOGEN_DEF tag is set to YES Doxygen will +# generate an AutoGen Definitions (see autogen.sf.net) file +# that captures the structure of the code including all +# documentation. Note that this feature is still experimental +# and incomplete at the moment. + +GENERATE_AUTOGEN_DEF = NO + +#--------------------------------------------------------------------------- +# configuration options related to the Perl module output +#--------------------------------------------------------------------------- + +# If the GENERATE_PERLMOD tag is set to YES Doxygen will +# generate a Perl module file that captures the structure of +# the code including all documentation. Note that this +# feature is still experimental and incomplete at the +# moment. + +GENERATE_PERLMOD = NO + +# If the PERLMOD_LATEX tag is set to YES Doxygen will generate +# the necessary Makefile rules, Perl scripts and LaTeX code to be able +# to generate PDF and DVI output from the Perl module output. + +PERLMOD_LATEX = NO + +# If the PERLMOD_PRETTY tag is set to YES the Perl module output will be +# nicely formatted so it can be parsed by a human reader. +# This is useful +# if you want to understand what is going on. +# On the other hand, if this +# tag is set to NO the size of the Perl module output will be much smaller +# and Perl will parse it just the same. + +PERLMOD_PRETTY = YES + +# The names of the make variables in the generated doxyrules.make file +# are prefixed with the string contained in PERLMOD_MAKEVAR_PREFIX. +# This is useful so different doxyrules.make files included by the same +# Makefile don't overwrite each other's variables. + +PERLMOD_MAKEVAR_PREFIX = + +#--------------------------------------------------------------------------- +# Configuration options related to the preprocessor +#--------------------------------------------------------------------------- + +# If the ENABLE_PREPROCESSING tag is set to YES (the default) Doxygen will +# evaluate all C-preprocessor directives found in the sources and include +# files. + +ENABLE_PREPROCESSING = YES + +# If the MACRO_EXPANSION tag is set to YES Doxygen will expand all macro +# names in the source code. If set to NO (the default) only conditional +# compilation will be performed. Macro expansion can be done in a controlled +# way by setting EXPAND_ONLY_PREDEF to YES. + +MACRO_EXPANSION = YES + +# If the EXPAND_ONLY_PREDEF and MACRO_EXPANSION tags are both set to YES +# then the macro expansion is limited to the macros specified with the +# PREDEFINED and EXPAND_AS_DEFINED tags. + +EXPAND_ONLY_PREDEF = YES + +# If the SEARCH_INCLUDES tag is set to YES (the default) the includes files +# in the INCLUDE_PATH (see below) will be search if a #include is found. + +SEARCH_INCLUDES = YES + +# The INCLUDE_PATH tag can be used to specify one or more directories that +# contain include files that are not input files but should be processed by +# the preprocessor. + +INCLUDE_PATH = + +# You can use the INCLUDE_FILE_PATTERNS tag to specify one or more wildcard +# patterns (like *.h and *.hpp) to filter out the header-files in the +# directories. If left blank, the patterns specified with FILE_PATTERNS will +# be used. + +INCLUDE_FILE_PATTERNS = + +# The PREDEFINED tag can be used to specify one or more macro names that +# are defined before the preprocessor is started (similar to the -D option of +# gcc). The argument of the tag is a list of macros of the form: name +# or name=definition (no spaces). If the definition and the = are +# omitted =1 is assumed. To prevent a macro definition from being +# undefined via #undef or recursively expanded use the := operator +# instead of the = operator. + +PREDEFINED = __DOXYGEN__ \ + PROGMEM + +# If the MACRO_EXPANSION and EXPAND_ONLY_PREDEF tags are set to YES then +# this tag can be used to specify a list of macro names that should be expanded. +# The macro definition that is found in the sources will be used. +# Use the PREDEFINED tag if you want to use a different macro definition. + +EXPAND_AS_DEFINED = __CALLBACK_PARAM + +# If the SKIP_FUNCTION_MACROS tag is set to YES (the default) then +# doxygen's preprocessor will remove all function-like macros that are alone +# on a line, have an all uppercase name, and do not end with a semicolon. Such +# function macros are typically used for boiler-plate code, and will confuse +# the parser if not removed. + +SKIP_FUNCTION_MACROS = YES + +#--------------------------------------------------------------------------- +# Configuration::additions related to external references +#--------------------------------------------------------------------------- + +# The TAGFILES option can be used to specify one or more tagfiles. +# Optionally an initial location of the external documentation +# can be added for each tagfile. The format of a tag file without +# this location is as follows: +# +# TAGFILES = file1 file2 ... +# Adding location for the tag files is done as follows: +# +# TAGFILES = file1=loc1 "file2 = loc2" ... +# where "loc1" and "loc2" can be relative or absolute paths or +# URLs. If a location is present for each tag, the installdox tool +# does not have to be run to correct the links. +# Note that each tag file must have a unique name +# (where the name does NOT include the path) +# If a tag file is not located in the directory in which doxygen +# is run, you must also specify the path to the tagfile here. + +TAGFILES = + +# When a file name is specified after GENERATE_TAGFILE, doxygen will create +# a tag file that is based on the input files it reads. + +GENERATE_TAGFILE = + +# If the ALLEXTERNALS tag is set to YES all external classes will be listed +# in the class index. If set to NO only the inherited external classes +# will be listed. + +ALLEXTERNALS = NO + +# If the EXTERNAL_GROUPS tag is set to YES all external groups will be listed +# in the modules index. If set to NO, only the current project's groups will +# be listed. + +EXTERNAL_GROUPS = YES + +# The PERL_PATH should be the absolute path and name of the perl script +# interpreter (i.e. the result of `which perl'). + +PERL_PATH = /usr/bin/perl + +#--------------------------------------------------------------------------- +# Configuration options related to the dot tool +#--------------------------------------------------------------------------- + +# If the CLASS_DIAGRAMS tag is set to YES (the default) Doxygen will +# generate a inheritance diagram (in HTML, RTF and LaTeX) for classes with base +# or super classes. Setting the tag to NO turns the diagrams off. Note that +# this option is superseded by the HAVE_DOT option below. This is only a +# fallback. It is recommended to install and use dot, since it yields more +# powerful graphs. + +CLASS_DIAGRAMS = NO + +# You can define message sequence charts within doxygen comments using the \msc +# command. Doxygen will then run the mscgen tool (see +# http://www.mcternan.me.uk/mscgen/) to produce the chart and insert it in the +# documentation. The MSCGEN_PATH tag allows you to specify the directory where +# the mscgen tool resides. If left empty the tool is assumed to be found in the +# default search path. + +MSCGEN_PATH = + +# If set to YES, the inheritance and collaboration graphs will hide +# inheritance and usage relations if the target is undocumented +# or is not a class. + +HIDE_UNDOC_RELATIONS = YES + +# If you set the HAVE_DOT tag to YES then doxygen will assume the dot tool is +# available from the path. This tool is part of Graphviz, a graph visualization +# toolkit from AT&T and Lucent Bell Labs. The other options in this section +# have no effect if this option is set to NO (the default) + +HAVE_DOT = NO + +# By default doxygen will write a font called FreeSans.ttf to the output +# directory and reference it in all dot files that doxygen generates. This +# font does not include all possible unicode characters however, so when you need +# these (or just want a differently looking font) you can specify the font name +# using DOT_FONTNAME. You need need to make sure dot is able to find the font, +# which can be done by putting it in a standard location or by setting the +# DOTFONTPATH environment variable or by setting DOT_FONTPATH to the directory +# containing the font. + +DOT_FONTNAME = FreeSans + +# The DOT_FONTSIZE tag can be used to set the size of the font of dot graphs. +# The default size is 10pt. + +DOT_FONTSIZE = 10 + +# By default doxygen will tell dot to use the output directory to look for the +# FreeSans.ttf font (which doxygen will put there itself). If you specify a +# different font using DOT_FONTNAME you can set the path where dot +# can find it using this tag. + +DOT_FONTPATH = + +# If the CLASS_GRAPH and HAVE_DOT tags are set to YES then doxygen +# will generate a graph for each documented class showing the direct and +# indirect inheritance relations. Setting this tag to YES will force the +# the CLASS_DIAGRAMS tag to NO. + +CLASS_GRAPH = NO + +# If the COLLABORATION_GRAPH and HAVE_DOT tags are set to YES then doxygen +# will generate a graph for each documented class showing the direct and +# indirect implementation dependencies (inheritance, containment, and +# class references variables) of the class with other documented classes. + +COLLABORATION_GRAPH = NO + +# If the GROUP_GRAPHS and HAVE_DOT tags are set to YES then doxygen +# will generate a graph for groups, showing the direct groups dependencies + +GROUP_GRAPHS = YES + +# If the UML_LOOK tag is set to YES doxygen will generate inheritance and +# collaboration diagrams in a style similar to the OMG's Unified Modeling +# Language. + +UML_LOOK = NO + +# If set to YES, the inheritance and collaboration graphs will show the +# relations between templates and their instances. + +TEMPLATE_RELATIONS = NO + +# If the ENABLE_PREPROCESSING, SEARCH_INCLUDES, INCLUDE_GRAPH, and HAVE_DOT +# tags are set to YES then doxygen will generate a graph for each documented +# file showing the direct and indirect include dependencies of the file with +# other documented files. + +INCLUDE_GRAPH = YES + +# If the ENABLE_PREPROCESSING, SEARCH_INCLUDES, INCLUDED_BY_GRAPH, and +# HAVE_DOT tags are set to YES then doxygen will generate a graph for each +# documented header file showing the documented files that directly or +# indirectly include this file. + +INCLUDED_BY_GRAPH = YES + +# If the CALL_GRAPH and HAVE_DOT options are set to YES then +# doxygen will generate a call dependency graph for every global function +# or class method. Note that enabling this option will significantly increase +# the time of a run. So in most cases it will be better to enable call graphs +# for selected functions only using the \callgraph command. + +CALL_GRAPH = NO + +# If the CALLER_GRAPH and HAVE_DOT tags are set to YES then +# doxygen will generate a caller dependency graph for every global function +# or class method. Note that enabling this option will significantly increase +# the time of a run. So in most cases it will be better to enable caller +# graphs for selected functions only using the \callergraph command. + +CALLER_GRAPH = NO + +# If the GRAPHICAL_HIERARCHY and HAVE_DOT tags are set to YES then doxygen +# will graphical hierarchy of all classes instead of a textual one. + +GRAPHICAL_HIERARCHY = NO + +# If the DIRECTORY_GRAPH, SHOW_DIRECTORIES and HAVE_DOT tags are set to YES +# then doxygen will show the dependencies a directory has on other directories +# in a graphical way. The dependency relations are determined by the #include +# relations between the files in the directories. + +DIRECTORY_GRAPH = YES + +# The DOT_IMAGE_FORMAT tag can be used to set the image format of the images +# generated by dot. Possible values are png, jpg, or gif +# If left blank png will be used. + +DOT_IMAGE_FORMAT = png + +# The tag DOT_PATH can be used to specify the path where the dot tool can be +# found. If left blank, it is assumed the dot tool can be found in the path. + +DOT_PATH = + +# The DOTFILE_DIRS tag can be used to specify one or more directories that +# contain dot files that are included in the documentation (see the +# \dotfile command). + +DOTFILE_DIRS = + +# The DOT_GRAPH_MAX_NODES tag can be used to set the maximum number of +# nodes that will be shown in the graph. If the number of nodes in a graph +# becomes larger than this value, doxygen will truncate the graph, which is +# visualized by representing a node as a red box. Note that doxygen if the +# number of direct children of the root node in a graph is already larger than +# DOT_GRAPH_MAX_NODES then the graph will not be shown at all. Also note +# that the size of a graph can be further restricted by MAX_DOT_GRAPH_DEPTH. + +DOT_GRAPH_MAX_NODES = 15 + +# The MAX_DOT_GRAPH_DEPTH tag can be used to set the maximum depth of the +# graphs generated by dot. A depth value of 3 means that only nodes reachable +# from the root by following a path via at most 3 edges will be shown. Nodes +# that lay further from the root node will be omitted. Note that setting this +# option to 1 or 2 may greatly reduce the computation time needed for large +# code bases. Also note that the size of a graph can be further restricted by +# DOT_GRAPH_MAX_NODES. Using a depth of 0 means no depth restriction. + +MAX_DOT_GRAPH_DEPTH = 2 + +# Set the DOT_TRANSPARENT tag to YES to generate images with a transparent +# background. This is disabled by default, because dot on Windows does not +# seem to support this out of the box. Warning: Depending on the platform used, +# enabling this option may lead to badly anti-aliased labels on the edges of +# a graph (i.e. they become hard to read). + +DOT_TRANSPARENT = YES + +# Set the DOT_MULTI_TARGETS tag to YES allow dot to generate multiple output +# files in one run (i.e. multiple -o and -T options on the command line). This +# makes dot run faster, but since only newer versions of dot (>1.8.10) +# support this, this feature is disabled by default. + +DOT_MULTI_TARGETS = NO + +# If the GENERATE_LEGEND tag is set to YES (the default) Doxygen will +# generate a legend page explaining the meaning of the various boxes and +# arrows in the dot generated graphs. + +GENERATE_LEGEND = YES + +# If the DOT_CLEANUP tag is set to YES (the default) Doxygen will +# remove the intermediate dot files that are used to generate +# the various graphs. + +DOT_CLEANUP = YES diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/DriverStubs/Buttons.h b/Tools/ArduPPM/ATMega32U2/LUFA/DriverStubs/Buttons.h new file mode 100644 index 0000000000..c92577a443 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/DriverStubs/Buttons.h @@ -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 + #include + + // 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 diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/DriverStubs/Dataflash.h b/Tools/ArduPPM/ATMega32U2/LUFA/DriverStubs/Dataflash.h new file mode 100644 index 0000000000..0df9ea11c0 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/DriverStubs/Dataflash.h @@ -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 diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/DriverStubs/Joystick.h b/Tools/ArduPPM/ATMega32U2/LUFA/DriverStubs/Joystick.h new file mode 100644 index 0000000000..4e7040a423 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/DriverStubs/Joystick.h @@ -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 + + // 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 diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/DriverStubs/LEDs.h b/Tools/ArduPPM/ATMega32U2/LUFA/DriverStubs/LEDs.h new file mode 100644 index 0000000000..04744de768 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/DriverStubs/LEDs.h @@ -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 + + // 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 diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/ATAVRUSBRF01/Buttons.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/ATAVRUSBRF01/Buttons.h new file mode 100644 index 0000000000..8859d39593 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/ATAVRUSBRF01/Buttons.h @@ -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 + #include + + #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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/ATAVRUSBRF01/LEDs.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/ATAVRUSBRF01/LEDs.h new file mode 100644 index 0000000000..b0fa0f66c6 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/ATAVRUSBRF01/LEDs.h @@ -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 + + #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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/BENITO/Buttons.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/BENITO/Buttons.h new file mode 100644 index 0000000000..5044d1eaee --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/BENITO/Buttons.h @@ -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 + #include + + #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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/BENITO/LEDs.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/BENITO/LEDs.h new file mode 100644 index 0000000000..37c1387d2d --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/BENITO/LEDs.h @@ -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 + +/* 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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/BUMBLEB/Buttons.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/BUMBLEB/Buttons.h new file mode 100644 index 0000000000..4494d928a9 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/BUMBLEB/Buttons.h @@ -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 + #include + + #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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/BUMBLEB/Joystick.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/BUMBLEB/Joystick.h new file mode 100644 index 0000000000..94465c89c9 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/BUMBLEB/Joystick.h @@ -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 + + #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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/BUMBLEB/LEDs.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/BUMBLEB/LEDs.h new file mode 100644 index 0000000000..1453da4d7b --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/BUMBLEB/LEDs.h @@ -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 + + #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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/Buttons.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/Buttons.h new file mode 100644 index 0000000000..02550a1db4 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/Buttons.h @@ -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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/Dataflash.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/Dataflash.h new file mode 100644 index 0000000000..92eae7a8f8 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/Dataflash.h @@ -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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/EVK527/AT45DB321C.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/EVK527/AT45DB321C.h new file mode 100644 index 0000000000..7f34c77d86 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/EVK527/AT45DB321C.h @@ -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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/EVK527/Buttons.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/EVK527/Buttons.h new file mode 100644 index 0000000000..d37d4de27a --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/EVK527/Buttons.h @@ -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 + #include + + #include "../../../Common/Common.h" + + /* Includes: */ + #include + #include + + #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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/EVK527/Dataflash.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/EVK527/Dataflash.h new file mode 100644 index 0000000000..4440d76ba7 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/EVK527/Dataflash.h @@ -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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/EVK527/Joystick.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/EVK527/Joystick.h new file mode 100644 index 0000000000..855270564a --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/EVK527/Joystick.h @@ -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 + + #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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/EVK527/LEDs.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/EVK527/LEDs.h new file mode 100644 index 0000000000..7612ba060a --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/EVK527/LEDs.h @@ -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 + + #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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/JMDBU2/Buttons.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/JMDBU2/Buttons.h new file mode 100644 index 0000000000..ac2954ce43 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/JMDBU2/Buttons.h @@ -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 + #include + + #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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/JMDBU2/LEDs.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/JMDBU2/LEDs.h new file mode 100644 index 0000000000..1acf2a9f46 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/JMDBU2/LEDs.h @@ -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 + + #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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/Joystick.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/Joystick.h new file mode 100644 index 0000000000..4119a9be5a --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/Joystick.h @@ -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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/LEDs.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/LEDs.h new file mode 100644 index 0000000000..b8e45559f4 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/LEDs.h @@ -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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/RZUSBSTICK/LEDs.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/RZUSBSTICK/LEDs.h new file mode 100644 index 0000000000..6abd0e3a3c --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/RZUSBSTICK/LEDs.h @@ -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 + + #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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/STK525/AT45DB321C.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/STK525/AT45DB321C.h new file mode 100644 index 0000000000..de1f73ee95 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/STK525/AT45DB321C.h @@ -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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/STK525/Buttons.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/STK525/Buttons.h new file mode 100644 index 0000000000..208f8caca8 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/STK525/Buttons.h @@ -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 + #include + + #include "../../../Common/Common.h" + + /* Includes: */ + #include + #include + + #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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/STK525/Dataflash.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/STK525/Dataflash.h new file mode 100644 index 0000000000..2a1f707140 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/STK525/Dataflash.h @@ -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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/STK525/Joystick.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/STK525/Joystick.h new file mode 100644 index 0000000000..dd775b73bb --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/STK525/Joystick.h @@ -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 + + #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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/STK525/LEDs.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/STK525/LEDs.h new file mode 100644 index 0000000000..d2d1bbb2c3 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/STK525/LEDs.h @@ -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 + + #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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/STK526/AT45DB642D.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/STK526/AT45DB642D.h new file mode 100644 index 0000000000..1913cde093 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/STK526/AT45DB642D.h @@ -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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/STK526/Buttons.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/STK526/Buttons.h new file mode 100644 index 0000000000..0ab686cbda --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/STK526/Buttons.h @@ -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 + #include + + #include "../../../Common/Common.h" + + /* Includes: */ + #include + #include + + #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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/STK526/Dataflash.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/STK526/Dataflash.h new file mode 100644 index 0000000000..cb412440c1 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/STK526/Dataflash.h @@ -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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/STK526/Joystick.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/STK526/Joystick.h new file mode 100644 index 0000000000..4cea565cd9 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/STK526/Joystick.h @@ -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 + + #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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/STK526/LEDs.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/STK526/LEDs.h new file mode 100644 index 0000000000..2d20e54667 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/STK526/LEDs.h @@ -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 + + #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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/TEENSY/LEDs.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/TEENSY/LEDs.h new file mode 100644 index 0000000000..be6640ca29 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/TEENSY/LEDs.h @@ -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 + + #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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/Temperature.c b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/Temperature.c new file mode 100644 index 0000000000..a5e82a2a1f --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/Temperature.c @@ -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; +} diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/Temperature.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/Temperature.h new file mode 100644 index 0000000000..d07446a675 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/Temperature.h @@ -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 (Makefile source module name: LUFA_SRC_TEMPERATURE) + * + * \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 + + #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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/USBKEY/AT45DB642D.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/USBKEY/AT45DB642D.h new file mode 100644 index 0000000000..a37ddf68ac --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/USBKEY/AT45DB642D.h @@ -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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/USBKEY/Buttons.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/USBKEY/Buttons.h new file mode 100644 index 0000000000..e926fe623c --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/USBKEY/Buttons.h @@ -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 + #include + + #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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/USBKEY/Dataflash.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/USBKEY/Dataflash.h new file mode 100644 index 0000000000..27ff34e076 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/USBKEY/Dataflash.h @@ -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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/USBKEY/Joystick.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/USBKEY/Joystick.h new file mode 100644 index 0000000000..0b2fa456e7 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/USBKEY/Joystick.h @@ -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 + + #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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/USBKEY/LEDs.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/USBKEY/LEDs.h new file mode 100644 index 0000000000..86981f5236 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/USBKEY/LEDs.h @@ -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 + + #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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/USBTINYMKII/Buttons.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/USBTINYMKII/Buttons.h new file mode 100644 index 0000000000..c922518a35 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/USBTINYMKII/Buttons.h @@ -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 + #include + + #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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/USBTINYMKII/LEDs.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/USBTINYMKII/LEDs.h new file mode 100644 index 0000000000..b0383a64a4 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/USBTINYMKII/LEDs.h @@ -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 + + /* 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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/XPLAIN/AT45DB642D.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/XPLAIN/AT45DB642D.h new file mode 100644 index 0000000000..97f94e0513 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/XPLAIN/AT45DB642D.h @@ -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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/XPLAIN/Dataflash.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/XPLAIN/Dataflash.h new file mode 100644 index 0000000000..c1b8cd6728 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/XPLAIN/Dataflash.h @@ -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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/XPLAIN/LEDs.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/XPLAIN/LEDs.h new file mode 100644 index 0000000000..00f7bc2a34 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Board/XPLAIN/LEDs.h @@ -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 + + #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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Misc/TerminalCodes.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Misc/TerminalCodes.h new file mode 100644 index 0000000000..ec35d1262c --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Misc/TerminalCodes.h @@ -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 + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Peripheral/ADC.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Peripheral/ADC.h new file mode 100644 index 0000000000..24997f5835 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Peripheral/ADC.h @@ -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 diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Peripheral/AVRU4U6U7/ADC.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Peripheral/AVRU4U6U7/ADC.h new file mode 100644 index 0000000000..ed42b34e94 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Peripheral/AVRU4U6U7/ADC.h @@ -0,0 +1,391 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief ADC peripheral driver for the U7, U6 and U4 USB AVRs. + * + * ADC driver for the AT90USB1287, AT90USB1286, AT90USB647, AT90USB646, ATMEGA16U4 and ATMEGA32U4 AVRs. + * + * \note This file should not be included directly. It is automatically included as needed by the ADC driver + * dispatch header located in LUFA/Drivers/Peripheral/ADC.h. + */ + +/** \ingroup Group_ADC + * @defgroup Group_ADC_AVRU4U6U7 Series U4, U6 and U7 Model ADC Driver + * + * ADC driver for the AT90USB1287, AT90USB1286, AT90USB647, AT90USB646, ATMEGA16U4 and ATMEGA32U4 AVRs. + * + * \note This file should not be included directly. It is automatically included as needed by the ADC driver + * dispatch header located in LUFA/Drivers/Peripheral/ADC.h. + * + * @{ + */ + +#ifndef __ADC_AVRU4U6U7_H__ +#define __ADC_AVRU4U6U7_H__ + + /* Includes: */ + #include "../../../Common/Common.h" + + #include + #include + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_ADC_H) + #error Do not include this file directly. Include LUFA/Drivers/Peripheral/ADC.h instead. + #endif + + /* Public Interface - May be used in end-application: */ + /* Macros: */ + /** Reference mask, for using the voltage present at the AVR's AREF pin for the ADC reference. */ + #define ADC_REFERENCE_AREF 0 + + /** Reference mask, for using the voltage present at the AVR's AVCC pin for the ADC reference. */ + #define ADC_REFERENCE_AVCC (1 << REFS0) + + /** Reference mask, for using the internally generated 2.56V reference voltage as the ADC reference. */ + #define ADC_REFERENCE_INT2560MV ((1 << REFS1) | (1 << REFS0)) + + /** Left-adjusts the 10-bit ADC result, so that the upper 8 bits of the value returned by the + * ADC_GetResult() macro contain the 8 most significant bits of the result. */ + #define ADC_LEFT_ADJUSTED (1 << ADLAR) + + /** Right-adjusts the 10-bit ADC result, so that the lower 8 bits of the value returned by the + * ADC_GetResult() macro contain the 8 least significant bits of the result. */ + #define ADC_RIGHT_ADJUSTED (0 << ADLAR) + + /** Sets the ADC mode to free running, so that conversions take place continuously as fast as the ADC + * is capable of at the given input clock speed. */ + #define ADC_FREE_RUNNING (1 << ADATE) + + /** Sets the ADC mode to single conversion, so that only a single conversion will take place before + * the ADC returns to idle. */ + #define ADC_SINGLE_CONVERSION (0 << ADATE) + + /** Sets the ADC input clock to prescale by a factor of 2 the AVR's system clock. */ + #define ADC_PRESCALE_2 (1 << ADPS0) + + /** Sets the ADC input clock to prescale by a factor of 4 the AVR's system clock. */ + #define ADC_PRESCALE_4 (1 << ADPS1) + + /** Sets the ADC input clock to prescale by a factor of 8 the AVR's system clock. */ + #define ADC_PRESCALE_8 ((1 << ADPS0) | (1 << ADPS1)) + + /** Sets the ADC input clock to prescale by a factor of 16 the AVR's system clock. */ + #define ADC_PRESCALE_16 (1 << ADPS2) + + /** Sets the ADC input clock to prescale by a factor of 32 the AVR's system clock. */ + #define ADC_PRESCALE_32 ((1 << ADPS2) | (1 << ADPS0)) + + /** Sets the ADC input clock to prescale by a factor of 64 the AVR's system clock. */ + #define ADC_PRESCALE_64 ((1 << ADPS2) | (1 << ADPS1)) + + /** Sets the ADC input clock to prescale by a factor of 128 the AVR's system clock. */ + #define ADC_PRESCALE_128 ((1 << ADPS2) | (1 << ADPS1) | (1 << ADPS0)) + + //@{ + /** MUX mask define for the ADC0 channel of the ADC. See \ref ADC_StartReading and \ref ADC_GetChannelReading. */ + #define ADC_CHANNEL0 (0x00 << MUX0) + + /** MUX mask define for the ADC1 channel of the ADC. See \ref ADC_StartReading and \ref ADC_GetChannelReading. */ + #define ADC_CHANNEL1 (0x01 << MUX0) + + #if !(defined(__AVR_ATmega16U4__) || defined(__AVR_ATmega32U4__) || defined(__DOXYGEN__)) + /** MUX mask define for the ADC2 channel of the ADC. See \ref ADC_StartReading and \ref ADC_GetChannelReading. + * + * \note Not available on all AVR models. + */ + #define ADC_CHANNEL2 (0x02 << MUX0) + + /** MUX mask define for the ADC3 channel of the ADC. See \ref ADC_StartReading and \ref ADC_GetChannelReading. + * + * \note Not available on all AVR models. + */ + #define ADC_CHANNEL3 (0x03 << MUX0) + #endif + + /** MUX mask define for the ADC4 channel of the ADC. See \ref ADC_StartReading and \ref ADC_GetChannelReading. */ + #define ADC_CHANNEL4 (0x04 << MUX0) + + /** MUX mask define for the ADC5 channel of the ADC. See \ref ADC_StartReading and \ref ADC_GetChannelReading. */ + #define ADC_CHANNEL5 (0x05 << MUX0) + + /** MUX mask define for the ADC6 channel of the ADC. See \ref ADC_StartReading and \ref ADC_GetChannelReading. */ + #define ADC_CHANNEL6 (0x06 << MUX0) + + /** MUX mask define for the ADC7 channel of the ADC. See \ref ADC_StartReading and \ref ADC_GetChannelReading. */ + #define ADC_CHANNEL7 (0x07 << MUX0) + + /** MUX mask define for the internal 1.1V bandgap channel of the ADC. See \ref ADC_StartReading and \ref ADC_GetChannelReading. */ + #define ADC_1100MV_BANDGAP (0x1E << MUX0) + + #if (defined(__AVR_ATmega16U4__) || defined(__AVR_ATmega32U4__) || defined(__DOXYGEN__)) + /** MUX mask define for the ADC8 channel of the ADC. See \ref ADC_StartReading and \ref ADC_GetChannelReading. + * + * \note Not available on all AVR models. + */ + #define ADC_CHANNEL8 ((1 << 8) | (0x00 << MUX0)) + + /** MUX mask define for the ADC9 channel of the ADC. See \ref ADC_StartReading and \ref ADC_GetChannelReading. + * + * \note Not available on all AVR models. + */ + #define ADC_CHANNEL9 ((1 << 8) | (0x01 << MUX0)) + + /** MUX mask define for the ADC10 channel of the ADC. See \ref ADC_StartReading and \ref ADC_GetChannelReading. + * + * \note Not available on all AVR models. + */ + #define ADC_CHANNEL10 ((1 << 8) | (0x02 << MUX0)) + + /** MUX mask define for the ADC11 channel of the ADC. See \ref ADC_StartReading and \ref ADC_GetChannelReading. + * + * \note Not available on all AVR models. + */ + #define ADC_CHANNEL11 ((1 << 8) | (0x03 << MUX0)) + + /** MUX mask define for the ADC12 channel of the ADC. See \ref ADC_StartReading and \ref ADC_GetChannelReading. + * + * \note Not available on all AVR models. + */ + #define ADC_CHANNEL12 ((1 << 8) | (0x04 << MUX0)) + + /** MUX mask define for the ADC13 channel of the ADC. See \ref ADC_StartReading and \ref ADC_GetChannelReading. + * + * \note Not available on all AVR models. + */ + #define ADC_CHANNEL13 ((1 << 8) | (0x05 << MUX0)) + + /** MUX mask define for the internal temperature sensor channel of the ADC. See \ref ADC_StartReading and + * \ref ADC_GetChannelReading. + * + * \note Not available on all AVR models. + */ + #define ADC_INT_TEMP_SENS ((1 << 8) | (0x07 << MUX0)) + #endif + //@} + + /* Inline Functions: */ + /** Configures the given ADC channel, ready for ADC conversions. This function sets the + * associated port pin as an input and disables the digital portion of the I/O to reduce + * power consumption. + * + * \note This must only be called for ADC channels with are connected to a physical port + * pin of the AVR, denoted by its special alternative function ADCx. + * \n\n + * + * \note The channel number must be specified as an integer, and NOT a ADC_CHANNELx mask. + * + * \param[in] Channel ADC channel number to set up for conversions. + */ + static inline void ADC_SetupChannel(const uint8_t Channel) + { + #if (defined(__AVR_AT90USB1286__) || defined(__AVR_AT90USB646__) || \ + defined(__AVR_AT90USB1287__) || defined(__AVR_AT90USB647__) || \ + defined(__AVR_ATmega32U6__)) + DDRF &= ~(1 << Channel); + DIDR0 |= (1 << Channel); + #elif (defined(__AVR_ATmega16U4__) || defined(__AVR_ATmega32U4__)) + if (Channel < 8) + { + DDRF &= ~(1 << Channel); + DIDR0 |= (1 << Channel); + } + else if (Channel == 8) + { + DDRD &= ~(1 << 4); + DIDR2 |= (1 << 0); + } + else if (Channel < 11) + { + DDRD &= ~(1 << (Channel - 3)); + DIDR2 |= (1 << (Channel - 8)); + } + else + { + DDRB &= ~(1 << (Channel - 7)); + DIDR2 |= (1 << (Channel - 8)); + } + #endif + } + + /** De-configures the given ADC channel, re-enabling digital I/O mode instead of analog. This + * function sets the associated port pin as an input and re-enabled the digital portion of + * the I/O. + * + * \note This must only be called for ADC channels with are connected to a physical port + * pin of the AVR, denoted by its special alternative function ADCx. + * \n\n + * + * \note The channel number must be specified as an integer, and NOT a ADC_CHANNELx mask. + * + * \param[in] Channel ADC channel number to set up for conversions. + */ + static inline void ADC_DisableChannel(const uint8_t Channel) + { + #if (defined(__AVR_AT90USB1286__) || defined(__AVR_AT90USB646__) || \ + defined(__AVR_AT90USB1287__) || defined(__AVR_AT90USB647__) || \ + defined(__AVR_ATmega32U6__)) + DDRF &= ~(1 << Channel); + DIDR0 &= ~(1 << Channel); + #elif (defined(__AVR_ATmega16U4__) || defined(__AVR_ATmega32U4__)) + if (Channel < 8) + { + DDRF &= ~(1 << Channel); + DIDR0 &= ~(1 << Channel); + } + else if (Channel == 8) + { + DDRD &= ~(1 << 4); + DIDR2 &= ~(1 << 0); + } + else if (Channel < 11) + { + DDRD &= ~(1 << (Channel - 3)); + DIDR2 &= ~(1 << (Channel - 8)); + } + else + { + DDRB &= ~(1 << (Channel - 7)); + DIDR2 &= ~(1 << (Channel - 8)); + } + #endif + } + + /** Starts the reading of the given channel, but does not wait until the conversion has completed. + * Once executed, the conversion status can be determined via the \ref ADC_IsReadingComplete() macro and + * the result read via the \ref ADC_GetResult() macro. + * + * If the ADC has been initialized in free running mode, calling this function once will begin the repeated + * conversions. If the ADC is in single conversion mode (or the channel to convert from is to be changed), + * this function must be called each time a conversion is to take place. + * + * \param[in] MUXMask Mask comprising of an ADC channel mask, reference mask and adjustment mask. + */ + static inline void ADC_StartReading(const uint16_t MUXMask) + { + ADMUX = MUXMask; + + #if (defined(__AVR_ATmega16U4__) || defined(__AVR_ATmega32U4__) || defined(__DOXYGEN__)) + if (MUXMask & (1 << 8)) + ADCSRB |= (1 << MUX5); + else + ADCSRB &= ~(1 << MUX5); + #endif + + ADCSRA |= (1 << ADSC); + } + + /** Indicates if the current ADC conversion is completed, or still in progress. + * + * \return Boolean false if the reading is still taking place, or true if the conversion is + * complete and ready to be read out with \ref ADC_GetResult(). + */ + static inline bool ADC_IsReadingComplete(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline bool ADC_IsReadingComplete(void) + { + return ((ADCSRA & (1 << ADIF)) ? true : false); + } + + /** Retrieves the conversion value of the last completed ADC conversion and clears the reading + * completion flag. + * + * \return The result of the last ADC conversion as an unsigned value. + */ + static inline uint16_t ADC_GetResult(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline uint16_t ADC_GetResult(void) + { + ADCSRA |= (1 << ADIF); + return ADC; + } + + /** Performs a complete single reading from channel, including a polling spin-loop to wait for the + * conversion to complete, and the returning of the converted value. + * + * \note For free running mode, the automated conversions should be initialized with a single call + * to \ref ADC_StartReading() to select the channel and begin the automated conversions, and + * the results read directly from the \ref ADC_GetResult() instead to reduce overhead. + * + * \param[in] MUXMask Mask comprising of an ADC channel mask, reference mask and adjustment mask. + */ + static inline uint16_t ADC_GetChannelReading(const uint16_t MUXMask) ATTR_WARN_UNUSED_RESULT; + static inline uint16_t ADC_GetChannelReading(const uint16_t MUXMask) + { + ADC_StartReading(MUXMask); + + while (!(ADC_IsReadingComplete())); + + return ADC_GetResult(); + } + + /** Initialises the ADC, ready for conversions. This must be called before any other ADC operations. + * The "mode" parameter should be a mask comprised of a conversion mode (free running or single) and + * prescaler masks. + * + * \param[in] Mode Mask of ADC settings, including adjustment, prescale, mode and reference. + */ + static inline void ADC_Init(uint8_t Mode) ATTR_ALWAYS_INLINE; + static inline void ADC_Init(uint8_t Mode) + { + ADCSRA = ((1 << ADEN) | Mode); + } + + /** Turns off the ADC. If this is called, any further ADC operations will require a call to + * \ref ADC_Init() before the ADC can be used again. + */ + static inline void ADC_ShutDown(void) ATTR_ALWAYS_INLINE; + static inline void ADC_ShutDown(void) + { + ADCSRA = 0; + } + + /** Indicates if the ADC is currently enabled. + * + * \return Boolean true if the ADC subsystem is currently enabled, false otherwise. + */ + static inline bool ADC_GetStatus(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline bool ADC_GetStatus(void) + { + return ((ADCSRA & (1 << ADEN)) ? true : false); + } + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Peripheral/AVRU4U6U7/TWI.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Peripheral/AVRU4U6U7/TWI.h new file mode 100644 index 0000000000..5111059851 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Peripheral/AVRU4U6U7/TWI.h @@ -0,0 +1,154 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief TWI peripheral driver for the U7, U6 and U4 USB AVRs. + * + * Master mode TWI driver for the AT90USB1287, AT90USB1286, AT90USB647, AT90USB646, ATMEGA16U4 and ATMEGA32U4 AVRs. + * + * \note This file should not be included directly. It is automatically included as needed by the TWI driver + * dispatch header located in LUFA/Drivers/Peripheral/TWI.h. + */ + +/** \ingroup Group_TWI + * @defgroup Group_TWI_AVRU4U6U7 Series U4, U6 and U7 Model TWI Driver + * + * Master mode TWI driver for the AT90USB1287, AT90USB1286, AT90USB647, AT90USB646, ATMEGA16U4 and ATMEGA32U4 AVRs. + * + * \note This file should not be included directly. It is automatically included as needed by the TWI driver + * dispatch header located in LUFA/Drivers/Peripheral/TWI.h. + * + * @{ + */ + +#ifndef __TWI_AVRU4U6U7_H__ +#define __TWI_AVRU4U6U7_H__ + + /* Includes: */ + #include "../../../Common/Common.h" + + #include + #include + #include + #include + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_TWI_H) + #error Do not include this file directly. Include LUFA/Drivers/Peripheral/TWI.h instead. + #endif + + /* Public Interface - May be used in end-application: */ + /* Inline Functions: */ + /** Initialises the TWI hardware into master mode, ready for data transmission and reception. This must be + * before any other TWI operations. + */ + static inline void TWI_Init(void) ATTR_ALWAYS_INLINE; + static inline void TWI_Init(void) + { + TWCR |= (1 << TWEN); + } + + /** Turns off the TWI driver hardware. If this is called, any further TWI operations will require a call to + * \ref TWI_Init() before the TWI can be used again. + */ + static inline void TWI_ShutDown(void) ATTR_ALWAYS_INLINE; + static inline void TWI_ShutDown(void) + { + TWCR &= ~(1 << TWEN); + } + + /** Sends a TWI STOP onto the TWI bus, terminating communication with the currently addressed device. */ + static inline void TWI_StopTransmission(void) ATTR_ALWAYS_INLINE; + static inline void TWI_StopTransmission(void) + { + TWCR = ((1 << TWINT) | (1 << TWSTO) | (1 << TWEN)); + } + + /** Sends a byte to the currently addressed device on the TWI bus. + * + * \param[in] Byte Byte to send to the currently addressed device + * + * \return Boolean true if the recipient ACKed the byte, false otherwise + */ + static inline bool TWI_SendByte(const uint8_t Byte) + { + TWDR = Byte; + TWCR = ((1 << TWINT) | (1 << TWEN)); + while (!(TWCR & (1 << TWINT))); + + return ((TWSR & TW_STATUS_MASK) == TW_MT_DATA_ACK); + } + + /** Receives a byte from the currently addressed device on the TWI bus. + * + * \param[in] Byte Location where the read byte is to be stored + * \param[in] LastByte Indicates if the byte should be ACKed if false, NAKed if true + * + * \return Boolean true if the byte reception successfully completed, false otherwise + */ + static inline bool TWI_ReceiveByte(uint8_t* const Byte, + const bool LastByte) + { + uint8_t TWCRMask = ((1 << TWINT) | (1 << TWEN)); + + if (!(LastByte)) + TWCRMask |= (1 << TWEA); + + TWCR = TWCRMask; + while (!(TWCR & (1 << TWINT))); + *Byte = TWDR; + + return ((TWSR & TW_STATUS_MASK) == TW_MR_DATA_ACK); + } + + /* Function Prototypes: */ + /** Begins a master mode TWI bus communication with the given slave device address. + * + * \param[in] SlaveAddress Address of the slave TWI device to communicate with + * \param[in] TimeoutMS Timeout period within which the slave must respond, in milliseconds + * + * \return Boolean true if the device is ready for data, false otherwise + */ + bool TWI_StartTransmission(const uint8_t SlaveAddress, + const uint8_t TimeoutMS); + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Peripheral/SPI.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Peripheral/SPI.h new file mode 100644 index 0000000000..c6db9f9623 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Peripheral/SPI.h @@ -0,0 +1,191 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief Master include file for the SPI peripheral driver. + * + * Hardware SPI subsystem driver for the supported USB AVRs models. + */ + +/** \ingroup Group_PeripheralDrivers + * @defgroup Group_SPI SPI Driver - LUFA/Drivers/Peripheral/SPI.h + * + * \section Sec_Dependencies Module Source Dependencies + * The following files must be built with any user project that uses this module: + * - None + * + * \section Module Description + * Driver for the hardware SPI port available on most AVR models. This module provides + * an easy to use driver for the setup of and transfer of data over the AVR's SPI port. + * + * @{ + */ + +#ifndef __SPI_H__ +#define __SPI_H__ + + /* Includes: */ + #include + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Private Interface - For use in library only: */ + #if !defined(__DOXYGEN__) + /* Macros: */ + #define SPI_USE_DOUBLESPEED (1 << SPE) + #endif + + /* Public Interface - May be used in end-application: */ + /* Macros: */ + /** SPI prescaler mask for SPI_Init(). Divides the system clock by a factor of 2. */ + #define SPI_SPEED_FCPU_DIV_2 SPI_USE_DOUBLESPEED + + /** SPI prescaler mask for SPI_Init(). Divides the system clock by a factor of 4. */ + #define SPI_SPEED_FCPU_DIV_4 0 + + /** SPI prescaler mask for SPI_Init(). Divides the system clock by a factor of 8. */ + #define SPI_SPEED_FCPU_DIV_8 (SPI_USE_DOUBLESPEED | (1 << SPR0)) + + /** SPI prescaler mask for SPI_Init(). Divides the system clock by a factor of 16. */ + #define SPI_SPEED_FCPU_DIV_16 (1 << SPR0) + + /** SPI prescaler mask for SPI_Init(). Divides the system clock by a factor of 32. */ + #define SPI_SPEED_FCPU_DIV_32 (SPI_USE_DOUBLESPEED | (1 << SPR1)) + + /** SPI prescaler mask for SPI_Init(). Divides the system clock by a factor of 64. */ + #define SPI_SPEED_FCPU_DIV_64 (SPI_USE_DOUBLESPEED | (1 << SPR1) | (1 << SPR0)) + + /** SPI prescaler mask for SPI_Init(). Divides the system clock by a factor of 128. */ + #define SPI_SPEED_FCPU_DIV_128 ((1 << SPR1) | (1 << SPR0)) + + /** SPI clock polarity mask for SPI_Init(). Indicates that the SCK should lead on the rising edge. */ + #define SPI_SCK_LEAD_RISING (0 << CPOL) + + /** SPI clock polarity mask for SPI_Init(). Indicates that the SCK should lead on the falling edge. */ + #define SPI_SCK_LEAD_FALLING (1 << CPOL) + + /** SPI data sample mode mask for SPI_Init(). Indicates that the data should sampled on the leading edge. */ + #define SPI_SAMPLE_LEADING (0 << CPHA) + + /** SPI data sample mode mask for SPI_Init(). Indicates that the data should be sampled on the trailing edge. */ + #define SPI_SAMPLE_TRAILING (1 << CPHA) + + /** SPI data order mask for SPI_Init(). Indicates that data should be shifted out MSB first. */ + #define SPI_ORDER_MSB_FIRST (0 << DORD) + + /** SPI data order mask for SPI_Init(). Indicates that data should be shifted out MSB first. */ + #define SPI_ORDER_LSB_FIRST (1 << DORD) + + /** SPI mode mask for SPI_Init(). Indicates that the SPI interface should be initialized into slave mode. */ + #define SPI_MODE_SLAVE (0 << MSTR) + + /** SPI mode mask for SPI_Init(). Indicates that the SPI interface should be initialized into master mode. */ + #define SPI_MODE_MASTER (1 << MSTR) + + /* Inline Functions: */ + /** Initialises the SPI subsystem, ready for transfers. Must be called before calling any other + * SPI routines. + * + * \param[in] SPIOptions SPI Options, a mask consisting of one of each of the SPI_SPEED_*, + * SPI_SCK_*, SPI_SAMPLE_*, SPI_ORDER_* and SPI_MODE_* masks. + */ + static inline void SPI_Init(const uint8_t SPIOptions) + { + DDRB |= ((1 << 1) | (1 << 2)); + PORTB |= ((1 << 0) | (1 << 3)); + + SPCR = ((1 << SPE) | SPIOptions); + + if (SPIOptions & SPI_USE_DOUBLESPEED) + SPSR |= (1 << SPI2X); + else + SPSR &= ~(1 << SPI2X); + } + + /** Turns off the SPI driver, disabling and returning used hardware to their default configuration. */ + static inline void SPI_ShutDown(void) + { + DDRB &= ~((1 << 1) | (1 << 2)); + PORTB &= ~((1 << 0) | (1 << 3)); + + SPCR = 0; + SPSR = 0; + } + + /** Sends and receives a byte through the SPI interface, blocking until the transfer is complete. + * + * \param[in] Byte Byte to send through the SPI interface. + * + * \return Response byte from the attached SPI device. + */ + static inline uint8_t SPI_TransferByte(const uint8_t Byte) ATTR_ALWAYS_INLINE; + static inline uint8_t SPI_TransferByte(const uint8_t Byte) + { + SPDR = Byte; + while (!(SPSR & (1 << SPIF))); + return SPDR; + } + + /** Sends a byte through the SPI interface, blocking until the transfer is complete. The response + * byte sent to from the attached SPI device is ignored. + * + * \param[in] Byte Byte to send through the SPI interface. + */ + static inline void SPI_SendByte(const uint8_t Byte) ATTR_ALWAYS_INLINE; + static inline void SPI_SendByte(const uint8_t Byte) + { + SPDR = Byte; + while (!(SPSR & (1 << SPIF))); + } + + /** Sends a dummy byte through the SPI interface, blocking until the transfer is complete. The response + * byte from the attached SPI device is returned. + * + * \return The response byte from the attached SPI device. + */ + static inline uint8_t SPI_ReceiveByte(void) ATTR_ALWAYS_INLINE ATTR_WARN_UNUSED_RESULT; + static inline uint8_t SPI_ReceiveByte(void) + { + SPDR = 0x00; + while (!(SPSR & (1 << SPIF))); + return SPDR; + } + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Peripheral/Serial.c b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Peripheral/Serial.c new file mode 100644 index 0000000000..b1141de14a --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Peripheral/Serial.c @@ -0,0 +1,53 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +#include "Serial.h" + +void Serial_TxString_P(const char* FlashStringPtr) +{ + uint8_t CurrByte; + + while ((CurrByte = pgm_read_byte(FlashStringPtr)) != 0x00) + { + Serial_TxByte(CurrByte); + FlashStringPtr++; + } +} + +void Serial_TxString(const char* StringPtr) +{ + uint8_t CurrByte; + + while ((CurrByte = *StringPtr) != 0x00) + { + Serial_TxByte(CurrByte); + StringPtr++; + } +} diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Peripheral/Serial.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Peripheral/Serial.h new file mode 100644 index 0000000000..47f65ea7bc --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Peripheral/Serial.h @@ -0,0 +1,166 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief Master include file for the USART peripheral driver. + * + * Driver for the USART subsystem on supported USB AVRs. + */ + +/** \ingroup Group_PeripheralDrivers + * @defgroup Group_Serial Serial USART Driver - LUFA/Drivers/Peripheral/Serial.h + * + * \section Sec_Dependencies Module Source Dependencies + * The following files must be built with any user project that uses this module: + * - LUFA/Drivers/Peripheral/Serial.c (Makefile source module name: LUFA_SRC_SERIAL) + * + * \section Module Description + * Hardware serial USART driver. This module provides an easy to use driver for + * the setup of and transfer of data over the AVR's USART port. + * + * @{ + */ + +#ifndef __SERIAL_H__ +#define __SERIAL_H__ + + /* Includes: */ + #include + #include + #include + + #include "../../Common/Common.h" + #include "../Misc/TerminalCodes.h" + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Public Interface - May be used in end-application: */ + /* Macros: */ + /** Macro for calculating the baud value from a given baud rate when the U2X (double speed) bit is + * not set. + */ + #define SERIAL_UBBRVAL(baud) ((((F_CPU / 16) + (baud / 2)) / (baud)) - 1) + + /** Macro for calculating the baud value from a given baud rate when the U2X (double speed) bit is + * set. + */ + #define SERIAL_2X_UBBRVAL(baud) ((((F_CPU / 8) + (baud / 2)) / (baud)) - 1) + + /* Function Prototypes: */ + /** Transmits a given string located in program space (FLASH) through the USART. + * + * \param[in] FlashStringPtr Pointer to a string located in program space. + */ + void Serial_TxString_P(const char* FlashStringPtr) ATTR_NON_NULL_PTR_ARG(1); + + /** Transmits a given string located in SRAM memory through the USART. + * + * \param[in] StringPtr Pointer to a string located in SRAM space. + */ + void Serial_TxString(const char* StringPtr) ATTR_NON_NULL_PTR_ARG(1); + + /* Inline Functions: */ + /** Initializes the USART, ready for serial data transmission and reception. This initializes the interface to + * standard 8-bit, no parity, 1 stop bit settings suitable for most applications. + * + * \param[in] BaudRate Serial baud rate, in bits per second. + * \param[in] DoubleSpeed Enables double speed mode when set, halving the sample time to double the baud rate. + */ + static inline void Serial_Init(const uint32_t BaudRate, + const bool DoubleSpeed) + { + UBRR1 = (DoubleSpeed ? SERIAL_2X_UBBRVAL(BaudRate) : SERIAL_UBBRVAL(BaudRate)); + + UCSR1C = ((1 << UCSZ11) | (1 << UCSZ10)); + UCSR1A = (DoubleSpeed ? (1 << U2X1) : 0); + UCSR1B = ((1 << TXEN1) | (1 << RXEN1)); + + DDRD |= (1 << 3); + PORTD |= (1 << 2); + } + + /** Turns off the USART driver, disabling and returning used hardware to their default configuration. */ + static inline void Serial_ShutDown(void) + { + UCSR1B = 0; + UCSR1A = 0; + UCSR1C = 0; + + UBRR1 = 0; + + DDRD &= ~(1 << 3); + PORTD &= ~(1 << 2); + } + + /** Indicates whether a character has been received through the USART. + * + * \return Boolean true if a character has been received, false otherwise. + */ + static inline bool Serial_IsCharReceived(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline bool Serial_IsCharReceived(void) + { + return ((UCSR1A & (1 << RXC1)) ? true : false); + } + + /** Transmits a given byte through the USART. + * + * \param[in] DataByte Byte to transmit through the USART. + */ + static inline void Serial_TxByte(const char DataByte) ATTR_ALWAYS_INLINE; + static inline void Serial_TxByte(const char DataByte) + { + while (!(UCSR1A & (1 << UDRE1))); + UDR1 = DataByte; + } + + /** Receives a byte from the USART. This function blocks until a byte has been + * received; if non-blocking behaviour is required, test for a received character + * beforehand with \ref Serial_IsCharReceived(). + * + * \return Byte received from the USART. + */ + static inline char Serial_RxByte(void) ATTR_ALWAYS_INLINE; + static inline char Serial_RxByte(void) + { + while (!(UCSR1A & (1 << RXC1))); + return UDR1; + } + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Peripheral/SerialStream.c b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Peripheral/SerialStream.c new file mode 100644 index 0000000000..36a0548765 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Peripheral/SerialStream.c @@ -0,0 +1,53 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +#define __INCLUDE_FROM_SERIALSTREAM_C +#include "SerialStream.h" + +FILE USARTStream = FDEV_SETUP_STREAM(SerialStream_TxByte, SerialStream_RxByte, _FDEV_SETUP_RW); + +static int SerialStream_TxByte(char DataByte, + FILE *Stream) +{ + (void)Stream; + + Serial_TxByte(DataByte); + return 0; +} + +static int SerialStream_RxByte(FILE *Stream) +{ + (void)Stream; + + if (!(Serial_IsCharReceived())) + return _FDEV_EOF; + + return Serial_RxByte(); +} diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Peripheral/SerialStream.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Peripheral/SerialStream.h new file mode 100644 index 0000000000..938d8f0164 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Peripheral/SerialStream.h @@ -0,0 +1,115 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief Standard avr-libc character stream driver for the USART. + * + * Serial stream driver for the USART subsystem on supported USB AVRs. This makes use of the functions in the + * regular USART driver (see \ref Group_Serial), but allows the avr-libc standard stream functions (printf, + * puts, etc.) to work with the + * USART. + */ + +/** \ingroup Group_PeripheralDrivers + * @defgroup Group_SerialStream Serial Stream Driver - LUFA/Drivers/Peripheral/SerialStream.h + * + * \section Sec_Dependencies Module Source Dependencies + * The following files must be built with any user project that uses this module: + * - LUFA/Drivers/Peripheral/SerialStream.c (Makefile source module name: LUFA_SRC_SERIALSTREAM) + * + * \section Module Description + * Serial stream driver for the USART subsystem on supported USB AVRs. This makes use of the functions in the + * regular USART driver (see \ref Group_Serial), but allows the avr-libc standard stream functions (printf, + * puts, etc.) to work with the + * USART. + * + * @{ + */ + +#ifndef __SERIAL_STREAM_H__ +#define __SERIAL_STREAM_H__ + + /* Includes: */ + #include + #include + + #include "Serial.h" + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Private Interface - For use in library only: */ + #if !defined(__DOXYGEN__) + /* External Variables: */ + extern FILE USARTStream; + + /* Function Prototypes: */ + #if defined(__INCLUDE_FROM_SERIALSTREAM_C) + static int SerialStream_TxByte(char DataByte, + FILE *Stream) ATTR_NON_NULL_PTR_ARG(2); + static int SerialStream_RxByte(FILE *Stream) ATTR_NON_NULL_PTR_ARG(1); + #endif + #endif + + /* Public Interface - May be used in end-application: */ + /* Inline Functions: */ + /** Initialises the serial stream (and regular USART driver) so that both the stream and regular + * USART driver functions can be used. Must be called before any stream or regular USART functions. + * + * \param[in] BaudRate Baud rate to configure the USART to. + * \param[in] DoubleSpeed Enables double speed mode when set, halving the sample time to double the baud rate. + */ + static inline void SerialStream_Init(const uint32_t BaudRate, + const bool DoubleSpeed) + { + Serial_Init(BaudRate, DoubleSpeed); + + stdout = &USARTStream; + stdin = &USARTStream; + } + + /** Turns off the serial stream (and regular USART driver), disabling and returning used hardware to + * their default configuration. + */ + static inline void SerialStream_ShutDown(void) + { + Serial_ShutDown(); + } + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Peripheral/TWI.c b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Peripheral/TWI.c new file mode 100644 index 0000000000..b8aec48522 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Peripheral/TWI.c @@ -0,0 +1,74 @@ +/* + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +#include "TWI.h" + +bool TWI_StartTransmission(const uint8_t SlaveAddress, + const uint8_t TimeoutMS) +{ + for (;;) + { + bool BusCaptured = false; + uint16_t TimeoutRemaining; + + TWCR = ((1 << TWINT) | (1 << TWSTA) | (1 << TWEN)); + + TimeoutRemaining = (TimeoutMS * 100); + while (TimeoutRemaining-- && !(BusCaptured)) + { + if (TWCR & (1 << TWINT)) + { + switch (TWSR & TW_STATUS_MASK) + { + case TW_START: + case TW_REP_START: + BusCaptured = true; + break; + case TW_MT_ARB_LOST: + TWCR = ((1 << TWINT) | (1 << TWSTA) | (1 << TWEN)); + continue; + default: + TWCR = (1 << TWEN); + return false; + } + } + + _delay_us(10); + } + + if (!(BusCaptured)) + { + TWCR = (1 << TWEN); + return false; + } + + TWDR = SlaveAddress; + TWCR = ((1 << TWINT) | (1 << TWEN)); + + TimeoutRemaining = (TimeoutMS * 100); + while (TimeoutRemaining--) + { + if (TWCR & (1 << TWINT)) + break; + + _delay_us(10); + } + + if (!(TimeoutRemaining)) + return false; + + switch (TWSR & TW_STATUS_MASK) + { + case TW_MT_SLA_ACK: + case TW_MR_SLA_ACK: + return true; + default: + TWCR = ((1 << TWINT) | (1 << TWSTO) | (1 << TWEN)); + return false; + } + } +} diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Peripheral/TWI.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Peripheral/TWI.h new file mode 100644 index 0000000000..42539203e1 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/Peripheral/TWI.h @@ -0,0 +1,71 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief Master include file for the TWI peripheral driver. + * + * This file is the master dispatch header file for the device-specific ADC driver, for AVRs containing an ADC. + * + * User code should include this file, which will in turn include the correct ADC driver header file for the + * currently selected AVR model. + */ + +/** \ingroup Group_PeripheralDrivers + * @defgroup Group_TWI TWI Driver - LUFA/Drivers/Peripheral/TWI.h + * + * \section Sec_Dependencies Module Source Dependencies + * The following files must be built with any user project that uses this module: + * - LUFA/Drivers/Peripheral/TWI.c (Makefile source module name: LUFA_SRC_TWI) + * + * + * \section Module Description + * Master Mode Hardware TWI driver. This module provides an easy to use driver for the hardware + * TWI present on many AVR models, for the transmission and reception of data on a TWI bus. + */ + +#ifndef __TWI_H__ +#define __TWI_H__ + + /* Macros: */ + #if !defined(__DOXYGEN__) + #define __INCLUDE_FROM_TWI_H + #endif + + /* Includes: */ + #if (defined(__AVR_AT90USB1286__) || defined(__AVR_AT90USB646__) || \ + defined(__AVR_AT90USB1287__) || defined(__AVR_AT90USB647__) || \ + defined(__AVR_ATmega16U4__) || defined(__AVR_ATmega32U4__) || \ + defined(__AVR_ATmega32U6__)) + #include "AVRU4U6U7/TWI.h" + #else + #error "TWI is not available for the currently selected AVR model." + #endif + +#endif diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Audio.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Audio.h new file mode 100644 index 0000000000..1efbaab52a --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Audio.h @@ -0,0 +1,78 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief Master include file for the library USB Audio Class driver. + * + * Master include file for the library USB Audio Class driver, for both host and device modes, where available. + * + * This file should be included in all user projects making use of this optional class driver, instead of + * including any headers in the USB/ClassDriver/Device, USB/ClassDriver/Host or USB/ClassDriver/Common subdirectories. + */ + +/** \ingroup Group_USBClassDrivers + * @defgroup Group_USBClassAudio Audio Class Driver - LUFA/Drivers/Class/Audio.h + * + * \section Sec_Dependencies Module Source Dependencies + * The following files must be built with any user project that uses this module: + * - LUFA/Drivers/USB/Class/Device/Audio.c (Makefile source module name: LUFA_SRC_USBCLASS) + * + * \section Module Description + * Audio Class Driver module. This module contains an internal implementation of the USB Audio Class, for Device + * USB mode only. User applications can use this class driver instead of implementing the Audio class manually via + * the low-level LUFA APIs. + * + * This module is designed to simplify the user code by exposing only the required interface needed to interface with + * Hosts or Devices using the USB Audio Class. + * + * @{ + */ + +#ifndef _AUDIO_CLASS_H_ +#define _AUDIO_CLASS_H_ + + /* Macros: */ + #define __INCLUDE_FROM_AUDIO_DRIVER + #define __INCLUDE_FROM_USB_DRIVER + + /* Includes: */ + #include "../HighLevel/USBMode.h" + + #if defined(NO_STREAM_CALLBACKS) + #error The NO_STREAM_CALLBACKS compile time option cannot be used in projects using the library Class drivers. + #endif + + #if defined(USB_CAN_BE_DEVICE) + #include "Device/Audio.h" + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/CDC.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/CDC.h new file mode 100644 index 0000000000..a33ebb179a --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/CDC.h @@ -0,0 +1,83 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief Master include file for the library USB CDC-ACM Class driver. + * + * Master include file for the library USB CDC Class driver, for both host and device modes, where available. + * + * This file should be included in all user projects making use of this optional class driver, instead of + * including any headers in the USB/ClassDriver/Device, USB/ClassDriver/Host or USB/ClassDriver/Common subdirectories. + */ + +/** \ingroup Group_USBClassDrivers + * @defgroup Group_USBClassCDC CDC-ACM (Virtual Serial) Class Driver - LUFA/Drivers/Class/CDC.h + * + * \section Sec_Dependencies Module Source Dependencies + * The following files must be built with any user project that uses this module: + * - LUFA/Drivers/USB/Class/Device/CDC.c (Makefile source module name: LUFA_SRC_USBCLASS) + * - LUFA/Drivers/USB/Class/Host/CDC.c (Makefile source module name: LUFA_SRC_USBCLASS) + * + * \section Module Description + * CDC Class Driver module. This module contains an internal implementation of the USB CDC-ACM class Virtual Serial + * Ports, for both Device and Host USB modes. User applications can use this class driver instead of implementing the + * CDC class manually via the low-level LUFA APIs. + * + * This module is designed to simplify the user code by exposing only the required interface needed to interface with + * Hosts or Devices using the USB CDC Class. + * + * @{ + */ + +#ifndef _CDC_CLASS_H_ +#define _CDC_CLASS_H_ + + /* Macros: */ + #define __INCLUDE_FROM_CDC_DRIVER + #define __INCLUDE_FROM_USB_DRIVER + + /* Includes: */ + #include "../HighLevel/USBMode.h" + + #if defined(NO_STREAM_CALLBACKS) + #error The NO_STREAM_CALLBACKS compile time option cannot be used in projects using the library Class drivers. + #endif + + #if defined(USB_CAN_BE_DEVICE) + #include "Device/CDC.h" + #endif + + #if defined(USB_CAN_BE_HOST) + #include "Host/CDC.h" + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Common/Audio.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Common/Audio.h new file mode 100644 index 0000000000..eb2e95b653 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Common/Audio.h @@ -0,0 +1,406 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief Common definitions and declarations for the library USB Audio Class driver. + * + * Common definitions and declarations for the library USB Audio Class driver. + * + * \note This file should not be included directly. It is automatically included as needed by the class driver + * dispatch header located in LUFA/Drivers/USB/Class/Audio.h. + */ + +/** \ingroup Group_USBClassAudio + * @defgroup Group_USBClassAudioCommon Common Class Definitions + * + * \section Module Description + * Constants, Types and Enum definitions that are common to both Device and Host modes for the USB + * Audio Class. + * + * @{ + */ + +#ifndef _AUDIO_CLASS_COMMON_H_ +#define _AUDIO_CLASS_COMMON_H_ + + /* Includes: */ + #include "../../USB.h" + + #include + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_AUDIO_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/Class/Audio.h instead. + #endif + + /* Macros: */ + #if !defined(AUDIO_TOTAL_SAMPLE_RATES) || defined(__DOXYGEN__) + /** Total number of discrete audio sample rates supported by the device. This value can be overridden by defining this + * token in the project makefile to the desired value, and passing it to the compiler via the -D switch. + */ + #define AUDIO_TOTAL_SAMPLE_RATES 1 + #endif + + /** Descriptor header constant to indicate a Audio class interface descriptor. */ + #define DTYPE_AudioInterface 0x24 + + /** Descriptor header constant to indicate a Audio class endpoint descriptor. */ + #define DTYPE_AudioEndpoint 0x25 + + /** Audio class descriptor subtype value for a Audio class-specific header descriptor. */ + #define DSUBTYPE_Header 0x01 + + /** Audio class descriptor subtype value for an Output Terminal Audio class-specific descriptor. */ + #define DSUBTYPE_InputTerminal 0x02 + + /** Audio class descriptor subtype value for an Input Terminal Audio class-specific descriptor. */ + #define DSUBTYPE_OutputTerminal 0x03 + + /** Audio class descriptor subtype value for a Feature Unit Audio class-specific descriptor. */ + #define DSUBTYPE_FeatureUnit 0x06 + + /** Audio class descriptor subtype value for a general Audio class-specific descriptor. */ + #define DSUBTYPE_General 0x01 + + /** Audio class descriptor subtype value for an Audio class-specific descriptor indicating the format of an audio stream. */ + #define DSUBTYPE_Format 0x02 + + /** Supported channel mask for an Audio class terminal descriptor. See the Audio class specification for more details. */ + #define CHANNEL_LEFT_FRONT (1 << 0) + + /** Supported channel mask for an Audio class terminal descriptor. See the Audio class specification for more details. */ + #define CHANNEL_RIGHT_FRONT (1 << 1) + + /** Supported channel mask for an Audio class terminal descriptor. See the Audio class specification for more details. */ + #define CHANNEL_CENTER_FRONT (1 << 2) + + /** Supported channel mask for an Audio class terminal descriptor. See the Audio class specification for more details. */ + #define CHANNEL_LOW_FREQ_ENHANCE (1 << 3) + + /** Supported channel mask for an Audio class terminal descriptor. See the Audio class specification for more details. */ + #define CHANNEL_LEFT_SURROUND (1 << 4) + + /** Supported channel mask for an Audio class terminal descriptor. See the Audio class specification for more details. */ + #define CHANNEL_RIGHT_SURROUND (1 << 5) + + /** Supported channel mask for an Audio class terminal descriptor. See the Audio class specification for more details. */ + #define CHANNEL_LEFT_OF_CENTER (1 << 6) + + /** Supported channel mask for an Audio class terminal descriptor. See the Audio class specification for more details. */ + #define CHANNEL_RIGHT_OF_CENTER (1 << 7) + + /** Supported channel mask for an Audio class terminal descriptor. See the Audio class specification for more details. */ + #define CHANNEL_SURROUND (1 << 8) + + /** Supported channel mask for an Audio class terminal descriptor. See the Audio class specification for more details. */ + #define CHANNEL_SIDE_LEFT (1 << 9) + + /** Supported channel mask for an Audio class terminal descriptor. See the Audio class specification for more details. */ + #define CHANNEL_SIDE_RIGHT (1 << 10) + + /** Supported channel mask for an Audio class terminal descriptor. See the Audio class specification for more details. */ + #define CHANNEL_TOP (1 << 11) + + /** Supported feature mask for an Audio class feature unit descriptor. See the Audio class specification for more details. */ + #define FEATURE_MUTE (1 << 0) + + /** Supported feature mask for an Audio class feature unit descriptor. See the Audio class specification for more details. */ + #define FEATURE_VOLUME (1 << 1) + + /** Supported feature mask for an Audio class feature unit descriptor. See the Audio class specification for more details. */ + #define FEATURE_BASS (1 << 2) + + /** Supported feature mask for an Audio class feature unit descriptor. See the Audio class specification for more details. */ + #define FEATURE_MID (1 << 3) + + /** Supported feature mask for an Audio class feature unit descriptor. See the Audio class specification for more details. */ + #define FEATURE_TREBLE (1 << 4) + + /** Supported feature mask for an Audio class feature unit descriptor. See the Audio class specification for more details. */ + #define FEATURE_GRAPHIC_EQUALIZER (1 << 5) + + /** Supported feature mask for an Audio class feature unit descriptor. See the Audio class specification for more details. */ + + /** Supported feature mask for an Audio class feature unit descriptor. See the Audio class specification for more details. */ + #define FEATURE_AUTOMATIC_GAIN (1 << 6) + + /** Supported feature mask for an Audio class feature unit descriptor. See the Audio class specification for more details. */ + #define FEATURE_DELAY (1 << 7) + + /** Supported feature mask for an Audio class feature unit descriptor. See the Audio class specification for more details. */ + #define FEATURE_BASS_BOOST (1 << 8) + + /** Supported feature mask for an Audio class feature unit descriptor. See the Audio class specification for more details. */ + #define FEATURE_BASS_LOUDNESS (1 << 9) + + /** Terminal type constant for an Audio class terminal descriptor. See the Audio class specification for more details. */ + #define TERMINAL_UNDEFINED 0x0100 + + /** Terminal type constant for an Audio class terminal descriptor. See the Audio class specification for more details. */ + #define TERMINAL_STREAMING 0x0101 + + /** Terminal type constant for an Audio class terminal descriptor. See the Audio class specification for more details. */ + #define TERMINAL_VENDOR 0x01FF + + /** Terminal type constant for an Audio class terminal descriptor. See the Audio class specification for more details. */ + #define TERMINAL_IN_UNDEFINED 0x0200 + + /** Terminal type constant for an Audio class terminal descriptor. See the Audio class specification for more details. */ + #define TERMINAL_IN_MIC 0x0201 + + /** Terminal type constant for an Audio class terminal descriptor. See the Audio class specification for more details. */ + #define TERMINAL_IN_DESKTOP_MIC 0x0202 + + /** Terminal type constant for an Audio class terminal descriptor. See the Audio class specification for more details. */ + #define TERMINAL_IN_PERSONAL_MIC 0x0203 + + /** Terminal type constant for an Audio class terminal descriptor. See the Audio class specification for more details. */ + #define TERMINAL_IN_OMNIDIR_MIC 0x0204 + + /** Terminal type constant for an Audio class terminal descriptor. See the Audio class specification for more details. */ + #define TERMINAL_IN_MIC_ARRAY 0x0205 + + /** Terminal type constant for an Audio class terminal descriptor. See the Audio class specification for more details. */ + #define TERMINAL_IN_PROCESSING_MIC 0x0206 + + /** Terminal type constant for an Audio class terminal descriptor. See the Audio class specification for more details. */ + #define TERMINAL_IN_OUT_UNDEFINED 0x0300 + + /** Terminal type constant for an Audio class terminal descriptor. See the Audio class specification for more details. */ + #define TERMINAL_OUT_SPEAKER 0x0301 + + /** Terminal type constant for an Audio class terminal descriptor. See the Audio class specification for more details. */ + #define TERMINAL_OUT_HEADPHONES 0x0302 + + /** Terminal type constant for an Audio class terminal descriptor. See the Audio class specification for more details. */ + #define TERMINAL_OUT_HEAD_MOUNTED 0x0303 + + /** Terminal type constant for an Audio class terminal descriptor. See the Audio class specification for more details. */ + #define TERMINAL_OUT_DESKTOP 0x0304 + + /** Terminal type constant for an Audio class terminal descriptor. See the Audio class specification for more details. */ + #define TERMINAL_OUT_ROOM 0x0305 + + /** Terminal type constant for an Audio class terminal descriptor. See the Audio class specification for more details. */ + #define TERMINAL_OUT_COMMUNICATION 0x0306 + + /** Terminal type constant for an Audio class terminal descriptor. See the Audio class specification for more details. */ + #define TERMINAL_OUT_LOWFREQ 0x0307 + + /** Convenience macro, to fill a 24-bit AudioSampleFreq_t structure with the given sample rate as a 24-bit number. + * + * \param[in] freq Required audio sampling frequency in HZ + */ + #define AUDIO_SAMPLE_FREQ(freq) {LowWord: ((uint32_t)freq & 0x00FFFF), HighByte: (((uint32_t)freq >> 16) & 0x0000FF)} + + /** Mask for the attributes parameter of an Audio class-specific Endpoint descriptor, indicating that the endpoint + * accepts only filled endpoint packets of audio samples. + */ + #define EP_ACCEPTS_ONLY_FULL_PACKETS (1 << 7) + + /** Mask for the attributes parameter of an Audio class-specific Endpoint descriptor, indicating that the endpoint + * will accept partially filled endpoint packets of audio samples. + */ + #define EP_ACCEPTS_SMALL_PACKETS (0 << 7) + + /* Type Defines: */ + /** \brief Audio class-specific Interface Descriptor. + * + * Type define for an Audio class-specific interface descriptor. This follows a regular interface descriptor to + * supply extra information about the audio device's layout to the host. See the USB Audio specification for more + * details. + */ + typedef struct + { + USB_Descriptor_Header_t Header; /**< Regular descriptor header containing the descriptor's type and length. */ + uint8_t Subtype; /**< Sub type value used to distinguish between audio class-specific descriptors. */ + + uint16_t ACSpecification; /**< Binary coded decimal value, indicating the supported Audio Class specification version. */ + uint16_t TotalLength; /**< Total length of the Audio class-specific descriptors, including this descriptor. */ + + uint8_t InCollection; /**< Total number of audio class interfaces within this device. */ + uint8_t InterfaceNumbers[1]; /**< Interface numbers of each audio interface. */ + } USB_Audio_Interface_AC_t; + + /** \brief Audio class-specific Feature Unit Descriptor. + * + * Type define for an Audio class-specific Feature Unit descriptor. This indicates to the host what features + * are present in the device's audio stream for basic control, such as per-channel volume. See the USB Audio + * specification for more details. + */ + typedef struct + { + USB_Descriptor_Header_t Header; /**< Regular descriptor header containing the descriptor's type and length. */ + uint8_t Subtype; /**< Sub type value used to distinguish between audio class-specific descriptors. */ + + uint8_t UnitID; /**< ID value of this feature unit - must be a unique value within the device. */ + uint8_t SourceID; /**< Source ID value of the audio source input into this feature unit. */ + + uint8_t ControlSize; /**< Size of each element in the ChanelControlls array. */ + uint8_t ChannelControls[3]; /**< Feature masks for the control channel, and each separate audio channel. */ + + uint8_t FeatureUnitStrIndex; /**< Index of a string descriptor describing this descriptor within the device. */ + } USB_Audio_FeatureUnit_t; + + /** \brief Audio class-specific Input Terminal Descriptor. + * + * Type define for an Audio class-specific input terminal descriptor. This indicates to the host that the device + * contains an input audio source, either from a physical terminal on the device, or a logical terminal (for example, + * a USB endpoint). See the USB Audio specification for more details. + */ + typedef struct + { + USB_Descriptor_Header_t Header; /**< Regular descriptor header containing the descriptor's type and length. */ + uint8_t Subtype; /**< Sub type value used to distinguish between audio class-specific descriptors. */ + + uint8_t TerminalID; /**< ID value of this terminal unit - must be a unique value within the device. */ + uint16_t TerminalType; /**< Type of terminal, a TERMINAL_* mask. */ + uint8_t AssociatedOutputTerminal; /**< ID of associated output terminal, for physically grouped terminals + * such as the speaker and microphone of a phone handset. + */ + uint8_t TotalChannels; /**< Total number of separate audio channels within this interface (right, left, etc.) */ + uint16_t ChannelConfig; /**< CHANNEL_* masks indicating what channel layout is supported by this terminal. */ + + uint8_t ChannelStrIndex; /**< Index of a string descriptor describing this channel within the device. */ + uint8_t TerminalStrIndex; /**< Index of a string descriptor describing this descriptor within the device. */ + } USB_Audio_InputTerminal_t; + + /** \brief Audio class-specific Output Terminal Descriptor. + * + * Type define for an Audio class-specific output terminal descriptor. This indicates to the host that the device + * contains an output audio sink, either to a physical terminal on the device, or a logical terminal (for example, + * a USB endpoint). See the USB Audio specification for more details. + */ + typedef struct + { + USB_Descriptor_Header_t Header; /**< Regular descriptor header containing the descriptor's type and length. */ + uint8_t Subtype; /**< Sub type value used to distinguish between audio class-specific descriptors. */ + + uint8_t TerminalID; /**< ID value of this terminal unit - must be a unique value within the device. */ + uint16_t TerminalType; /**< Type of terminal, a TERMINAL_* mask. */ + uint8_t AssociatedInputTerminal; /**< ID of associated input terminal, for physically grouped terminals + * such as the speaker and microphone of a phone handset. + */ + uint8_t SourceID; /**< ID value of the unit this terminal's audio is sourced from. */ + + uint8_t TerminalStrIndex; /**< Index of a string descriptor describing this descriptor within the device. */ + } USB_Audio_OutputTerminal_t; + + /** \brief Audio class-specific Streaming Audio Interface Descriptor. + * + * Type define for an Audio class-specific streaming interface descriptor. This indicates to the host + * how audio streams within the device are formatted. See the USB Audio specification for more details. + */ + typedef struct + { + USB_Descriptor_Header_t Header; /**< Regular descriptor header containing the descriptor's type and length. */ + uint8_t Subtype; /**< Sub type value used to distinguish between audio class-specific descriptors. */ + + uint8_t TerminalLink; /**< ID value of the output terminal this descriptor is describing. */ + + uint8_t FrameDelay; /**< Delay in frames resulting from the complete sample processing from input to output. */ + uint16_t AudioFormat; /**< Format of the audio stream, see Audio Device Formats specification. */ + } USB_Audio_Interface_AS_t; + + /** \brief 24-Bit Audio Frequency Structure. + * + * Type define for a 24bit audio sample frequency structure. GCC does not contain a built in 24bit datatype, + * this this structure is used to build up the value instead. Fill this structure with the \ref AUDIO_SAMPLE_FREQ() macro. + */ + typedef struct + { + uint16_t LowWord; /**< Low 16 bits of the 24-bit value. */ + uint8_t HighByte; /**< Upper 8 bits of the 24-bit value. */ + } USB_Audio_SampleFreq_t; + + /** \brief Audio class-specific Format Descriptor. + * + * Type define for an Audio class-specific audio format descriptor. This is used to give the host full details + * about the number of channels, the sample resolution, acceptable sample frequencies and encoding method used + * in the device's audio streams. See the USB Audio specification for more details. + */ + typedef struct + { + USB_Descriptor_Header_t Header; /**< Regular descriptor header containing the descriptor's type and length. */ + uint8_t Subtype; /**< Sub type value used to distinguish between audio class-specific descriptors. */ + + uint8_t FormatType; /**< Format of the audio stream, see Audio Device Formats specification. */ + uint8_t Channels; /**< Total number of discrete channels in the stream. */ + + uint8_t SubFrameSize; /**< Size in bytes of each channel's sample data in the stream. */ + uint8_t BitResolution; /**< Bits of resolution of each channel's samples in the stream. */ + + uint8_t SampleFrequencyType; /**< Total number of sample frequencies supported by the device. */ + USB_Audio_SampleFreq_t SampleFrequencies[AUDIO_TOTAL_SAMPLE_RATES]; /**< Sample frequencies supported by the device. */ + } USB_Audio_Format_t; + + /** \brief Audio class-specific Streaming Endpoint Descriptor. + * + * Type define for an Audio class-specific endpoint descriptor. This contains a regular endpoint + * descriptor with a few Audio-class-specific extensions. See the USB Audio specification for more details. + */ + typedef struct + { + USB_Descriptor_Endpoint_t Endpoint; /**< Standard endpoint descriptor describing the audio endpoint. */ + + uint8_t Refresh; /**< Always set to zero for Audio class devices. */ + uint8_t SyncEndpointNumber; /**< Endpoint address to send synchronization information to, if needed (zero otherwise). */ + } USB_Audio_StreamEndpoint_Std_t; + + /** \brief Audio class-specific Extended Endpoint Descriptor. + * + * Type define for an Audio class-specific extended endpoint descriptor. This contains extra information + * on the usage of endpoints used to stream audio in and out of the USB Audio device, and follows an Audio + * class-specific extended endpoint descriptor. See the USB Audio specification for more details. + */ + typedef struct + { + USB_Descriptor_Header_t Header; /**< Regular descriptor header containing the descriptor's type and length. */ + uint8_t Subtype; /**< Sub type value used to distinguish between audio class-specific descriptors. */ + + uint8_t Attributes; /**< Audio class-specific endpoint attributes, such as ACCEPTS_SMALL_PACKETS. */ + + uint8_t LockDelayUnits; /**< Units used for the LockDelay field, see Audio class specification. */ + uint16_t LockDelay; /**< Time required to internally lock endpoint's internal clock recovery circuitry. */ + } USB_Audio_StreamEndpoint_Spc_t; + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Common/CDC.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Common/CDC.h new file mode 100644 index 0000000000..c41907f088 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Common/CDC.h @@ -0,0 +1,179 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief Common definitions and declarations for the library USB CDC Class driver. + * + * Common definitions and declarations for the library USB CDC Class driver. + * + * \note This file should not be included directly. It is automatically included as needed by the class driver + * dispatch header located in LUFA/Drivers/USB/Class/CDC.h. + */ + +/** \ingroup Group_USBClassCDC + * @defgroup Group_USBClassCDCCommon Common Class Definitions + * + * \section Module Description + * Constants, Types and Enum definitions that are common to both Device and Host modes for the USB + * CDC Class. + * + * @{ + */ + +#ifndef _CDC_CLASS_COMMON_H_ +#define _CDC_CLASS_COMMON_H_ + + /* Includes: */ + #include "../../USB.h" + + #include + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_CDC_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/Class/CDC.h instead. + #endif + + /* Macros: */ + /** CDC class-specific request to get the current virtual serial port configuration settings. */ + #define REQ_GetLineEncoding 0x21 + + /** CDC class-specific request to set the current virtual serial port configuration settings. */ + #define REQ_SetLineEncoding 0x20 + + /** CDC class-specific request to set the current virtual serial port handshake line states. */ + #define REQ_SetControlLineState 0x22 + + /** CDC class-specific request to send a break to the receiver via the carrier channel. */ + #define REQ_SendBreak 0x23 + + /** CDC class-specific request to send an encapsulated command to the device. */ + #define REQ_SendEncapsulatedCommand 0x00 + + /** CDC class-specific request to retrieve an encapsulated command response from the device. */ + #define REQ_GetEncapsulatedResponse 0x01 + + /** Notification type constant for a change in the virtual serial port handshake line states, for + * use with a USB_Notification_Header_t notification structure when sent to the host via the CDC + * notification endpoint. + */ + #define NOTIF_SerialState 0x20 + + /** Mask for the DTR handshake line for use with the REQ_SetControlLineState class-specific request + * from the host, to indicate that the DTR line state should be high. + */ + #define CDC_CONTROL_LINE_OUT_DTR (1 << 0) + + /** Mask for the RTS handshake line for use with the REQ_SetControlLineState class-specific request + * from the host, to indicate that theRTS line state should be high. + */ + #define CDC_CONTROL_LINE_OUT_RTS (1 << 1) + + /** Mask for the DCD handshake line for use with the a NOTIF_SerialState class-specific notification + * from the device to the host, to indicate that the DCD line state is currently high. + */ + #define CDC_CONTROL_LINE_IN_DCD (1 << 0) + + /** Mask for the DSR handshake line for use with the a NOTIF_SerialState class-specific notification + * from the device to the host, to indicate that the DSR line state is currently high. + */ + #define CDC_CONTROL_LINE_IN_DSR (1 << 1) + + /** Mask for the BREAK handshake line for use with the a NOTIF_SerialState class-specific notification + * from the device to the host, to indicate that the BREAK line state is currently high. + */ + #define CDC_CONTROL_LINE_IN_BREAK (1 << 2) + + /** Mask for the RING handshake line for use with the a NOTIF_SerialState class-specific notification + * from the device to the host, to indicate that the RING line state is currently high. + */ + #define CDC_CONTROL_LINE_IN_RING (1 << 3) + + /** Mask for use with the a NOTIF_SerialState class-specific notification from the device to the host, + * to indicate that a framing error has occurred on the virtual serial port. + */ + #define CDC_CONTROL_LINE_IN_FRAMEERROR (1 << 4) + + /** Mask for use with the a NOTIF_SerialState class-specific notification from the device to the host, + * to indicate that a parity error has occurred on the virtual serial port. + */ + #define CDC_CONTROL_LINE_IN_PARITYERROR (1 << 5) + + /** Mask for use with the a NOTIF_SerialState class-specific notification from the device to the host, + * to indicate that a data overrun error has occurred on the virtual serial port. + */ + #define CDC_CONTROL_LINE_IN_OVERRUNERROR (1 << 6) + + /** Macro to define a CDC class-specific functional descriptor. CDC functional descriptors have a + * uniform structure but variable sized data payloads, thus cannot be represented accurately by + * a single typedef struct. A macro is used instead so that functional descriptors can be created + * easily by specifying the size of the payload. This allows sizeof() to work correctly. + * + * \param[in] DataSize Size in bytes of the CDC functional descriptor's data payload. + */ + #define CDC_FUNCTIONAL_DESCRIPTOR(DataSize) \ + struct \ + { \ + USB_Descriptor_Header_t Header; \ + uint8_t SubType; \ + uint8_t Data[DataSize]; \ + } + + /* Enums: */ + /** Enum for the possible line encoding formats of a virtual serial port. */ + enum CDC_LineEncodingFormats_t + { + CDC_LINEENCODING_OneStopBit = 0, /**< Each frame contains one stop bit. */ + CDC_LINEENCODING_OneAndAHalfStopBits = 1, /**< Each frame contains one and a half stop bits. */ + CDC_LINEENCODING_TwoStopBits = 2, /**< Each frame contains two stop bits. */ + }; + + /** Enum for the possible line encoding parity settings of a virtual serial port. */ + enum CDC_LineEncodingParity_t + { + CDC_PARITY_None = 0, /**< No parity bit mode on each frame. */ + CDC_PARITY_Odd = 1, /**< Odd parity bit mode on each frame. */ + CDC_PARITY_Even = 2, /**< Even parity bit mode on each frame. */ + CDC_PARITY_Mark = 3, /**< Mark parity bit mode on each frame. */ + CDC_PARITY_Space = 4, /**< Space parity bit mode on each frame. */ + }; + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Common/HID.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Common/HID.h new file mode 100644 index 0000000000..739a7ab332 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Common/HID.h @@ -0,0 +1,195 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief Common definitions and declarations for the library USB HID Class driver. + * + * Common definitions and declarations for the library USB HID Class driver. + * + * \note This file should not be included directly. It is automatically included as needed by the class driver + * dispatch header located in LUFA/Drivers/USB/Class/HID.h. + */ + +/** \ingroup Group_USBClassHID + * @defgroup Group_USBClassHIDCommon Common Class Definitions + * + * \section Module Description + * Constants, Types and Enum definitions that are common to both Device and Host modes for the USB + * HID Class. + * + * @{ + */ + +#ifndef _HID_CLASS_COMMON_H_ +#define _HID_CLASS_COMMON_H_ + + /* Includes: */ + #include "../../USB.h" + + #include + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_HID_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/Class/HID.h instead. + #endif + + /* Macros: */ + /** HID class-specific Request to get the current HID report from the device. */ + #define REQ_GetReport 0x01 + + /** HID class-specific Request to get the current device idle count. */ + #define REQ_GetIdle 0x02 + + /** HID class-specific Request to set the current HID report to the device. */ + #define REQ_SetReport 0x09 + + /** HID class-specific Request to set the device's idle count. */ + #define REQ_SetIdle 0x0A + + /** HID class-specific Request to get the current HID report protocol mode. */ + #define REQ_GetProtocol 0x03 + + /** HID class-specific Request to set the current HID report protocol mode. */ + #define REQ_SetProtocol 0x0B + + /** Descriptor header type value, to indicate a HID class HID descriptor. */ + #define DTYPE_HID 0x21 + + /** Descriptor header type value, to indicate a HID class HID report descriptor. */ + #define DTYPE_Report 0x22 + + /** Constant for the protocol value of a HID interface descriptor, indicating that the interface does not support + * any HID class boot protocol (see HID Class Specification). + */ + #define HID_NON_BOOT_PROTOCOL 0x00 + + /** Constant for the protocol value of a HID interface descriptor, indicating that the interface supports the + * HID class Keyboard boot protocol (see HID Class Specification). + */ + #define HID_BOOT_KEYBOARD_PROTOCOL 0x01 + + /** Constant for the protocol value of a HID interface descriptor, indicating that the interface supports the + * HID class Mouse boot protocol (see HID Class Specification). + */ + #define HID_BOOT_MOUSE_PROTOCOL 0x02 + + /** Constant for a keyboard report modifier byte, indicating that the keyboard's left control key is currently pressed. */ + #define HID_KEYBOARD_MODIFER_LEFTCTRL (1 << 0) + + /** Constant for a keyboard report modifier byte, indicating that the keyboard's left shift key is currently pressed. */ + #define HID_KEYBOARD_MODIFER_LEFTSHIFT (1 << 1) + + /** Constant for a keyboard report modifier byte, indicating that the keyboard's left alt key is currently pressed. */ + #define HID_KEYBOARD_MODIFER_LEFTALT (1 << 2) + + /** Constant for a keyboard report modifier byte, indicating that the keyboard's left GUI key is currently pressed. */ + #define HID_KEYBOARD_MODIFER_LEFTGUI (1 << 3) + + /** Constant for a keyboard report modifier byte, indicating that the keyboard's right control key is currently pressed. */ + #define HID_KEYBOARD_MODIFER_RIGHTCTRL (1 << 4) + + /** Constant for a keyboard report modifier byte, indicating that the keyboard's right shift key is currently pressed. */ + #define HID_KEYBOARD_MODIFER_RIGHTSHIFT (1 << 5) + + /** Constant for a keyboard report modifier byte, indicating that the keyboard's right alt key is currently pressed. */ + #define HID_KEYBOARD_MODIFER_RIGHTALT (1 << 6) + + /** Constant for a keyboard report modifier byte, indicating that the keyboard's right GUI key is currently pressed. */ + #define HID_KEYBOARD_MODIFER_RIGHTGUI (1 << 7) + + /** Constant for a keyboard output report LED byte, indicating that the host's NUM LOCK mode is currently set. */ + #define HID_KEYBOARD_LED_NUMLOCK (1 << 0) + + /** Constant for a keyboard output report LED byte, indicating that the host's CAPS LOCK mode is currently set. */ + #define HID_KEYBOARD_LED_CAPSLOCK (1 << 1) + + /** Constant for a keyboard output report LED byte, indicating that the host's SCROLL LOCK mode is currently set. */ + #define HID_KEYBOARD_LED_SCROLLLOCK (1 << 2) + + /** Constant for a keyboard output report LED byte, indicating that the host's KATANA mode is currently set. */ + #define HID_KEYBOARD_LED_KATANA (1 << 3) + + /* Type Defines: */ + /** Enum for the different types of HID reports. */ + enum HID_ReportItemTypes_t + { + REPORT_ITEM_TYPE_In = 0, /**< Indicates that the item is an IN report type. */ + REPORT_ITEM_TYPE_Out = 1, /**< Indicates that the item is an OUT report type. */ + REPORT_ITEM_TYPE_Feature = 2, /**< Indicates that the item is a FEATURE report type. */ + }; + + /** \brief HID class-specific HID Descriptor. + * + * Type define for the HID class-specific HID descriptor, to describe the HID device's specifications. Refer to the HID + * specification for details on the structure elements. + */ + typedef struct + { + USB_Descriptor_Header_t Header; /**< Regular descriptor header containing the descriptor's type and length. */ + + uint16_t HIDSpec; /**< BCD encoded version that the HID descriptor and device complies to. */ + uint8_t CountryCode; /**< Country code of the localized device, or zero if universal. */ + + uint8_t TotalReportDescriptors; /**< Total number of HID report descriptors for the interface. */ + + uint8_t HIDReportType; /**< Type of HID report, set to \ref DTYPE_Report. */ + uint16_t HIDReportLength; /**< Length of the associated HID report descriptor, in bytes. */ + } USB_HID_Descriptor_t; + + /** \brief Standard HID Boot Protocol Mouse Report. + * + * Type define for a standard Boot Protocol Mouse report + */ + typedef struct + { + uint8_t Button; /**< Button mask for currently pressed buttons in the mouse. */ + int8_t X; /**< Current delta X movement of the mouse. */ + int8_t Y; /**< Current delta Y movement on the mouse. */ + } USB_MouseReport_Data_t; + + /** \brief Standard HID Boot Protocol Keyboard Report. + * + * Type define for a standard Boot Protocol Keyboard report + */ + typedef struct + { + uint8_t Modifier; /**< Keyboard modifier byte, indicating pressed modifier keys (a combination of + * HID_KEYBOARD_MODIFER_* masks). + */ + uint8_t Reserved; /**< Reserved for OEM use, always set to 0. */ + uint8_t KeyCode[6]; /**< Key codes of the currently pressed keys. */ + } USB_KeyboardReport_Data_t; + + /** Type define for the data type used to store HID report descriptor elements. */ + typedef uint8_t USB_Descriptor_HIDReport_Datatype_t; + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Common/MIDI.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Common/MIDI.h new file mode 100644 index 0000000000..688ef09b32 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Common/MIDI.h @@ -0,0 +1,191 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief Common definitions and declarations for the library USB MIDI Class driver. + * + * Common definitions and declarations for the library USB MIDI Class driver. + * + * \note This file should not be included directly. It is automatically included as needed by the class driver + * dispatch header located in LUFA/Drivers/USB/Class/MIDI.h. + */ + +/** \ingroup Group_USBClassMIDI + * @defgroup Group_USBClassMIDICommon Common Class Definitions + * + * \section Module Description + * Constants, Types and Enum definitions that are common to both Device and Host modes for the USB + * MIDI Class. + * + * @{ + */ + +#ifndef _MIDI_CLASS_COMMON_H_ +#define _MIDI_CLASS_COMMON_H_ + + /* Macros: */ + #define __INCLUDE_FROM_AUDIO_DRIVER + + /* Includes: */ + #include "../../USB.h" + #include "Audio.h" + + #include + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_MIDI_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/Class/MIDI.h instead. + #endif + + /* Macros: */ + /** Audio class descriptor subtype value for a Audio class-specific MIDI input jack descriptor. */ + #define DSUBTYPE_InputJack 0x02 + + /** Audio class descriptor subtype value for a Audio class-specific MIDI output jack descriptor. */ + #define DSUBTYPE_OutputJack 0x03 + + /** Audio class descriptor jack type value for an embedded (logical) MIDI input or output jack. */ + #define MIDI_JACKTYPE_EMBEDDED 0x01 + + /** Audio class descriptor jack type value for an external (physical) MIDI input or output jack. */ + #define MIDI_JACKTYPE_EXTERNAL 0x02 + + /** MIDI command for a note on (activation) event. */ + #define MIDI_COMMAND_NOTE_ON 0x90 + + /** MIDI command for a note off (deactivation) event. */ + #define MIDI_COMMAND_NOTE_OFF 0x80 + + /** Standard key press velocity value used for all note events. */ + #define MIDI_STANDARD_VELOCITY 64 + + /** Convenience macro. MIDI channels are numbered from 1-10 (natural numbers) however the logical channel + * addresses are zero-indexed. This converts a natural MIDI channel number into the logical channel address. + * + * \param[in] channel MIDI channel number to address. + */ + #define MIDI_CHANNEL(channel) ((channel) - 1) + + /* Type Defines: */ + /** \brief MIDI class-specific Streaming Interface Descriptor. + * + * Type define for an Audio class-specific MIDI streaming interface descriptor. This indicates to the host + * how MIDI the specification compliance of the device and the total length of the Audio class-specific descriptors. + * See the USB Audio specification for more details. + */ + typedef struct + { + USB_Descriptor_Header_t Header; /**< Regular descriptor header containing the descriptor's type and length. */ + uint8_t Subtype; /**< Sub type value used to distinguish between audio class-specific descriptors. */ + + uint16_t AudioSpecification; /**< Binary coded decimal value, indicating the supported Audio Class + * specification version. + */ + uint16_t TotalLength; /**< Total length of the Audio class-specific descriptors, including this descriptor. */ + } USB_MIDI_AudioInterface_AS_t; + + /** \brief MIDI class-specific Input Jack Descriptor. + * + * Type define for an Audio class-specific MIDI IN jack. This gives information to the host on a MIDI input, either + * a physical input jack, or a logical jack (receiving input data internally, or from the host via an endpoint). + */ + typedef struct + { + USB_Descriptor_Header_t Header; /**< Regular descriptor header containing the descriptor's type and length. */ + uint8_t Subtype; /**< Sub type value used to distinguish between audio class-specific descriptors. */ + + uint8_t JackType; /**< Type of jack, one of the JACKTYPE_* mask values. */ + uint8_t JackID; /**< ID value of this jack - must be a unique value within the device. */ + + uint8_t JackStrIndex; /**< Index of a string descriptor describing this descriptor within the device. */ + } USB_MIDI_In_Jack_t; + + /** \brief MIDI class-specific Output Jack Descriptor. + * + * Type define for an Audio class-specific MIDI OUT jack. This gives information to the host on a MIDI output, either + * a physical output jack, or a logical jack (sending output data internally, or to the host via an endpoint). + */ + typedef struct + { + USB_Descriptor_Header_t Header; /**< Regular descriptor header containing the descriptor's type and length. */ + uint8_t Subtype; /**< Sub type value used to distinguish between audio class-specific descriptors. */ + + uint8_t JackType; /**< Type of jack, one of the JACKTYPE_* mask values. */ + uint8_t JackID; /**< ID value of this jack - must be a unique value within the device. */ + + uint8_t NumberOfPins; /**< Number of output channels within the jack, either physical or logical. */ + uint8_t SourceJackID[1]; /**< ID of each output pin's source data jack. */ + uint8_t SourcePinID[1]; /**< Pin number in the input jack of each output pin's source data. */ + + uint8_t JackStrIndex; /**< Index of a string descriptor describing this descriptor within the device. */ + } USB_MIDI_Out_Jack_t; + + /** \brief Audio class-specific Jack Endpoint Descriptor. + * + * Type define for an Audio class-specific extended MIDI jack endpoint descriptor. This contains extra information + * on the usage of MIDI endpoints used to stream MIDI events in and out of the USB Audio device, and follows an Audio + * class-specific extended MIDI endpoint descriptor. See the USB Audio specification for more details. + */ + typedef struct + { + USB_Descriptor_Header_t Header; /**< Regular descriptor header containing the descriptor's type and length. */ + uint8_t Subtype; /**< Sub type value used to distinguish between audio class-specific descriptors. */ + + uint8_t TotalEmbeddedJacks; /**< Total number of jacks inside this endpoint. */ + uint8_t AssociatedJackID[1]; /**< IDs of each jack inside the endpoint. */ + } USB_MIDI_Jack_Endpoint_t; + + /** \brief MIDI Class Driver Event Packet. + * + * Type define for a USB MIDI event packet, used to encapsulate sent and received MIDI messages from a USB MIDI interface. + */ + typedef struct + { + unsigned char Command : 4; /**< Upper nibble of the MIDI command being sent or received in the event packet. */ + unsigned char CableNumber : 4; /**< Virtual cable number of the event being sent or received in the given MIDI interface. */ + + uint8_t Data1; /**< First byte of data in the MIDI event. */ + uint8_t Data2; /**< Second byte of data in the MIDI event. */ + uint8_t Data3; /**< Third byte of data in the MIDI event. */ + } MIDI_EventPacket_t; + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Common/MassStorage.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Common/MassStorage.h new file mode 100644 index 0000000000..dd2da2ffb4 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Common/MassStorage.h @@ -0,0 +1,322 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief Common definitions and declarations for the library USB Mass Storage Class driver. + * + * Common definitions and declarations for the library USB Mass Storage Class driver. + * + * \note This file should not be included directly. It is automatically included as needed by the class driver + * dispatch header located in LUFA/Drivers/USB/Class/MassStorage.h. + */ + +/** \ingroup Group_USBClassMS + * @defgroup Group_USBClassMSCommon Common Class Definitions + * + * \section Module Description + * Constants, Types and Enum definitions that are common to both Device and Host modes for the USB + * Mass Storage Class. + * + * @{ + */ + +#ifndef _MS_CLASS_COMMON_H_ +#define _MS_CLASS_COMMON_H_ + + /* Includes: */ + #include "../../USB.h" + + #include + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_MS_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/Class/MassStorage.h instead. + #endif + + /* Macros: */ + /** Mass Storage class-specific request to reset the Mass Storage interface, ready for the next command. */ + #define REQ_MassStorageReset 0xFF + + /** Mass Storage class-specific request to retrieve the total number of Logical Units (drives) in the SCSI device. */ + #define REQ_GetMaxLUN 0xFE + + /** Magic signature for a Command Block Wrapper used in the Mass Storage Bulk-Only transport protocol. */ + #define MS_CBW_SIGNATURE 0x43425355UL + + /** Magic signature for a Command Status Wrapper used in the Mass Storage Bulk-Only transport protocol. */ + #define MS_CSW_SIGNATURE 0x53425355UL + + /** Mask for a Command Block Wrapper's flags attribute to specify a command with data sent from host-to-device. */ + #define MS_COMMAND_DIR_DATA_OUT (0 << 7) + + /** Mask for a Command Block Wrapper's flags attribute to specify a command with data sent from device-to-host. */ + #define MS_COMMAND_DIR_DATA_IN (1 << 7) + + /** SCSI Command Code for an INQUIRY command. */ + #define SCSI_CMD_INQUIRY 0x12 + + /** SCSI Command Code for a REQUEST SENSE command. */ + #define SCSI_CMD_REQUEST_SENSE 0x03 + + /** SCSI Command Code for a TEST UNIT READY command. */ + #define SCSI_CMD_TEST_UNIT_READY 0x00 + + /** SCSI Command Code for a READ CAPACITY (10) command. */ + #define SCSI_CMD_READ_CAPACITY_10 0x25 + + /** SCSI Command Code for a SEND DIAGNOSTIC command. */ + #define SCSI_CMD_SEND_DIAGNOSTIC 0x1D + + /** SCSI Command Code for a PREVENT ALLOW MEDIUM REMOVAL command. */ + #define SCSI_CMD_PREVENT_ALLOW_MEDIUM_REMOVAL 0x1E + + /** SCSI Command Code for a WRITE (10) command. */ + #define SCSI_CMD_WRITE_10 0x2A + + /** SCSI Command Code for a READ (10) command. */ + #define SCSI_CMD_READ_10 0x28 + + /** SCSI Command Code for a WRITE (6) command. */ + #define SCSI_CMD_WRITE_6 0x0A + + /** SCSI Command Code for a READ (6) command. */ + #define SCSI_CMD_READ_6 0x08 + + /** SCSI Command Code for a VERIFY (10) command. */ + #define SCSI_CMD_VERIFY_10 0x2F + + /** SCSI Command Code for a MODE SENSE (6) command. */ + #define SCSI_CMD_MODE_SENSE_6 0x1A + + /** SCSI Command Code for a MODE SENSE (10) command. */ + #define SCSI_CMD_MODE_SENSE_10 0x5A + + /** SCSI Sense Code to indicate no error has occurred. */ + #define SCSI_SENSE_KEY_GOOD 0x00 + + /** SCSI Sense Code to indicate that the device has recovered from an error. */ + #define SCSI_SENSE_KEY_RECOVERED_ERROR 0x01 + + /** SCSI Sense Code to indicate that the device is not ready for a new command. */ + #define SCSI_SENSE_KEY_NOT_READY 0x02 + + /** SCSI Sense Code to indicate an error whilst accessing the medium. */ + #define SCSI_SENSE_KEY_MEDIUM_ERROR 0x03 + + /** SCSI Sense Code to indicate a hardware has occurred. */ + #define SCSI_SENSE_KEY_HARDWARE_ERROR 0x04 + + /** SCSI Sense Code to indicate that an illegal request has been issued. */ + #define SCSI_SENSE_KEY_ILLEGAL_REQUEST 0x05 + + /** SCSI Sense Code to indicate that the unit requires attention from the host to indicate + * a reset event, medium removal or other condition. + */ + #define SCSI_SENSE_KEY_UNIT_ATTENTION 0x06 + + /** SCSI Sense Code to indicate that a write attempt on a protected block has been made. */ + #define SCSI_SENSE_KEY_DATA_PROTECT 0x07 + + /** SCSI Sense Code to indicate an error while trying to write to a write-once medium. */ + #define SCSI_SENSE_KEY_BLANK_CHECK 0x08 + + /** SCSI Sense Code to indicate a vendor specific error has occurred. */ + #define SCSI_SENSE_KEY_VENDOR_SPECIFIC 0x09 + + /** SCSI Sense Code to indicate that an EXTENDED COPY command has aborted due to an error. */ + #define SCSI_SENSE_KEY_COPY_ABORTED 0x0A + + /** SCSI Sense Code to indicate that the device has aborted the issued command. */ + #define SCSI_SENSE_KEY_ABORTED_COMMAND 0x0B + + /** SCSI Sense Code to indicate an attempt to write past the end of a partition has been made. */ + #define SCSI_SENSE_KEY_VOLUME_OVERFLOW 0x0D + + /** SCSI Sense Code to indicate that the source data did not match the data read from the medium. */ + #define SCSI_SENSE_KEY_MISCOMPARE 0x0E + + /** SCSI Additional Sense Code to indicate no additional sense information is available. */ + #define SCSI_ASENSE_NO_ADDITIONAL_INFORMATION 0x00 + + /** SCSI Additional Sense Code to indicate that the logical unit (LUN) addressed is not ready. */ + #define SCSI_ASENSE_LOGICAL_UNIT_NOT_READY 0x04 + + /** SCSI Additional Sense Code to indicate an invalid field was encountered while processing the issued command. */ + #define SCSI_ASENSE_INVALID_FIELD_IN_CDB 0x24 + + /** SCSI Additional Sense Code to indicate that an attempt to write to a protected area was made. */ + #define SCSI_ASENSE_WRITE_PROTECTED 0x27 + + /** SCSI Additional Sense Code to indicate an error whilst formatting the device medium. */ + #define SCSI_ASENSE_FORMAT_ERROR 0x31 + + /** SCSI Additional Sense Code to indicate an invalid command was issued. */ + #define SCSI_ASENSE_INVALID_COMMAND 0x20 + + /** SCSI Additional Sense Code to indicate a write to a block out outside of the medium's range was issued. */ + #define SCSI_ASENSE_LOGICAL_BLOCK_ADDRESS_OUT_OF_RANGE 0x21 + + /** SCSI Additional Sense Code to indicate that no removable medium is inserted into the device. */ + #define SCSI_ASENSE_MEDIUM_NOT_PRESENT 0x3A + + /** SCSI Additional Sense Qualifier Code to indicate no additional sense qualifier information is available. */ + #define SCSI_ASENSEQ_NO_QUALIFIER 0x00 + + /** SCSI Additional Sense Qualifier Code to indicate that a medium format command failed to complete. */ + #define SCSI_ASENSEQ_FORMAT_COMMAND_FAILED 0x01 + + /** SCSI Additional Sense Qualifier Code to indicate that an initializing command must be issued before the issued + * command can be executed. + */ + #define SCSI_ASENSEQ_INITIALIZING_COMMAND_REQUIRED 0x02 + + /** SCSI Additional Sense Qualifier Code to indicate that an operation is currently in progress. */ + #define SCSI_ASENSEQ_OPERATION_IN_PROGRESS 0x07 + + /* Type defines: */ + /** \brief Mass Storage Class Command Block Wrapper. + * + * Type define for a Command Block Wrapper, used in the Mass Storage Bulk-Only Transport protocol. */ + typedef struct + { + uint32_t Signature; /**< Command block signature, must be CBW_SIGNATURE to indicate a valid Command Block. */ + uint32_t Tag; /**< Unique command ID value, to associate a command block wrapper with its command status wrapper. */ + uint32_t DataTransferLength; /**< Length of the optional data portion of the issued command, in bytes. */ + uint8_t Flags; /**< Command block flags, indicating command data direction. */ + uint8_t LUN; /**< Logical Unit number this command is issued to. */ + uint8_t SCSICommandLength; /**< Length of the issued SCSI command within the SCSI command data array. */ + uint8_t SCSICommandData[16]; /**< Issued SCSI command in the Command Block. */ + } MS_CommandBlockWrapper_t; + + /** \brief Mass Storage Class Command Status Wrapper. + * + * Type define for a Command Status Wrapper, used in the Mass Storage Bulk-Only Transport protocol. + */ + typedef struct + { + uint32_t Signature; /**< Status block signature, must be CSW_SIGNATURE to indicate a valid Command Status. */ + uint32_t Tag; /**< Unique command ID value, to associate a command block wrapper with its command status wrapper. */ + uint32_t DataTransferResidue; /**< Number of bytes of data not processed in the SCSI command. */ + uint8_t Status; /**< Status code of the issued command - a value from the MassStorage_CommandStatusCodes_t enum. */ + } MS_CommandStatusWrapper_t; + + /** \brief Mass Storage Class SCSI Sense Structure + * + * Type define for a SCSI Sense structure. Structures of this type are filled out by the + * device via the \ref MS_Host_RequestSense() function, indicating the current sense data of the + * device (giving explicit error codes for the last issued command). For details of the + * structure contents, refer to the SCSI specifications. + */ + typedef struct + { + uint8_t ResponseCode; + + uint8_t SegmentNumber; + + unsigned char SenseKey : 4; + unsigned char Reserved : 1; + unsigned char ILI : 1; + unsigned char EOM : 1; + unsigned char FileMark : 1; + + uint8_t Information[4]; + uint8_t AdditionalLength; + uint8_t CmdSpecificInformation[4]; + uint8_t AdditionalSenseCode; + uint8_t AdditionalSenseQualifier; + uint8_t FieldReplaceableUnitCode; + uint8_t SenseKeySpecific[3]; + } SCSI_Request_Sense_Response_t; + + /** \brief Mass Storage Class SCSI Inquiry Structure. + * + * Type define for a SCSI Inquiry structure. Structures of this type are filled out by the + * device via the \ref MS_Host_GetInquiryData() function, retrieving the attached device's + * information. + * + * For details of the structure contents, refer to the SCSI specifications. + */ + typedef struct + { + unsigned char DeviceType : 5; + unsigned char PeripheralQualifier : 3; + + unsigned char Reserved : 7; + unsigned char Removable : 1; + + uint8_t Version; + + unsigned char ResponseDataFormat : 4; + unsigned char Reserved2 : 1; + unsigned char NormACA : 1; + unsigned char TrmTsk : 1; + unsigned char AERC : 1; + + uint8_t AdditionalLength; + uint8_t Reserved3[2]; + + unsigned char SoftReset : 1; + unsigned char CmdQue : 1; + unsigned char Reserved4 : 1; + unsigned char Linked : 1; + unsigned char Sync : 1; + unsigned char WideBus16Bit : 1; + unsigned char WideBus32Bit : 1; + unsigned char RelAddr : 1; + + uint8_t VendorID[8]; + uint8_t ProductID[16]; + uint8_t RevisionID[4]; + } SCSI_Inquiry_Response_t; + + /* Enums: */ + /** Enum for the possible command status wrapper return status codes. */ + enum MassStorage_CommandStatusCodes_t + { + SCSI_Command_Pass = 0, /**< Command completed with no error */ + SCSI_Command_Fail = 1, /**< Command failed to complete - host may check the exact error via a + * SCSI REQUEST SENSE command. + */ + SCSI_Phase_Error = 2 /**< Command failed due to being invalid in the current phase. */ + }; + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Common/Printer.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Common/Printer.h new file mode 100644 index 0000000000..7e89b41be6 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Common/Printer.h @@ -0,0 +1,85 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief Common definitions and declarations for the library USB Printer Class driver. + * + * Common definitions and declarations for the library USB Printer Class driver. + * + * \note This file should not be included directly. It is automatically included as needed by the class driver + * dispatch header located in LUFA/Drivers/USB/Class/Printer.h. + */ + +/** \ingroup Group_USBClassPrinter + * @defgroup Group_USBClassPrinterCommon Common Class Definitions + * + * \section Module Description + * Constants, Types and Enum definitions that are common to both Device and Host modes for the USB + * Printer Class. + * + * @{ + */ + +#ifndef _PRINTER_CLASS_COMMON_H_ +#define _PRINTER_CLASS_COMMON_H_ + + /* Includes: */ + #include "../../USB.h" + + #include + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_PRINTER_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/Class/Printer.h instead. + #endif + + /* Macros: */ + /** Port status mask for a printer device, indicating that an error has *not* occurred. */ + #define PRNT_PORTSTATUS_NOTERROR (1 << 3) + + /** Port status mask for a printer device, indicating that the device is currently selected. */ + #define PRNT_PORTSTATUS_SELECT (1 << 4) + + /** Port status mask for a printer device, indicating that the device is currently out of paper. */ + #define PRNT_PORTSTATUS_PAPEREMPTY (1 << 5) + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Common/RNDIS.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Common/RNDIS.h new file mode 100644 index 0000000000..a6549c5e3d --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Common/RNDIS.h @@ -0,0 +1,303 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief Common definitions and declarations for the library USB RNDIS Class driver. + * + * Common definitions and declarations for the library USB RNDIS Class driver. + * + * \note This file should not be included directly. It is automatically included as needed by the class driver + * dispatch header located in LUFA/Drivers/USB/Class/RNDIS.h. + */ + +/** \ingroup Group_USBClassRNDIS + * @defgroup Group_USBClassRNDISCommon Common Class Definitions + * + * \section Module Description + * Constants, Types and Enum definitions that are common to both Device and Host modes for the USB + * RNDIS Class. + * + * @{ + */ + +#ifndef _RNDIS_CLASS_COMMON_H_ +#define _RNDIS_CLASS_COMMON_H_ + + /* Macros: */ + #define __INCLUDE_FROM_CDC_DRIVER + + /* Includes: */ + #include "../../USB.h" + #include "RNDISConstants.h" + #include "CDC.h" + + #include + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_RNDIS_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/Class/RNDIS.h instead. + #endif + + /* Macros: */ + /** Implemented RNDIS Version Major. */ + #define REMOTE_NDIS_VERSION_MAJOR 0x01 + + /** Implemented RNDIS Version Minor. */ + #define REMOTE_NDIS_VERSION_MINOR 0x00 + + /** RNDIS request to issue a host-to-device NDIS command. */ + #define REQ_SendEncapsulatedCommand 0x00 + + /** RNDIS request to issue a device-to-host NDIS response. */ + #define REQ_GetEncapsulatedResponse 0x01 + + /** Maximum size in bytes of a RNDIS control message which can be sent or received. */ + #define RNDIS_MESSAGE_BUFFER_SIZE 128 + + /** Maximum size in bytes of an Ethernet frame according to the Ethernet standard. */ + #define ETHERNET_FRAME_SIZE_MAX 1500 + + /** Notification request value for a RNDIS Response Available notification. */ + #define NOTIF_ResponseAvailable 1 + + /* Enums: */ + /** Enum for the possible NDIS adapter states. */ + enum RNDIS_States_t + { + RNDIS_Uninitialized = 0, /**< Adapter currently uninitialized. */ + RNDIS_Initialized = 1, /**< Adapter currently initialized but not ready for data transfers. */ + RNDIS_Data_Initialized = 2, /**< Adapter currently initialized and ready for data transfers. */ + }; + + /** Enum for the NDIS hardware states. */ + enum NDIS_Hardware_Status_t + { + NDIS_HardwareStatus_Ready, /**< Hardware Ready to accept commands from the host. */ + NDIS_HardwareStatus_Initializing, /**< Hardware busy initializing. */ + NDIS_HardwareStatus_Reset, /**< Hardware reset. */ + NDIS_HardwareStatus_Closing, /**< Hardware currently closing. */ + NDIS_HardwareStatus_NotReady /**< Hardware not ready to accept commands from the host. */ + }; + + /* Type Defines: */ + /** \brief MAC Address Structure. + * + * Type define for a physical MAC address of a device on a network. + */ + typedef struct + { + uint8_t Octets[6]; /**< Individual bytes of a MAC address */ + } MAC_Address_t; + + /** \brief RNDIS Ethernet Frame Packet Information Structure. + * + * Type define for an Ethernet frame buffer data and information structure. + */ + typedef struct + { + uint8_t FrameData[ETHERNET_FRAME_SIZE_MAX]; /**< Ethernet frame contents. */ + uint16_t FrameLength; /**< Length in bytes of the Ethernet frame stored in the buffer. */ + bool FrameInBuffer; /**< Indicates if a frame is currently stored in the buffer. */ + } Ethernet_Frame_Info_t; + + /** \brief RNDIS Common Message Header Structure. + * + * Type define for a RNDIS message header, sent before RNDIS messages. + */ + typedef struct + { + uint32_t MessageType; /**< RNDIS message type, a REMOTE_NDIS_*_MSG constant */ + uint32_t MessageLength; /**< Total length of the RNDIS message, in bytes */ + } RNDIS_Message_Header_t; + + /** \brief RNDIS Message Structure. + * + * Type define for a RNDIS packet message, used to encapsulate Ethernet packets sent to and from the adapter. + */ + typedef struct + { + uint32_t MessageType; + uint32_t MessageLength; + uint32_t DataOffset; + uint32_t DataLength; + uint32_t OOBDataOffset; + uint32_t OOBDataLength; + uint32_t NumOOBDataElements; + uint32_t PerPacketInfoOffset; + uint32_t PerPacketInfoLength; + uint32_t VcHandle; + uint32_t Reserved; + } RNDIS_Packet_Message_t; + + /** \brief RNDIS Initialization Message Structure. + * + * Type define for a RNDIS Initialize command message. + */ + typedef struct + { + uint32_t MessageType; + uint32_t MessageLength; + uint32_t RequestId; + + uint32_t MajorVersion; + uint32_t MinorVersion; + uint32_t MaxTransferSize; + } RNDIS_Initialize_Message_t; + + /** \brief RNDIS Initialize Complete Message Structure. + * + * Type define for a RNDIS Initialize Complete response message. + */ + typedef struct + { + uint32_t MessageType; + uint32_t MessageLength; + uint32_t RequestId; + uint32_t Status; + + uint32_t MajorVersion; + uint32_t MinorVersion; + uint32_t DeviceFlags; + uint32_t Medium; + uint32_t MaxPacketsPerTransfer; + uint32_t MaxTransferSize; + uint32_t PacketAlignmentFactor; + uint32_t AFListOffset; + uint32_t AFListSize; + } RNDIS_Initialize_Complete_t; + + /** \brief RNDIS Keep Alive Message Structure. + * + * Type define for a RNDIS Keep Alive command message. + */ + typedef struct + { + uint32_t MessageType; + uint32_t MessageLength; + uint32_t RequestId; + } RNDIS_KeepAlive_Message_t; + + /** \brief RNDIS Keep Alive Complete Message Structure. + * + * Type define for a RNDIS Keep Alive Complete response message. + */ + typedef struct + { + uint32_t MessageType; + uint32_t MessageLength; + uint32_t RequestId; + uint32_t Status; + } RNDIS_KeepAlive_Complete_t; + + /** \brief RNDIS Reset Complete Message Structure. + * + * Type define for a RNDIS Reset Complete response message. + */ + typedef struct + { + uint32_t MessageType; + uint32_t MessageLength; + uint32_t Status; + + uint32_t AddressingReset; + } RNDIS_Reset_Complete_t; + + /** \brief RNDIS OID Property Set Message Structure. + * + * Type define for a RNDIS OID Property Set command message. + */ + typedef struct + { + uint32_t MessageType; + uint32_t MessageLength; + uint32_t RequestId; + + uint32_t Oid; + uint32_t InformationBufferLength; + uint32_t InformationBufferOffset; + uint32_t DeviceVcHandle; + } RNDIS_Set_Message_t; + + /** \brief RNDIS OID Property Set Complete Message Structure. + * + * Type define for a RNDIS OID Property Set Complete response message. + */ + typedef struct + { + uint32_t MessageType; + uint32_t MessageLength; + uint32_t RequestId; + uint32_t Status; + } RNDIS_Set_Complete_t; + + /** \brief RNDIS OID Property Query Message Structure. + * + * Type define for a RNDIS OID Property Query command message. + */ + typedef struct + { + uint32_t MessageType; + uint32_t MessageLength; + uint32_t RequestId; + + uint32_t Oid; + uint32_t InformationBufferLength; + uint32_t InformationBufferOffset; + uint32_t DeviceVcHandle; + } RNDIS_Query_Message_t; + + /** \brief RNDIS OID Property Query Complete Message Structure. + * + * Type define for a RNDIS OID Property Query Complete response message. + */ + typedef struct + { + uint32_t MessageType; + uint32_t MessageLength; + uint32_t RequestId; + uint32_t Status; + + uint32_t InformationBufferLength; + uint32_t InformationBufferOffset; + } RNDIS_Query_Complete_t; + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Common/RNDISConstants.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Common/RNDISConstants.h new file mode 100644 index 0000000000..7cd80aba7d --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Common/RNDISConstants.h @@ -0,0 +1,121 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief Common RNDIS class constant definitions. + * + * Common RNDIS class constant definitions. + * + * \note This file should not be included directly. It is automatically included as needed by the class driver + * dispatch header located in LUFA/Drivers/USB/Class/Audio.h. + */ + +/** \file + * + * RNDIS specification related constants. For more information on these + * constants, please refer to the Microsoft RNDIS specification. + */ + +#ifndef _RNDIS_CONSTANTS_DEVICE_H_ +#define _RNDIS_CONSTANTS_DEVICE_H_ + + /* Macros: */ + #define REMOTE_NDIS_PACKET_MSG 0x00000001UL + #define REMOTE_NDIS_INITIALIZE_MSG 0x00000002UL + #define REMOTE_NDIS_HALT_MSG 0x00000003UL + #define REMOTE_NDIS_QUERY_MSG 0x00000004UL + #define REMOTE_NDIS_SET_MSG 0x00000005UL + #define REMOTE_NDIS_RESET_MSG 0x00000006UL + #define REMOTE_NDIS_INDICATE_STATUS_MSG 0x00000007UL + #define REMOTE_NDIS_KEEPALIVE_MSG 0x00000008UL + + #define REMOTE_NDIS_INITIALIZE_CMPLT 0x80000002UL + #define REMOTE_NDIS_QUERY_CMPLT 0x80000004UL + #define REMOTE_NDIS_SET_CMPLT 0x80000005UL + #define REMOTE_NDIS_RESET_CMPLT 0x80000006UL + #define REMOTE_NDIS_KEEPALIVE_CMPLT 0x80000008UL + + #define REMOTE_NDIS_STATUS_SUCCESS 0x00000000UL + #define REMOTE_NDIS_STATUS_FAILURE 0xC0000001UL + #define REMOTE_NDIS_STATUS_INVALID_DATA 0xC0010015UL + #define REMOTE_NDIS_STATUS_NOT_SUPPORTED 0xC00000BBUL + #define REMOTE_NDIS_STATUS_MEDIA_CONNECT 0x4001000BUL + #define REMOTE_NDIS_STATUS_MEDIA_DISCONNECT 0x4001000CUL + + #define REMOTE_NDIS_MEDIA_STATE_CONNECTED 0x00000000UL + #define REMOTE_NDIS_MEDIA_STATE_DISCONNECTED 0x00000001UL + + #define REMOTE_NDIS_MEDIUM_802_3 0x00000000UL + + #define REMOTE_NDIS_DF_CONNECTIONLESS 0x00000001UL + #define REMOTE_NDIS_DF_CONNECTION_ORIENTED 0x00000002UL + + #define REMOTE_NDIS_PACKET_DIRECTED 0x00000001UL + #define REMOTE_NDIS_PACKET_MULTICAST 0x00000002UL + #define REMOTE_NDIS_PACKET_ALL_MULTICAST 0x00000004UL + #define REMOTE_NDIS_PACKET_BROADCAST 0x00000008UL + #define REMOTE_NDIS_PACKET_SOURCE_ROUTING 0x00000010UL + #define REMOTE_NDIS_PACKET_PROMISCUOUS 0x00000020UL + #define REMOTE_NDIS_PACKET_SMT 0x00000040UL + #define REMOTE_NDIS_PACKET_ALL_LOCAL 0x00000080UL + #define REMOTE_NDIS_PACKET_GROUP 0x00001000UL + #define REMOTE_NDIS_PACKET_ALL_FUNCTIONAL 0x00002000UL + #define REMOTE_NDIS_PACKET_FUNCTIONAL 0x00004000UL + #define REMOTE_NDIS_PACKET_MAC_FRAME 0x00008000UL + + #define OID_GEN_SUPPORTED_LIST 0x00010101UL + #define OID_GEN_HARDWARE_STATUS 0x00010102UL + #define OID_GEN_MEDIA_SUPPORTED 0x00010103UL + #define OID_GEN_MEDIA_IN_USE 0x00010104UL + #define OID_GEN_MAXIMUM_FRAME_SIZE 0x00010106UL + #define OID_GEN_MAXIMUM_TOTAL_SIZE 0x00010111UL + #define OID_GEN_LINK_SPEED 0x00010107UL + #define OID_GEN_TRANSMIT_BLOCK_SIZE 0x0001010AUL + #define OID_GEN_RECEIVE_BLOCK_SIZE 0x0001010BUL + #define OID_GEN_VENDOR_ID 0x0001010CUL + #define OID_GEN_VENDOR_DESCRIPTION 0x0001010DUL + #define OID_GEN_CURRENT_PACKET_FILTER 0x0001010EUL + #define OID_GEN_MAXIMUM_TOTAL_SIZE 0x00010111UL + #define OID_GEN_MEDIA_CONNECT_STATUS 0x00010114UL + #define OID_GEN_PHYSICAL_MEDIUM 0x00010202UL + #define OID_GEN_XMIT_OK 0x00020101UL + #define OID_GEN_RCV_OK 0x00020102UL + #define OID_GEN_XMIT_ERROR 0x00020103UL + #define OID_GEN_RCV_ERROR 0x00020104UL + #define OID_GEN_RCV_NO_BUFFER 0x00020105UL + #define OID_802_3_PERMANENT_ADDRESS 0x01010101UL + #define OID_802_3_CURRENT_ADDRESS 0x01010102UL + #define OID_802_3_MULTICAST_LIST 0x01010103UL + #define OID_802_3_MAXIMUM_LIST_SIZE 0x01010104UL + #define OID_802_3_RCV_ERROR_ALIGNMENT 0x01020101UL + #define OID_802_3_XMIT_ONE_COLLISION 0x01020102UL + #define OID_802_3_XMIT_MORE_COLLISIONS 0x01020103UL + +#endif diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Common/StillImage.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Common/StillImage.h new file mode 100644 index 0000000000..434d65a1e4 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Common/StillImage.h @@ -0,0 +1,146 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief Common definitions and declarations for the library USB Still Image Class driver. + * + * Common definitions and declarations for the library USB Still Image Class driver. + * + * \note This file should not be included directly. It is automatically included as needed by the class driver + * dispatch header located in LUFA/Drivers/USB/Class/StillImage.h. + */ + +/** \ingroup Group_USBClassSI + * @defgroup Group_USBClassSICommon Common Class Definitions + * + * \section Module Description + * Constants, Types and Enum definitions that are common to both Device and Host modes for the USB + * Still Image Class. + * + * @{ + */ + +#ifndef _SI_CLASS_COMMON_H_ +#define _SI_CLASS_COMMON_H_ + + /* Includes: */ + #include "../../USB.h" + + #include + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_SI_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/Class/StillImage.h instead. + #endif + + /* Macros: */ + /** Length in bytes of a given Unicode string's character length. + * + * \param[in] Chars Total number of Unicode characters in the string. + * + * \return Number of bytes of the given unicode string. + */ + #define UNICODE_STRING_LENGTH(Chars) ((Chars) << 1) + + /** Used in the DataLength field of a PIMA container, to give the total container size in bytes for + * a command container. + * + * \param[in] Params Number of parameters which are to be sent in the Param field of the container. + */ + #define PIMA_COMMAND_SIZE(Params) ((sizeof(SI_PIMA_Container_t) - 12) + \ + ((Params) * sizeof(uint32_t))) + + /** Used in the DataLength field of a PIMA container, to give the total container size in bytes for + * a data container. + * + * \param[in] DataLen Length in bytes of the data in the container. + */ + #define PIMA_DATA_SIZE(DataLen) ((sizeof(SI_PIMA_Container_t) - 12) + \ + (DataLen)) + + /* Enums: */ + /** Enum for the possible PIMA contains types. */ + enum SI_PIMA_Container_Types_t + { + CType_Undefined = 0, /**< Undefined container type. */ + CType_CommandBlock = 1, /**< Command Block container type. */ + CType_DataBlock = 2, /**< Data Block container type. */ + CType_ResponseBlock = 3, /**< Response container type. */ + CType_EventBlock = 4, /**< Event Block container type. */ + }; + + /* Enums: */ + /** Enums for the possible status codes of a returned Response Block from an attached PIMA compliant Still Image device. */ + enum SI_PIMA_ResponseCodes_t + { + PIMA_RESPONSE_OK = 1, /**< Response code indicating no error in the issued command. */ + PIMA_RESPONSE_GeneralError = 2, /**< Response code indicating a general error while processing the + * issued command. + */ + PIMA_RESPONSE_SessionNotOpen = 3, /**< Response code indicating that the sent command requires an open + * session before being issued. + */ + PIMA_RESPONSE_InvalidTransaction = 4, /**< Response code indicating an invalid transaction occurred. */ + PIMA_RESPONSE_OperationNotSupported = 5, /**< Response code indicating that the issued command is not supported + * by the attached device. + */ + PIMA_RESPONSE_ParameterNotSupported = 6, /**< Response code indicating that one or more of the issued command's + * parameters are not supported by the device. + */ + }; + + /* Type Defines: */ + /** \brief PIMA Still Image Device Command/Response Container. + * + * Type define for a PIMA container, use to send commands and receive responses to and from an + * attached Still Image device. + */ + typedef struct + { + uint32_t DataLength; /**< Length of the container and data, in bytes. */ + uint16_t Type; /**< Container type, a value from the \ref SI_PIMA_Container_Types_t enum. */ + uint16_t Code; /**< Command, event or response code of the container. */ + uint32_t TransactionID; /**< Unique container ID to link blocks together. */ + uint32_t Params[3]; /**< Block parameters to be issued along with the block code (command blocks only). */ + } SI_PIMA_Container_t; + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Device/Audio.c b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Device/Audio.c new file mode 100644 index 0000000000..1569316541 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Device/Audio.c @@ -0,0 +1,89 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +#define __INCLUDE_FROM_USB_DRIVER +#include "../../HighLevel/USBMode.h" +#if defined(USB_CAN_BE_DEVICE) + +#define __INCLUDE_FROM_AUDIO_DRIVER +#include "Audio.h" + +void Audio_Device_ProcessControlRequest(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo) +{ + if (!(Endpoint_IsSETUPReceived())) + return; + + if (USB_ControlRequest.wIndex != AudioInterfaceInfo->Config.StreamingInterfaceNumber) + return; + + switch (USB_ControlRequest.bRequest) + { + case REQ_SetInterface: + if (USB_ControlRequest.bmRequestType == (REQDIR_HOSTTODEVICE | REQTYPE_STANDARD | REQREC_INTERFACE)) + { + Endpoint_ClearSETUP(); + + AudioInterfaceInfo->State.InterfaceEnabled = ((USB_ControlRequest.wValue & 0xFF) != 0); + + Endpoint_ClearStatusStage(); + } + + break; + } +} + +bool Audio_Device_ConfigureEndpoints(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo) +{ + memset(&AudioInterfaceInfo->State, 0x00, sizeof(AudioInterfaceInfo->State)); + + if (AudioInterfaceInfo->Config.DataINEndpointNumber) + { + if (!(Endpoint_ConfigureEndpoint(AudioInterfaceInfo->Config.DataINEndpointNumber, EP_TYPE_ISOCHRONOUS, + ENDPOINT_DIR_IN, AudioInterfaceInfo->Config.DataINEndpointSize, + ENDPOINT_BANK_DOUBLE))) + { + return false; + } + } + + if (AudioInterfaceInfo->Config.DataOUTEndpointNumber) + { + if (!(Endpoint_ConfigureEndpoint(AudioInterfaceInfo->Config.DataOUTEndpointNumber, EP_TYPE_ISOCHRONOUS, + ENDPOINT_DIR_OUT, AudioInterfaceInfo->Config.DataOUTEndpointSize, + ENDPOINT_BANK_DOUBLE))) + { + return false; + } + } + + return true; +} + +#endif \ No newline at end of file diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Device/Audio.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Device/Audio.h new file mode 100644 index 0000000000..7fdd8aa1d7 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Device/Audio.h @@ -0,0 +1,327 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief Device mode driver for the library USB Audio Class driver. + * + * Device mode driver for the library USB Audio Class driver. + * + * \note This file should not be included directly. It is automatically included as needed by the class driver + * dispatch header located in LUFA/Drivers/USB/Class/Audio.h. + */ + +/** \ingroup Group_USBClassAudio + * @defgroup Group_USBClassAudioDevice Audio Class Device Mode Driver + * + * \section Sec_Dependencies Module Source Dependencies + * The following files must be built with any user project that uses this module: + * - LUFA/Drivers/USB/Class/Device/Audio.c (Makefile source module name: LUFA_SRC_USBCLASS) + * + * \section Module Description + * Device Mode USB Class driver framework interface, for the Audio USB Class driver. + * + * @{ + */ + +#ifndef _AUDIO_CLASS_DEVICE_H_ +#define _AUDIO_CLASS_DEVICE_H_ + + /* Includes: */ + #include "../../USB.h" + #include "../Common/Audio.h" + + #include + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_AUDIO_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/Class/Audio.h instead. + #endif + + /* Public Interface - May be used in end-application: */ + /* Type Defines: */ + /** \brief Audio Class Device Mode Configuration and State Structure. + * + * Class state structure. An instance of this structure should be made for each Audio interface + * within the user application, and passed to each of the Audio class driver functions as the + * AudioInterfaceInfo parameter. This stores each Audio interface's configuration and state information. + */ + typedef struct + { + const struct + { + uint8_t StreamingInterfaceNumber; /**< Index of the Audio Streaming interface within the device this + * structure controls. + */ + + uint8_t DataINEndpointNumber; /**< Endpoint number of the incoming Audio Streaming data, if available + * (zero if unused). + */ + uint16_t DataINEndpointSize; /**< Size in bytes of the incoming Audio Streaming data endpoint, if available + * (zero if unused). + */ + + uint8_t DataOUTEndpointNumber; /**< Endpoint number of the outgoing Audio Streaming data, if available + * (zero if unused). + */ + uint16_t DataOUTEndpointSize; /**< Size in bytes of the outgoing Audio Streaming data endpoint, if available + * (zero if unused). + */ + } Config; /**< Config data for the USB class interface within the device. All elements in this section + * must be set or the interface will fail to enumerate and operate correctly. + */ + struct + { + bool InterfaceEnabled; /**< Set and cleared by the class driver to indicate if the host has enabled the streaming endpoints + * of the Audio Streaming interface. + */ + } State; /**< State data for the USB class interface within the device. All elements in this section + * are reset to their defaults when the interface is enumerated. + */ + } USB_ClassInfo_Audio_Device_t; + + /* Function Prototypes: */ + /** Configures the endpoints of a given Audio interface, ready for use. This should be linked to the library + * \ref EVENT_USB_Device_ConfigurationChanged() event so that the endpoints are configured when the configuration containing the + * given Audio interface is selected. + * + * \param[in,out] AudioInterfaceInfo Pointer to a structure containing an Audio Class configuration and state. + * + * \return Boolean true if the endpoints were successfully configured, false otherwise. + */ + bool Audio_Device_ConfigureEndpoints(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** Processes incoming control requests from the host, that are directed to the given Audio class interface. This should be + * linked to the library \ref EVENT_USB_Device_UnhandledControlRequest() event. + * + * \param[in,out] AudioInterfaceInfo Pointer to a structure containing an Audio Class configuration and state. + */ + void Audio_Device_ProcessControlRequest(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /* Inline Functions: */ + /** General management task for a given Audio class interface, required for the correct operation of the interface. This should + * be called frequently in the main program loop, before the master USB management task \ref USB_USBTask(). + * + * \param[in,out] AudioInterfaceInfo Pointer to a structure containing an Audio Class configuration and state. + */ + static inline void Audio_Device_USBTask(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo) + ATTR_NON_NULL_PTR_ARG(1) ATTR_ALWAYS_INLINE; + static inline void Audio_Device_USBTask(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo) + { + (void)AudioInterfaceInfo; + } + + /** Determines if the given audio interface is ready for a sample to be read from it, and selects the streaming + * OUT endpoint ready for reading. + * + * \pre This function must only be called when the Device state machine is in the DEVICE_STATE_Configured state or + * the call will fail. + * + * \param[in,out] AudioInterfaceInfo Pointer to a structure containing an Audio Class configuration and state. + * + * \return Boolean true if the given Audio interface has a sample to be read, false otherwise. + */ + static inline bool Audio_Device_IsSampleReceived(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo) + ATTR_NON_NULL_PTR_ARG(1) ATTR_ALWAYS_INLINE; + static inline bool Audio_Device_IsSampleReceived(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo) + { + if ((USB_DeviceState != DEVICE_STATE_Configured) || !(AudioInterfaceInfo->State.InterfaceEnabled)) + return false; + + Endpoint_SelectEndpoint(AudioInterfaceInfo->Config.DataOUTEndpointNumber); + return Endpoint_IsOUTReceived(); + } + + /** Determines if the given audio interface is ready to accept the next sample to be written to it, and selects + * the streaming IN endpoint ready for writing. + * + * \pre This function must only be called when the Device state machine is in the DEVICE_STATE_Configured state or + * the call will fail. + * + * \param[in,out] AudioInterfaceInfo Pointer to a structure containing an Audio Class configuration and state. + * + * \return Boolean true if the given Audio interface is ready to accept the next sample, false otherwise. + */ + static inline bool Audio_Device_IsReadyForNextSample(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo) + ATTR_NON_NULL_PTR_ARG(1) ATTR_ALWAYS_INLINE; + static inline bool Audio_Device_IsReadyForNextSample(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo) + { + if ((USB_DeviceState != DEVICE_STATE_Configured) || !(AudioInterfaceInfo->State.InterfaceEnabled)) + return false; + + Endpoint_SelectEndpoint(AudioInterfaceInfo->Config.DataINEndpointNumber); + return Endpoint_IsINReady(); + } + + /** Reads the next 8-bit audio sample from the current audio interface. + * + * \pre This should be preceded immediately by a call to the \ref Audio_Device_IsSampleReceived() function to ensure + * ensure the correct endpoint is selected and ready for data. + * + * \param[in,out] AudioInterfaceInfo Pointer to a structure containing an Audio Class configuration and state. + * + * \return Signed 8-bit audio sample from the audio interface. + */ + static inline int8_t Audio_Device_ReadSample8(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo) + ATTR_NON_NULL_PTR_ARG(1) ATTR_ALWAYS_INLINE; + static inline int8_t Audio_Device_ReadSample8(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo) + { + int8_t Sample; + + (void)AudioInterfaceInfo; + + Sample = Endpoint_Read_Byte(); + + if (!(Endpoint_BytesInEndpoint())) + Endpoint_ClearOUT(); + + return Sample; + } + + /** Reads the next 16-bit audio sample from the current audio interface. + * + * \pre This should be preceded immediately by a call to the \ref Audio_Device_IsSampleReceived() function to ensure + * that the correct endpoint is selected and ready for data. + * + * \param[in,out] AudioInterfaceInfo Pointer to a structure containing an Audio Class configuration and state. + * + * \return Signed 16-bit audio sample from the audio interface. + */ + static inline int16_t Audio_Device_ReadSample16(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo) + ATTR_NON_NULL_PTR_ARG(1) ATTR_ALWAYS_INLINE; + static inline int16_t Audio_Device_ReadSample16(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo) + { + int16_t Sample; + + (void)AudioInterfaceInfo; + + Sample = (int16_t)Endpoint_Read_Word_LE(); + + if (!(Endpoint_BytesInEndpoint())) + Endpoint_ClearOUT(); + + return Sample; + } + + /** Reads the next 24-bit audio sample from the current audio interface. + * + * \pre This should be preceded immediately by a call to the \ref Audio_Device_IsSampleReceived() function to ensure + * that the correct endpoint is selected and ready for data. + * + * \param[in,out] AudioInterfaceInfo Pointer to a structure containing an Audio Class configuration and state. + * + * \return Signed 24-bit audio sample from the audio interface. + */ + static inline int32_t Audio_Device_ReadSample24(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo) + ATTR_NON_NULL_PTR_ARG(1) ATTR_ALWAYS_INLINE; + static inline int32_t Audio_Device_ReadSample24(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo) + { + int32_t Sample; + + (void)AudioInterfaceInfo; + + Sample = (((uint32_t)Endpoint_Read_Byte() << 16) | Endpoint_Read_Word_LE()); + + if (!(Endpoint_BytesInEndpoint())) + Endpoint_ClearOUT(); + + return Sample; + } + + /** Writes the next 8-bit audio sample to the current audio interface. + * + * \pre This should be preceded immediately by a call to the \ref Audio_Device_IsReadyForNextSample() function to + * ensure that the correct endpoint is selected and ready for data. + * + * \param[in,out] AudioInterfaceInfo Pointer to a structure containing an Audio Class configuration and state. + * \param[in] Sample Signed 8-bit audio sample. + */ + static inline void Audio_Device_WriteSample8(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo, + const int8_t Sample) ATTR_NON_NULL_PTR_ARG(1) ATTR_ALWAYS_INLINE; + static inline void Audio_Device_WriteSample8(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo, + const int8_t Sample) + { + Endpoint_Write_Byte(Sample); + + if (Endpoint_BytesInEndpoint() == AudioInterfaceInfo->Config.DataINEndpointSize) + Endpoint_ClearIN(); + } + + /** Writes the next 16-bit audio sample to the current audio interface. + * + * \pre This should be preceded immediately by a call to the \ref Audio_Device_IsReadyForNextSample() function to + * ensure that the correct endpoint is selected and ready for data. + * + * \param[in,out] AudioInterfaceInfo Pointer to a structure containing an Audio Class configuration and state. + * \param[in] Sample Signed 16-bit audio sample. + */ + static inline void Audio_Device_WriteSample16(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo, + const int16_t Sample) ATTR_NON_NULL_PTR_ARG(1) ATTR_ALWAYS_INLINE; + static inline void Audio_Device_WriteSample16(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo, + const int16_t Sample) + { + Endpoint_Write_Word_LE(Sample); + + if (Endpoint_BytesInEndpoint() == AudioInterfaceInfo->Config.DataINEndpointSize) + Endpoint_ClearIN(); + } + + /** Writes the next 24-bit audio sample to the current audio interface. + * + * \pre This should be preceded immediately by a call to the \ref Audio_Device_IsReadyForNextSample() function to + * ensure that the correct endpoint is selected and ready for data. + * + * \param[in,out] AudioInterfaceInfo Pointer to a structure containing an Audio Class configuration and state. + * \param[in] Sample Signed 24-bit audio sample. + */ + static inline void Audio_Device_WriteSample24(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo, + const int32_t Sample) ATTR_NON_NULL_PTR_ARG(1) ATTR_ALWAYS_INLINE; + static inline void Audio_Device_WriteSample24(USB_ClassInfo_Audio_Device_t* const AudioInterfaceInfo, + const int32_t Sample) + { + Endpoint_Write_Byte(Sample >> 16); + Endpoint_Write_Word_LE(Sample); + + if (Endpoint_BytesInEndpoint() == AudioInterfaceInfo->Config.DataINEndpointSize) + Endpoint_ClearIN(); + } + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Device/CDC.c b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Device/CDC.c new file mode 100644 index 0000000000..39154608e4 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Device/CDC.c @@ -0,0 +1,310 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +#define __INCLUDE_FROM_USB_DRIVER +#include "../../HighLevel/USBMode.h" +#if defined(USB_CAN_BE_DEVICE) + +#define __INCLUDE_FROM_CDC_CLASS_DEVICE_C +#define __INCLUDE_FROM_CDC_DRIVER +#include "CDC.h" + +void CDC_Device_Event_Stub(void) +{ + +} + +void CDC_Device_ProcessControlRequest(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo) +{ + if (!(Endpoint_IsSETUPReceived())) + return; + + if (USB_ControlRequest.wIndex != CDCInterfaceInfo->Config.ControlInterfaceNumber) + return; + + switch (USB_ControlRequest.bRequest) + { + case REQ_GetLineEncoding: + if (USB_ControlRequest.bmRequestType == (REQDIR_DEVICETOHOST | REQTYPE_CLASS | REQREC_INTERFACE)) + { + Endpoint_ClearSETUP(); + Endpoint_Write_Control_Stream_LE(&CDCInterfaceInfo->State.LineEncoding, sizeof(CDCInterfaceInfo->State.LineEncoding)); + Endpoint_ClearOUT(); + } + + break; + case REQ_SetLineEncoding: + if (USB_ControlRequest.bmRequestType == (REQDIR_HOSTTODEVICE | REQTYPE_CLASS | REQREC_INTERFACE)) + { + Endpoint_ClearSETUP(); + Endpoint_Read_Control_Stream_LE(&CDCInterfaceInfo->State.LineEncoding, sizeof(CDCInterfaceInfo->State.LineEncoding)); + EVENT_CDC_Device_LineEncodingChanged(CDCInterfaceInfo); + Endpoint_ClearIN(); + } + + break; + case REQ_SetControlLineState: + if (USB_ControlRequest.bmRequestType == (REQDIR_HOSTTODEVICE | REQTYPE_CLASS | REQREC_INTERFACE)) + { + Endpoint_ClearSETUP(); + + CDCInterfaceInfo->State.ControlLineStates.HostToDevice = USB_ControlRequest.wValue; + EVENT_CDC_Device_ControLineStateChanged(CDCInterfaceInfo); + + Endpoint_ClearStatusStage(); + } + + break; + case REQ_SendBreak: + if (USB_ControlRequest.bmRequestType == (REQDIR_HOSTTODEVICE | REQTYPE_CLASS | REQREC_INTERFACE)) + { + Endpoint_ClearSETUP(); + + EVENT_CDC_Device_BreakSent(CDCInterfaceInfo, (uint8_t)USB_ControlRequest.wValue); + + Endpoint_ClearStatusStage(); + } + + break; + } +} + +bool CDC_Device_ConfigureEndpoints(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo) +{ + memset(&CDCInterfaceInfo->State, 0x00, sizeof(CDCInterfaceInfo->State)); + + if (!(Endpoint_ConfigureEndpoint(CDCInterfaceInfo->Config.DataINEndpointNumber, EP_TYPE_BULK, + ENDPOINT_DIR_IN, CDCInterfaceInfo->Config.DataINEndpointSize, + CDCInterfaceInfo->Config.DataINEndpointDoubleBank ? ENDPOINT_BANK_DOUBLE : ENDPOINT_BANK_SINGLE))) + { + return false; + } + + if (!(Endpoint_ConfigureEndpoint(CDCInterfaceInfo->Config.DataOUTEndpointNumber, EP_TYPE_BULK, + ENDPOINT_DIR_OUT, CDCInterfaceInfo->Config.DataOUTEndpointSize, + CDCInterfaceInfo->Config.DataOUTEndpointDoubleBank ? ENDPOINT_BANK_DOUBLE : ENDPOINT_BANK_SINGLE))) + { + return false; + } + + if (!(Endpoint_ConfigureEndpoint(CDCInterfaceInfo->Config.NotificationEndpointNumber, EP_TYPE_INTERRUPT, + ENDPOINT_DIR_IN, CDCInterfaceInfo->Config.NotificationEndpointSize, + CDCInterfaceInfo->Config.NotificationEndpointDoubleBank ? ENDPOINT_BANK_DOUBLE : ENDPOINT_BANK_SINGLE))) + { + return false; + } + + return true; +} + +void CDC_Device_USBTask(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo) +{ + if ((USB_DeviceState != DEVICE_STATE_Configured) || !(CDCInterfaceInfo->State.LineEncoding.BaudRateBPS)) + return; + + CDC_Device_Flush(CDCInterfaceInfo); +} + +uint8_t CDC_Device_SendString(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo, + const char* const Data, + const uint16_t Length) +{ + if ((USB_DeviceState != DEVICE_STATE_Configured) || !(CDCInterfaceInfo->State.LineEncoding.BaudRateBPS)) + return ENDPOINT_RWSTREAM_DeviceDisconnected; + + Endpoint_SelectEndpoint(CDCInterfaceInfo->Config.DataINEndpointNumber); + return Endpoint_Write_Stream_LE(Data, Length, NO_STREAM_CALLBACK); +} + +uint8_t CDC_Device_SendByte(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo, + const uint8_t Data) +{ + if ((USB_DeviceState != DEVICE_STATE_Configured) || !(CDCInterfaceInfo->State.LineEncoding.BaudRateBPS)) + return ENDPOINT_RWSTREAM_DeviceDisconnected; + + Endpoint_SelectEndpoint(CDCInterfaceInfo->Config.DataINEndpointNumber); + + if (!(Endpoint_IsReadWriteAllowed())) + { + Endpoint_ClearIN(); + + uint8_t ErrorCode; + + if ((ErrorCode = Endpoint_WaitUntilReady()) != ENDPOINT_READYWAIT_NoError) + return ErrorCode; + } + + Endpoint_Write_Byte(Data); + return ENDPOINT_READYWAIT_NoError; +} + +uint8_t CDC_Device_Flush(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo) +{ + if ((USB_DeviceState != DEVICE_STATE_Configured) || !(CDCInterfaceInfo->State.LineEncoding.BaudRateBPS)) + return ENDPOINT_RWSTREAM_DeviceDisconnected; + + uint8_t ErrorCode; + + Endpoint_SelectEndpoint(CDCInterfaceInfo->Config.DataINEndpointNumber); + + if (!(Endpoint_BytesInEndpoint())) + return ENDPOINT_READYWAIT_NoError; + + bool BankFull = !(Endpoint_IsReadWriteAllowed()); + + Endpoint_ClearIN(); + + if (BankFull) + { + if ((ErrorCode = Endpoint_WaitUntilReady()) != ENDPOINT_READYWAIT_NoError) + return ErrorCode; + + Endpoint_ClearIN(); + } + + return ENDPOINT_READYWAIT_NoError; +} + +uint16_t CDC_Device_BytesReceived(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo) +{ + if ((USB_DeviceState != DEVICE_STATE_Configured) || !(CDCInterfaceInfo->State.LineEncoding.BaudRateBPS)) + return 0; + + Endpoint_SelectEndpoint(CDCInterfaceInfo->Config.DataOUTEndpointNumber); + + if (Endpoint_IsOUTReceived()) + { + if (!(Endpoint_BytesInEndpoint())) + { + Endpoint_ClearOUT(); + return 0; + } + else + { + return Endpoint_BytesInEndpoint(); + } + } + else + { + return 0; + } +} + +int16_t CDC_Device_ReceiveByte(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo) +{ + if ((USB_DeviceState != DEVICE_STATE_Configured) || !(CDCInterfaceInfo->State.LineEncoding.BaudRateBPS)) + return -1; + + int16_t ReceivedByte = -1; + + Endpoint_SelectEndpoint(CDCInterfaceInfo->Config.DataOUTEndpointNumber); + + if (Endpoint_IsOUTReceived()) + { + if (Endpoint_BytesInEndpoint()) + ReceivedByte = Endpoint_Read_Byte(); + + if (!(Endpoint_BytesInEndpoint())) + Endpoint_ClearOUT(); + } + + return ReceivedByte; +} + +void CDC_Device_SendControlLineStateChange(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo) +{ + if ((USB_DeviceState != DEVICE_STATE_Configured) || !(CDCInterfaceInfo->State.LineEncoding.BaudRateBPS)) + return; + + Endpoint_SelectEndpoint(CDCInterfaceInfo->Config.NotificationEndpointNumber); + + USB_Request_Header_t Notification = (USB_Request_Header_t) + { + .bmRequestType = (REQDIR_DEVICETOHOST | REQTYPE_CLASS | REQREC_INTERFACE), + .bRequest = NOTIF_SerialState, + .wValue = 0, + .wIndex = 0, + .wLength = sizeof(CDCInterfaceInfo->State.ControlLineStates.DeviceToHost), + }; + + Endpoint_Write_Stream_LE(&Notification, sizeof(USB_Request_Header_t), NO_STREAM_CALLBACK); + Endpoint_Write_Stream_LE(&CDCInterfaceInfo->State.ControlLineStates.DeviceToHost, + sizeof(CDCInterfaceInfo->State.ControlLineStates.DeviceToHost), + NO_STREAM_CALLBACK); + Endpoint_ClearIN(); +} + +void CDC_Device_CreateStream(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo, + FILE* const Stream) +{ + *Stream = (FILE)FDEV_SETUP_STREAM(CDC_Device_putchar, CDC_Device_getchar, _FDEV_SETUP_RW); + fdev_set_udata(Stream, CDCInterfaceInfo); +} + +void CDC_Device_CreateBlockingStream(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo, + FILE* const Stream) +{ + *Stream = (FILE)FDEV_SETUP_STREAM(CDC_Device_putchar, CDC_Device_getchar_Blocking, _FDEV_SETUP_RW); + fdev_set_udata(Stream, CDCInterfaceInfo); +} + +static int CDC_Device_putchar(char c, + FILE* Stream) +{ + return CDC_Device_SendByte((USB_ClassInfo_CDC_Device_t*)fdev_get_udata(Stream), c) ? _FDEV_ERR : 0; +} + +static int CDC_Device_getchar(FILE* Stream) +{ + int16_t ReceivedByte = CDC_Device_ReceiveByte((USB_ClassInfo_CDC_Device_t*)fdev_get_udata(Stream)); + + if (ReceivedByte < 0) + return _FDEV_EOF; + + return ReceivedByte; +} + +static int CDC_Device_getchar_Blocking(FILE* Stream) +{ + int16_t ReceivedByte; + + while ((ReceivedByte = CDC_Device_ReceiveByte((USB_ClassInfo_CDC_Device_t*)fdev_get_udata(Stream))) < 0) + { + if (USB_DeviceState == DEVICE_STATE_Unattached) + return _FDEV_EOF; + + CDC_Device_USBTask((USB_ClassInfo_CDC_Device_t*)fdev_get_udata(Stream)); + USB_USBTask(); + } + + return ReceivedByte; +} + +#endif diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Device/CDC.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Device/CDC.h new file mode 100644 index 0000000000..1b0b86810a --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Device/CDC.h @@ -0,0 +1,342 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief Device mode driver for the library USB CDC Class driver. + * + * Device mode driver for the library USB CDC Class driver. + * + * \note This file should not be included directly. It is automatically included as needed by the class driver + * dispatch header located in LUFA/Drivers/USB/Class/CDC.h. + */ + +/** \ingroup Group_USBClassCDC + * @defgroup Group_USBClassCDCDevice CDC Class Device Mode Driver + * + * \section Sec_Dependencies Module Source Dependencies + * The following files must be built with any user project that uses this module: + * - LUFA/Drivers/USB/Class/Device/CDC.c (Makefile source module name: LUFA_SRC_USBCLASS) + * + * \section Module Description + * Device Mode USB Class driver framework interface, for the CDC USB Class driver. + * + * \note There are several major drawbacks to the CDC-ACM standard USB class, however + * it is very standardized and thus usually available as a built-in driver on + * most platforms, and so is a better choice than a proprietary serial class. + * + * One major issue with CDC-ACM is that it requires two Interface descriptors, + * which will upset most hosts when part of a multi-function "Composite" USB + * device, as each interface will be loaded into a separate driver instance. To + * combat this, you should use the "Interface Association Descriptor" addendum to + * the USB standard which is available on most OSes when creating Composite devices. + * + * Another major oversight is that there is no mechanism for the host to notify the + * device that there is a data sink on the host side ready to accept data. This + * means that the device may try to send data while the host isn't listening, causing + * lengthy blocking timeouts in the transmission routines. To combat this, it is + * recommended that the virtual serial line DTR (Data Terminal Ready) be used where + * possible to determine if a host application is ready for data. + * + * @{ + */ + +#ifndef _CDC_CLASS_DEVICE_H_ +#define _CDC_CLASS_DEVICE_H_ + + /* Includes: */ + #include "../../USB.h" + #include "../Common/CDC.h" + + #include + #include + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_CDC_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/Class/CDC.h instead. + #endif + + /* Public Interface - May be used in end-application: */ + /* Type Defines: */ + /** \brief CDC Class Device Mode Configuration and State Structure. + * + * Class state structure. An instance of this structure should be made for each CDC interface + * within the user application, and passed to each of the CDC class driver functions as the + * CDCInterfaceInfo parameter. This stores each CDC interface's configuration and state information. + */ + typedef struct + { + const struct + { + uint8_t ControlInterfaceNumber; /**< Interface number of the CDC control interface within the device. */ + + uint8_t DataINEndpointNumber; /**< Endpoint number of the CDC interface's IN data endpoint. */ + uint16_t DataINEndpointSize; /**< Size in bytes of the CDC interface's IN data endpoint. */ + bool DataINEndpointDoubleBank; /**< Indicates if the CDC interface's IN data endpoint should use double banking. */ + + uint8_t DataOUTEndpointNumber; /**< Endpoint number of the CDC interface's OUT data endpoint. */ + uint16_t DataOUTEndpointSize; /**< Size in bytes of the CDC interface's OUT data endpoint. */ + bool DataOUTEndpointDoubleBank; /**< Indicates if the CDC interface's OUT data endpoint should use double banking. */ + + uint8_t NotificationEndpointNumber; /**< Endpoint number of the CDC interface's IN notification endpoint, if used. */ + uint16_t NotificationEndpointSize; /**< Size in bytes of the CDC interface's IN notification endpoint, if used. */ + bool NotificationEndpointDoubleBank; /**< Indicates if the CDC interface's notification endpoint should use double banking. */ + } Config; /**< Config data for the USB class interface within the device. All elements in this section + * must be set or the interface will fail to enumerate and operate correctly. + */ + struct + { + struct + { + uint8_t HostToDevice; /**< Control line states from the host to device, as a set of CDC_CONTROL_LINE_OUT_* + * masks. This value is updated each time \ref CDC_Device_USBTask() is called. + */ + uint8_t DeviceToHost; /**< Control line states from the device to host, as a set of CDC_CONTROL_LINE_IN_* + * masks - to notify the host of changes to these values, call the + * \ref CDC_Device_SendControlLineStateChange() function. + */ + } ControlLineStates; /**< Current states of the virtual serial port's control lines between the device and host. */ + + struct + { + uint32_t BaudRateBPS; /**< Baud rate of the virtual serial port, in bits per second. */ + uint8_t CharFormat; /**< Character format of the virtual serial port, a value from the + * \ref CDC_LineEncodingFormats_t enum. + */ + uint8_t ParityType; /**< Parity setting of the virtual serial port, a value from the + * \ref CDC_LineEncodingParity_t enum. + */ + uint8_t DataBits; /**< Bits of data per character of the virtual serial port. */ + } LineEncoding; /** Line encoding used in the virtual serial port, for the device's information. This is generally + * only used if the virtual serial port data is to be reconstructed on a physical UART. + */ + } State; /**< State data for the USB class interface within the device. All elements in this section + * are reset to their defaults when the interface is enumerated. + */ + } USB_ClassInfo_CDC_Device_t; + + /* Function Prototypes: */ + /** Configures the endpoints of a given CDC interface, ready for use. This should be linked to the library + * \ref EVENT_USB_Device_ConfigurationChanged() event so that the endpoints are configured when the configuration containing + * the given CDC interface is selected. + * + * \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class configuration and state. + * + * \return Boolean true if the endpoints were successfully configured, false otherwise. + */ + bool CDC_Device_ConfigureEndpoints(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** Processes incoming control requests from the host, that are directed to the given CDC class interface. This should be + * linked to the library \ref EVENT_USB_Device_UnhandledControlRequest() event. + * + * \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class configuration and state. + */ + void CDC_Device_ProcessControlRequest(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** General management task for a given CDC class interface, required for the correct operation of the interface. This should + * be called frequently in the main program loop, before the master USB management task \ref USB_USBTask(). + * + * \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class configuration and state. + */ + void CDC_Device_USBTask(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** CDC class driver event for a line encoding change on a CDC interface. This event fires each time the host requests a + * line encoding change (containing the serial parity, baud and other configuration information) and may be hooked in the + * user program by declaring a handler function with the same name and parameters listed here. The new line encoding + * settings are available in the LineEncoding structure inside the CDC interface structure passed as a parameter. + * + * \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class configuration and state. + */ + void EVENT_CDC_Device_LineEncodingChanged(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** CDC class driver event for a control line state change on a CDC interface. This event fires each time the host requests a + * control line state change (containing the virtual serial control line states, such as DTR) and may be hooked in the + * user program by declaring a handler function with the same name and parameters listed here. The new control line states + * are available in the ControlLineStates.HostToDevice value inside the CDC interface structure passed as a parameter, set as + * a mask of CDC_CONTROL_LINE_OUT_* masks. + * + * \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class configuration and state. + */ + void EVENT_CDC_Device_ControLineStateChanged(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** CDC class driver event for a send break request sent to the device from the host. This is generally used to separate + * data or to indicate a special condition to the receiving device. + * + * \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class configuration and state. + * \param[in] Duration Duration of the break that has been sent by the host, in milliseconds. + */ + void EVENT_CDC_Device_BreakSent(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo, + const uint8_t Duration) ATTR_NON_NULL_PTR_ARG(1); + + /** Sends a given string to the attached USB host, if connected. If a host is not connected when the function is called, the + * string is discarded. Bytes will be queued for transmission to the host until either the endpoint bank becomes full, or the + * \ref CDC_Device_Flush() function is called to flush the pending data to the host. This allows for multiple bytes to be + * packed into a single endpoint packet, increasing data throughput. + * + * \pre This function must only be called when the Device state machine is in the DEVICE_STATE_Configured state or + * the call will fail. + * + * \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class configuration and state. + * \param[in] Data Pointer to the string to send to the host. + * \param[in] Length Size in bytes of the string to send to the host. + * + * \return A value from the \ref Endpoint_Stream_RW_ErrorCodes_t enum. + */ + uint8_t CDC_Device_SendString(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo, + const char* const Data, + const uint16_t Length) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(2); + + /** Sends a given byte to the attached USB host, if connected. If a host is not connected when the function is called, the + * byte is discarded. Bytes will be queued for transmission to the host until either the endpoint bank becomes full, or the + * \ref CDC_Device_Flush() function is called to flush the pending data to the host. This allows for multiple bytes to be + * packed into a single endpoint packet, increasing data throughput. + * + * \pre This function must only be called when the Device state machine is in the DEVICE_STATE_Configured state or + * the call will fail. + * + * \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class configuration and state. + * \param[in] Data Byte of data to send to the host. + * + * \return A value from the \ref Endpoint_WaitUntilReady_ErrorCodes_t enum. + */ + uint8_t CDC_Device_SendByte(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo, + const uint8_t Data) ATTR_NON_NULL_PTR_ARG(1); + + /** Determines the number of bytes received by the CDC interface from the host, waiting to be read. This indicates the number + * of bytes in the OUT endpoint bank only, and thus the number of calls to \ref CDC_Device_ReceiveByte() which are guaranteed to + * succeed immediately. If multiple bytes are to be received, they should be buffered by the user application, as the endpoint + * bank will not be released back to the USB controller until all bytes are read. + * + * \pre This function must only be called when the Device state machine is in the DEVICE_STATE_Configured state or + * the call will fail. + * + * \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class configuration and state. + * + * \return Total number of buffered bytes received from the host. + */ + uint16_t CDC_Device_BytesReceived(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** Reads a byte of data from the host. If no data is waiting to be read of if a USB host is not connected, the function + * returns a negative value. The \ref CDC_Device_BytesReceived() function may be queried in advance to determine how many + * bytes are currently buffered in the CDC interface's data receive endpoint bank, and thus how many repeated calls to this + * function which are guaranteed to succeed. + * + * \pre This function must only be called when the Device state machine is in the DEVICE_STATE_Configured state or + * the call will fail. + * + * \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class configuration and state. + * + * \return Next received byte from the host, or a negative value if no data received. + */ + int16_t CDC_Device_ReceiveByte(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** Flushes any data waiting to be sent, ensuring that the send buffer is cleared. + * + * \pre This function must only be called when the Device state machine is in the DEVICE_STATE_Configured state or + * the call will fail. + * + * \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class configuration and state. + * + * \return A value from the \ref Endpoint_WaitUntilReady_ErrorCodes_t enum. + */ + uint8_t CDC_Device_Flush(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** Sends a Serial Control Line State Change notification to the host. This should be called when the virtual serial + * control lines (DCD, DSR, etc.) have changed states, or to give BREAK notifications to the host. Line states persist + * until they are cleared via a second notification. This should be called each time the CDC class driver's + * ControlLineStates.DeviceToHost value is updated to push the new states to the USB host. + * + * \pre This function must only be called when the Device state machine is in the DEVICE_STATE_Configured state or + * the call will fail. + * + * \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class configuration and state. + */ + void CDC_Device_SendControlLineStateChange(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** Creates a standard character stream for the given CDC Device instance so that it can be used with all the regular + * functions in the avr-libc library that accept a FILE stream as a destination (e.g. fprintf). The created + * stream is bidirectional and can be used for both input and output functions. + * + * Reading data from this stream is non-blocking, i.e. in most instances, complete strings cannot be read in by a single + * fetch, as the endpoint will not be ready at some point in the transmission, aborting the transfer. However, this may + * be used when the read data is processed byte-per-bye (via getc()) or when the user application will implement its own + * line buffering. + * + * \note The created stream can be given as stdout if desired to direct the standard output from all functions + * to the given CDC interface. + * + * \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class configuration and state. + * \param[in,out] Stream Pointer to a FILE structure where the created stream should be placed. + */ + void CDC_Device_CreateStream(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo, + FILE* const Stream) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(2); + + /** Identical to CDC_Device_CreateStream(), except that reads are blocking until the calling stream function terminates + * the transfer. While blocking, the USB and CDC service tasks are called repeatedly to maintain USB communications. + * + * \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class configuration and state. + * \param[in,out] Stream Pointer to a FILE structure where the created stream should be placed. + */ + void CDC_Device_CreateBlockingStream(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo, + FILE* const Stream) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(2); + + /* Private Interface - For use in library only: */ + #if !defined(__DOXYGEN__) + /* Function Prototypes: */ + #if defined(__INCLUDE_FROM_CDC_CLASS_DEVICE_C) + static int CDC_Device_putchar(char c, + FILE* Stream) ATTR_NON_NULL_PTR_ARG(2); + static int CDC_Device_getchar(FILE* Stream) ATTR_NON_NULL_PTR_ARG(1); + static int CDC_Device_getchar_Blocking(FILE* Stream) ATTR_NON_NULL_PTR_ARG(1); + + void CDC_Device_Event_Stub(void); + void EVENT_CDC_Device_LineEncodingChanged(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo) + ATTR_WEAK ATTR_NON_NULL_PTR_ARG(1) ATTR_ALIAS(CDC_Device_Event_Stub); + void EVENT_CDC_Device_ControLineStateChanged(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo) + ATTR_WEAK ATTR_NON_NULL_PTR_ARG(1) ATTR_ALIAS(CDC_Device_Event_Stub); + void EVENT_CDC_Device_BreakSent(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo, + const uint8_t Duration) ATTR_WEAK ATTR_NON_NULL_PTR_ARG(1) + ATTR_ALIAS(CDC_Device_Event_Stub); + #endif + + #endif + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Device/HID.c b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Device/HID.c new file mode 100644 index 0000000000..203023142d --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Device/HID.c @@ -0,0 +1,194 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +#define __INCLUDE_FROM_USB_DRIVER +#include "../../HighLevel/USBMode.h" +#if defined(USB_CAN_BE_DEVICE) + +#define __INCLUDE_FROM_HID_DRIVER +#include "HID.h" + +void HID_Device_ProcessControlRequest(USB_ClassInfo_HID_Device_t* const HIDInterfaceInfo) +{ + if (!(Endpoint_IsSETUPReceived())) + return; + + if (USB_ControlRequest.wIndex != HIDInterfaceInfo->Config.InterfaceNumber) + return; + + switch (USB_ControlRequest.bRequest) + { + case REQ_GetReport: + if (USB_ControlRequest.bmRequestType == (REQDIR_DEVICETOHOST | REQTYPE_CLASS | REQREC_INTERFACE)) + { + Endpoint_ClearSETUP(); + + uint16_t ReportSize = 0; + uint8_t ReportID = (USB_ControlRequest.wValue & 0xFF); + uint8_t ReportType = (USB_ControlRequest.wValue >> 8) - 1; + uint8_t ReportData[HIDInterfaceInfo->Config.PrevReportINBufferSize]; + + memset(ReportData, 0, sizeof(ReportData)); + + CALLBACK_HID_Device_CreateHIDReport(HIDInterfaceInfo, &ReportID, ReportType, ReportData, &ReportSize); + + if (HIDInterfaceInfo->Config.PrevReportINBuffer != NULL) + memcpy(HIDInterfaceInfo->Config.PrevReportINBuffer, ReportData, HIDInterfaceInfo->Config.PrevReportINBufferSize); + + Endpoint_SelectEndpoint(ENDPOINT_CONTROLEP); + Endpoint_Write_Control_Stream_LE(ReportData, ReportSize); + Endpoint_ClearOUT(); + } + + break; + case REQ_SetReport: + if (USB_ControlRequest.bmRequestType == (REQDIR_HOSTTODEVICE | REQTYPE_CLASS | REQREC_INTERFACE)) + { + Endpoint_ClearSETUP(); + + uint16_t ReportSize = USB_ControlRequest.wLength; + uint8_t ReportID = (USB_ControlRequest.wValue & 0xFF); + uint8_t ReportType = (USB_ControlRequest.wValue >> 8) - 1; + uint8_t ReportData[ReportSize]; + + Endpoint_Read_Control_Stream_LE(ReportData, ReportSize); + CALLBACK_HID_Device_ProcessHIDReport(HIDInterfaceInfo, ReportID, ReportType, ReportData, ReportSize); + Endpoint_ClearIN(); + } + + break; + case REQ_GetProtocol: + if (USB_ControlRequest.bmRequestType == (REQDIR_DEVICETOHOST | REQTYPE_CLASS | REQREC_INTERFACE)) + { + Endpoint_ClearSETUP(); + + Endpoint_Write_Byte(HIDInterfaceInfo->State.UsingReportProtocol); + Endpoint_ClearIN(); + + Endpoint_ClearStatusStage(); + } + + break; + case REQ_SetProtocol: + if (USB_ControlRequest.bmRequestType == (REQDIR_HOSTTODEVICE | REQTYPE_CLASS | REQREC_INTERFACE)) + { + Endpoint_ClearSETUP(); + + HIDInterfaceInfo->State.UsingReportProtocol = ((USB_ControlRequest.wValue & 0xFF) != 0x00); + + Endpoint_ClearStatusStage(); + } + + break; + case REQ_SetIdle: + if (USB_ControlRequest.bmRequestType == (REQDIR_HOSTTODEVICE | REQTYPE_CLASS | REQREC_INTERFACE)) + { + Endpoint_ClearSETUP(); + + HIDInterfaceInfo->State.IdleCount = ((USB_ControlRequest.wValue & 0xFF00) >> 6); + + Endpoint_ClearStatusStage(); + } + + break; + case REQ_GetIdle: + if (USB_ControlRequest.bmRequestType == (REQDIR_DEVICETOHOST | REQTYPE_CLASS | REQREC_INTERFACE)) + { + Endpoint_ClearSETUP(); + + Endpoint_Write_Byte(HIDInterfaceInfo->State.IdleCount >> 2); + Endpoint_ClearIN(); + + Endpoint_ClearStatusStage(); + } + + break; + } +} + +bool HID_Device_ConfigureEndpoints(USB_ClassInfo_HID_Device_t* const HIDInterfaceInfo) +{ + memset(&HIDInterfaceInfo->State, 0x00, sizeof(HIDInterfaceInfo->State)); + HIDInterfaceInfo->State.UsingReportProtocol = true; + HIDInterfaceInfo->State.IdleCount = 500; + + if (!(Endpoint_ConfigureEndpoint(HIDInterfaceInfo->Config.ReportINEndpointNumber, EP_TYPE_INTERRUPT, + ENDPOINT_DIR_IN, HIDInterfaceInfo->Config.ReportINEndpointSize, + HIDInterfaceInfo->Config.ReportINEndpointDoubleBank ? ENDPOINT_BANK_DOUBLE : ENDPOINT_BANK_SINGLE))) + { + return false; + } + + return true; +} + +void HID_Device_USBTask(USB_ClassInfo_HID_Device_t* const HIDInterfaceInfo) +{ + if (USB_DeviceState != DEVICE_STATE_Configured) + return; + + Endpoint_SelectEndpoint(HIDInterfaceInfo->Config.ReportINEndpointNumber); + + if (Endpoint_IsReadWriteAllowed()) + { + uint8_t ReportINData[HIDInterfaceInfo->Config.PrevReportINBufferSize]; + uint8_t ReportID = 0; + uint16_t ReportINSize = 0; + + memset(ReportINData, 0, sizeof(ReportINData)); + + bool ForceSend = CALLBACK_HID_Device_CreateHIDReport(HIDInterfaceInfo, &ReportID, REPORT_ITEM_TYPE_In, + ReportINData, &ReportINSize); + bool StatesChanged = false; + bool IdlePeriodElapsed = (HIDInterfaceInfo->State.IdleCount && !(HIDInterfaceInfo->State.IdleMSRemaining)); + + if (HIDInterfaceInfo->Config.PrevReportINBuffer != NULL) + { + StatesChanged = (memcmp(ReportINData, HIDInterfaceInfo->Config.PrevReportINBuffer, ReportINSize) != 0); + memcpy(HIDInterfaceInfo->Config.PrevReportINBuffer, ReportINData, HIDInterfaceInfo->Config.PrevReportINBufferSize); + } + + if (ReportINSize && (ForceSend || StatesChanged || IdlePeriodElapsed)) + { + HIDInterfaceInfo->State.IdleMSRemaining = HIDInterfaceInfo->State.IdleCount; + + Endpoint_SelectEndpoint(HIDInterfaceInfo->Config.ReportINEndpointNumber); + + if (ReportID) + Endpoint_Write_Byte(ReportID); + + Endpoint_Write_Stream_LE(ReportINData, ReportINSize, NO_STREAM_CALLBACK); + + Endpoint_ClearIN(); + } + } +} + +#endif diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Device/HID.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Device/HID.h new file mode 100644 index 0000000000..638dac1597 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Device/HID.h @@ -0,0 +1,212 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief Device mode driver for the library USB HID Class driver. + * + * Device mode driver for the library USB HID Class driver. + * + * \note This file should not be included directly. It is automatically included as needed by the class driver + * dispatch header located in LUFA/Drivers/USB/Class/HID.h. + */ + +/** \ingroup Group_USBClassHID + * @defgroup Group_USBClassHIDDevice HID Class Device Mode Driver + * + * \section Sec_Dependencies Module Source Dependencies + * The following files must be built with any user project that uses this module: + * - LUFA/Drivers/USB/Class/Device/HID.c (Makefile source module name: LUFA_SRC_USBCLASS) + * + * \section Module Description + * Device Mode USB Class driver framework interface, for the HID USB Class driver. + * + * @{ + */ + +#ifndef _HID_CLASS_DEVICE_H_ +#define _HID_CLASS_DEVICE_H_ + + /* Includes: */ + #include "../../USB.h" + #include "../Common/HID.h" + + #include + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_HID_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/Class/HID.h instead. + #endif + + /* Public Interface - May be used in end-application: */ + /* Type Defines: */ + /** \brief HID Class Device Mode Configuration and State Structure. + * + * Class state structure. An instance of this structure should be made for each HID interface + * within the user application, and passed to each of the HID class driver functions as the + * HIDInterfaceInfo parameter. This stores each HID interface's configuration and state information. + * + * \note Due to technical limitations, the HID device class driver does not utilize a separate OUT + * endpoint for host->device communications. Instead, the host->device data (if any) is sent to + * the device via the control endpoint. + */ + typedef struct + { + const struct + { + uint8_t InterfaceNumber; /**< Interface number of the HID interface within the device. */ + + uint8_t ReportINEndpointNumber; /**< Endpoint number of the HID interface's IN report endpoint. */ + uint16_t ReportINEndpointSize; /**< Size in bytes of the HID interface's IN report endpoint. */ + bool ReportINEndpointDoubleBank; /**< Indicates if the HID interface's IN report endpoint should use double banking. */ + + void* PrevReportINBuffer; /**< Pointer to a buffer where the previously created HID input report can be + * stored by the driver, for comparison purposes to detect report changes that + * must be sent immediately to the host. This should point to a buffer big enough + * to hold the largest HID input report sent from the HID interface. If this is set + * to NULL, it is up to the user to force transfers when needed in the + * \ref CALLBACK_HID_Device_CreateHIDReport() callback function. + * + * \note Due to the single buffer, the internal driver can only correctly compare + * subsequent reports with identical report IDs. In multiple report devices, + * this buffer should be set to NULL and the decision to send reports made + * by the user application instead. + */ + uint8_t PrevReportINBufferSize; /**< Size in bytes of the given input report buffer. This is used to create a + * second buffer of the same size within the driver so that subsequent reports + * can be compared. If the user app is to determine when reports are to be sent + * exclusively (i.e. \ref PrevReportINBuffer is NULL) this value must still be + * set to the size of the largest report the device can issue to the host. + */ + } Config; /**< Config data for the USB class interface within the device. All elements in this section + * must be set or the interface will fail to enumerate and operate correctly. + */ + struct + { + bool UsingReportProtocol; /**< Indicates if the HID interface is set to Boot or Report protocol mode. */ + uint16_t IdleCount; /**< Report idle period, in milliseconds, set by the host. */ + uint16_t IdleMSRemaining; /**< Total number of milliseconds remaining before the idle period elapsed - this + * should be decremented by the user application if non-zero each millisecond. */ + } State; /**< State data for the USB class interface within the device. All elements in this section + * are reset to their defaults when the interface is enumerated. + */ + } USB_ClassInfo_HID_Device_t; + + /* Function Prototypes: */ + /** Configures the endpoints of a given HID interface, ready for use. This should be linked to the library + * \ref EVENT_USB_Device_ConfigurationChanged() event so that the endpoints are configured when the configuration + * containing the given HID interface is selected. + * + * \param[in,out] HIDInterfaceInfo Pointer to a structure containing a HID Class configuration and state. + * + * \return Boolean true if the endpoints were successfully configured, false otherwise. + */ + bool HID_Device_ConfigureEndpoints(USB_ClassInfo_HID_Device_t* const HIDInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** Processes incoming control requests from the host, that are directed to the given HID class interface. This should be + * linked to the library \ref EVENT_USB_Device_UnhandledControlRequest() event. + * + * \param[in,out] HIDInterfaceInfo Pointer to a structure containing a HID Class configuration and state. + */ + void HID_Device_ProcessControlRequest(USB_ClassInfo_HID_Device_t* const HIDInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** General management task for a given HID class interface, required for the correct operation of the interface. This should + * be called frequently in the main program loop, before the master USB management task \ref USB_USBTask(). + * + * \param[in,out] HIDInterfaceInfo Pointer to a structure containing a HID Class configuration and state. + */ + void HID_Device_USBTask(USB_ClassInfo_HID_Device_t* const HIDInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** HID class driver callback for the user creation of a HID IN report. This callback may fire in response to either + * HID class control requests from the host, or by the normal HID endpoint polling procedure. Inside this callback the + * user is responsible for the creation of the next HID input report to be sent to the host. + * + * \param[in,out] HIDInterfaceInfo Pointer to a structure containing a HID Class configuration and state. + * \param[in,out] ReportID If preset to a non-zero value, this is the report ID being requested by the host. If zero, + * this should be set to the report ID of the generated HID input report (if any). If multiple + * reports are not sent via the given HID interface, this parameter should be ignored. + * \param[in] ReportType Type of HID report to generate, either \ref REPORT_ITEM_TYPE_In or \ref REPORT_ITEM_TYPE_Feature. + * \param[out] ReportData Pointer to a buffer where the generated HID report should be stored. + * \param[out] ReportSize Number of bytes in the generated input report, or zero if no report is to be sent. + * + * \return Boolean true to force the sending of the report even if it is identical to the previous report and still within + * the idle period (useful for devices which report relative movement), false otherwise. + */ + bool CALLBACK_HID_Device_CreateHIDReport(USB_ClassInfo_HID_Device_t* const HIDInterfaceInfo, + uint8_t* const ReportID, + const uint8_t ReportType, + void* ReportData, + uint16_t* const ReportSize) ATTR_NON_NULL_PTR_ARG(1) + ATTR_NON_NULL_PTR_ARG(2) ATTR_NON_NULL_PTR_ARG(4) ATTR_NON_NULL_PTR_ARG(5); + + /** HID class driver callback for the user processing of a received HID OUT report. This callback may fire in response to + * either HID class control requests from the host, or by the normal HID endpoint polling procedure. Inside this callback + * the user is responsible for the processing of the received HID output report from the host. + * + * \param[in,out] HIDInterfaceInfo Pointer to a structure containing a HID Class configuration and state. + * \param[in] ReportID Report ID of the received output report. If multiple reports are not received via the given HID + * interface, this parameter should be ignored. + * \param[in] ReportType Type of received HID report, either \ref REPORT_ITEM_TYPE_Out or \ref REPORT_ITEM_TYPE_Feature. + * \param[in] ReportData Pointer to a buffer where the received HID report is stored. + * \param[in] ReportSize Size in bytes of the received report from the host. + */ + void CALLBACK_HID_Device_ProcessHIDReport(USB_ClassInfo_HID_Device_t* const HIDInterfaceInfo, + const uint8_t ReportID, + const uint8_t ReportType, + const void* ReportData, + const uint16_t ReportSize) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(4); + + /* Inline Functions: */ + /** Indicates that a millisecond of idle time has elapsed on the given HID interface, and the interface's idle count should be + * decremented. This should be called once per millisecond so that hardware key-repeats function correctly. It is recommended + * that this be called by the \ref EVENT_USB_Device_StartOfFrame() event, once SOF events have been enabled via + * \ref USB_Device_EnableSOFEvents(). + * + * \param[in,out] HIDInterfaceInfo Pointer to a structure containing a HID Class configuration and state. + */ + static inline void HID_Device_MillisecondElapsed(USB_ClassInfo_HID_Device_t* const HIDInterfaceInfo) ATTR_ALWAYS_INLINE ATTR_NON_NULL_PTR_ARG(1); + static inline void HID_Device_MillisecondElapsed(USB_ClassInfo_HID_Device_t* const HIDInterfaceInfo) + { + if (HIDInterfaceInfo->State.IdleMSRemaining) + HIDInterfaceInfo->State.IdleMSRemaining--; + } + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Device/MIDI.c b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Device/MIDI.c new file mode 100644 index 0000000000..5f0bb249cf --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Device/MIDI.c @@ -0,0 +1,126 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +#define __INCLUDE_FROM_USB_DRIVER +#include "../../HighLevel/USBMode.h" +#if defined(USB_CAN_BE_DEVICE) + +#define __INCLUDE_FROM_MIDI_DRIVER +#include "MIDI.h" + +bool MIDI_Device_ConfigureEndpoints(USB_ClassInfo_MIDI_Device_t* const MIDIInterfaceInfo) +{ + memset(&MIDIInterfaceInfo->State, 0x00, sizeof(MIDIInterfaceInfo->State)); + + if (MIDIInterfaceInfo->Config.DataINEndpointNumber) + { + if (!(Endpoint_ConfigureEndpoint(MIDIInterfaceInfo->Config.DataINEndpointNumber, EP_TYPE_BULK, + ENDPOINT_DIR_IN, MIDIInterfaceInfo->Config.DataINEndpointSize, + MIDIInterfaceInfo->Config.DataINEndpointDoubleBank ? ENDPOINT_BANK_DOUBLE : ENDPOINT_BANK_SINGLE))) + { + return false; + } + } + + if (MIDIInterfaceInfo->Config.DataOUTEndpointNumber) + { + if (!(Endpoint_ConfigureEndpoint(MIDIInterfaceInfo->Config.DataOUTEndpointNumber, EP_TYPE_BULK, + ENDPOINT_DIR_OUT, MIDIInterfaceInfo->Config.DataOUTEndpointSize, + MIDIInterfaceInfo->Config.DataOUTEndpointDoubleBank ? ENDPOINT_BANK_DOUBLE : ENDPOINT_BANK_SINGLE))) + { + return false; + } + } + + return true; +} + +uint8_t MIDI_Device_SendEventPacket(USB_ClassInfo_MIDI_Device_t* const MIDIInterfaceInfo, + const MIDI_EventPacket_t* const Event) +{ + if (USB_DeviceState != DEVICE_STATE_Configured) + return ENDPOINT_RWSTREAM_DeviceDisconnected; + + Endpoint_SelectEndpoint(MIDIInterfaceInfo->Config.DataINEndpointNumber); + + if (Endpoint_IsReadWriteAllowed()) + { + uint8_t ErrorCode; + + if ((ErrorCode = Endpoint_Write_Stream_LE(Event, sizeof(MIDI_EventPacket_t), NO_STREAM_CALLBACK)) != ENDPOINT_RWSTREAM_NoError) + return ErrorCode; + + if (!(Endpoint_IsReadWriteAllowed())) + Endpoint_ClearIN(); + } + + return ENDPOINT_RWSTREAM_NoError; +} + +uint8_t MIDI_Device_Flush(USB_ClassInfo_MIDI_Device_t* const MIDIInterfaceInfo) +{ + if (USB_DeviceState != DEVICE_STATE_Configured) + return ENDPOINT_RWSTREAM_DeviceDisconnected; + + uint8_t ErrorCode; + + Endpoint_SelectEndpoint(MIDIInterfaceInfo->Config.DataINEndpointNumber); + + if (Endpoint_BytesInEndpoint()) + { + Endpoint_ClearIN(); + + if ((ErrorCode = Endpoint_WaitUntilReady()) != ENDPOINT_READYWAIT_NoError) + return ErrorCode; + } + + return ENDPOINT_READYWAIT_NoError; +} + +bool MIDI_Device_ReceiveEventPacket(USB_ClassInfo_MIDI_Device_t* const MIDIInterfaceInfo, + MIDI_EventPacket_t* const Event) +{ + if (USB_DeviceState != DEVICE_STATE_Configured) + return false; + + Endpoint_SelectEndpoint(MIDIInterfaceInfo->Config.DataOUTEndpointNumber); + + if (!(Endpoint_IsReadWriteAllowed())) + return false; + + Endpoint_Read_Stream_LE(Event, sizeof(MIDI_EventPacket_t), NO_STREAM_CALLBACK); + + if (!(Endpoint_IsReadWriteAllowed())) + Endpoint_ClearOUT(); + + return true; +} + +#endif diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Device/MIDI.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Device/MIDI.h new file mode 100644 index 0000000000..e733bfecdc --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Device/MIDI.h @@ -0,0 +1,184 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief Device mode driver for the library USB MIDI Class driver. + * + * Device mode driver for the library USB MIDI Class driver. + * + * \note This file should not be included directly. It is automatically included as needed by the class driver + * dispatch header located in LUFA/Drivers/USB/Class/MIDI.h. + */ + +/** \ingroup Group_USBClassMIDI + * @defgroup Group_USBClassMIDIDevice MIDI Class Device Mode Driver + * + * \section Sec_Dependencies Module Source Dependencies + * The following files must be built with any user project that uses this module: + * - LUFA/Drivers/USB/Class/Device/MIDI.c (Makefile source module name: LUFA_SRC_USBCLASS) + * + * \section Module Description + * Device Mode USB Class driver framework interface, for the MIDI USB Class driver. + * + * @{ + */ + +#ifndef _MIDI_CLASS_DEVICE_H_ +#define _MIDI_CLASS_DEVICE_H_ + + /* Includes: */ + #include "../../USB.h" + #include "../Common/MIDI.h" + + #include + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_MIDI_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/Class/MIDI.h instead. + #endif + + /* Public Interface - May be used in end-application: */ + /* Type Define: */ + /** \brief MIDI Class Device Mode Configuration and State Structure. + * + * Class state structure. An instance of this structure should be made for each MIDI interface + * within the user application, and passed to each of the MIDI class driver functions as the + * MIDIInterfaceInfo parameter. This stores each MIDI interface's configuration and state information. + */ + typedef struct + { + const struct + { + uint8_t StreamingInterfaceNumber; /**< Index of the Audio Streaming interface within the device this structure controls. */ + + uint8_t DataINEndpointNumber; /**< Endpoint number of the incoming MIDI data, if available (zero if unused). */ + uint16_t DataINEndpointSize; /**< Size in bytes of the incoming MIDI data endpoint, if available (zero if unused). */ + bool DataINEndpointDoubleBank; /**< Indicates if the MIDI interface's IN data endpoint should use double banking. */ + + uint8_t DataOUTEndpointNumber; /**< Endpoint number of the outgoing MIDI data, if available (zero if unused). */ + uint16_t DataOUTEndpointSize; /**< Size in bytes of the outgoing MIDI data endpoint, if available (zero if unused). */ + bool DataOUTEndpointDoubleBank; /**< Indicates if the MIDI interface's IN data endpoint should use double banking. */ + } Config; /**< Config data for the USB class interface within the device. All elements in this section + * must be set or the interface will fail to enumerate and operate correctly. + */ + struct + { + // No state information for this class yet + } State; /**< State data for the USB class interface within the device. All elements in this section + * are reset to their defaults when the interface is enumerated. + */ + } USB_ClassInfo_MIDI_Device_t; + + /* Function Prototypes: */ + /** Configures the endpoints of a given MIDI interface, ready for use. This should be linked to the library + * \ref EVENT_USB_Device_ConfigurationChanged() event so that the endpoints are configured when the configuration + * containing the given MIDI interface is selected. + * + * \param[in,out] MIDIInterfaceInfo Pointer to a structure containing a MIDI Class configuration and state. + * + * \return Boolean true if the endpoints were successfully configured, false otherwise. + */ + bool MIDI_Device_ConfigureEndpoints(USB_ClassInfo_MIDI_Device_t* const MIDIInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** Sends a MIDI event packet to the host. If no host is connected, the event packet is discarded. Events are queued into the + * endpoint bank until either the endpoint bank is full, or \ref MIDI_Device_Flush() is called. This allows for multiple + * MIDI events to be packed into a single endpoint packet, increasing data throughput. + * + * \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the + * call will fail. + * + * \param[in,out] MIDIInterfaceInfo Pointer to a structure containing a MIDI Class configuration and state. + * \param[in] Event Pointer to a populated USB_MIDI_EventPacket_t structure containing the MIDI event to send. + * + * \return A value from the \ref Endpoint_Stream_RW_ErrorCodes_t enum. + */ + uint8_t MIDI_Device_SendEventPacket(USB_ClassInfo_MIDI_Device_t* const MIDIInterfaceInfo, + const MIDI_EventPacket_t* const Event) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(2); + + + /** Flushes the MIDI send buffer, sending any queued MIDI events to the host. This should be called to override the + * \ref MIDI_Device_SendEventPacket() function's packing behaviour, to flush queued events. + * + * \param[in,out] MIDIInterfaceInfo Pointer to a structure containing a MIDI Class configuration and state. + * + * \return A value from the \ref Endpoint_WaitUntilReady_ErrorCodes_t enum. + */ + uint8_t MIDI_Device_Flush(USB_ClassInfo_MIDI_Device_t* const MIDIInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** Receives a MIDI event packet from the host. Events are unpacked from the endpoint, thus if the endpoint bank contains + * multiple MIDI events from the host in the one packet, multiple calls to this function will return each individual event. + * + * \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the + * call will fail. + * + * \param[in,out] MIDIInterfaceInfo Pointer to a structure containing a MIDI Class configuration and state. + * \param[out] Event Pointer to a USB_MIDI_EventPacket_t structure where the received MIDI event is to be placed. + * + * \return Boolean true if a MIDI event packet was received, false otherwise. + */ + bool MIDI_Device_ReceiveEventPacket(USB_ClassInfo_MIDI_Device_t* const MIDIInterfaceInfo, + MIDI_EventPacket_t* const Event) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(2); + + /* Inline Functions: */ + /** General management task for a given MIDI class interface, required for the correct operation of the interface. This should + * be called frequently in the main program loop, before the master USB management task \ref USB_USBTask(). + * + * \param[in,out] MIDIInterfaceInfo Pointer to a structure containing a MIDI Class configuration and state. + */ + static inline void MIDI_Device_USBTask(USB_ClassInfo_MIDI_Device_t* const MIDIInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + static inline void MIDI_Device_USBTask(USB_ClassInfo_MIDI_Device_t* const MIDIInterfaceInfo) + { + (void)MIDIInterfaceInfo; + } + + /** Processes incoming control requests from the host, that are directed to the given MIDI class interface. This should be + * linked to the library \ref EVENT_USB_Device_UnhandledControlRequest() event. + * + * \param[in,out] MIDIInterfaceInfo Pointer to a structure containing a MIDI Class configuration and state. + */ + static inline void MIDI_Device_ProcessControlRequest(USB_ClassInfo_MIDI_Device_t* const MIDIInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + static inline void MIDI_Device_ProcessControlRequest(USB_ClassInfo_MIDI_Device_t* const MIDIInterfaceInfo) + { + (void)MIDIInterfaceInfo; + } + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Device/MassStorage.c b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Device/MassStorage.c new file mode 100644 index 0000000000..c31eb86cbd --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Device/MassStorage.c @@ -0,0 +1,230 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +#define __INCLUDE_FROM_USB_DRIVER +#include "../../HighLevel/USBMode.h" +#if defined(USB_CAN_BE_DEVICE) + +#define __INCLUDE_FROM_MS_CLASS_DEVICE_C +#define __INCLUDE_FROM_MS_DRIVER +#include "MassStorage.h" + +static volatile bool* CallbackIsResetSource; + +void MS_Device_ProcessControlRequest(USB_ClassInfo_MS_Device_t* const MSInterfaceInfo) +{ + if (!(Endpoint_IsSETUPReceived())) + return; + + if (USB_ControlRequest.wIndex != MSInterfaceInfo->Config.InterfaceNumber) + return; + + switch (USB_ControlRequest.bRequest) + { + case REQ_MassStorageReset: + if (USB_ControlRequest.bmRequestType == (REQDIR_HOSTTODEVICE | REQTYPE_CLASS | REQREC_INTERFACE)) + { + Endpoint_ClearSETUP(); + + MSInterfaceInfo->State.IsMassStoreReset = true; + + Endpoint_ClearStatusStage(); + } + + break; + case REQ_GetMaxLUN: + if (USB_ControlRequest.bmRequestType == (REQDIR_DEVICETOHOST | REQTYPE_CLASS | REQREC_INTERFACE)) + { + Endpoint_ClearSETUP(); + + Endpoint_Write_Byte(MSInterfaceInfo->Config.TotalLUNs - 1); + Endpoint_ClearIN(); + + Endpoint_ClearStatusStage(); + } + + break; + } +} + +bool MS_Device_ConfigureEndpoints(USB_ClassInfo_MS_Device_t* const MSInterfaceInfo) +{ + memset(&MSInterfaceInfo->State, 0x00, sizeof(MSInterfaceInfo->State)); + + if (!(Endpoint_ConfigureEndpoint(MSInterfaceInfo->Config.DataINEndpointNumber, EP_TYPE_BULK, + ENDPOINT_DIR_IN, MSInterfaceInfo->Config.DataINEndpointSize, + MSInterfaceInfo->Config.DataINEndpointDoubleBank ? ENDPOINT_BANK_DOUBLE : ENDPOINT_BANK_SINGLE))) + { + return false; + } + + if (!(Endpoint_ConfigureEndpoint(MSInterfaceInfo->Config.DataOUTEndpointNumber, EP_TYPE_BULK, + ENDPOINT_DIR_OUT, MSInterfaceInfo->Config.DataOUTEndpointSize, + MSInterfaceInfo->Config.DataOUTEndpointDoubleBank ? ENDPOINT_BANK_DOUBLE : ENDPOINT_BANK_SINGLE))) + { + return false; + } + + return true; +} + +void MS_Device_USBTask(USB_ClassInfo_MS_Device_t* const MSInterfaceInfo) +{ + if (USB_DeviceState != DEVICE_STATE_Configured) + return; + + Endpoint_SelectEndpoint(MSInterfaceInfo->Config.DataOUTEndpointNumber); + + if (Endpoint_IsReadWriteAllowed()) + { + if (MS_Device_ReadInCommandBlock(MSInterfaceInfo)) + { + if (MSInterfaceInfo->State.CommandBlock.Flags & MS_COMMAND_DIR_DATA_IN) + Endpoint_SelectEndpoint(MSInterfaceInfo->Config.DataINEndpointNumber); + + MSInterfaceInfo->State.CommandStatus.Status = CALLBACK_MS_Device_SCSICommandReceived(MSInterfaceInfo) ? + SCSI_Command_Pass : SCSI_Command_Fail; + MSInterfaceInfo->State.CommandStatus.Signature = MS_CSW_SIGNATURE; + MSInterfaceInfo->State.CommandStatus.Tag = MSInterfaceInfo->State.CommandBlock.Tag; + MSInterfaceInfo->State.CommandStatus.DataTransferResidue = MSInterfaceInfo->State.CommandBlock.DataTransferLength; + + if ((MSInterfaceInfo->State.CommandStatus.Status == SCSI_Command_Fail) && + (MSInterfaceInfo->State.CommandStatus.DataTransferResidue)) + { + Endpoint_StallTransaction(); + } + + MS_Device_ReturnCommandStatus(MSInterfaceInfo); + } + } + + if (MSInterfaceInfo->State.IsMassStoreReset) + { + Endpoint_ResetFIFO(MSInterfaceInfo->Config.DataOUTEndpointNumber); + Endpoint_ResetFIFO(MSInterfaceInfo->Config.DataINEndpointNumber); + + Endpoint_SelectEndpoint(MSInterfaceInfo->Config.DataOUTEndpointNumber); + Endpoint_ClearStall(); + Endpoint_ResetDataToggle(); + Endpoint_SelectEndpoint(MSInterfaceInfo->Config.DataINEndpointNumber); + Endpoint_ClearStall(); + Endpoint_ResetDataToggle(); + + MSInterfaceInfo->State.IsMassStoreReset = false; + } +} + +static bool MS_Device_ReadInCommandBlock(USB_ClassInfo_MS_Device_t* const MSInterfaceInfo) +{ + Endpoint_SelectEndpoint(MSInterfaceInfo->Config.DataOUTEndpointNumber); + + CallbackIsResetSource = &MSInterfaceInfo->State.IsMassStoreReset; + if (Endpoint_Read_Stream_LE(&MSInterfaceInfo->State.CommandBlock, + (sizeof(MS_CommandBlockWrapper_t) - 16), + StreamCallback_MS_Device_AbortOnMassStoreReset)) + { + return false; + } + + if ((MSInterfaceInfo->State.CommandBlock.Signature != MS_CBW_SIGNATURE) || + (MSInterfaceInfo->State.CommandBlock.LUN >= MSInterfaceInfo->Config.TotalLUNs) || + (MSInterfaceInfo->State.CommandBlock.Flags & 0x1F) || + (MSInterfaceInfo->State.CommandBlock.SCSICommandLength == 0) || + (MSInterfaceInfo->State.CommandBlock.SCSICommandLength > 16)) + { + Endpoint_StallTransaction(); + Endpoint_SelectEndpoint(MSInterfaceInfo->Config.DataINEndpointNumber); + Endpoint_StallTransaction(); + + return false; + } + + CallbackIsResetSource = &MSInterfaceInfo->State.IsMassStoreReset; + if (Endpoint_Read_Stream_LE(&MSInterfaceInfo->State.CommandBlock.SCSICommandData, + MSInterfaceInfo->State.CommandBlock.SCSICommandLength, + StreamCallback_MS_Device_AbortOnMassStoreReset)) + { + return false; + } + + Endpoint_ClearOUT(); + + return true; +} + +static void MS_Device_ReturnCommandStatus(USB_ClassInfo_MS_Device_t* const MSInterfaceInfo) +{ + Endpoint_SelectEndpoint(MSInterfaceInfo->Config.DataOUTEndpointNumber); + + while (Endpoint_IsStalled()) + { + #if !defined(INTERRUPT_CONTROL_ENDPOINT) + USB_USBTask(); + #endif + + if (MSInterfaceInfo->State.IsMassStoreReset) + return; + } + + Endpoint_SelectEndpoint(MSInterfaceInfo->Config.DataINEndpointNumber); + + while (Endpoint_IsStalled()) + { + #if !defined(INTERRUPT_CONTROL_ENDPOINT) + USB_USBTask(); + #endif + + if (MSInterfaceInfo->State.IsMassStoreReset) + return; + } + + CallbackIsResetSource = &MSInterfaceInfo->State.IsMassStoreReset; + if (Endpoint_Write_Stream_LE(&MSInterfaceInfo->State.CommandStatus, sizeof(MS_CommandStatusWrapper_t), + StreamCallback_MS_Device_AbortOnMassStoreReset)) + { + return; + } + + Endpoint_ClearIN(); +} + +static uint8_t StreamCallback_MS_Device_AbortOnMassStoreReset(void) +{ + #if !defined(INTERRUPT_CONTROL_ENDPOINT) + USB_USBTask(); + #endif + + if (*CallbackIsResetSource) + return STREAMCALLBACK_Abort; + else + return STREAMCALLBACK_Continue; +} + +#endif diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Device/MassStorage.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Device/MassStorage.h new file mode 100644 index 0000000000..9e8cccb6f6 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Device/MassStorage.h @@ -0,0 +1,168 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief Device mode driver for the library USB Mass Storage Class driver. + * + * Device mode driver for the library USB Mass Storage Class driver. + * + * \note This file should not be included directly. It is automatically included as needed by the class driver + * dispatch header located in LUFA/Drivers/USB/Class/MassStorage.h. + */ + +/** \ingroup Group_USBClassMS + * @defgroup Group_USBClassMSDevice Mass Storage Class Device Mode Driver + * + * \section Sec_Dependencies Module Source Dependencies + * The following files must be built with any user project that uses this module: + * - LUFA/Drivers/USB/Class/Device/MassStorage.c (Makefile source module name: LUFA_SRC_USBCLASS) + * + * \section Module Description + * Device Mode USB Class driver framework interface, for the Mass Storage USB Class driver. + * + * @{ + */ + +#ifndef _MS_CLASS_DEVICE_H_ +#define _MS_CLASS_DEVICE_H_ + + /* Includes: */ + #include "../../USB.h" + #include "../Common/MassStorage.h" + + #include + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_MS_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/Class/MassStorage.h instead. + #endif + + /* Public Interface - May be used in end-application: */ + /* Type Defines: */ + /** \brief Mass Storage Class Device Mode Configuration and State Structure. + * + * Class state structure. An instance of this structure should be made for each Mass Storage interface + * within the user application, and passed to each of the Mass Storage class driver functions as the + * MSInterfaceInfo parameter. This stores each Mass Storage interface's configuration and state information. + */ + typedef struct + { + const struct + { + uint8_t InterfaceNumber; /**< Interface number of the Mass Storage interface within the device. */ + + uint8_t DataINEndpointNumber; /**< Endpoint number of the Mass Storage interface's IN data endpoint. */ + uint16_t DataINEndpointSize; /**< Size in bytes of the Mass Storage interface's IN data endpoint. */ + bool DataINEndpointDoubleBank; /**< Indicates if the Mass Storage interface's IN data endpoint should use double banking. */ + + uint8_t DataOUTEndpointNumber; /**< Endpoint number of the Mass Storage interface's OUT data endpoint. */ + uint16_t DataOUTEndpointSize; /**< Size in bytes of the Mass Storage interface's OUT data endpoint. */ + bool DataOUTEndpointDoubleBank; /**< Indicates if the Mass Storage interface's OUT data endpoint should use double banking. */ + + uint8_t TotalLUNs; /**< Total number of logical drives in the Mass Storage interface. */ + } Config; /**< Config data for the USB class interface within the device. All elements in this section + * must be set or the interface will fail to enumerate and operate correctly. + */ + struct + { + MS_CommandBlockWrapper_t CommandBlock; /**< Mass Storage class command block structure, stores the received SCSI + * command from the host which is to be processed. + */ + MS_CommandStatusWrapper_t CommandStatus; /**< Mass Storage class command status structure, set elements to indicate + * the issued command's success or failure to the host. + */ + volatile bool IsMassStoreReset; /**< Flag indicating that the host has requested that the Mass Storage interface be reset + * and that all current Mass Storage operations should immediately abort. + */ + } State; /**< State data for the USB class interface within the device. All elements in this section + * are reset to their defaults when the interface is enumerated. + */ + } USB_ClassInfo_MS_Device_t; + + /* Function Prototypes: */ + /** Configures the endpoints of a given Mass Storage interface, ready for use. This should be linked to the library + * \ref EVENT_USB_Device_ConfigurationChanged() event so that the endpoints are configured when the configuration + * containing the given Mass Storage interface is selected. + * + * \param[in,out] MSInterfaceInfo Pointer to a structure containing a Mass Storage Class configuration and state. + * + * \return Boolean true if the endpoints were successfully configured, false otherwise. + */ + bool MS_Device_ConfigureEndpoints(USB_ClassInfo_MS_Device_t* const MSInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** Processes incoming control requests from the host, that are directed to the given Mass Storage class interface. This should be + * linked to the library \ref EVENT_USB_Device_UnhandledControlRequest() event. + * + * \param[in,out] MSInterfaceInfo Pointer to a structure containing a Mass Storage Class configuration and state. + */ + void MS_Device_ProcessControlRequest(USB_ClassInfo_MS_Device_t* const MSInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** General management task for a given Mass Storage class interface, required for the correct operation of the interface. This should + * be called frequently in the main program loop, before the master USB management task \ref USB_USBTask(). + * + * \param[in,out] MSInterfaceInfo Pointer to a structure containing a Mass Storage configuration and state. + */ + void MS_Device_USBTask(USB_ClassInfo_MS_Device_t* const MSInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** Mass Storage class driver callback for the user processing of a received SCSI command. This callback will fire each time the + * host sends a SCSI command which requires processing by the user application. Inside this callback the user is responsible + * for the processing of the received SCSI command from the host. The SCSI command is available in the CommandBlock structure + * inside the Mass Storage class state structure passed as a parameter to the callback function. + * + * \param[in,out] MSInterfaceInfo Pointer to a structure containing a Mass Storage Class configuration and state. + * + * \return Boolean true if the SCSI command was successfully processed, false otherwise. + */ + bool CALLBACK_MS_Device_SCSICommandReceived(USB_ClassInfo_MS_Device_t* const MSInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /* Private Interface - For use in library only: */ + #if !defined(__DOXYGEN__) + /* Function Prototypes: */ + #if defined(__INCLUDE_FROM_MS_CLASS_DEVICE_C) + static void MS_Device_ReturnCommandStatus(USB_ClassInfo_MS_Device_t* const MSInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + static bool MS_Device_ReadInCommandBlock(USB_ClassInfo_MS_Device_t* const MSInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + static uint8_t StreamCallback_MS_Device_AbortOnMassStoreReset(void); + #endif + + #endif + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Device/RNDIS.c b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Device/RNDIS.c new file mode 100644 index 0000000000..ff790b771f --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Device/RNDIS.c @@ -0,0 +1,477 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +#define __INCLUDE_FROM_USB_DRIVER +#include "../../HighLevel/USBMode.h" +#if defined(USB_CAN_BE_DEVICE) + +#define __INCLUDE_FROM_RNDIS_CLASS_DEVICE_C +#define __INCLUDE_FROM_RNDIS_DRIVER +#include "RNDIS.h" + +static const uint32_t PROGMEM AdapterSupportedOIDList[] = + { + OID_GEN_SUPPORTED_LIST, + OID_GEN_PHYSICAL_MEDIUM, + OID_GEN_HARDWARE_STATUS, + OID_GEN_MEDIA_SUPPORTED, + OID_GEN_MEDIA_IN_USE, + OID_GEN_MAXIMUM_FRAME_SIZE, + OID_GEN_MAXIMUM_TOTAL_SIZE, + OID_GEN_LINK_SPEED, + OID_GEN_TRANSMIT_BLOCK_SIZE, + OID_GEN_RECEIVE_BLOCK_SIZE, + OID_GEN_VENDOR_ID, + OID_GEN_VENDOR_DESCRIPTION, + OID_GEN_CURRENT_PACKET_FILTER, + OID_GEN_MAXIMUM_TOTAL_SIZE, + OID_GEN_MEDIA_CONNECT_STATUS, + OID_GEN_XMIT_OK, + OID_GEN_RCV_OK, + OID_GEN_XMIT_ERROR, + OID_GEN_RCV_ERROR, + OID_GEN_RCV_NO_BUFFER, + OID_802_3_PERMANENT_ADDRESS, + OID_802_3_CURRENT_ADDRESS, + OID_802_3_MULTICAST_LIST, + OID_802_3_MAXIMUM_LIST_SIZE, + OID_802_3_RCV_ERROR_ALIGNMENT, + OID_802_3_XMIT_ONE_COLLISION, + OID_802_3_XMIT_MORE_COLLISIONS, + }; + +void RNDIS_Device_ProcessControlRequest(USB_ClassInfo_RNDIS_Device_t* const RNDISInterfaceInfo) +{ + if (!(Endpoint_IsSETUPReceived())) + return; + + if (USB_ControlRequest.wIndex != RNDISInterfaceInfo->Config.ControlInterfaceNumber) + return; + + switch (USB_ControlRequest.bRequest) + { + case REQ_SendEncapsulatedCommand: + if (USB_ControlRequest.bmRequestType == (REQDIR_HOSTTODEVICE | REQTYPE_CLASS | REQREC_INTERFACE)) + { + Endpoint_ClearSETUP(); + + Endpoint_Read_Control_Stream_LE(RNDISInterfaceInfo->State.RNDISMessageBuffer, USB_ControlRequest.wLength); + RNDIS_Device_ProcessRNDISControlMessage(RNDISInterfaceInfo); + Endpoint_ClearIN(); + } + + break; + case REQ_GetEncapsulatedResponse: + if (USB_ControlRequest.bmRequestType == (REQDIR_DEVICETOHOST | REQTYPE_CLASS | REQREC_INTERFACE)) + { + Endpoint_ClearSETUP(); + + RNDIS_Message_Header_t* MessageHeader = (RNDIS_Message_Header_t*)&RNDISInterfaceInfo->State.RNDISMessageBuffer; + + if (!(MessageHeader->MessageLength)) + { + RNDISInterfaceInfo->State.RNDISMessageBuffer[0] = 0; + MessageHeader->MessageLength = 1; + } + + Endpoint_Write_Control_Stream_LE(RNDISInterfaceInfo->State.RNDISMessageBuffer, MessageHeader->MessageLength); + Endpoint_ClearOUT(); + + MessageHeader->MessageLength = 0; + } + + break; + } +} + +bool RNDIS_Device_ConfigureEndpoints(USB_ClassInfo_RNDIS_Device_t* const RNDISInterfaceInfo) +{ + memset(&RNDISInterfaceInfo->State, 0x00, sizeof(RNDISInterfaceInfo->State)); + + if (!(Endpoint_ConfigureEndpoint(RNDISInterfaceInfo->Config.DataINEndpointNumber, EP_TYPE_BULK, + ENDPOINT_DIR_IN, RNDISInterfaceInfo->Config.DataINEndpointSize, + RNDISInterfaceInfo->Config.DataINEndpointDoubleBank ? ENDPOINT_BANK_DOUBLE : ENDPOINT_BANK_SINGLE))) + { + return false; + } + + if (!(Endpoint_ConfigureEndpoint(RNDISInterfaceInfo->Config.DataOUTEndpointNumber, EP_TYPE_BULK, + ENDPOINT_DIR_OUT, RNDISInterfaceInfo->Config.DataOUTEndpointSize, + RNDISInterfaceInfo->Config.DataOUTEndpointDoubleBank ? ENDPOINT_BANK_DOUBLE : ENDPOINT_BANK_SINGLE))) + { + return false; + } + + if (!(Endpoint_ConfigureEndpoint(RNDISInterfaceInfo->Config.NotificationEndpointNumber, EP_TYPE_INTERRUPT, + ENDPOINT_DIR_IN, RNDISInterfaceInfo->Config.NotificationEndpointSize, + RNDISInterfaceInfo->Config.NotificationEndpointDoubleBank ? ENDPOINT_BANK_DOUBLE : ENDPOINT_BANK_SINGLE))) + { + return false; + } + + return true; +} + +void RNDIS_Device_USBTask(USB_ClassInfo_RNDIS_Device_t* const RNDISInterfaceInfo) +{ + if (USB_DeviceState != DEVICE_STATE_Configured) + return; + + RNDIS_Message_Header_t* MessageHeader = (RNDIS_Message_Header_t*)&RNDISInterfaceInfo->State.RNDISMessageBuffer; + + Endpoint_SelectEndpoint(RNDISInterfaceInfo->Config.NotificationEndpointNumber); + + if (Endpoint_IsINReady() && RNDISInterfaceInfo->State.ResponseReady) + { + USB_Request_Header_t Notification = (USB_Request_Header_t) + { + .bmRequestType = (REQDIR_DEVICETOHOST | REQTYPE_CLASS | REQREC_INTERFACE), + .bRequest = NOTIF_ResponseAvailable, + .wValue = 0, + .wIndex = 0, + .wLength = 0, + }; + + Endpoint_Write_Stream_LE(&Notification, sizeof(USB_Request_Header_t), NO_STREAM_CALLBACK); + + Endpoint_ClearIN(); + + RNDISInterfaceInfo->State.ResponseReady = false; + } + + if ((RNDISInterfaceInfo->State.CurrRNDISState == RNDIS_Data_Initialized) && !(MessageHeader->MessageLength)) + { + RNDIS_Packet_Message_t RNDISPacketHeader; + + Endpoint_SelectEndpoint(RNDISInterfaceInfo->Config.DataOUTEndpointNumber); + + if (Endpoint_IsOUTReceived() && !(RNDISInterfaceInfo->State.FrameIN.FrameInBuffer)) + { + Endpoint_Read_Stream_LE(&RNDISPacketHeader, sizeof(RNDIS_Packet_Message_t), NO_STREAM_CALLBACK); + + if (RNDISPacketHeader.DataLength > ETHERNET_FRAME_SIZE_MAX) + { + Endpoint_StallTransaction(); + return; + } + + Endpoint_Read_Stream_LE(RNDISInterfaceInfo->State.FrameIN.FrameData, RNDISPacketHeader.DataLength, NO_STREAM_CALLBACK); + + Endpoint_ClearOUT(); + + RNDISInterfaceInfo->State.FrameIN.FrameLength = RNDISPacketHeader.DataLength; + + RNDISInterfaceInfo->State.FrameIN.FrameInBuffer = true; + } + + Endpoint_SelectEndpoint(RNDISInterfaceInfo->Config.DataINEndpointNumber); + + if (Endpoint_IsINReady() && RNDISInterfaceInfo->State.FrameOUT.FrameInBuffer) + { + memset(&RNDISPacketHeader, 0, sizeof(RNDIS_Packet_Message_t)); + + RNDISPacketHeader.MessageType = REMOTE_NDIS_PACKET_MSG; + RNDISPacketHeader.MessageLength = (sizeof(RNDIS_Packet_Message_t) + RNDISInterfaceInfo->State.FrameOUT.FrameLength); + RNDISPacketHeader.DataOffset = (sizeof(RNDIS_Packet_Message_t) - sizeof(RNDIS_Message_Header_t)); + RNDISPacketHeader.DataLength = RNDISInterfaceInfo->State.FrameOUT.FrameLength; + + Endpoint_Write_Stream_LE(&RNDISPacketHeader, sizeof(RNDIS_Packet_Message_t), NO_STREAM_CALLBACK); + Endpoint_Write_Stream_LE(RNDISInterfaceInfo->State.FrameOUT.FrameData, RNDISPacketHeader.DataLength, NO_STREAM_CALLBACK); + Endpoint_ClearIN(); + + RNDISInterfaceInfo->State.FrameOUT.FrameInBuffer = false; + } + } +} + +void RNDIS_Device_ProcessRNDISControlMessage(USB_ClassInfo_RNDIS_Device_t* const RNDISInterfaceInfo) +{ + /* Note: Only a single buffer is used for both the received message and its response to save SRAM. Because of + this, response bytes should be filled in order so that they do not clobber unread data in the buffer. */ + + RNDIS_Message_Header_t* MessageHeader = (RNDIS_Message_Header_t*)&RNDISInterfaceInfo->State.RNDISMessageBuffer; + + switch (MessageHeader->MessageType) + { + case REMOTE_NDIS_INITIALIZE_MSG: + RNDISInterfaceInfo->State.ResponseReady = true; + + RNDIS_Initialize_Message_t* INITIALIZE_Message = + (RNDIS_Initialize_Message_t*)&RNDISInterfaceInfo->State.RNDISMessageBuffer; + RNDIS_Initialize_Complete_t* INITIALIZE_Response = + (RNDIS_Initialize_Complete_t*)&RNDISInterfaceInfo->State.RNDISMessageBuffer; + + INITIALIZE_Response->MessageType = REMOTE_NDIS_INITIALIZE_CMPLT; + INITIALIZE_Response->MessageLength = sizeof(RNDIS_Initialize_Complete_t); + INITIALIZE_Response->RequestId = INITIALIZE_Message->RequestId; + INITIALIZE_Response->Status = REMOTE_NDIS_STATUS_SUCCESS; + + INITIALIZE_Response->MajorVersion = REMOTE_NDIS_VERSION_MAJOR; + INITIALIZE_Response->MinorVersion = REMOTE_NDIS_VERSION_MINOR; + INITIALIZE_Response->DeviceFlags = REMOTE_NDIS_DF_CONNECTIONLESS; + INITIALIZE_Response->Medium = REMOTE_NDIS_MEDIUM_802_3; + INITIALIZE_Response->MaxPacketsPerTransfer = 1; + INITIALIZE_Response->MaxTransferSize = (sizeof(RNDIS_Packet_Message_t) + ETHERNET_FRAME_SIZE_MAX); + INITIALIZE_Response->PacketAlignmentFactor = 0; + INITIALIZE_Response->AFListOffset = 0; + INITIALIZE_Response->AFListSize = 0; + + RNDISInterfaceInfo->State.CurrRNDISState = RNDIS_Initialized; + + break; + case REMOTE_NDIS_HALT_MSG: + RNDISInterfaceInfo->State.ResponseReady = false; + MessageHeader->MessageLength = 0; + + RNDISInterfaceInfo->State.CurrRNDISState = RNDIS_Uninitialized; + + break; + case REMOTE_NDIS_QUERY_MSG: + RNDISInterfaceInfo->State.ResponseReady = true; + + RNDIS_Query_Message_t* QUERY_Message = (RNDIS_Query_Message_t*)&RNDISInterfaceInfo->State.RNDISMessageBuffer; + RNDIS_Query_Complete_t* QUERY_Response = (RNDIS_Query_Complete_t*)&RNDISInterfaceInfo->State.RNDISMessageBuffer; + uint32_t Query_Oid = QUERY_Message->Oid; + + void* QueryData = &RNDISInterfaceInfo->State.RNDISMessageBuffer[sizeof(RNDIS_Message_Header_t) + + QUERY_Message->InformationBufferOffset]; + void* ResponseData = &RNDISInterfaceInfo->State.RNDISMessageBuffer[sizeof(RNDIS_Query_Complete_t)]; + uint16_t ResponseSize; + + QUERY_Response->MessageType = REMOTE_NDIS_QUERY_CMPLT; + QUERY_Response->MessageLength = sizeof(RNDIS_Query_Complete_t); + + if (RNDIS_Device_ProcessNDISQuery(RNDISInterfaceInfo, Query_Oid, QueryData, QUERY_Message->InformationBufferLength, + ResponseData, &ResponseSize)) + { + QUERY_Response->Status = REMOTE_NDIS_STATUS_SUCCESS; + QUERY_Response->MessageLength += ResponseSize; + + QUERY_Response->InformationBufferLength = ResponseSize; + QUERY_Response->InformationBufferOffset = (sizeof(RNDIS_Query_Complete_t) - sizeof(RNDIS_Message_Header_t)); + } + else + { + QUERY_Response->Status = REMOTE_NDIS_STATUS_NOT_SUPPORTED; + + QUERY_Response->InformationBufferLength = 0; + QUERY_Response->InformationBufferOffset = 0; + } + + break; + case REMOTE_NDIS_SET_MSG: + RNDISInterfaceInfo->State.ResponseReady = true; + + RNDIS_Set_Message_t* SET_Message = (RNDIS_Set_Message_t*)&RNDISInterfaceInfo->State.RNDISMessageBuffer; + RNDIS_Set_Complete_t* SET_Response = (RNDIS_Set_Complete_t*)&RNDISInterfaceInfo->State.RNDISMessageBuffer; + uint32_t SET_Oid = SET_Message->Oid; + + SET_Response->MessageType = REMOTE_NDIS_SET_CMPLT; + SET_Response->MessageLength = sizeof(RNDIS_Set_Complete_t); + SET_Response->RequestId = SET_Message->RequestId; + + void* SetData = &RNDISInterfaceInfo->State.RNDISMessageBuffer[sizeof(RNDIS_Message_Header_t) + + SET_Message->InformationBufferOffset]; + + SET_Response->Status = RNDIS_Device_ProcessNDISSet(RNDISInterfaceInfo, SET_Oid, SetData, + SET_Message->InformationBufferLength) ? + REMOTE_NDIS_STATUS_SUCCESS : REMOTE_NDIS_STATUS_NOT_SUPPORTED; + break; + case REMOTE_NDIS_RESET_MSG: + RNDISInterfaceInfo->State.ResponseReady = true; + + RNDIS_Reset_Complete_t* RESET_Response = (RNDIS_Reset_Complete_t*)&RNDISInterfaceInfo->State.RNDISMessageBuffer; + + RESET_Response->MessageType = REMOTE_NDIS_RESET_CMPLT; + RESET_Response->MessageLength = sizeof(RNDIS_Reset_Complete_t); + RESET_Response->Status = REMOTE_NDIS_STATUS_SUCCESS; + RESET_Response->AddressingReset = 0; + + break; + case REMOTE_NDIS_KEEPALIVE_MSG: + RNDISInterfaceInfo->State.ResponseReady = true; + + RNDIS_KeepAlive_Message_t* KEEPALIVE_Message = + (RNDIS_KeepAlive_Message_t*)&RNDISInterfaceInfo->State.RNDISMessageBuffer; + RNDIS_KeepAlive_Complete_t* KEEPALIVE_Response = + (RNDIS_KeepAlive_Complete_t*)&RNDISInterfaceInfo->State.RNDISMessageBuffer; + + KEEPALIVE_Response->MessageType = REMOTE_NDIS_KEEPALIVE_CMPLT; + KEEPALIVE_Response->MessageLength = sizeof(RNDIS_KeepAlive_Complete_t); + KEEPALIVE_Response->RequestId = KEEPALIVE_Message->RequestId; + KEEPALIVE_Response->Status = REMOTE_NDIS_STATUS_SUCCESS; + + break; + } +} + +static bool RNDIS_Device_ProcessNDISQuery(USB_ClassInfo_RNDIS_Device_t* const RNDISInterfaceInfo, + const uint32_t OId, + void* const QueryData, + const uint16_t QuerySize, + void* ResponseData, + uint16_t* const ResponseSize) +{ + (void)QueryData; + (void)QuerySize; + + switch (OId) + { + case OID_GEN_SUPPORTED_LIST: + *ResponseSize = sizeof(AdapterSupportedOIDList); + + memcpy_P(ResponseData, AdapterSupportedOIDList, sizeof(AdapterSupportedOIDList)); + + return true; + case OID_GEN_PHYSICAL_MEDIUM: + *ResponseSize = sizeof(uint32_t); + + /* Indicate that the device is a true ethernet link */ + *((uint32_t*)ResponseData) = 0; + + return true; + case OID_GEN_HARDWARE_STATUS: + *ResponseSize = sizeof(uint32_t); + + *((uint32_t*)ResponseData) = NDIS_HardwareStatus_Ready; + + return true; + case OID_GEN_MEDIA_SUPPORTED: + case OID_GEN_MEDIA_IN_USE: + *ResponseSize = sizeof(uint32_t); + + *((uint32_t*)ResponseData) = REMOTE_NDIS_MEDIUM_802_3; + + return true; + case OID_GEN_VENDOR_ID: + *ResponseSize = sizeof(uint32_t); + + /* Vendor ID 0x0xFFFFFF is reserved for vendors who have not purchased a NDIS VID */ + *((uint32_t*)ResponseData) = 0x00FFFFFF; + + return true; + case OID_GEN_MAXIMUM_FRAME_SIZE: + case OID_GEN_TRANSMIT_BLOCK_SIZE: + case OID_GEN_RECEIVE_BLOCK_SIZE: + *ResponseSize = sizeof(uint32_t); + + *((uint32_t*)ResponseData) = ETHERNET_FRAME_SIZE_MAX; + + return true; + case OID_GEN_VENDOR_DESCRIPTION: + *ResponseSize = (strlen(RNDISInterfaceInfo->Config.AdapterVendorDescription) + 1); + + memcpy(ResponseData, RNDISInterfaceInfo->Config.AdapterVendorDescription, *ResponseSize); + + return true; + case OID_GEN_MEDIA_CONNECT_STATUS: + *ResponseSize = sizeof(uint32_t); + + *((uint32_t*)ResponseData) = REMOTE_NDIS_MEDIA_STATE_CONNECTED; + + return true; + case OID_GEN_LINK_SPEED: + *ResponseSize = sizeof(uint32_t); + + /* Indicate 10Mb/s link speed */ + *((uint32_t*)ResponseData) = 100000; + + return true; + case OID_802_3_PERMANENT_ADDRESS: + case OID_802_3_CURRENT_ADDRESS: + *ResponseSize = sizeof(MAC_Address_t); + + memcpy(ResponseData, &RNDISInterfaceInfo->Config.AdapterMACAddress, sizeof(MAC_Address_t)); + + return true; + case OID_802_3_MAXIMUM_LIST_SIZE: + *ResponseSize = sizeof(uint32_t); + + /* Indicate only one multicast address supported */ + *((uint32_t*)ResponseData) = 1; + + return true; + case OID_GEN_CURRENT_PACKET_FILTER: + *ResponseSize = sizeof(uint32_t); + + *((uint32_t*)ResponseData) = RNDISInterfaceInfo->State.CurrPacketFilter; + + return true; + case OID_GEN_XMIT_OK: + case OID_GEN_RCV_OK: + case OID_GEN_XMIT_ERROR: + case OID_GEN_RCV_ERROR: + case OID_GEN_RCV_NO_BUFFER: + case OID_802_3_RCV_ERROR_ALIGNMENT: + case OID_802_3_XMIT_ONE_COLLISION: + case OID_802_3_XMIT_MORE_COLLISIONS: + *ResponseSize = sizeof(uint32_t); + + /* Unused statistic OIDs - always return 0 for each */ + *((uint32_t*)ResponseData) = 0; + + return true; + case OID_GEN_MAXIMUM_TOTAL_SIZE: + *ResponseSize = sizeof(uint32_t); + + /* Indicate maximum overall buffer (Ethernet frame and RNDIS header) the adapter can handle */ + *((uint32_t*)ResponseData) = (RNDIS_MESSAGE_BUFFER_SIZE + ETHERNET_FRAME_SIZE_MAX); + + return true; + default: + return false; + } +} + +static bool RNDIS_Device_ProcessNDISSet(USB_ClassInfo_RNDIS_Device_t* const RNDISInterfaceInfo, + const uint32_t OId, + const void* SetData, + const uint16_t SetSize) +{ + (void)SetSize; + + switch (OId) + { + case OID_GEN_CURRENT_PACKET_FILTER: + RNDISInterfaceInfo->State.CurrPacketFilter = *((uint32_t*)SetData); + RNDISInterfaceInfo->State.CurrRNDISState = ((RNDISInterfaceInfo->State.CurrPacketFilter) ? + RNDIS_Data_Initialized : RNDIS_Data_Initialized); + + return true; + case OID_802_3_MULTICAST_LIST: + /* Do nothing - throw away the value from the host as it is unused */ + + return true; + default: + return false; + } +} + +#endif diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Device/RNDIS.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Device/RNDIS.h new file mode 100644 index 0000000000..8af656322d --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Device/RNDIS.h @@ -0,0 +1,176 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief Device mode driver for the library USB RNDIS Class driver. + * + * Device mode driver for the library USB RNDIS Class driver. + * + * \note This file should not be included directly. It is automatically included as needed by the class driver + * dispatch header located in LUFA/Drivers/USB/Class/RNDIS.h. + */ + +/** \ingroup Group_USBClassRNDIS + * @defgroup Group_USBClassRNDISDevice RNDIS Class Device Mode Driver + * + * \section Sec_Dependencies Module Source Dependencies + * The following files must be built with any user project that uses this module: + * - LUFA/Drivers/USB/Class/Device/RNDIS.c (Makefile source module name: LUFA_SRC_USBCLASS) + * + * \section Module Description + * Device Mode USB Class driver framework interface, for the RNDIS USB Class driver. + * + * @{ + */ + +#ifndef _RNDIS_CLASS_DEVICE_H_ +#define _RNDIS_CLASS_DEVICE_H_ + + /* Includes: */ + #include "../../USB.h" + #include "../Common/RNDIS.h" + + #include + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_RNDIS_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/Class/RNDIS.h instead. + #endif + + /* Public Interface - May be used in end-application: */ + /* Type Defines: */ + /** \brief RNDIS Class Device Mode Configuration and State Structure. + * + * Class state structure. An instance of this structure should be made for each RNDIS interface + * within the user application, and passed to each of the RNDIS class driver functions as the + * RNDISInterfaceInfo parameter. This stores each RNDIS interface's configuration and state information. + */ + typedef struct + { + const struct + { + uint8_t ControlInterfaceNumber; /**< Interface number of the CDC control interface within the device. */ + + uint8_t DataINEndpointNumber; /**< Endpoint number of the CDC interface's IN data endpoint. */ + uint16_t DataINEndpointSize; /**< Size in bytes of the CDC interface's IN data endpoint. */ + bool DataINEndpointDoubleBank; /**< Indicates if the RNDIS interface's IN data endpoint should use double banking. */ + + uint8_t DataOUTEndpointNumber; /**< Endpoint number of the CDC interface's OUT data endpoint. */ + uint16_t DataOUTEndpointSize; /**< Size in bytes of the CDC interface's OUT data endpoint. */ + bool DataOUTEndpointDoubleBank; /**< Indicates if the RNDIS interface's OUT data endpoint should use double banking. */ + + uint8_t NotificationEndpointNumber; /**< Endpoint number of the CDC interface's IN notification endpoint, if used. */ + uint16_t NotificationEndpointSize; /**< Size in bytes of the CDC interface's IN notification endpoint, if used. */ + bool NotificationEndpointDoubleBank; /**< Indicates if the RNDIS interface's notification endpoint should use double banking. */ + + char* AdapterVendorDescription; /**< String description of the adapter vendor. */ + MAC_Address_t AdapterMACAddress; /**< MAC address of the adapter. */ + } Config; /**< Config data for the USB class interface within the device. All elements in this section. + * must be set or the interface will fail to enumerate and operate correctly. + */ + struct + { + uint8_t RNDISMessageBuffer[RNDIS_MESSAGE_BUFFER_SIZE]; /**< Buffer to hold RNDIS messages to and from the host, + * managed by the class driver. + */ + bool ResponseReady; /**< Internal flag indicating if a RNDIS message is waiting to be returned to the host. */ + uint8_t CurrRNDISState; /**< Current RNDIS state of the adapter, a value from the RNDIS_States_t enum. */ + uint32_t CurrPacketFilter; /**< Current packet filter mode, used internally by the class driver. */ + Ethernet_Frame_Info_t FrameIN; /**< Structure holding the last received Ethernet frame from the host, for user + * processing. + */ + Ethernet_Frame_Info_t FrameOUT; /**< Structure holding the next Ethernet frame to send to the host, populated by the + * user application. + */ + } State; /**< State data for the USB class interface within the device. All elements in this section + * are reset to their defaults when the interface is enumerated. + */ + } USB_ClassInfo_RNDIS_Device_t; + + /* Function Prototypes: */ + /** Configures the endpoints of a given RNDIS interface, ready for use. This should be linked to the library + * \ref EVENT_USB_Device_ConfigurationChanged() event so that the endpoints are configured when the configuration + * containing the given HID interface is selected. + * + * \param[in,out] RNDISInterfaceInfo Pointer to a structure containing a RNDIS Class configuration and state. + * + * \return Boolean true if the endpoints were successfully configured, false otherwise. + */ + bool RNDIS_Device_ConfigureEndpoints(USB_ClassInfo_RNDIS_Device_t* const RNDISInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** Processes incoming control requests from the host, that are directed to the given RNDIS class interface. This should be + * linked to the library \ref EVENT_USB_Device_UnhandledControlRequest() event. + * + * \param[in,out] RNDISInterfaceInfo Pointer to a structure containing a RNDIS Class configuration and state. + */ + void RNDIS_Device_ProcessControlRequest(USB_ClassInfo_RNDIS_Device_t* const RNDISInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** General management task for a given HID class interface, required for the correct operation of the interface. This should + * be called frequently in the main program loop, before the master USB management task \ref USB_USBTask(). + * + * \param[in,out] RNDISInterfaceInfo Pointer to a structure containing a RNDIS Class configuration and state. + */ + void RNDIS_Device_USBTask(USB_ClassInfo_RNDIS_Device_t* const RNDISInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /* Private Interface - For use in library only: */ + #if !defined(__DOXYGEN__) + /* Function Prototypes: */ + #if defined(__INCLUDE_FROM_RNDIS_CLASS_DEVICE_C) + static void RNDIS_Device_ProcessRNDISControlMessage(USB_ClassInfo_RNDIS_Device_t* const RNDISInterfaceInfo) + ATTR_NON_NULL_PTR_ARG(1); + static bool RNDIS_Device_ProcessNDISQuery(USB_ClassInfo_RNDIS_Device_t* const RNDISInterfaceInfo, + const uint32_t OId, + void* const QueryData, + const uint16_t QuerySize, + void* ResponseData, + uint16_t* const ResponseSize) ATTR_NON_NULL_PTR_ARG(1) + ATTR_NON_NULL_PTR_ARG(5) ATTR_NON_NULL_PTR_ARG(6); + static bool RNDIS_Device_ProcessNDISSet(USB_ClassInfo_RNDIS_Device_t* const RNDISInterfaceInfo, + const uint32_t OId, + const void* SetData, + const uint16_t SetSize) ATTR_NON_NULL_PTR_ARG(1) + ATTR_NON_NULL_PTR_ARG(3); + #endif + + #endif + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/HID.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/HID.h new file mode 100644 index 0000000000..6def55d594 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/HID.h @@ -0,0 +1,84 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief Master include file for the library USB HID Class driver. + * + * Master include file for the library USB HID Class driver, for both host and device modes, where available. + * + * This file should be included in all user projects making use of this optional class driver, instead of + * including any headers in the USB/ClassDriver/Device, USB/ClassDriver/Host or USB/ClassDriver/Common subdirectories. + */ + +/** \ingroup Group_USBClassDrivers + * @defgroup Group_USBClassHID HID Class Driver - LUFA/Drivers/Class/HID.h + * + * \section Sec_Dependencies Module Source Dependencies + * The following files must be built with any user project that uses this module: + * - LUFA/Drivers/USB/Class/Device/HID.c (Makefile source module name: LUFA_SRC_USBCLASS) + * - LUFA/Drivers/USB/Class/Host/HID.c (Makefile source module name: LUFA_SRC_USBCLASS) + * - LUFA/Drivers/USB/Class/Host/HIDParser.c (Makefile source module name: LUFA_SRC_USB) + * + * \section Module Description + * HID Class Driver module. This module contains an internal implementation of the USB HID Class, for both Device + * and Host USB modes. User applications can use this class driver instead of implementing the HID class manually + * via the low-level LUFA APIs. + * + * This module is designed to simplify the user code by exposing only the required interface needed to interface with + * Hosts or Devices using the USB HID Class. + * + * @{ + */ + +#ifndef _HID_CLASS_H_ +#define _HID_CLASS_H_ + + /* Macros: */ + #define __INCLUDE_FROM_HID_DRIVER + #define __INCLUDE_FROM_USB_DRIVER + + /* Includes: */ + #include "../HighLevel/USBMode.h" + + #if defined(NO_STREAM_CALLBACKS) + #error The NO_STREAM_CALLBACKS compile time option cannot be used in projects using the library Class drivers. + #endif + + #if defined(USB_CAN_BE_DEVICE) + #include "Device/HID.h" + #endif + + #if defined(USB_CAN_BE_HOST) + #include "Host/HID.h" + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/CDC.c b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/CDC.c new file mode 100644 index 0000000000..b9e4c9ebfe --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/CDC.c @@ -0,0 +1,464 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +#define __INCLUDE_FROM_USB_DRIVER +#include "../../HighLevel/USBMode.h" +#if defined(USB_CAN_BE_HOST) + +#define __INCLUDE_FROM_CDC_CLASS_HOST_C +#define __INCLUDE_FROM_CDC_DRIVER +#include "CDC.h" + +uint8_t CDC_Host_ConfigurePipes(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo, + uint16_t ConfigDescriptorSize, + void* ConfigDescriptorData) +{ + uint8_t FoundEndpoints = 0; + + memset(&CDCInterfaceInfo->State, 0x00, sizeof(CDCInterfaceInfo->State)); + + if (DESCRIPTOR_TYPE(ConfigDescriptorData) != DTYPE_Configuration) + return CDC_ENUMERROR_InvalidConfigDescriptor; + + if (USB_GetNextDescriptorComp(&ConfigDescriptorSize, &ConfigDescriptorData, + DCOMP_CDC_Host_NextCDCControlInterface) != DESCRIPTOR_SEARCH_COMP_Found) + { + return CDC_ENUMERROR_NoCDCInterfaceFound; + } + + CDCInterfaceInfo->State.ControlInterfaceNumber = DESCRIPTOR_CAST(ConfigDescriptorData, USB_Descriptor_Interface_t).InterfaceNumber; + + while (FoundEndpoints != (CDC_FOUND_NOTIFICATION_IN | CDC_FOUND_DATAPIPE_IN | CDC_FOUND_DATAPIPE_OUT)) + { + if (USB_GetNextDescriptorComp(&ConfigDescriptorSize, &ConfigDescriptorData, + DCOMP_CDC_Host_NextCDCInterfaceEndpoint) != DESCRIPTOR_SEARCH_COMP_Found) + { + if (FoundEndpoints & CDC_FOUND_NOTIFICATION_IN) + { + if (USB_GetNextDescriptorComp(&ConfigDescriptorSize, &ConfigDescriptorData, + DCOMP_CDC_Host_NextCDCDataInterface) != DESCRIPTOR_SEARCH_COMP_Found) + { + return CDC_ENUMERROR_NoCDCInterfaceFound; + } + } + else + { + FoundEndpoints = 0; + + Pipe_SelectPipe(CDCInterfaceInfo->Config.DataINPipeNumber); + Pipe_DisablePipe(); + Pipe_SelectPipe(CDCInterfaceInfo->Config.DataOUTPipeNumber); + Pipe_DisablePipe(); + Pipe_SelectPipe(CDCInterfaceInfo->Config.NotificationPipeNumber); + Pipe_DisablePipe(); + + if (USB_GetNextDescriptorComp(&ConfigDescriptorSize, &ConfigDescriptorData, + DCOMP_CDC_Host_NextCDCControlInterface) != DESCRIPTOR_SEARCH_COMP_Found) + { + return CDC_ENUMERROR_NoCDCInterfaceFound; + } + } + + if (USB_GetNextDescriptorComp(&ConfigDescriptorSize, &ConfigDescriptorData, + DCOMP_CDC_Host_NextCDCInterfaceEndpoint) != DESCRIPTOR_SEARCH_COMP_Found) + { + return CDC_ENUMERROR_EndpointsNotFound; + } + } + + USB_Descriptor_Endpoint_t* EndpointData = DESCRIPTOR_PCAST(ConfigDescriptorData, USB_Descriptor_Endpoint_t); + + if ((EndpointData->Attributes & EP_TYPE_MASK) == EP_TYPE_INTERRUPT) + { + if (EndpointData->EndpointAddress & ENDPOINT_DESCRIPTOR_DIR_IN) + { + Pipe_ConfigurePipe(CDCInterfaceInfo->Config.NotificationPipeNumber, EP_TYPE_INTERRUPT, PIPE_TOKEN_IN, + EndpointData->EndpointAddress, EndpointData->EndpointSize, + CDCInterfaceInfo->Config.NotificationPipeDoubleBank ? PIPE_BANK_DOUBLE : PIPE_BANK_SINGLE); + CDCInterfaceInfo->State.NotificationPipeSize = EndpointData->EndpointSize; + + Pipe_SetInterruptPeriod(EndpointData->PollingIntervalMS); + + FoundEndpoints |= CDC_FOUND_NOTIFICATION_IN; + } + } + else + { + if (EndpointData->EndpointAddress & ENDPOINT_DESCRIPTOR_DIR_IN) + { + Pipe_ConfigurePipe(CDCInterfaceInfo->Config.DataINPipeNumber, EP_TYPE_BULK, PIPE_TOKEN_IN, + EndpointData->EndpointAddress, EndpointData->EndpointSize, + CDCInterfaceInfo->Config.DataINPipeDoubleBank ? PIPE_BANK_DOUBLE : PIPE_BANK_SINGLE); + + CDCInterfaceInfo->State.DataINPipeSize = EndpointData->EndpointSize; + + FoundEndpoints |= CDC_FOUND_DATAPIPE_IN; + } + else + { + Pipe_ConfigurePipe(CDCInterfaceInfo->Config.DataOUTPipeNumber, EP_TYPE_BULK, PIPE_TOKEN_OUT, + EndpointData->EndpointAddress, EndpointData->EndpointSize, + CDCInterfaceInfo->Config.DataOUTPipeDoubleBank ? PIPE_BANK_DOUBLE : PIPE_BANK_SINGLE); + + CDCInterfaceInfo->State.DataOUTPipeSize = EndpointData->EndpointSize; + + FoundEndpoints |= CDC_FOUND_DATAPIPE_OUT; + } + } + } + + CDCInterfaceInfo->State.ControlLineStates.HostToDevice = (CDC_CONTROL_LINE_OUT_RTS | CDC_CONTROL_LINE_OUT_DTR); + CDCInterfaceInfo->State.ControlLineStates.DeviceToHost = (CDC_CONTROL_LINE_IN_DCD | CDC_CONTROL_LINE_IN_DSR); + CDCInterfaceInfo->State.IsActive = true; + return CDC_ENUMERROR_NoError; +} + +static uint8_t DCOMP_CDC_Host_NextCDCControlInterface(void* const CurrentDescriptor) +{ + if (DESCRIPTOR_TYPE(CurrentDescriptor) == DTYPE_Interface) + { + USB_Descriptor_Interface_t* CurrentInterface = DESCRIPTOR_PCAST(CurrentDescriptor, + USB_Descriptor_Interface_t); + + if ((CurrentInterface->Class == CDC_CONTROL_CLASS) && + (CurrentInterface->SubClass == CDC_CONTROL_SUBCLASS) && + (CurrentInterface->Protocol == CDC_CONTROL_PROTOCOL)) + { + return DESCRIPTOR_SEARCH_Found; + } + } + + return DESCRIPTOR_SEARCH_NotFound; +} + +static uint8_t DCOMP_CDC_Host_NextCDCDataInterface(void* const CurrentDescriptor) +{ + if (DESCRIPTOR_TYPE(CurrentDescriptor) == DTYPE_Interface) + { + USB_Descriptor_Interface_t* CurrentInterface = DESCRIPTOR_PCAST(CurrentDescriptor, + USB_Descriptor_Interface_t); + + if ((CurrentInterface->Class == CDC_DATA_CLASS) && + (CurrentInterface->SubClass == CDC_DATA_SUBCLASS) && + (CurrentInterface->Protocol == CDC_DATA_PROTOCOL)) + { + return DESCRIPTOR_SEARCH_Found; + } + } + + return DESCRIPTOR_SEARCH_NotFound; +} + +static uint8_t DCOMP_CDC_Host_NextCDCInterfaceEndpoint(void* const CurrentDescriptor) +{ + if (DESCRIPTOR_TYPE(CurrentDescriptor) == DTYPE_Endpoint) + { + USB_Descriptor_Endpoint_t* CurrentEndpoint = DESCRIPTOR_PCAST(CurrentDescriptor, + USB_Descriptor_Endpoint_t); + + uint8_t EndpointType = (CurrentEndpoint->Attributes & EP_TYPE_MASK); + + if (((EndpointType == EP_TYPE_BULK) || (EndpointType == EP_TYPE_INTERRUPT)) && + !(Pipe_IsEndpointBound(CurrentEndpoint->EndpointAddress))) + { + return DESCRIPTOR_SEARCH_Found; + } + } + else if (DESCRIPTOR_TYPE(CurrentDescriptor) == DTYPE_Interface) + { + return DESCRIPTOR_SEARCH_Fail; + } + + return DESCRIPTOR_SEARCH_NotFound; +} + +void CDC_Host_USBTask(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo) +{ + if ((USB_HostState != HOST_STATE_Configured) || !(CDCInterfaceInfo->State.IsActive)) + return; + + Pipe_SelectPipe(CDCInterfaceInfo->Config.NotificationPipeNumber); + Pipe_Unfreeze(); + + if (Pipe_IsINReceived()) + { + USB_Request_Header_t Notification; + Pipe_Read_Stream_LE(&Notification, sizeof(USB_Request_Header_t), NO_STREAM_CALLBACK); + + if ((Notification.bRequest == NOTIF_SerialState) && + (Notification.bmRequestType == (REQDIR_DEVICETOHOST | REQTYPE_CLASS | REQREC_INTERFACE))) + { + Pipe_Read_Stream_LE(&CDCInterfaceInfo->State.ControlLineStates.DeviceToHost, + sizeof(CDCInterfaceInfo->State.ControlLineStates.DeviceToHost), + NO_STREAM_CALLBACK); + + Pipe_ClearIN(); + + EVENT_CDC_Host_ControLineStateChanged(CDCInterfaceInfo); + } + else + { + Pipe_ClearIN(); + } + } + + Pipe_Freeze(); + + CDC_Host_Flush(CDCInterfaceInfo); +} + +uint8_t CDC_Host_SetLineEncoding(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo) +{ + USB_ControlRequest = (USB_Request_Header_t) + { + .bmRequestType = (REQDIR_HOSTTODEVICE | REQTYPE_CLASS | REQREC_INTERFACE), + .bRequest = REQ_SetLineEncoding, + .wValue = 0, + .wIndex = CDCInterfaceInfo->State.ControlInterfaceNumber, + .wLength = sizeof(CDCInterfaceInfo->State.LineEncoding), + }; + + Pipe_SelectPipe(PIPE_CONTROLPIPE); + + return USB_Host_SendControlRequest(&CDCInterfaceInfo->State.LineEncoding); +} + +uint8_t CDC_Host_SendControlLineStateChange(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo) +{ + USB_ControlRequest = (USB_Request_Header_t) + { + .bmRequestType = (REQDIR_HOSTTODEVICE | REQTYPE_CLASS | REQREC_INTERFACE), + .bRequest = REQ_SetControlLineState, + .wValue = CDCInterfaceInfo->State.ControlLineStates.HostToDevice, + .wIndex = CDCInterfaceInfo->State.ControlInterfaceNumber, + .wLength = 0, + }; + + Pipe_SelectPipe(PIPE_CONTROLPIPE); + + return USB_Host_SendControlRequest(NULL); +} + +uint8_t CDC_Host_SendBreak(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo, + const uint8_t Duration) +{ + USB_ControlRequest = (USB_Request_Header_t) + { + .bmRequestType = (REQDIR_HOSTTODEVICE | REQTYPE_CLASS | REQREC_INTERFACE), + .bRequest = REQ_SendBreak, + .wValue = Duration, + .wIndex = CDCInterfaceInfo->State.ControlInterfaceNumber, + .wLength = 0, + }; + + Pipe_SelectPipe(PIPE_CONTROLPIPE); + + return USB_Host_SendControlRequest(NULL); +} + +uint8_t CDC_Host_SendString(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo, + const char* const Data, + const uint16_t Length) +{ + if ((USB_HostState != HOST_STATE_Configured) || !(CDCInterfaceInfo->State.IsActive)) + return PIPE_READYWAIT_DeviceDisconnected; + + uint8_t ErrorCode; + + Pipe_SelectPipe(CDCInterfaceInfo->Config.DataOUTPipeNumber); + + Pipe_Unfreeze(); + ErrorCode = Pipe_Write_Stream_LE(Data, Length, NO_STREAM_CALLBACK); + Pipe_Freeze(); + + return ErrorCode; +} + +uint8_t CDC_Host_SendByte(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo, + const uint8_t Data) +{ + if ((USB_HostState != HOST_STATE_Configured) || !(CDCInterfaceInfo->State.IsActive)) + return PIPE_READYWAIT_DeviceDisconnected; + + uint8_t ErrorCode; + + Pipe_SelectPipe(CDCInterfaceInfo->Config.DataOUTPipeNumber); + Pipe_Unfreeze(); + + if (!(Pipe_IsReadWriteAllowed())) + { + Pipe_ClearOUT(); + + if ((ErrorCode = Pipe_WaitUntilReady()) != PIPE_READYWAIT_NoError) + return ErrorCode; + } + + Pipe_Write_Byte(Data); + Pipe_Freeze(); + + return PIPE_READYWAIT_NoError; +} + +uint16_t CDC_Host_BytesReceived(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo) +{ + if ((USB_HostState != HOST_STATE_Configured) || !(CDCInterfaceInfo->State.IsActive)) + return 0; + + Pipe_SelectPipe(CDCInterfaceInfo->Config.DataINPipeNumber); + Pipe_Unfreeze(); + + if (Pipe_IsINReceived()) + { + if (!(Pipe_BytesInPipe())) + { + Pipe_ClearIN(); + Pipe_Freeze(); + return 0; + } + else + { + Pipe_Freeze(); + return Pipe_BytesInPipe(); + } + } + else + { + Pipe_Freeze(); + + return 0; + } +} + +int16_t CDC_Host_ReceiveByte(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo) +{ + if ((USB_HostState != HOST_STATE_Configured) || !(CDCInterfaceInfo->State.IsActive)) + return -1; + + int16_t ReceivedByte = -1; + + Pipe_SelectPipe(CDCInterfaceInfo->Config.DataINPipeNumber); + Pipe_Unfreeze(); + + if (Pipe_IsINReceived()) + { + if (Pipe_BytesInPipe()) + ReceivedByte = Pipe_Read_Byte(); + + if (!(Pipe_BytesInPipe())) + Pipe_ClearIN(); + } + + Pipe_Freeze(); + + return ReceivedByte; +} + +uint8_t CDC_Host_Flush(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo) +{ + if ((USB_HostState != HOST_STATE_Configured) || !(CDCInterfaceInfo->State.IsActive)) + return PIPE_READYWAIT_DeviceDisconnected; + + uint8_t ErrorCode; + + Pipe_SelectPipe(CDCInterfaceInfo->Config.DataOUTPipeNumber); + Pipe_Unfreeze(); + + if (!(Pipe_BytesInPipe())) + return PIPE_READYWAIT_NoError; + + bool BankFull = !(Pipe_IsReadWriteAllowed()); + + Pipe_ClearOUT(); + + if (BankFull) + { + if ((ErrorCode = Pipe_WaitUntilReady()) != PIPE_READYWAIT_NoError) + return ErrorCode; + + Pipe_ClearOUT(); + } + + Pipe_Freeze(); + + return PIPE_READYWAIT_NoError; +} + +void CDC_Host_CreateStream(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo, + FILE* const Stream) +{ + *Stream = (FILE)FDEV_SETUP_STREAM(CDC_Host_putchar, CDC_Host_getchar, _FDEV_SETUP_RW); + fdev_set_udata(Stream, CDCInterfaceInfo); +} + +void CDC_Host_CreateBlockingStream(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo, + FILE* const Stream) +{ + *Stream = (FILE)FDEV_SETUP_STREAM(CDC_Host_putchar, CDC_Host_getchar_Blocking, _FDEV_SETUP_RW); + fdev_set_udata(Stream, CDCInterfaceInfo); +} + +static int CDC_Host_putchar(char c, + FILE* Stream) +{ + return CDC_Host_SendByte((USB_ClassInfo_CDC_Host_t*)fdev_get_udata(Stream), c) ? _FDEV_ERR : 0; +} + +static int CDC_Host_getchar(FILE* Stream) +{ + int16_t ReceivedByte = CDC_Host_ReceiveByte((USB_ClassInfo_CDC_Host_t*)fdev_get_udata(Stream)); + + if (ReceivedByte < 0) + return _FDEV_EOF; + + return ReceivedByte; +} + +static int CDC_Host_getchar_Blocking(FILE* Stream) +{ + int16_t ReceivedByte; + + while ((ReceivedByte = CDC_Host_ReceiveByte((USB_ClassInfo_CDC_Host_t*)fdev_get_udata(Stream))) < 0) + { + if (USB_HostState == HOST_STATE_Unattached) + return _FDEV_EOF; + + CDC_Host_USBTask((USB_ClassInfo_CDC_Host_t*)fdev_get_udata(Stream)); + USB_USBTask(); + } + + return ReceivedByte; +} + +void CDC_Host_Event_Stub(void) +{ + +} + +#endif diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/CDC.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/CDC.h new file mode 100644 index 0000000000..3e9d055e45 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/CDC.h @@ -0,0 +1,347 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief Host mode driver for the library USB CDC Class driver. + * + * Host mode driver for the library USB CDC Class driver. + * + * \note This file should not be included directly. It is automatically included as needed by the class driver + * dispatch header located in LUFA/Drivers/USB/Class/CDC.h. + */ + +/** \ingroup Group_USBClassCDC + * @defgroup Group_USBClassCDCHost CDC Class Host Mode Driver + * + * \section Sec_Dependencies Module Source Dependencies + * The following files must be built with any user project that uses this module: + * - LUFA/Drivers/USB/Class/Host/CDC.c (Makefile source module name: LUFA_SRC_USBCLASS) + * + * \section Module Description + * Host Mode USB Class driver framework interface, for the CDC USB Class driver. + * + * @{ + */ + +#ifndef __CDC_CLASS_HOST_H__ +#define __CDC_CLASS_HOST_H__ + + /* Includes: */ + #include "../../USB.h" + #include "../Common/CDC.h" + + #include + #include + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_CDC_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/Class/CDC.h instead. + #endif + + /* Public Interface - May be used in end-application: */ + /* Type Defines: */ + /** \brief CDC Class Host Mode Configuration and State Structure. + * + * Class state structure. An instance of this structure should be made within the user application, + * and passed to each of the CDC class driver functions as the CDCInterfaceInfo parameter. This + * stores each CDC interface's configuration and state information. + */ + typedef struct + { + const struct + { + uint8_t DataINPipeNumber; /**< Pipe number of the CDC interface's IN data pipe. */ + bool DataINPipeDoubleBank; /**< Indicates if the CDC interface's IN data pipe should use double banking. */ + + uint8_t DataOUTPipeNumber; /**< Pipe number of the CDC interface's OUT data pipe. */ + bool DataOUTPipeDoubleBank; /**< Indicates if the CDC interface's OUT data pipe should use double banking. */ + + uint8_t NotificationPipeNumber; /**< Pipe number of the CDC interface's IN notification endpoint, if used. */ + bool NotificationPipeDoubleBank; /**< Indicates if the CDC interface's notification pipe should use double banking. */ + } Config; /**< Config data for the USB class interface within the device. All elements in this section + * must be set or the interface will fail to enumerate and operate correctly. + */ + struct + { + bool IsActive; /**< Indicates if the current interface instance is connected to an attached device, valid + * after \ref CDC_Host_ConfigurePipes() is called and the Host state machine is in the + * Configured state. + */ + uint8_t ControlInterfaceNumber; /**< Interface index of the CDC-ACM control interface within the attached device. */ + + uint16_t DataINPipeSize; /**< Size in bytes of the CDC interface's IN data pipe. */ + uint16_t DataOUTPipeSize; /**< Size in bytes of the CDC interface's OUT data pipe. */ + uint16_t NotificationPipeSize; /**< Size in bytes of the CDC interface's IN notification pipe, if used. */ + + struct + { + uint8_t HostToDevice; /**< Control line states from the host to device, as a set of CDC_CONTROL_LINE_OUT_* + * masks - to notify the device of changes to these values, call the + * \ref CDC_Host_SendControlLineStateChange() function. + */ + uint8_t DeviceToHost; /**< Control line states from the device to host, as a set of CDC_CONTROL_LINE_IN_* + * masks. This value is updated each time \ref CDC_Host_USBTask() is called. + */ + } ControlLineStates; /**< Current states of the virtual serial port's control lines between the device and host. */ + + struct + { + uint32_t BaudRateBPS; /**< Baud rate of the virtual serial port, in bits per second. */ + uint8_t CharFormat; /**< Character format of the virtual serial port, a value from the + * \ref CDC_LineEncodingFormats_t enum. + */ + uint8_t ParityType; /**< Parity setting of the virtual serial port, a value from the + * \ref CDC_LineEncodingParity_t enum. + */ + uint8_t DataBits; /**< Bits of data per character of the virtual serial port. */ + } LineEncoding; /**< Line encoding used in the virtual serial port, for the device's information. This is generally + * only used if the virtual serial port data is to be reconstructed on a physical UART. When set + * by the host application, the \ref CDC_Host_SetLineEncoding() function must be called to push + * the changes to the device. + */ + } State; /**< State data for the USB class interface within the device. All elements in this section + * may be set to initial values, but may also be ignored to default to sane values when + * the interface is enumerated. + */ + } USB_ClassInfo_CDC_Host_t; + + /* Enums: */ + /** Enum for the possible error codes returned by the \ref CDC_Host_ConfigurePipes() function. */ + enum CDCHost_EnumerationFailure_ErrorCodes_t + { + CDC_ENUMERROR_NoError = 0, /**< Configuration Descriptor was processed successfully. */ + CDC_ENUMERROR_InvalidConfigDescriptor = 1, /**< The device returned an invalid Configuration Descriptor. */ + CDC_ENUMERROR_NoCDCInterfaceFound = 2, /**< A compatible CDC interface was not found in the device's Configuration Descriptor. */ + CDC_ENUMERROR_EndpointsNotFound = 3, /**< Compatible CDC endpoints were not found in the device's CDC interface. */ + }; + + /* Function Prototypes: */ + /** General management task for a given CDC host class interface, required for the correct operation of the interface. This should + * be called frequently in the main program loop, before the master USB management task \ref USB_USBTask(). + * + * \param[in,out] CDCInterfaceInfo Pointer to a structure containing an CDC Class host configuration and state. + */ + void CDC_Host_USBTask(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** Host interface configuration routine, to configure a given CDC host interface instance using the Configuration + * Descriptor read from an attached USB device. This function automatically updates the given CDC Host instance's + * state values and configures the pipes required to communicate with the interface if it is found within the device. + * This should be called once after the stack has enumerated the attached device, while the host state machine is in + * the Addressed state. + * + * \param[in,out] CDCInterfaceInfo Pointer to a structure containing an CDC Class host configuration and state. + * \param[in] ConfigDescriptorSize Length of the attached device's Configuration Descriptor. + * \param[in] DeviceConfigDescriptor Pointer to a buffer containing the attached device's Configuration Descriptor. + * + * \return A value from the \ref CDCHost_EnumerationFailure_ErrorCodes_t enum. + */ + uint8_t CDC_Host_ConfigurePipes(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo, + uint16_t ConfigDescriptorSize, + void* DeviceConfigDescriptor) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(3); + + /** Sets the line encoding for the attached device's virtual serial port. This should be called when the LineEncoding + * values of the interface have been changed to push the new settings to the USB device. + * + * \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class host configuration and state. + * + * \return A value from the \ref USB_Host_SendControlErrorCodes_t enum. + */ + uint8_t CDC_Host_SetLineEncoding(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** Sends a Serial Control Line State Change notification to the device. This should be called when the virtual serial + * control lines (DTR, RTS, etc.) have changed states. Line states persist until they are cleared via a second + * notification. This should be called each time the CDC class driver's ControlLineStates.HostToDevice value is updated + * to push the new states to the USB device. + * + * \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class host configuration and state. + * + * \return A value from the \ref USB_Host_SendControlErrorCodes_t enum. + */ + uint8_t CDC_Host_SendControlLineStateChange(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** Sends a Send Break request to the device. This is generally used to separate data data or to indicate a special condition + * to the receiving device. + * + * \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class host configuration and state. + * \param[in] Duration Duration of the break, in milliseconds. + * + * \return A value from the \ref USB_Host_SendControlErrorCodes_t enum. + */ + uint8_t CDC_Host_SendBreak(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo, + const uint8_t Duration) ATTR_NON_NULL_PTR_ARG(1); + + /** Sends a given string to the attached USB device, if connected. If a device is not connected when the function is called, the + * string is discarded. Bytes will be queued for transmission to the device until either the pipe bank becomes full, or the + * \ref CDC_Host_Flush() function is called to flush the pending data to the host. This allows for multiple bytes to be + * packed into a single pipe packet, increasing data throughput. + * + * \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the + * call will fail. + * + * \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class host configuration and state. + * \param[in] Data Pointer to the string to send to the device. + * \param[in] Length Size in bytes of the string to send to the device. + * + * \return A value from the \ref Pipe_Stream_RW_ErrorCodes_t enum. + */ + uint8_t CDC_Host_SendString(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo, + const char* const Data, + const uint16_t Length) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(2); + + /** Sends a given byte to the attached USB device, if connected. If a device is not connected when the function is called, the + * byte is discarded. Bytes will be queued for transmission to the device until either the pipe bank becomes full, or the + * \ref CDC_Host_Flush() function is called to flush the pending data to the host. This allows for multiple bytes to be + * packed into a single pipe packet, increasing data throughput. + * + * \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the + * call will fail. + * + * \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class host configuration and state. + * \param[in] Data Byte of data to send to the device. + * + * \return A value from the \ref Pipe_WaitUntilReady_ErrorCodes_t enum. + */ + uint8_t CDC_Host_SendByte(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo, + const uint8_t Data) ATTR_NON_NULL_PTR_ARG(1); + + /** Determines the number of bytes received by the CDC interface from the device, waiting to be read. This indicates the number + * of bytes in the IN pipe bank only, and thus the number of calls to \ref CDC_Host_ReceiveByte() which are guaranteed to succeed + * immediately. If multiple bytes are to be received, they should be buffered by the user application, as the pipe bank will not be + * released back to the USB controller until all bytes are read. + * + * \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the + * call will fail. + * + * \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class host configuration and state. + * + * \return Total number of buffered bytes received from the device. + */ + uint16_t CDC_Host_BytesReceived(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** Reads a byte of data from the device. If no data is waiting to be read of if a USB device is not connected, the function + * returns a negative value. The \ref CDC_Host_BytesReceived() function may be queried in advance to determine how many bytes + * are currently buffered in the CDC interface's data receive pipe. + * + * \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the + * call will fail. + * + * \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class host configuration and state. + * + * \return Next received byte from the device, or a negative value if no data received. + */ + int16_t CDC_Host_ReceiveByte(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** Flushes any data waiting to be sent, ensuring that the send buffer is cleared. + * + * \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the + * call will fail. + * + * \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class host configuration and state. + * + * \return A value from the \ref Pipe_WaitUntilReady_ErrorCodes_t enum. + */ + uint8_t CDC_Host_Flush(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** Creates a standard character stream for the given CDC Device instance so that it can be used with all the regular + * functions in the avr-libc library that accept a FILE stream as a destination (e.g. fprintf). The created + * stream is bidirectional and can be used for both input and output functions. + * + * \note The created stream can be given as stdout if desired to direct the standard output from all functions + * to the given CDC interface. + * + * \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class configuration and state. + * \param[in,out] Stream Pointer to a FILE structure where the created stream should be placed. + */ + void CDC_Host_CreateStream(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo, + FILE* const Stream); + + /** Identical to CDC_Host_CreateStream(), except that reads are blocking until the calling stream function terminates + * the transfer. While blocking, the USB and CDC service tasks are called repeatedly to maintain USB communications. + * + * \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class configuration and state. + * \param[in,out] Stream Pointer to a FILE structure where the created stream should be placed. + */ + void CDC_Host_CreateBlockingStream(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo, + FILE* const Stream); + + /** CDC class driver event for a control line state change on a CDC host interface. This event fires each time the device notifies + * the host of a control line state change (containing the virtual serial control line states, such as DCD) and may be hooked in the + * user program by declaring a handler function with the same name and parameters listed here. The new control line states + * are available in the ControlLineStates.DeviceToHost value inside the CDC host interface structure passed as a parameter, set as + * a mask of CDC_CONTROL_LINE_IN_* masks. + * + * \param[in,out] CDCInterfaceInfo Pointer to a structure containing a CDC Class host configuration and state. + */ + void EVENT_CDC_Host_ControLineStateChanged(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /* Private Interface - For use in library only: */ + #if !defined(__DOXYGEN__) + /* Macros: */ + #define CDC_CONTROL_CLASS 0x02 + #define CDC_CONTROL_SUBCLASS 0x02 + #define CDC_CONTROL_PROTOCOL 0x01 + #define CDC_DATA_CLASS 0x0A + #define CDC_DATA_SUBCLASS 0x00 + #define CDC_DATA_PROTOCOL 0x00 + + #define CDC_FOUND_DATAPIPE_IN (1 << 0) + #define CDC_FOUND_DATAPIPE_OUT (1 << 1) + #define CDC_FOUND_NOTIFICATION_IN (1 << 2) + + /* Function Prototypes: */ + #if defined(__INCLUDE_FROM_CDC_CLASS_HOST_C) + static int CDC_Host_putchar(char c, + FILE* Stream) ATTR_NON_NULL_PTR_ARG(2); + static int CDC_Host_getchar(FILE* Stream) ATTR_NON_NULL_PTR_ARG(1); + static int CDC_Host_getchar_Blocking(FILE* Stream) ATTR_NON_NULL_PTR_ARG(1); + + void CDC_Host_Event_Stub(void); + void EVENT_CDC_Host_ControLineStateChanged(USB_ClassInfo_CDC_Host_t* const CDCInterfaceInfo) + ATTR_WEAK ATTR_NON_NULL_PTR_ARG(1) ATTR_ALIAS(CDC_Host_Event_Stub); + + static uint8_t DCOMP_CDC_Host_NextCDCControlInterface(void* const CurrentDescriptor) ATTR_NON_NULL_PTR_ARG(1); + static uint8_t DCOMP_CDC_Host_NextCDCDataInterface(void* const CurrentDescriptor) ATTR_NON_NULL_PTR_ARG(1); + static uint8_t DCOMP_CDC_Host_NextCDCInterfaceEndpoint(void* const CurrentDescriptor) ATTR_NON_NULL_PTR_ARG(1); + #endif + #endif + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/HID.c b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/HID.c new file mode 100644 index 0000000000..66c044b563 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/HID.c @@ -0,0 +1,368 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +#define __INCLUDE_FROM_USB_DRIVER +#include "../../HighLevel/USBMode.h" +#if defined(USB_CAN_BE_HOST) + +#define __INCLUDE_FROM_HID_CLASS_HOST_C +#define __INCLUDE_FROM_HID_DRIVER +#include "HID.h" + +uint8_t HID_Host_ConfigurePipes(USB_ClassInfo_HID_Host_t* const HIDInterfaceInfo, + uint16_t ConfigDescriptorSize, + void* ConfigDescriptorData) +{ + uint8_t FoundEndpoints = 0; + + memset(&HIDInterfaceInfo->State, 0x00, sizeof(HIDInterfaceInfo->State)); + + if (DESCRIPTOR_TYPE(ConfigDescriptorData) != DTYPE_Configuration) + return HID_ENUMERROR_InvalidConfigDescriptor; + + USB_Descriptor_Interface_t* CurrentHIDInterface; + + do + { + if (USB_GetNextDescriptorComp(&ConfigDescriptorSize, &ConfigDescriptorData, + DCOMP_HID_Host_NextHIDInterface) != DESCRIPTOR_SEARCH_COMP_Found) + { + return HID_ENUMERROR_NoHIDInterfaceFound; + } + + CurrentHIDInterface = DESCRIPTOR_PCAST(ConfigDescriptorData, USB_Descriptor_Interface_t); + } while (HIDInterfaceInfo->Config.HIDInterfaceProtocol && + (CurrentHIDInterface->Protocol != HIDInterfaceInfo->Config.HIDInterfaceProtocol)); + + HIDInterfaceInfo->State.InterfaceNumber = CurrentHIDInterface->InterfaceNumber; + HIDInterfaceInfo->State.SupportsBootProtocol = (CurrentHIDInterface->SubClass != HID_NON_BOOT_PROTOCOL); + + if (USB_GetNextDescriptorComp(&ConfigDescriptorSize, &ConfigDescriptorData, DCOMP_HID_NextHID) != DESCRIPTOR_SEARCH_COMP_Found) + { + return HID_ENUMERROR_NoHIDDescriptorFound; + } + + HIDInterfaceInfo->State.HIDReportSize = DESCRIPTOR_CAST(ConfigDescriptorData, USB_HID_Descriptor_t).HIDReportLength; + + while (FoundEndpoints != (HID_FOUND_DATAPIPE_IN | HID_FOUND_DATAPIPE_OUT)) + { + if (USB_GetNextDescriptorComp(&ConfigDescriptorSize, &ConfigDescriptorData, + DCOMP_HID_Host_NextHIDInterfaceEndpoint) != DESCRIPTOR_SEARCH_COMP_Found) + { + if (FoundEndpoints & HID_FOUND_DATAPIPE_IN) + break; + + return HID_ENUMERROR_EndpointsNotFound; + } + + USB_Descriptor_Endpoint_t* EndpointData = DESCRIPTOR_PCAST(ConfigDescriptorData, USB_Descriptor_Endpoint_t); + + if (EndpointData->EndpointAddress & ENDPOINT_DESCRIPTOR_DIR_IN) + { + Pipe_ConfigurePipe(HIDInterfaceInfo->Config.DataINPipeNumber, EP_TYPE_INTERRUPT, PIPE_TOKEN_IN, + EndpointData->EndpointAddress, EndpointData->EndpointSize, + HIDInterfaceInfo->Config.DataINPipeDoubleBank ? PIPE_BANK_DOUBLE : PIPE_BANK_SINGLE); + HIDInterfaceInfo->State.DataINPipeSize = EndpointData->EndpointSize; + + FoundEndpoints |= HID_FOUND_DATAPIPE_IN; + } + else + { + Pipe_ConfigurePipe(HIDInterfaceInfo->Config.DataOUTPipeNumber, EP_TYPE_INTERRUPT, PIPE_TOKEN_OUT, + EndpointData->EndpointAddress, EndpointData->EndpointSize, + HIDInterfaceInfo->Config.DataOUTPipeDoubleBank ? PIPE_BANK_DOUBLE : PIPE_BANK_SINGLE); + HIDInterfaceInfo->State.DataOUTPipeSize = EndpointData->EndpointSize; + + HIDInterfaceInfo->State.DeviceUsesOUTPipe = true; + + FoundEndpoints |= HID_FOUND_DATAPIPE_OUT; + } + } + + HIDInterfaceInfo->State.LargestReportSize = 8; + HIDInterfaceInfo->State.IsActive = true; + return HID_ENUMERROR_NoError; +} + +static uint8_t DCOMP_HID_Host_NextHIDInterface(void* const CurrentDescriptor) +{ + if (DESCRIPTOR_TYPE(CurrentDescriptor) == DTYPE_Interface) + { + USB_Descriptor_Interface_t* CurrentInterface = DESCRIPTOR_PCAST(CurrentDescriptor, + USB_Descriptor_Interface_t); + + if (CurrentInterface->Class == HID_INTERFACE_CLASS) + return DESCRIPTOR_SEARCH_Found; + } + + return DESCRIPTOR_SEARCH_NotFound; +} + +static uint8_t DCOMP_HID_NextHID(void* const CurrentDescriptor) +{ + if (DESCRIPTOR_TYPE(CurrentDescriptor) == DTYPE_HID) + return DESCRIPTOR_SEARCH_Found; + else if (DESCRIPTOR_TYPE(CurrentDescriptor) == DTYPE_Interface) + return DESCRIPTOR_SEARCH_Fail; + else + return DESCRIPTOR_SEARCH_NotFound; +} + +static uint8_t DCOMP_HID_Host_NextHIDInterfaceEndpoint(void* const CurrentDescriptor) +{ + if (DESCRIPTOR_TYPE(CurrentDescriptor) == DTYPE_Endpoint) + { + USB_Descriptor_Endpoint_t* CurrentEndpoint = DESCRIPTOR_PCAST(CurrentDescriptor, + USB_Descriptor_Endpoint_t); + + if (!(Pipe_IsEndpointBound(CurrentEndpoint->EndpointAddress))) + return DESCRIPTOR_SEARCH_Found; + } + else if (DESCRIPTOR_TYPE(CurrentDescriptor) == DTYPE_Interface) + { + return DESCRIPTOR_SEARCH_Fail; + } + + return DESCRIPTOR_SEARCH_NotFound; +} + +#if !defined(HID_HOST_BOOT_PROTOCOL_ONLY) +uint8_t HID_Host_ReceiveReportByID(USB_ClassInfo_HID_Host_t* const HIDInterfaceInfo, + const uint8_t ReportID, + void* Buffer) +{ + USB_ControlRequest = (USB_Request_Header_t) + { + .bmRequestType = (REQDIR_HOSTTODEVICE | REQTYPE_CLASS | REQREC_INTERFACE), + .bRequest = REQ_SetReport, + .wValue = ((REPORT_ITEM_TYPE_In + 1) << 8) | ReportID, + .wIndex = HIDInterfaceInfo->State.InterfaceNumber, + .wLength = USB_GetHIDReportSize(HIDInterfaceInfo->Config.HIDParserData, ReportID, REPORT_ITEM_TYPE_In), + }; + + Pipe_SelectPipe(PIPE_CONTROLPIPE); + + return USB_Host_SendControlRequest(Buffer); +} +#endif + +uint8_t HID_Host_ReceiveReport(USB_ClassInfo_HID_Host_t* const HIDInterfaceInfo, + void* Buffer) +{ + if ((USB_HostState != HOST_STATE_Configured) || !(HIDInterfaceInfo->State.IsActive)) + return PIPE_READYWAIT_DeviceDisconnected; + + uint8_t ErrorCode; + + Pipe_SelectPipe(HIDInterfaceInfo->Config.DataINPipeNumber); + Pipe_Unfreeze(); + + uint16_t ReportSize; + uint8_t* BufferPos = Buffer; + +#if !defined(HID_HOST_BOOT_PROTOCOL_ONLY) + if (!(HIDInterfaceInfo->State.UsingBootProtocol)) + { + uint8_t ReportID = 0; + + if (HIDInterfaceInfo->Config.HIDParserData->UsingReportIDs) + { + ReportID = Pipe_Read_Byte(); + *(BufferPos++) = ReportID; + } + + ReportSize = USB_GetHIDReportSize(HIDInterfaceInfo->Config.HIDParserData, ReportID, REPORT_ITEM_TYPE_In); + } + else +#endif + { + ReportSize = Pipe_BytesInPipe(); + } + + if ((ErrorCode = Pipe_Read_Stream_LE(BufferPos, ReportSize, NO_STREAM_CALLBACK)) != PIPE_RWSTREAM_NoError) + return ErrorCode; + + Pipe_ClearIN(); + Pipe_Freeze(); + + return PIPE_RWSTREAM_NoError; +} + +uint8_t HID_Host_SendReportByID(USB_ClassInfo_HID_Host_t* const HIDInterfaceInfo, +#if !defined(HID_HOST_BOOT_PROTOCOL_ONLY) + const uint8_t ReportID, +#endif + const uint8_t ReportType, + void* Buffer, + const uint16_t ReportSize) +{ +#if !defined(HID_HOST_BOOT_PROTOCOL_ONLY) + if ((USB_HostState != HOST_STATE_Configured) || !(HIDInterfaceInfo->State.IsActive)) + return false; + + if (HIDInterfaceInfo->State.DeviceUsesOUTPipe && (ReportType == REPORT_ITEM_TYPE_Out)) + { + uint8_t ErrorCode; + + Pipe_SelectPipe(HIDInterfaceInfo->Config.DataOUTPipeNumber); + Pipe_Unfreeze(); + + if (ReportID) + Pipe_Write_Stream_LE(&ReportID, sizeof(ReportID), NO_STREAM_CALLBACK); + + if ((ErrorCode = Pipe_Write_Stream_LE(Buffer, ReportSize, NO_STREAM_CALLBACK)) != PIPE_RWSTREAM_NoError) + return ErrorCode; + + Pipe_ClearOUT(); + Pipe_Freeze(); + + return PIPE_RWSTREAM_NoError; + } + else +#endif + { + USB_ControlRequest = (USB_Request_Header_t) + { + .bmRequestType = (REQDIR_HOSTTODEVICE | REQTYPE_CLASS | REQREC_INTERFACE), + .bRequest = REQ_SetReport, +#if !defined(HID_HOST_BOOT_PROTOCOL_ONLY) + .wValue = ((ReportType + 1) << 8) | ReportID, +#else + .wValue = ((ReportType + 1) << 8), +#endif + .wIndex = HIDInterfaceInfo->State.InterfaceNumber, + .wLength = ReportSize, + }; + + Pipe_SelectPipe(PIPE_CONTROLPIPE); + + return USB_Host_SendControlRequest(Buffer); + } +} + +bool HID_Host_IsReportReceived(USB_ClassInfo_HID_Host_t* const HIDInterfaceInfo) +{ + if ((USB_HostState != HOST_STATE_Configured) || !(HIDInterfaceInfo->State.IsActive)) + return false; + + bool ReportReceived; + + Pipe_SelectPipe(HIDInterfaceInfo->Config.DataINPipeNumber); + Pipe_Unfreeze(); + + ReportReceived = Pipe_IsINReceived(); + + Pipe_Freeze(); + + return ReportReceived; +} + +uint8_t HID_Host_SetBootProtocol(USB_ClassInfo_HID_Host_t* const HIDInterfaceInfo) +{ + uint8_t ErrorCode; + + USB_ControlRequest = (USB_Request_Header_t) + { + .bmRequestType = (REQDIR_HOSTTODEVICE | REQTYPE_CLASS | REQREC_INTERFACE), + .bRequest = REQ_SetProtocol, + .wValue = 0, + .wIndex = HIDInterfaceInfo->State.InterfaceNumber, + .wLength = 0, + }; + + Pipe_SelectPipe(PIPE_CONTROLPIPE); + + if (!(HIDInterfaceInfo->State.SupportsBootProtocol)) + return HID_ERROR_LOGICAL; + + if ((ErrorCode = USB_Host_SendControlRequest(NULL)) != HOST_SENDCONTROL_Successful) + return ErrorCode; + + HIDInterfaceInfo->State.LargestReportSize = 8; + HIDInterfaceInfo->State.UsingBootProtocol = true; + + return HOST_SENDCONTROL_Successful; +} + +#if !defined(HID_HOST_BOOT_PROTOCOL_ONLY) +uint8_t HID_Host_SetReportProtocol(USB_ClassInfo_HID_Host_t* const HIDInterfaceInfo) +{ + uint8_t ErrorCode; + + uint8_t HIDReportData[HIDInterfaceInfo->State.HIDReportSize]; + + USB_ControlRequest = (USB_Request_Header_t) + { + .bmRequestType = (REQDIR_DEVICETOHOST | REQTYPE_STANDARD | REQREC_INTERFACE), + .bRequest = REQ_GetDescriptor, + .wValue = (DTYPE_Report << 8), + .wIndex = HIDInterfaceInfo->State.InterfaceNumber, + .wLength = HIDInterfaceInfo->State.HIDReportSize, + }; + + Pipe_SelectPipe(PIPE_CONTROLPIPE); + + if ((ErrorCode = USB_Host_SendControlRequest(HIDReportData)) != HOST_SENDCONTROL_Successful) + return ErrorCode; + + if (HIDInterfaceInfo->State.UsingBootProtocol) + { + USB_ControlRequest = (USB_Request_Header_t) + { + .bmRequestType = (REQDIR_HOSTTODEVICE | REQTYPE_CLASS | REQREC_INTERFACE), + .bRequest = REQ_SetProtocol, + .wValue = 1, + .wIndex = HIDInterfaceInfo->State.InterfaceNumber, + .wLength = 0, + }; + + if ((ErrorCode = USB_Host_SendControlRequest(NULL)) != HOST_SENDCONTROL_Successful) + return ErrorCode; + + HIDInterfaceInfo->State.UsingBootProtocol = false; + } + + if (HIDInterfaceInfo->Config.HIDParserData == NULL) + return HID_ERROR_LOGICAL; + + if ((ErrorCode = USB_ProcessHIDReport(HIDReportData, HIDInterfaceInfo->State.HIDReportSize, + HIDInterfaceInfo->Config.HIDParserData)) != HID_PARSE_Successful) + { + return HID_ERROR_LOGICAL | ErrorCode; + } + + uint8_t LargestReportSizeBits = HIDInterfaceInfo->Config.HIDParserData->LargestReportSizeBits; + HIDInterfaceInfo->State.LargestReportSize = (LargestReportSizeBits >> 3) + ((LargestReportSizeBits & 0x07) != 0); + + return 0; +} +#endif + +#endif diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/HID.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/HID.h new file mode 100644 index 0000000000..88d16640c2 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/HID.h @@ -0,0 +1,314 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief Host mode driver for the library USB HID Class driver. + * + * Host mode driver for the library USB HID Class driver. + * + * \note This file should not be included directly. It is automatically included as needed by the class driver + * dispatch header located in LUFA/Drivers/USB/Class/HID.h. + */ + +/** \ingroup Group_USBClassHID + * @defgroup Group_USBClassHIDHost HID Class Host Mode Driver + * + * \section Sec_Dependencies Module Source Dependencies + * The following files must be built with any user project that uses this module: + * - LUFA/Drivers/USB/Class/Host/HID.c (Makefile source module name: LUFA_SRC_USBCLASS) + * - LUFA/Drivers/USB/Class/Host/HIDParser.c (Makefile source module name: LUFA_SRC_USB) + * + * \section Module Description + * Host Mode USB Class driver framework interface, for the HID USB Class driver. + * + * @{ + */ + +#ifndef __HID_CLASS_HOST_H__ +#define __HID_CLASS_HOST_H__ + + /* Includes: */ + #include "../../USB.h" + #include "../Common/HID.h" + #include "HIDParser.h" + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_HID_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/Class/HID.h instead. + #endif + + /* Public Interface - May be used in end-application: */ + /* Macros: */ + /** Error code for some HID Host functions, indicating a logical (and not hardware) error. */ + #define HID_ERROR_LOGICAL 0x80 + + /* Type Defines: */ + /** \brief HID Class Host Mode Configuration and State Structure. + * + * Class state structure. An instance of this structure should be made within the user application, + * and passed to each of the HID class driver functions as the HIDInterfaceInfo parameter. This + * stores each HID interface's configuration and state information. + */ + typedef struct + { + const struct + { + uint8_t DataINPipeNumber; /**< Pipe number of the HID interface's IN data pipe. */ + bool DataINPipeDoubleBank; /**< Indicates if the HID interface's IN data pipe should use double banking. */ + + uint8_t DataOUTPipeNumber; /**< Pipe number of the HID interface's OUT data pipe. */ + bool DataOUTPipeDoubleBank; /**< Indicates if the HID interface's OUT data pipe should use double banking. */ + + uint8_t HIDInterfaceProtocol; /**< HID interface protocol value to match against if a specific + * boot subclass protocol is required, either \ref HID_BOOT_MOUSE_PROTOCOL, + * \ref HID_BOOT_KEYBOARD_PROTOCOL or \ref HID_NON_BOOT_PROTOCOL if any + * HID device should be enumerated by the interface. + */ + #if !defined(HID_HOST_BOOT_PROTOCOL_ONLY) + HID_ReportInfo_t* HIDParserData; /**< HID parser data to store the parsed HID report data, when boot protocol + * is not used. + * + * \note When the HID_HOST_BOOT_PROTOCOL_ONLY compile time token is defined, + * this method is unavailable. + */ + #endif + } Config; /**< Config data for the USB class interface within the device. All elements in this section + * must be set or the interface will fail to enumerate and operate correctly. + */ + struct + { + bool IsActive; /**< Indicates if the current interface instance is connected to an attached device, valid + * after \ref HID_Host_ConfigurePipes() is called and the Host state machine is in the + * Configured state. + */ + uint8_t InterfaceNumber; /**< Interface index of the HID interface within the attached device. */ + + uint16_t DataINPipeSize; /**< Size in bytes of the HID interface's IN data pipe. */ + uint16_t DataOUTPipeSize; /**< Size in bytes of the HID interface's OUT data pipe. */ + + bool SupportsBootProtocol; /**< Indicates if the current interface instance supports the HID Boot + * Protocol when enabled via \ref HID_Host_SetBootProtocol(). + */ + bool DeviceUsesOUTPipe; /**< Indicates if the current interface instance uses a separate OUT data pipe for + * OUT reports, or if OUT reports are sent via the control pipe instead. + */ + bool UsingBootProtocol; /**< Indicates that the interface is currently initialized in Boot Protocol mode */ + uint16_t HIDReportSize; /**< Size in bytes of the HID report descriptor in the device. */ + + uint8_t LargestReportSize; /**< Largest report the device will send, in bytes. */ + } State; /**< State data for the USB class interface within the device. All elements in this section + * may be set to initial values, but may also be ignored to default to sane values when + * the interface is enumerated. + */ + } USB_ClassInfo_HID_Host_t; + + /* Enums: */ + /** Enum for the possible error codes returned by the \ref HID_Host_ConfigurePipes() function. */ + enum HIDHost_EnumerationFailure_ErrorCodes_t + { + HID_ENUMERROR_NoError = 0, /**< Configuration Descriptor was processed successfully. */ + HID_ENUMERROR_InvalidConfigDescriptor = 1, /**< The device returned an invalid Configuration Descriptor. */ + HID_ENUMERROR_NoHIDInterfaceFound = 2, /**< A compatible HID interface was not found in the device's Configuration Descriptor. */ + HID_ENUMERROR_NoHIDDescriptorFound = 3, /**< The HID descriptor was not found in the device's HID interface. */ + HID_ENUMERROR_EndpointsNotFound = 4, /**< Compatible HID endpoints were not found in the device's HID interface. */ + }; + + /* Function Prototypes: */ + /** Host interface configuration routine, to configure a given HID host interface instance using the Configuration + * Descriptor read from an attached USB device. This function automatically updates the given HID Host instance's + * state values and configures the pipes required to communicate with the interface if it is found within the + * device. This should be called once after the stack has enumerated the attached device, while the host state + * machine is in the Addressed state. + * + * \note Once the device pipes are configured, the HID device's reporting protocol must be set via a call + * to either the \ref HID_Host_SetBootProtocol() or \ref HID_Host_SetReportProtocol() function. + * + * \param[in,out] HIDInterfaceInfo Pointer to a structure containing a HID Class host configuration and state. + * \param[in] ConfigDescriptorSize Length of the attached device's Configuration Descriptor. + * \param[in] DeviceConfigDescriptor Pointer to a buffer containing the attached device's Configuration Descriptor. + * + * \return A value from the \ref HIDHost_EnumerationFailure_ErrorCodes_t enum. + */ + uint8_t HID_Host_ConfigurePipes(USB_ClassInfo_HID_Host_t* const HIDInterfaceInfo, + uint16_t ConfigDescriptorSize, + void* DeviceConfigDescriptor) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(3); + + + /** Receives a HID IN report from the attached HID device, when a report has been received on the HID IN Data pipe. + * + * \pre This function must only be called when the Host state machine is in the \ref HOST_STATE_Configured state or the + * call will fail. + * + * \note The destination buffer should be large enough to accommodate the largest report that the attached device + * can generate. + * + * \param[in,out] HIDInterfaceInfo Pointer to a structure containing a HID Class host configuration and state. + * \param[in] Buffer Buffer to store the received report into. + * + * \return An error code from the \ref Pipe_Stream_RW_ErrorCodes_t enum. + */ + uint8_t HID_Host_ReceiveReport(USB_ClassInfo_HID_Host_t* const HIDInterfaceInfo, + void* Buffer) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(2); + + #if !defined(HID_HOST_BOOT_PROTOCOL_ONLY) + /** Receives a HID IN report from the attached device, by the report ID. + * + * \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the + * call will fail. + * + * \note When the HID_HOST_BOOT_PROTOCOL_ONLY compile time token is defined, this method is unavailable. + * + * \param[in,out] HIDInterfaceInfo Pointer to a structure containing a HID Class host configuration and state. + * \param[in] ReportID Report ID of the received report if ControlRequest is false, set by the to the Report ID to fetch. + * \param[in] Buffer Buffer to store the received report into. + * + * \return A value from the \ref USB_Host_SendControlErrorCodes_t enum. + */ + uint8_t HID_Host_ReceiveReportByID(USB_ClassInfo_HID_Host_t* const HIDInterfaceInfo, + const uint8_t ReportID, + void* Buffer) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(3); + #endif + + /** Sends an OUT or FEATURE report to the currently attached HID device, using the device's OUT pipe if available, + * or the device's Control pipe if not. + * + * \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the + * call will fail. + * + * \note When the HID_HOST_BOOT_PROTOCOL_ONLY compile time token is defined, the ReportID parameter is removed + * from the parameter list of this function. + * + * \param[in,out] HIDInterfaceInfo Pointer to a structure containing a HID Class host configuration and state. + * \param[in] ReportID Report ID of the report to send to the device, or 0 if the device does not use report IDs. + * \param[in] ReportType Type of report to issue to the device, either \ref REPORT_ITEM_TYPE_Out or \ref REPORT_ITEM_TYPE_Feature. + * \param[in] Buffer Buffer containing the report to send to the attached device. + * \param[in] ReportSize Report size in bytes to send to the attached device. + * + * \return An error code from the \ref USB_Host_SendControlErrorCodes_t enum if the DeviceUsesOUTPipe flag is set in + * the interface's state structure, a value from the \ref Pipe_Stream_RW_ErrorCodes_t enum otherwise. + */ + uint8_t HID_Host_SendReportByID(USB_ClassInfo_HID_Host_t* const HIDInterfaceInfo, + #if !defined(HID_HOST_BOOT_PROTOCOL_ONLY) + const uint8_t ReportID, + #endif + const uint8_t ReportType, + void* Buffer, + const uint16_t ReportSize) ATTR_NON_NULL_PTR_ARG(1) + #if !defined(HID_HOST_BOOT_PROTOCOL_ONLY) + ATTR_NON_NULL_PTR_ARG(4); + #else + ATTR_NON_NULL_PTR_ARG(3); + #endif + + /** Determines if a HID IN report has been received from the attached device on the data IN pipe. + * + * \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the + * call will fail. + * + * \param[in,out] HIDInterfaceInfo Pointer to a structure containing a HID Class host configuration and state. + * + * \return Boolean true if a report has been received, false otherwise. + */ + bool HID_Host_IsReportReceived(USB_ClassInfo_HID_Host_t* const HIDInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** Switches the attached HID device's reporting protocol over to the Boot Report protocol mode, on supported devices. + * + * \note When the HID_HOST_BOOT_PROTOCOL_ONLY compile time token is defined, this method must still be called + * to explicitly place the attached device into boot protocol mode before use. + * + * \param[in,out] HIDInterfaceInfo Pointer to a structure containing a HID Class host configuration and state. + * + * \return \ref HID_ERROR_LOGICAL if the device does not support Boot Protocol mode, a value from the + * \ref USB_Host_SendControlErrorCodes_t enum otherwise. + */ + uint8_t HID_Host_SetBootProtocol(USB_ClassInfo_HID_Host_t* const HIDInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + #if !defined(HID_HOST_BOOT_PROTOCOL_ONLY) + /** Switches the attached HID device's reporting protocol over to the standard Report protocol mode. This also retrieves + * and parses the device's HID report descriptor, so that the size of each report can be determined in advance. + * + * \note Whether this function is used or not, the \ref CALLBACK_HIDParser_FilterHIDReportItem() callback from the HID + * Report Parser this function references must be implemented in the user code. + * \n\n + * + * \note When the HID_HOST_BOOT_PROTOCOL_ONLY compile time token is defined, this method is unavailable. + * + * \param[in,out] HIDInterfaceInfo Pointer to a structure containing a HID Class host configuration and state. + * + * \return A value from the \ref USB_Host_SendControlErrorCodes_t enum if an error occurs while retrieving the HID + * Report descriptor or the setting of the Report protocol, \ref HID_ERROR_LOGICAL if the HID interface does + * not have a valid \ref HID_ReportInfo_t structure set in its configuration, a mask of \ref HID_ERROR_LOGICAL + * and a value from the \ref HID_Parse_ErrorCodes_t otherwise. + */ + uint8_t HID_Host_SetReportProtocol(USB_ClassInfo_HID_Host_t* const HIDInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + #endif + + /* Inline Functions: */ + /** General management task for a given Human Interface Class host class interface, required for the correct operation of + * the interface. This should be called frequently in the main program loop, before the master USB management task + * \ref USB_USBTask(). + * + * \param[in,out] HIDInterfaceInfo Pointer to a structure containing a HID Class host configuration and state. + */ + static inline void HID_Host_USBTask(USB_ClassInfo_HID_Host_t* const HIDInterfaceInfo); + static inline void HID_Host_USBTask(USB_ClassInfo_HID_Host_t* const HIDInterfaceInfo) + { + (void)HIDInterfaceInfo; + } + + /* Private Interface - For use in library only: */ + #if !defined(__DOXYGEN__) + /* Macros: */ + #define HID_INTERFACE_CLASS 0x03 + + #define HID_FOUND_DATAPIPE_IN (1 << 0) + #define HID_FOUND_DATAPIPE_OUT (1 << 1) + + /* Function Prototypes: */ + #if defined(__INCLUDE_FROM_HID_CLASS_HOST_C) + static uint8_t DCOMP_HID_Host_NextHIDInterface(void* const CurrentDescriptor) ATTR_NON_NULL_PTR_ARG(1); + static uint8_t DCOMP_HID_NextHID(void* const CurrentDescriptor) ATTR_NON_NULL_PTR_ARG(1); + static uint8_t DCOMP_HID_Host_NextHIDInterfaceEndpoint(void* const CurrentDescriptor) ATTR_NON_NULL_PTR_ARG(1); + #endif + #endif + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/HIDParser.c b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/HIDParser.c new file mode 100644 index 0000000000..1492112aad --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/HIDParser.c @@ -0,0 +1,359 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +#define __INCLUDE_FROM_USB_DRIVER +#include "../../HighLevel/USBMode.h" +#if defined(USB_CAN_BE_HOST) + +#include "HIDParser.h" + +uint8_t USB_ProcessHIDReport(const uint8_t* ReportData, + uint16_t ReportSize, + HID_ReportInfo_t* const ParserData) +{ + HID_StateTable_t StateTable[HID_STATETABLE_STACK_DEPTH]; + HID_StateTable_t* CurrStateTable = &StateTable[0]; + HID_CollectionPath_t* CurrCollectionPath = NULL; + HID_ReportSizeInfo_t* CurrReportIDInfo = &ParserData->ReportIDSizes[0]; + uint16_t UsageList[HID_USAGE_STACK_DEPTH]; + uint8_t UsageListSize = 0; + HID_MinMax_t UsageMinMax = {0, 0}; + + memset(ParserData, 0x00, sizeof(HID_ReportInfo_t)); + memset(CurrStateTable, 0x00, sizeof(HID_StateTable_t)); + memset(CurrReportIDInfo, 0x00, sizeof(HID_ReportSizeInfo_t)); + + ParserData->TotalDeviceReports = 1; + + while (ReportSize) + { + uint8_t HIDReportItem = *ReportData; + uint32_t ReportItemData = 0; + + ReportData++; + ReportSize--; + + switch (HIDReportItem & DATA_SIZE_MASK) + { + case DATA_SIZE_4: + ReportItemData = *((uint32_t*)ReportData); + ReportSize -= 4; + ReportData += 4; + break; + case DATA_SIZE_2: + ReportItemData = *((uint16_t*)ReportData); + ReportSize -= 2; + ReportData += 2; + break; + case DATA_SIZE_1: + ReportItemData = *((uint8_t*)ReportData); + ReportSize -= 1; + ReportData += 1; + break; + } + + switch (HIDReportItem & (TYPE_MASK | TAG_MASK)) + { + case (TYPE_GLOBAL | TAG_GLOBAL_PUSH): + if (CurrStateTable == &StateTable[HID_STATETABLE_STACK_DEPTH - 1]) + return HID_PARSE_HIDStackOverflow; + + memcpy((CurrStateTable + 1), + CurrStateTable, + sizeof(HID_ReportItem_t)); + + CurrStateTable++; + break; + case (TYPE_GLOBAL | TAG_GLOBAL_POP): + if (CurrStateTable == &StateTable[0]) + return HID_PARSE_HIDStackUnderflow; + + CurrStateTable--; + break; + case (TYPE_GLOBAL | TAG_GLOBAL_USAGEPAGE): + CurrStateTable->Attributes.Usage.Page = ReportItemData; + break; + case (TYPE_GLOBAL | TAG_GLOBAL_LOGICALMIN): + CurrStateTable->Attributes.Logical.Minimum = ReportItemData; + break; + case (TYPE_GLOBAL | TAG_GLOBAL_LOGICALMAX): + CurrStateTable->Attributes.Logical.Maximum = ReportItemData; + break; + case (TYPE_GLOBAL | TAG_GLOBAL_PHYSMIN): + CurrStateTable->Attributes.Physical.Minimum = ReportItemData; + break; + case (TYPE_GLOBAL | TAG_GLOBAL_PHYSMAX): + CurrStateTable->Attributes.Physical.Maximum = ReportItemData; + break; + case (TYPE_GLOBAL | TAG_GLOBAL_UNITEXP): + CurrStateTable->Attributes.Unit.Exponent = ReportItemData; + break; + case (TYPE_GLOBAL | TAG_GLOBAL_UNIT): + CurrStateTable->Attributes.Unit.Type = ReportItemData; + break; + case (TYPE_GLOBAL | TAG_GLOBAL_REPORTSIZE): + CurrStateTable->Attributes.BitSize = ReportItemData; + break; + case (TYPE_GLOBAL | TAG_GLOBAL_REPORTCOUNT): + CurrStateTable->ReportCount = ReportItemData; + break; + case (TYPE_GLOBAL | TAG_GLOBAL_REPORTID): + CurrStateTable->ReportID = ReportItemData; + + if (ParserData->UsingReportIDs) + { + CurrReportIDInfo = NULL; + + for (uint8_t i = 0; i < ParserData->TotalDeviceReports; i++) + { + if (ParserData->ReportIDSizes[i].ReportID == CurrStateTable->ReportID) + { + CurrReportIDInfo = &ParserData->ReportIDSizes[i]; + break; + } + } + + if (CurrReportIDInfo == NULL) + { + if (ParserData->TotalDeviceReports == HID_MAX_REPORT_IDS) + return HID_PARSE_InsufficientReportIDItems; + + CurrReportIDInfo = &ParserData->ReportIDSizes[ParserData->TotalDeviceReports++]; + memset(CurrReportIDInfo, 0x00, sizeof(HID_ReportSizeInfo_t)); + } + } + + ParserData->UsingReportIDs = true; + + CurrReportIDInfo->ReportID = CurrStateTable->ReportID; + break; + case (TYPE_LOCAL | TAG_LOCAL_USAGE): + if (UsageListSize == HID_USAGE_STACK_DEPTH) + return HID_PARSE_UsageListOverflow; + + UsageList[UsageListSize++] = ReportItemData; + break; + case (TYPE_LOCAL | TAG_LOCAL_USAGEMIN): + UsageMinMax.Minimum = ReportItemData; + break; + case (TYPE_LOCAL | TAG_LOCAL_USAGEMAX): + UsageMinMax.Maximum = ReportItemData; + break; + case (TYPE_MAIN | TAG_MAIN_COLLECTION): + if (CurrCollectionPath == NULL) + { + CurrCollectionPath = &ParserData->CollectionPaths[0]; + } + else + { + HID_CollectionPath_t* ParentCollectionPath = CurrCollectionPath; + + CurrCollectionPath = &ParserData->CollectionPaths[1]; + + while (CurrCollectionPath->Parent != NULL) + { + if (CurrCollectionPath == &ParserData->CollectionPaths[HID_MAX_COLLECTIONS - 1]) + return HID_PARSE_InsufficientCollectionPaths; + + CurrCollectionPath++; + } + + CurrCollectionPath->Parent = ParentCollectionPath; + } + + CurrCollectionPath->Type = ReportItemData; + CurrCollectionPath->Usage.Page = CurrStateTable->Attributes.Usage.Page; + + if (UsageListSize) + { + CurrCollectionPath->Usage.Usage = UsageList[0]; + + for (uint8_t i = 0; i < UsageListSize; i++) + UsageList[i] = UsageList[i + 1]; + + UsageListSize--; + } + else if (UsageMinMax.Minimum <= UsageMinMax.Maximum) + { + CurrCollectionPath->Usage.Usage = UsageMinMax.Minimum++; + } + + break; + case (TYPE_MAIN | TAG_MAIN_ENDCOLLECTION): + if (CurrCollectionPath == NULL) + return HID_PARSE_UnexpectedEndCollection; + + CurrCollectionPath = CurrCollectionPath->Parent; + break; + case (TYPE_MAIN | TAG_MAIN_INPUT): + case (TYPE_MAIN | TAG_MAIN_OUTPUT): + case (TYPE_MAIN | TAG_MAIN_FEATURE): + for (uint8_t ReportItemNum = 0; ReportItemNum < CurrStateTable->ReportCount; ReportItemNum++) + { + HID_ReportItem_t NewReportItem; + + memcpy(&NewReportItem.Attributes, + &CurrStateTable->Attributes, + sizeof(HID_ReportItem_Attributes_t)); + + NewReportItem.ItemFlags = ReportItemData; + NewReportItem.CollectionPath = CurrCollectionPath; + NewReportItem.ReportID = CurrStateTable->ReportID; + + if (UsageListSize) + { + NewReportItem.Attributes.Usage.Usage = UsageList[0]; + + for (uint8_t i = 0; i < UsageListSize; i++) + UsageList[i] = UsageList[i + 1]; + + UsageListSize--; + } + else if (UsageMinMax.Minimum <= UsageMinMax.Maximum) + { + NewReportItem.Attributes.Usage.Usage = UsageMinMax.Minimum++; + } + + uint8_t ItemTag = (HIDReportItem & TAG_MASK); + + if (ItemTag == TAG_MAIN_INPUT) + NewReportItem.ItemType = REPORT_ITEM_TYPE_In; + else if (ItemTag == TAG_MAIN_OUTPUT) + NewReportItem.ItemType = REPORT_ITEM_TYPE_Out; + else + NewReportItem.ItemType = REPORT_ITEM_TYPE_Feature; + + NewReportItem.BitOffset = CurrReportIDInfo->ReportSizeBits[NewReportItem.ItemType]; + + CurrReportIDInfo->ReportSizeBits[NewReportItem.ItemType] += CurrStateTable->Attributes.BitSize; + + if (ParserData->LargestReportSizeBits < NewReportItem.BitOffset) + ParserData->LargestReportSizeBits = NewReportItem.BitOffset; + + if (!(ReportItemData & IOF_CONSTANT) && CALLBACK_HIDParser_FilterHIDReportItem(&NewReportItem)) + { + if (ParserData->TotalReportItems == HID_MAX_REPORTITEMS) + return HID_PARSE_InsufficientReportItems; + + memcpy(&ParserData->ReportItems[ParserData->TotalReportItems], + &NewReportItem, sizeof(HID_ReportItem_t)); + + ParserData->TotalReportItems++; + } + } + + break; + } + + if ((HIDReportItem & TYPE_MASK) == TYPE_MAIN) + { + UsageMinMax.Minimum = 0; + UsageMinMax.Maximum = 0; + UsageListSize = 0; + } + } + + if (!(ParserData->TotalReportItems)) + return HID_PARSE_NoUnfilteredReportItems; + + return HID_PARSE_Successful; +} + +bool USB_GetHIDReportItemInfo(const uint8_t* ReportData, + HID_ReportItem_t* const ReportItem) +{ + uint16_t DataBitsRem = ReportItem->Attributes.BitSize; + uint16_t CurrentBit = ReportItem->BitOffset; + uint32_t BitMask = (1 << 0); + + ReportItem->PreviousValue = ReportItem->Value; + ReportItem->Value = 0; + + if (ReportItem->ReportID) + { + if (ReportItem->ReportID != ReportData[0]) + return false; + + ReportData++; + } + + while (DataBitsRem--) + { + if (ReportData[CurrentBit / 8] & (1 << (CurrentBit % 8))) + ReportItem->Value |= BitMask; + + CurrentBit++; + BitMask <<= 1; + } + + return true; +} + +void USB_SetHIDReportItemInfo(uint8_t* ReportData, + HID_ReportItem_t* const ReportItem) +{ + uint16_t DataBitsRem = ReportItem->Attributes.BitSize; + uint16_t CurrentBit = ReportItem->BitOffset; + uint32_t BitMask = (1 << 0); + + if (ReportItem->ReportID) + { + ReportData[0] = ReportItem->ReportID; + ReportData++; + } + + ReportItem->PreviousValue = ReportItem->Value; + + while (DataBitsRem--) + { + if (ReportItem->Value & (1 << (CurrentBit % 8))) + ReportData[CurrentBit / 8] |= BitMask; + + CurrentBit++; + BitMask <<= 1; + } +} + +uint16_t USB_GetHIDReportSize(HID_ReportInfo_t* const ParserData, + const uint8_t ReportID, + const uint8_t ReportType) +{ + for (uint8_t i = 0; i < HID_MAX_REPORT_IDS; i++) + { + uint16_t ReportSizeBits = ParserData->ReportIDSizes[i].ReportSizeBits[ReportType]; + + if (ParserData->ReportIDSizes[i].ReportID == ReportID) + return ((ReportSizeBits >> 3) + ((ReportSizeBits & 0x07) ? 1 : 0)); + } + + return 0; +} + +#endif diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/HIDParser.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/HIDParser.h new file mode 100644 index 0000000000..5f8fa374fe --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/HIDParser.h @@ -0,0 +1,357 @@ +/* + 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 USB Human Interface Device (HID) Class report descriptor parser. + * + * This file allows for the easy parsing of complex HID report descriptors, which describes the data that + * a HID device transmits to the host. It also provides an easy API for extracting and processing the data + * elements inside a HID report sent from an attached HID device. + */ + +/** \ingroup Group_USB + * @defgroup Group_HIDParser HID Report Parser + * + * \section Sec_Dependencies Module Source Dependencies + * The following files must be built with any user project that uses this module: + * - LUFA/Drivers/USB/Class/Host/HIDParser.c (Makefile source module name: LUFA_SRC_USB) + * + * \section Module Description + * Functions, macros, variables, enums and types related to the parsing of HID class device report descriptors. + * + * The processed HID report is presented back to the user application as a flat structure containing each report + * item's IN, OUT and FEATURE items along with each item's attributes. + * + * This library portion also allows for easy setting and retrieval of data from a HID report, including devices + * with multiple reports on the one HID interface. + * + * @{ + */ + +#ifndef __HIDPARSER_H__ +#define __HIDPARSER_H__ + + /* Macros: */ + #define __INCLUDE_FROM_USB_DRIVER + #define __INCLUDE_FROM_HID_DRIVER + + /* Includes: */ + #include + #include + + #include "HIDReportData.h" + #include "../Common/HID.h" + + #include "../../../../Common/Common.h" + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Macros: */ + #if !defined(HID_STATETABLE_STACK_DEPTH) || defined(__DOXYGEN__) + /** Constant indicating the maximum stack depth of the state table. A larger state table + * allows for more PUSH/POP report items to be nested, but consumes more memory. By default + * this is set to 2 levels (allowing non-nested PUSH items) but this can be overridden by + * defining HID_STATETABLE_STACK_DEPTH to another value in the user project makefile, passing the + * define to the compiler using the -D compiler switch. + */ + #define HID_STATETABLE_STACK_DEPTH 2 + #endif + + #if !defined(HID_USAGE_STACK_DEPTH) || defined(__DOXYGEN__) + /** Constant indicating the maximum stack depth of the usage table. A larger usage table + * allows for more USAGE items to be indicated sequentially for REPORT COUNT entries of more than + * one, but requires more stack space. By default this is set to 8 levels (allowing for a report + * item with a count of 8) but this can be overridden by defining HID_USAGE_STACK_DEPTH to another + * value in the user project makefile, passing the define to the compiler using the -D compiler + * switch. + */ + #define HID_USAGE_STACK_DEPTH 8 + #endif + + #if !defined(HID_MAX_COLLECTIONS) || defined(__DOXYGEN__) + /** Constant indicating the maximum number of COLLECTION items (nested or unnested) that can be + * processed in the report item descriptor. A large value allows for more COLLECTION items to be + * processed, but consumes more memory. By default this is set to 10 collections, but this can be + * overridden by defining HID_MAX_COLLECTIONS to another value in the user project makefile, passing + * the define to the compiler using the -D compiler switch. + */ + #define HID_MAX_COLLECTIONS 10 + #endif + + #if !defined(HID_MAX_REPORTITEMS) || defined(__DOXYGEN__) + /** Constant indicating the maximum number of report items (IN, OUT or FEATURE) that can be processed + * in the report item descriptor and stored in the user HID Report Info structure. A large value allows + * for more report items to be stored, but consumes more memory. By default this is set to 20 items, + * but this can be overridden by defining HID_MAX_REPORTITEMS to another value in the user project + * makefile, and passing the define to the compiler using the -D compiler switch. + */ + #define HID_MAX_REPORTITEMS 20 + #endif + + #if !defined(HID_MAX_REPORT_IDS) || defined(__DOXYGEN__) + /** Constant indicating the maximum number of unique report IDs that can be processed in the report item + * descriptor for the report size information array in the user HID Report Info structure. A large value + * allows for more report ID report sizes to be stored, but consumes more memory. By default this is set + * to 10 items, but this can be overridden by defining HID_MAX_REPORT_IDS to another value in the user project + * makefile, and passing the define to the compiler using the -D compiler switch. Note that IN, OUT and FEATURE + * items sharing the same report ID consume only one size item in the array. + */ + #define HID_MAX_REPORT_IDS 10 + #endif + + /** Returns the value a given HID report item (once its value has been fetched via \ref USB_GetHIDReportItemInfo()) + * left-aligned to the given data type. This allows for signed data to be interpreted correctly, by shifting the data + * leftwards until the data's sign bit is in the correct position. + * + * \param[in] ReportItem HID Report Item whose retrieved value is to be aligned. + * \param[in] Type Data type to align the HID report item's value to. + * + * \return Left-aligned data of the given report item's pre-retrieved value for the given datatype. + */ + #define HID_ALIGN_DATA(ReportItem, Type) ((Type)(ReportItem->Value << ((8 * sizeof(Type)) - ReportItem->Attributes.BitSize))) + + /* Public Interface - May be used in end-application: */ + /* Enums: */ + /** Enum for the possible error codes in the return value of the \ref USB_ProcessHIDReport() function. */ + enum HID_Parse_ErrorCodes_t + { + HID_PARSE_Successful = 0, /**< Successful parse of the HID report descriptor, no error. */ + HID_PARSE_HIDStackOverflow = 1, /**< More than \ref HID_STATETABLE_STACK_DEPTH nested PUSHes in the report. */ + HID_PARSE_HIDStackUnderflow = 2, /**< A POP was found when the state table stack was empty. */ + HID_PARSE_InsufficientReportItems = 3, /**< More than \ref HID_MAX_REPORTITEMS report items in the report. */ + HID_PARSE_UnexpectedEndCollection = 4, /**< An END COLLECTION item found without matching COLLECTION item. */ + HID_PARSE_InsufficientCollectionPaths = 5, /**< More than \ref HID_MAX_COLLECTIONS collections in the report. */ + HID_PARSE_UsageListOverflow = 6, /**< More than \ref HID_USAGE_STACK_DEPTH usages listed in a row. */ + HID_PARSE_InsufficientReportIDItems = 7, /**< More than \ref HID_MAX_REPORT_IDS report IDs in the device. */ + HID_PARSE_NoUnfilteredReportItems = 8, /**< All report items from the device were filtered by the filtering callback routine. */ + }; + + /* Type Defines: */ + /** \brief HID Parser Report Item Min/Max Structure. + * + * Type define for an attribute with both minimum and maximum values (e.g. Logical Min/Max). + */ + typedef struct + { + uint32_t Minimum; /**< Minimum value for the attribute. */ + uint32_t Maximum; /**< Maximum value for the attribute. */ + } HID_MinMax_t; + + /** \brief HID Parser Report Item Unit Structure. + * + * Type define for the Unit attributes of a report item. + */ + typedef struct + { + uint32_t Type; /**< Unit type (refer to HID specifications for details). */ + uint8_t Exponent; /**< Unit exponent (refer to HID specifications for details). */ + } HID_Unit_t; + + /** \brief HID Parser Report Item Usage Structure. + * + * Type define for the Usage attributes of a report item. + */ + typedef struct + { + uint16_t Page; /**< Usage page of the report item. */ + uint16_t Usage; /**< Usage of the report item. */ + } HID_Usage_t; + + /** \brief HID Parser Report Item Collection Path Structure. + * + * Type define for a COLLECTION object. Contains the collection attributes and a reference to the + * parent collection if any. + */ + typedef struct CollectionPath + { + uint8_t Type; /**< Collection type (e.g. "Generic Desktop"). */ + HID_Usage_t Usage; /**< Collection usage. */ + struct CollectionPath* Parent; /**< Reference to parent collection, or NULL if root collection. */ + } HID_CollectionPath_t; + + /** \brief HID Parser Report Item Attributes Structure. + * + * Type define for all the data attributes of a report item, except flags. + */ + typedef struct + { + uint8_t BitSize; /**< Size in bits of the report item's data. */ + + HID_Usage_t Usage; /**< Usage of the report item. */ + HID_Unit_t Unit; /**< Unit type and exponent of the report item. */ + HID_MinMax_t Logical; /**< Logical minimum and maximum of the report item. */ + HID_MinMax_t Physical; /**< Physical minimum and maximum of the report item. */ + } HID_ReportItem_Attributes_t; + + /** \brief HID Parser Report Item Details Structure. + * + * Type define for a report item (IN, OUT or FEATURE) layout attributes and other details. + */ + typedef struct + { + uint16_t BitOffset; /**< Bit offset in the IN, OUT or FEATURE report of the item. */ + uint8_t ItemType; /**< Report item type, a value in HID_ReportItemTypes_t. */ + uint16_t ItemFlags; /**< Item data flags, such as constant/variable, etc. */ + uint8_t ReportID; /**< Report ID this item belongs to, or 0x00 if device has only one report */ + HID_CollectionPath_t* CollectionPath; /**< Collection path of the item. */ + + HID_ReportItem_Attributes_t Attributes; /**< Report item attributes. */ + + uint32_t Value; /**< Current value of the report item - use \ref HID_ALIGN_DATA() when processing + * a retrieved value so that it is aligned to a specific type. + */ + uint32_t PreviousValue; /**< Previous value of the report item. */ + } HID_ReportItem_t; + + /** \brief HID Parser Report Size Structure. + * + * Type define for a report item size information structure, to retain the size of a device's reports by ID. + */ + typedef struct + { + uint8_t ReportID; /**< Report ID of the report within the HID interface. */ + uint16_t ReportSizeBits[3]; /**< Total number of bits in each report type for the given Report ID, + * indexed by the \ref HID_ReportItemTypes_t enum. + */ + } HID_ReportSizeInfo_t; + + /** \brief HID Parser State Structure. + * + * Type define for a complete processed HID report, including all report item data and collections. + */ + typedef struct + { + uint8_t TotalReportItems; /**< Total number of report items stored in the + * ReportItems array. + */ + HID_ReportItem_t ReportItems[HID_MAX_REPORTITEMS]; /**< Report items array, including + * all IN, OUT and FEATURE items. + */ + HID_CollectionPath_t CollectionPaths[HID_MAX_COLLECTIONS]; /**< All collection items, referenced + * by the report items. + */ + uint8_t TotalDeviceReports; /**< Number of reports within the HID interface */ + HID_ReportSizeInfo_t ReportIDSizes[HID_MAX_REPORT_IDS]; /**< Report sizes for each report in the interface */ + uint16_t LargestReportSizeBits; /**< Largest report that the attached device will generate, in bits */ + bool UsingReportIDs; /**< Indicates if the device has at least one REPORT ID + * element in its HID report descriptor. + */ + } HID_ReportInfo_t; + + /* Function Prototypes: */ + /** Function to process a given HID report returned from an attached device, and store it into a given + * \ref HID_ReportInfo_t structure. + * + * \param[in] ReportData Buffer containing the device's HID report table. + * \param[in] ReportSize Size in bytes of the HID report table. + * \param[out] ParserData Pointer to a \ref HID_ReportInfo_t instance for the parser output. + * + * \return A value in the \ref HID_Parse_ErrorCodes_t enum. + */ + uint8_t USB_ProcessHIDReport(const uint8_t* ReportData, + uint16_t ReportSize, + HID_ReportInfo_t* const ParserData) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(3); + + /** Extracts the given report item's value out of the given HID report and places it into the Value + * member of the report item's \ref HID_ReportItem_t structure. + * + * When called, this copies the report item's Value element to it's PreviousValue element for easy + * checking to see if an item's value has changed before processing a report. + * + * \param[in] ReportData Buffer containing an IN or FEATURE report from an attached device. + * \param[in,out] ReportItem Pointer to the report item of interest in a \ref HID_ReportInfo_t ReportItem array. + * + * \returns Boolean true if the item to retrieve was located in the given report, false otherwise. + */ + bool USB_GetHIDReportItemInfo(const uint8_t* ReportData, + HID_ReportItem_t* const ReportItem) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(2); + + /** Retrieves the given report item's value out of the Value member of the report item's + * \ref HID_ReportItem_t structure and places it into the correct position in the HID report + * buffer. The report buffer is assumed to have the appropriate bits cleared before calling + * this function (i.e., the buffer should be explicitly cleared before report values are added). + * + * When called, this copies the report item's Value element to it's PreviousValue element for easy + * checking to see if an item's value has changed before sending a report. + * + * If the device has multiple HID reports, the first byte in the report is set to the report ID of the given item. + * + * \param[out] ReportData Buffer holding the current OUT or FEATURE report data. + * \param[in] ReportItem Pointer to the report item of interest in a \ref HID_ReportInfo_t ReportItem array. + */ + void USB_SetHIDReportItemInfo(uint8_t* ReportData, + HID_ReportItem_t* const ReportItem) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(2); + + /** Retrieves the size of a given HID report in bytes from it's Report ID. + * + * \param[in] ParserData Pointer to a \ref HID_ReportInfo_t instance containing the parser output. + * \param[in] ReportID Report ID of the report whose size is to be retrieved. + * \param[in] ReportType Type of the report whose size is to be determined, a valued from the + * \ref HID_ReportItemTypes_t enum. + * + * \return Size of the report in bytes, or 0 if the report does not exist. + */ + uint16_t USB_GetHIDReportSize(HID_ReportInfo_t* const ParserData, + const uint8_t ReportID, + const uint8_t ReportType) ATTR_CONST ATTR_NON_NULL_PTR_ARG(1); + + /** Callback routine for the HID Report Parser. This callback must be implemented by the user code when + * the parser is used, to determine what report IN, OUT and FEATURE item's information is stored into the user + * HID_ReportInfo_t structure. This can be used to filter only those items the application will be using, so that + * no RAM is wasted storing the attributes for report items which will never be referenced by the application. + * + * \param[in] CurrentItem Pointer to the current report item for user checking. + * + * \return Boolean true if the item should be stored into the HID_ReportInfo_t structure, false if it should be ignored. + */ + bool CALLBACK_HIDParser_FilterHIDReportItem(HID_ReportItem_t* const CurrentItem); + + /* Private Interface - For use in library only: */ + #if !defined(__DOXYGEN__) + /* Type Defines: */ + typedef struct + { + HID_ReportItem_Attributes_t Attributes; + uint8_t ReportCount; + uint8_t ReportID; + } HID_StateTable_t; + #endif + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/HIDReportData.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/HIDReportData.h new file mode 100644 index 0000000000..dca1ebb3a9 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/HIDReportData.h @@ -0,0 +1,141 @@ +/* + 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 Constants for HID report item attributes. + * + * HID report item constants for report item attributes. Refer to the HID specification for + * details on each flag's meaning when applied to an IN, OUT or FEATURE item. + */ + +/** \ingroup Group_HIDParser + * @defgroup Group_HIDIOFConst Input/Output/Feature Masks + * + * Masks indicating the type of Input, Output of Feature HID report item. + * + * @{ + */ + +#ifndef __HIDREPORTDATA_H__ +#define __HIDREPORTDATA_H__ + + /* Public Interface - May be used in end-application: */ + /* Macros: */ + /** HID_ReportItem_t.ItemFlags flag for constant data. */ + #define IOF_CONSTANT (1 << 0) + + /** HID_ReportItem_t.ItemFlags flag for data. */ + #define IOF_DATA (0 << 0) + + /** HID_ReportItem_t.ItemFlags flag for variable data. */ + #define IOF_VARIABLE (1 << 1) + + /** HID_ReportItem_t.ItemFlags flag for array data. */ + #define IOF_ARRAY (0 << 1) + + /** HID_ReportItem_t.ItemFlags flag for relative data. */ + #define IOF_RELATIVE (1 << 2) + + /** HID_ReportItem_t.ItemFlags flag for absolute data. */ + #define IOF_ABSOLUTE (0 << 2) + + /** HID_ReportItem_t.ItemFlags flag for wrapped value data. */ + #define IOF_WRAP (1 << 3) + + /** HID_ReportItem_t.ItemFlags flag for non-wrapped value data. */ + #define IOF_NOWRAP (0 << 3) + + /** HID_ReportItem_t.ItemFlags flag for non linear data. */ + #define IOF_NONLINEAR (1 << 4) + + /** HID_ReportItem_t.ItemFlags flag for linear data. */ + #define IOF_LINEAR (0 << 4) + + /** HID_ReportItem_t.ItemFlags flag for no preferred state. */ + #define IOF_NOPREFERRED (1 << 5) + + /** HID_ReportItem_t.ItemFlags flag for preferred state items. */ + #define IOF_PREFERREDSTATE (0 << 5) + + /** HID_ReportItem_t.ItemFlags flag for null state items. */ + #define IOF_NULLSTATE (1 << 6) + + /** HID_ReportItem_t.ItemFlags flag for no null position data. */ + #define IOF_NONULLPOSITION (0 << 6) + + /** HID_ReportItem_t.ItemFlags flag for buffered bytes. */ + #define IOF_BUFFEREDBYTES (1 << 8) + + /** HID_ReportItem_t.ItemFlags flag for bit field data. */ + #define IOF_BITFIELD (0 << 8) + + /* Private Interface - For use in library only: */ + #if !defined(__DOXYGEN__) + /* Macros: */ + #define DATA_SIZE_MASK 0x03 + #define TYPE_MASK 0x0C + #define TAG_MASK 0xF0 + + #define DATA_SIZE_0 0x00 + #define DATA_SIZE_1 0x01 + #define DATA_SIZE_2 0x02 + #define DATA_SIZE_4 0x03 + + #define TYPE_MAIN 0x00 + #define TYPE_GLOBAL 0x04 + #define TYPE_LOCAL 0x08 + + #define TAG_MAIN_INPUT 0x80 + #define TAG_MAIN_OUTPUT 0x90 + #define TAG_MAIN_COLLECTION 0xA0 + #define TAG_MAIN_FEATURE 0xB0 + #define TAG_MAIN_ENDCOLLECTION 0xC0 + + #define TAG_GLOBAL_USAGEPAGE 0x00 + #define TAG_GLOBAL_LOGICALMIN 0x10 + #define TAG_GLOBAL_LOGICALMAX 0x20 + #define TAG_GLOBAL_PHYSMIN 0x30 + #define TAG_GLOBAL_PHYSMAX 0x40 + #define TAG_GLOBAL_UNITEXP 0x50 + #define TAG_GLOBAL_UNIT 0x60 + #define TAG_GLOBAL_REPORTSIZE 0x70 + #define TAG_GLOBAL_REPORTID 0x80 + #define TAG_GLOBAL_REPORTCOUNT 0x90 + #define TAG_GLOBAL_PUSH 0xA0 + #define TAG_GLOBAL_POP 0xB0 + + #define TAG_LOCAL_USAGE 0x00 + #define TAG_LOCAL_USAGEMIN 0x10 + #define TAG_LOCAL_USAGEMAX 0x20 + #endif + +/** @} */ + +#endif diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/MIDI.c b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/MIDI.c new file mode 100644 index 0000000000..fd7f13ccdf --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/MIDI.c @@ -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. +*/ + +#define __INCLUDE_FROM_USB_DRIVER +#include "../../HighLevel/USBMode.h" +#if defined(USB_CAN_BE_HOST) + +#define __INCLUDE_FROM_MIDI_CLASS_HOST_C +#define __INCLUDE_FROM_MIDI_DRIVER +#include "MIDI.h" + +uint8_t MIDI_Host_ConfigurePipes(USB_ClassInfo_MIDI_Host_t* const MIDIInterfaceInfo, + uint16_t ConfigDescriptorSize, + void* ConfigDescriptorData) +{ + uint8_t FoundEndpoints = 0; + + memset(&MIDIInterfaceInfo->State, 0x00, sizeof(MIDIInterfaceInfo->State)); + + if (DESCRIPTOR_TYPE(ConfigDescriptorData) != DTYPE_Configuration) + return MIDI_ENUMERROR_InvalidConfigDescriptor; + + if (USB_GetNextDescriptorComp(&ConfigDescriptorSize, &ConfigDescriptorData, + DCOMP_MIDI_Host_NextMIDIStreamingInterface) != DESCRIPTOR_SEARCH_COMP_Found) + { + return MIDI_ENUMERROR_NoStreamingInterfaceFound; + } + + while (FoundEndpoints != (MIDI_FOUND_DATAPIPE_IN | MIDI_FOUND_DATAPIPE_OUT)) + { + if (USB_GetNextDescriptorComp(&ConfigDescriptorSize, &ConfigDescriptorData, + DCOMP_MIDI_Host_NextMIDIStreamingDataEndpoint) != DESCRIPTOR_SEARCH_COMP_Found) + { + return MIDI_ENUMERROR_EndpointsNotFound; + } + + USB_Descriptor_Endpoint_t* EndpointData = DESCRIPTOR_PCAST(ConfigDescriptorData, USB_Descriptor_Endpoint_t); + + if (EndpointData->EndpointAddress & ENDPOINT_DESCRIPTOR_DIR_IN) + { + Pipe_ConfigurePipe(MIDIInterfaceInfo->Config.DataINPipeNumber, EP_TYPE_BULK, PIPE_TOKEN_IN, + EndpointData->EndpointAddress, EndpointData->EndpointSize, + MIDIInterfaceInfo->Config.DataINPipeDoubleBank ? PIPE_BANK_DOUBLE : PIPE_BANK_SINGLE); + MIDIInterfaceInfo->State.DataINPipeSize = EndpointData->EndpointSize; + + FoundEndpoints |= MIDI_FOUND_DATAPIPE_IN; + } + else + { + Pipe_ConfigurePipe(MIDIInterfaceInfo->Config.DataOUTPipeNumber, EP_TYPE_BULK, PIPE_TOKEN_OUT, + EndpointData->EndpointAddress, EndpointData->EndpointSize, + MIDIInterfaceInfo->Config.DataOUTPipeDoubleBank ? PIPE_BANK_DOUBLE : PIPE_BANK_SINGLE); + MIDIInterfaceInfo->State.DataOUTPipeSize = EndpointData->EndpointSize; + + FoundEndpoints |= MIDI_FOUND_DATAPIPE_OUT; + } + } + + MIDIInterfaceInfo->State.IsActive = true; + return MIDI_ENUMERROR_NoError; +} + +static uint8_t DCOMP_MIDI_Host_NextMIDIStreamingInterface(void* const CurrentDescriptor) +{ + if (DESCRIPTOR_TYPE(CurrentDescriptor) == DTYPE_Interface) + { + USB_Descriptor_Interface_t* CurrentInterface = DESCRIPTOR_PCAST(CurrentDescriptor, + USB_Descriptor_Interface_t); + + if ((CurrentInterface->Class == MIDI_STREAMING_CLASS) && + (CurrentInterface->SubClass == MIDI_STREAMING_SUBCLASS) && + (CurrentInterface->Protocol == MIDI_STREAMING_PROTOCOL)) + { + return DESCRIPTOR_SEARCH_Found; + } + } + + return DESCRIPTOR_SEARCH_NotFound; +} + +static uint8_t DCOMP_MIDI_Host_NextMIDIStreamingDataEndpoint(void* const CurrentDescriptor) +{ + if (DESCRIPTOR_TYPE(CurrentDescriptor) == DTYPE_Endpoint) + { + USB_Descriptor_Endpoint_t* CurrentEndpoint = DESCRIPTOR_PCAST(CurrentDescriptor, + USB_Descriptor_Endpoint_t); + + uint8_t EndpointType = (CurrentEndpoint->Attributes & EP_TYPE_MASK); + + if ((EndpointType == EP_TYPE_BULK) && !(Pipe_IsEndpointBound(CurrentEndpoint->EndpointAddress))) + return DESCRIPTOR_SEARCH_Found; + } + else if (DESCRIPTOR_TYPE(CurrentDescriptor) == DTYPE_Interface) + { + return DESCRIPTOR_SEARCH_Fail; + } + + return DESCRIPTOR_SEARCH_NotFound; +} + +uint8_t MIDI_Host_Flush(USB_ClassInfo_MIDI_Host_t* const MIDIInterfaceInfo) +{ + if (USB_HostState != HOST_STATE_Configured) + return PIPE_RWSTREAM_DeviceDisconnected; + + uint8_t ErrorCode; + + Pipe_SelectPipe(MIDIInterfaceInfo->Config.DataOUTPipeNumber); + + if (Pipe_BytesInPipe()) + { + Pipe_ClearOUT(); + + if ((ErrorCode = Pipe_WaitUntilReady()) != PIPE_READYWAIT_NoError) + return ErrorCode; + } + + return PIPE_READYWAIT_NoError; +} + +uint8_t MIDI_Host_SendEventPacket(USB_ClassInfo_MIDI_Host_t* const MIDIInterfaceInfo, + MIDI_EventPacket_t* const Event) +{ + if ((USB_HostState != HOST_STATE_Configured) || !(MIDIInterfaceInfo->State.IsActive)) + return HOST_SENDCONTROL_DeviceDisconnected; + + Pipe_SelectPipe(MIDIInterfaceInfo->Config.DataOUTPipeNumber); + + if (Pipe_IsReadWriteAllowed()) + { + uint8_t ErrorCode; + + if ((ErrorCode = Pipe_Write_Stream_LE(Event, sizeof(MIDI_EventPacket_t), NO_STREAM_CALLBACK)) != PIPE_RWSTREAM_NoError) + return ErrorCode; + + if (!(Pipe_IsReadWriteAllowed())) + Pipe_ClearOUT(); + } + + return PIPE_RWSTREAM_NoError; +} + +bool MIDI_Host_ReceiveEventPacket(USB_ClassInfo_MIDI_Host_t* const MIDIInterfaceInfo, + MIDI_EventPacket_t* const Event) +{ + if ((USB_HostState != HOST_STATE_Configured) || !(MIDIInterfaceInfo->State.IsActive)) + return HOST_SENDCONTROL_DeviceDisconnected; + + Pipe_SelectPipe(MIDIInterfaceInfo->Config.DataINPipeNumber); + + if (!(Pipe_IsReadWriteAllowed())) + return false; + + Pipe_Read_Stream_LE(Event, sizeof(MIDI_EventPacket_t), NO_STREAM_CALLBACK); + + if (!(Pipe_IsReadWriteAllowed())) + Pipe_ClearIN(); + + return true; +} + +#endif diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/MIDI.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/MIDI.h new file mode 100644 index 0000000000..2cfb56e57a --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/MIDI.h @@ -0,0 +1,205 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief Host mode driver for the library USB MIDI Class driver. + * + * Host mode driver for the library USB MIDI Class driver. + * + * \note This file should not be included directly. It is automatically included as needed by the class driver + * dispatch header located in LUFA/Drivers/USB/Class/MIDI.h. + */ + +/** \ingroup Group_USBClassMIDI + * @defgroup Group_USBClassMIDIHost MIDI Class Host Mode Driver + * + * \section Sec_Dependencies Module Source Dependencies + * The following files must be built with any user project that uses this module: + * - LUFA/Drivers/USB/Class/Host/MIDI.c (Makefile source module name: LUFA_SRC_USBCLASS) + * + * \section Module Description + * Host Mode USB Class driver framework interface, for the MIDI USB Class driver. + * + * @{ + */ + +#ifndef __MIDI_CLASS_HOST_H__ +#define __MIDI_CLASS_HOST_H__ + + /* Includes: */ + #include "../../USB.h" + #include "../Common/MIDI.h" + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_MIDI_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/Class/MIDI.h instead. + #endif + + /* Public Interface - May be used in end-application: */ + /* Type Defines: */ + /** \brief MIDI Class Host Mode Configuration and State Structure. + * + * Class state structure. An instance of this structure should be made within the user application, + * and passed to each of the MIDI class driver functions as the MIDIInterfaceInfo parameter. This + * stores each MIDI interface's configuration and state information. + */ + typedef struct + { + const struct + { + uint8_t DataINPipeNumber; /**< Pipe number of the MIDI interface's streaming IN data pipe. */ + bool DataINPipeDoubleBank; /**< Indicates if the MIDI interface's IN data pipe should use double banking. */ + + uint8_t DataOUTPipeNumber; /**< Pipe number of the MIDI interface's streaming OUT data pipe. */ + bool DataOUTPipeDoubleBank; /**< Indicates if the MIDI interface's OUT data pipe should use double banking. */ + } Config; /**< Config data for the USB class interface within the device. All elements in this section + * must be set or the interface will fail to enumerate and operate correctly. + */ + struct + { + bool IsActive; /**< Indicates if the current interface instance is connected to an attached device, valid + * after \ref MIDI_Host_ConfigurePipes() is called and the Host state machine is in the + * Configured state. + */ + + uint16_t DataINPipeSize; /**< Size in bytes of the MIDI Streaming Data interface's IN data pipe. */ + uint16_t DataOUTPipeSize; /**< Size in bytes of the MIDI Streaming Data interface's OUT data pipe. */ + } State; /**< State data for the USB class interface within the device. All elements in this section + * may be set to initial values, but may also be ignored to default to sane values when + * the interface is enumerated. + */ + } USB_ClassInfo_MIDI_Host_t; + + /* Enums: */ + /** Enum for the possible error codes returned by the \ref MIDI_Host_ConfigurePipes() function. */ + enum MIDIHost_EnumerationFailure_ErrorCodes_t + { + MIDI_ENUMERROR_NoError = 0, /**< Configuration Descriptor was processed successfully. */ + MIDI_ENUMERROR_InvalidConfigDescriptor = 1, /**< The device returned an invalid Configuration Descriptor. */ + MIDI_ENUMERROR_NoStreamingInterfaceFound = 2, /**< A compatible MIDI interface was not found in the device's Configuration Descriptor. */ + MIDI_ENUMERROR_EndpointsNotFound = 3, /**< Compatible MIDI data endpoints were not found in the device's MIDI interface. */ + }; + + /* Function Prototypes: */ + /** Host interface configuration routine, to configure a given MIDI host interface instance using the Configuration + * Descriptor read from an attached USB device. This function automatically updates the given MIDI Host instance's + * state values and configures the pipes required to communicate with the interface if it is found within the device. + * This should be called once after the stack has enumerated the attached device, while the host state machine is in + * the Addressed state. + * + * \param[in,out] MIDIInterfaceInfo Pointer to a structure containing an MIDI Class host configuration and state. + * \param[in] ConfigDescriptorSize Length of the attached device's Configuration Descriptor. + * \param[in] DeviceConfigDescriptor Pointer to a buffer containing the attached device's Configuration Descriptor. + * + * \return A value from the \ref MIDIHost_EnumerationFailure_ErrorCodes_t enum. + */ + uint8_t MIDI_Host_ConfigurePipes(USB_ClassInfo_MIDI_Host_t* const MIDIInterfaceInfo, + uint16_t ConfigDescriptorSize, + void* DeviceConfigDescriptor) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(3); + + /** Sends a MIDI event packet to the device. If no device is connected, the event packet is discarded. + * + * \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the + * call will fail. + * + * \param[in,out] MIDIInterfaceInfo Pointer to a structure containing a MIDI Class configuration and state. + * \param[in] Event Pointer to a populated USB_MIDI_EventPacket_t structure containing the MIDI event to send. + * + * \return A value from the \ref Pipe_Stream_RW_ErrorCodes_t enum. + */ + uint8_t MIDI_Host_SendEventPacket(USB_ClassInfo_MIDI_Host_t* const MIDIInterfaceInfo, + MIDI_EventPacket_t* const Event) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(2); + + /** Flushes the MIDI send buffer, sending any queued MIDI events to the device. This should be called to override the + * \ref MIDI_Host_SendEventPacket() function's packing behaviour, to flush queued events. Events are queued into the + * pipe bank until either the pipe bank is full, or \ref MIDI_Host_Flush() is called. This allows for multiple MIDI + * events to be packed into a single pipe packet, increasing data throughput. + * + * \param[in,out] MIDIInterfaceInfo Pointer to a structure containing a MIDI Class configuration and state. + * + * \return A value from the \ref Pipe_WaitUntilReady_ErrorCodes_t enum. + */ + uint8_t MIDI_Host_Flush(USB_ClassInfo_MIDI_Host_t* const MIDIInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** Receives a MIDI event packet from the device. + * + * \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the + * call will fail. + * + * \param[in,out] MIDIInterfaceInfo Pointer to a structure containing a MIDI Class configuration and state. + * \param[out] Event Pointer to a USB_MIDI_EventPacket_t structure where the received MIDI event is to be placed. + * + * \return Boolean true if a MIDI event packet was received, false otherwise. + */ + bool MIDI_Host_ReceiveEventPacket(USB_ClassInfo_MIDI_Host_t* const MIDIInterfaceInfo, + MIDI_EventPacket_t* const Event) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(2); + + /* Inline Functions: */ + /** General management task for a given MIDI host class interface, required for the correct operation of the interface. This should + * be called frequently in the main program loop, before the master USB management task \ref USB_USBTask(). + * + * \param[in,out] MIDIInterfaceInfo Pointer to a structure containing an MIDI Class host configuration and state. + */ + static inline void MIDI_Host_USBTask(USB_ClassInfo_MIDI_Host_t* const MIDIInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + static inline void MIDI_Host_USBTask(USB_ClassInfo_MIDI_Host_t* const MIDIInterfaceInfo) + { + (void)MIDIInterfaceInfo; + } + + /* Private Interface - For use in library only: */ + #if !defined(__DOXYGEN__) + /* Macros: */ + #define MIDI_STREAMING_CLASS 0x01 + #define MIDI_STREAMING_SUBCLASS 0x03 + #define MIDI_STREAMING_PROTOCOL 0x00 + + #define MIDI_FOUND_DATAPIPE_IN (1 << 0) + #define MIDI_FOUND_DATAPIPE_OUT (1 << 1) + + /* Function Prototypes: */ + #if defined(__INCLUDE_FROM_MIDI_CLASS_HOST_C) + static uint8_t DCOMP_MIDI_Host_NextMIDIStreamingInterface(void* const CurrentDescriptor) ATTR_NON_NULL_PTR_ARG(1); + static uint8_t DCOMP_MIDI_Host_NextMIDIStreamingDataEndpoint(void* const CurrentDescriptor) ATTR_NON_NULL_PTR_ARG(1); + #endif + #endif + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/MassStorage.c b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/MassStorage.c new file mode 100644 index 0000000000..14b7741db3 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/MassStorage.c @@ -0,0 +1,611 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +#define __INCLUDE_FROM_USB_DRIVER +#include "../../HighLevel/USBMode.h" +#if defined(USB_CAN_BE_HOST) + +#define __INCLUDE_FROM_MS_CLASS_HOST_C +#define __INCLUDE_FROM_MS_DRIVER +#include "MassStorage.h" + +uint8_t MS_Host_ConfigurePipes(USB_ClassInfo_MS_Host_t* const MSInterfaceInfo, + uint16_t ConfigDescriptorSize, + void* DeviceConfigDescriptor) +{ + uint8_t FoundEndpoints = 0; + + memset(&MSInterfaceInfo->State, 0x00, sizeof(MSInterfaceInfo->State)); + + if (DESCRIPTOR_TYPE(DeviceConfigDescriptor) != DTYPE_Configuration) + return MS_ENUMERROR_InvalidConfigDescriptor; + + if (USB_GetNextDescriptorComp(&ConfigDescriptorSize, &DeviceConfigDescriptor, + DCOMP_MS_NextMSInterface) != DESCRIPTOR_SEARCH_COMP_Found) + { + return MS_ENUMERROR_NoMSInterfaceFound; + } + + MSInterfaceInfo->State.InterfaceNumber = DESCRIPTOR_PCAST(DeviceConfigDescriptor, USB_Descriptor_Interface_t)->InterfaceNumber; + + while (FoundEndpoints != (MS_FOUND_DATAPIPE_IN | MS_FOUND_DATAPIPE_OUT)) + { + if (USB_GetNextDescriptorComp(&ConfigDescriptorSize, &DeviceConfigDescriptor, + DCOMP_MS_NextMSInterfaceEndpoint) != DESCRIPTOR_SEARCH_COMP_Found) + { + return MS_ENUMERROR_EndpointsNotFound; + } + + USB_Descriptor_Endpoint_t* EndpointData = DESCRIPTOR_PCAST(DeviceConfigDescriptor, USB_Descriptor_Endpoint_t); + + if (EndpointData->EndpointAddress & ENDPOINT_DESCRIPTOR_DIR_IN) + { + Pipe_ConfigurePipe(MSInterfaceInfo->Config.DataINPipeNumber, EP_TYPE_BULK, PIPE_TOKEN_IN, + EndpointData->EndpointAddress, EndpointData->EndpointSize, + MSInterfaceInfo->Config.DataINPipeDoubleBank ? PIPE_BANK_DOUBLE : PIPE_BANK_SINGLE); + MSInterfaceInfo->State.DataINPipeSize = EndpointData->EndpointSize; + + FoundEndpoints |= MS_FOUND_DATAPIPE_IN; + } + else + { + Pipe_ConfigurePipe(MSInterfaceInfo->Config.DataOUTPipeNumber, EP_TYPE_BULK, PIPE_TOKEN_OUT, + EndpointData->EndpointAddress, EndpointData->EndpointSize, + MSInterfaceInfo->Config.DataOUTPipeDoubleBank ? PIPE_BANK_DOUBLE : PIPE_BANK_SINGLE); + MSInterfaceInfo->State.DataOUTPipeSize = EndpointData->EndpointSize; + + FoundEndpoints |= MS_FOUND_DATAPIPE_OUT; + } + } + + MSInterfaceInfo->State.IsActive = true; + return MS_ENUMERROR_NoError; +} + +static uint8_t DCOMP_MS_NextMSInterface(void* const CurrentDescriptor) +{ + if (DESCRIPTOR_TYPE(CurrentDescriptor) == DTYPE_Interface) + { + USB_Descriptor_Interface_t* CurrentInterface = DESCRIPTOR_PCAST(CurrentDescriptor, + USB_Descriptor_Interface_t); + + if ((CurrentInterface->Class == MASS_STORE_CLASS) && + (CurrentInterface->SubClass == MASS_STORE_SUBCLASS) && + (CurrentInterface->Protocol == MASS_STORE_PROTOCOL)) + { + return DESCRIPTOR_SEARCH_Found; + } + } + + return DESCRIPTOR_SEARCH_NotFound; +} + +static uint8_t DCOMP_MS_NextMSInterfaceEndpoint(void* const CurrentDescriptor) +{ + if (DESCRIPTOR_TYPE(CurrentDescriptor) == DTYPE_Endpoint) + { + USB_Descriptor_Endpoint_t* CurrentEndpoint = DESCRIPTOR_PCAST(CurrentDescriptor, + USB_Descriptor_Endpoint_t); + + uint8_t EndpointType = (CurrentEndpoint->Attributes & EP_TYPE_MASK); + + if ((EndpointType == EP_TYPE_BULK) && + (!(Pipe_IsEndpointBound(CurrentEndpoint->EndpointAddress)))) + { + return DESCRIPTOR_SEARCH_Found; + } + } + else if (DESCRIPTOR_TYPE(CurrentDescriptor) == DTYPE_Interface) + { + return DESCRIPTOR_SEARCH_Fail; + } + + return DESCRIPTOR_SEARCH_NotFound; +} + +static uint8_t MS_Host_SendCommand(USB_ClassInfo_MS_Host_t* const MSInterfaceInfo, + MS_CommandBlockWrapper_t* const SCSICommandBlock, + const void* const BufferPtr) +{ + uint8_t ErrorCode = PIPE_RWSTREAM_NoError; + + SCSICommandBlock->Signature = CBW_SIGNATURE; + SCSICommandBlock->Tag = ++MSInterfaceInfo->State.TransactionTag; + + if (MSInterfaceInfo->State.TransactionTag == 0xFFFFFFFF) + MSInterfaceInfo->State.TransactionTag = 1; + + Pipe_SelectPipe(MSInterfaceInfo->Config.DataOUTPipeNumber); + Pipe_Unfreeze(); + + if ((ErrorCode = Pipe_Write_Stream_LE(SCSICommandBlock, sizeof(MS_CommandBlockWrapper_t), + NO_STREAM_CALLBACK)) != PIPE_RWSTREAM_NoError) + return ErrorCode; + + Pipe_ClearOUT(); + Pipe_WaitUntilReady(); + + Pipe_Freeze(); + + if ((BufferPtr != NULL) && + ((ErrorCode = MS_Host_SendReceiveData(MSInterfaceInfo, SCSICommandBlock, (void*)BufferPtr)) != PIPE_RWSTREAM_NoError)) + { + Pipe_Freeze(); + return ErrorCode; + } + + return ErrorCode; +} + +static uint8_t MS_Host_WaitForDataReceived(USB_ClassInfo_MS_Host_t* const MSInterfaceInfo) +{ + uint16_t TimeoutMSRem = COMMAND_DATA_TIMEOUT_MS; + + Pipe_SelectPipe(MSInterfaceInfo->Config.DataINPipeNumber); + Pipe_Unfreeze(); + + while (!(Pipe_IsINReceived())) + { + if (USB_INT_HasOccurred(USB_INT_HSOFI)) + { + USB_INT_Clear(USB_INT_HSOFI); + TimeoutMSRem--; + + if (!(TimeoutMSRem)) + return PIPE_RWSTREAM_Timeout; + } + + Pipe_Freeze(); + Pipe_SelectPipe(MSInterfaceInfo->Config.DataOUTPipeNumber); + Pipe_Unfreeze(); + + if (Pipe_IsStalled()) + { + USB_Host_ClearPipeStall(MSInterfaceInfo->Config.DataOUTPipeNumber); + + return PIPE_RWSTREAM_PipeStalled; + } + + Pipe_Freeze(); + Pipe_SelectPipe(MSInterfaceInfo->Config.DataINPipeNumber); + Pipe_Unfreeze(); + + if (Pipe_IsStalled()) + { + USB_Host_ClearPipeStall(MSInterfaceInfo->Config.DataINPipeNumber); + + return PIPE_RWSTREAM_PipeStalled; + } + + if (USB_HostState == HOST_STATE_Unattached) + return PIPE_RWSTREAM_DeviceDisconnected; + }; + + Pipe_SelectPipe(MSInterfaceInfo->Config.DataINPipeNumber); + Pipe_Freeze(); + + Pipe_SelectPipe(MSInterfaceInfo->Config.DataOUTPipeNumber); + Pipe_Freeze(); + + return PIPE_RWSTREAM_NoError; +} + +static uint8_t MS_Host_SendReceiveData(USB_ClassInfo_MS_Host_t* const MSInterfaceInfo, + MS_CommandBlockWrapper_t* const SCSICommandBlock, + void* BufferPtr) +{ + uint8_t ErrorCode = PIPE_RWSTREAM_NoError; + uint16_t BytesRem = SCSICommandBlock->DataTransferLength; + + if (SCSICommandBlock->Flags & COMMAND_DIRECTION_DATA_IN) + { + if ((ErrorCode = MS_Host_WaitForDataReceived(MSInterfaceInfo)) != PIPE_RWSTREAM_NoError) + { + Pipe_Freeze(); + return ErrorCode; + } + + Pipe_SelectPipe(MSInterfaceInfo->Config.DataINPipeNumber); + Pipe_Unfreeze(); + + if ((ErrorCode = Pipe_Read_Stream_LE(BufferPtr, BytesRem, NO_STREAM_CALLBACK)) != PIPE_RWSTREAM_NoError) + return ErrorCode; + + Pipe_ClearIN(); + } + else + { + Pipe_SelectPipe(MSInterfaceInfo->Config.DataOUTPipeNumber); + Pipe_Unfreeze(); + + if ((ErrorCode = Pipe_Write_Stream_LE(BufferPtr, BytesRem, NO_STREAM_CALLBACK)) != PIPE_RWSTREAM_NoError) + return ErrorCode; + + Pipe_ClearOUT(); + + while (!(Pipe_IsOUTReady())) + { + if (USB_HostState == HOST_STATE_Unattached) + return PIPE_RWSTREAM_DeviceDisconnected; + } + } + + Pipe_Freeze(); + + return ErrorCode; +} + +static uint8_t MS_Host_GetReturnedStatus(USB_ClassInfo_MS_Host_t* const MSInterfaceInfo, + MS_CommandStatusWrapper_t* const SCSICommandStatus) +{ + uint8_t ErrorCode = PIPE_RWSTREAM_NoError; + + if ((ErrorCode = MS_Host_WaitForDataReceived(MSInterfaceInfo)) != PIPE_RWSTREAM_NoError) + return ErrorCode; + + Pipe_SelectPipe(MSInterfaceInfo->Config.DataINPipeNumber); + Pipe_Unfreeze(); + + if ((ErrorCode = Pipe_Read_Stream_LE(SCSICommandStatus, sizeof(MS_CommandStatusWrapper_t), + NO_STREAM_CALLBACK)) != PIPE_RWSTREAM_NoError) + { + return ErrorCode; + } + + Pipe_ClearIN(); + Pipe_Freeze(); + + if (SCSICommandStatus->Status != SCSI_Command_Pass) + ErrorCode = MS_ERROR_LOGICAL_CMD_FAILED; + + return ErrorCode; +} + +uint8_t MS_Host_ResetMSInterface(USB_ClassInfo_MS_Host_t* const MSInterfaceInfo) +{ + USB_ControlRequest = (USB_Request_Header_t) + { + .bmRequestType = (REQDIR_HOSTTODEVICE | REQTYPE_CLASS | REQREC_INTERFACE), + .bRequest = REQ_MassStorageReset, + .wValue = 0, + .wIndex = MSInterfaceInfo->State.InterfaceNumber, + .wLength = 0, + }; + + Pipe_SelectPipe(PIPE_CONTROLPIPE); + + return USB_Host_SendControlRequest(NULL); +} + +uint8_t MS_Host_GetMaxLUN(USB_ClassInfo_MS_Host_t* const MSInterfaceInfo, + uint8_t* const MaxLUNIndex) +{ + uint8_t ErrorCode = HOST_SENDCONTROL_Successful; + + USB_ControlRequest = (USB_Request_Header_t) + { + .bmRequestType = (REQDIR_DEVICETOHOST | REQTYPE_CLASS | REQREC_INTERFACE), + .bRequest = REQ_GetMaxLUN, + .wValue = 0, + .wIndex = MSInterfaceInfo->State.InterfaceNumber, + .wLength = 1, + }; + + Pipe_SelectPipe(PIPE_CONTROLPIPE); + + if ((ErrorCode = USB_Host_SendControlRequest(MaxLUNIndex)) != HOST_SENDCONTROL_Successful) + { + *MaxLUNIndex = 0; + ErrorCode = HOST_SENDCONTROL_Successful; + } + + return ErrorCode; +} + +uint8_t MS_Host_GetInquiryData(USB_ClassInfo_MS_Host_t* const MSInterfaceInfo, + const uint8_t LUNIndex, + SCSI_Inquiry_Response_t* const InquiryData) +{ + if ((USB_HostState != HOST_STATE_Configured) || !(MSInterfaceInfo->State.IsActive)) + return HOST_SENDCONTROL_DeviceDisconnected; + + uint8_t ErrorCode; + + MS_CommandBlockWrapper_t SCSICommandBlock = (MS_CommandBlockWrapper_t) + { + .DataTransferLength = sizeof(SCSI_Inquiry_Response_t), + .Flags = COMMAND_DIRECTION_DATA_IN, + .LUN = LUNIndex, + .SCSICommandLength = 6, + .SCSICommandData = + { + SCSI_CMD_INQUIRY, + 0x00, // Reserved + 0x00, // Reserved + 0x00, // Reserved + sizeof(SCSI_Inquiry_Response_t), // Allocation Length + 0x00 // Unused (control) + } + }; + + MS_CommandStatusWrapper_t SCSICommandStatus; + + if ((ErrorCode = MS_Host_SendCommand(MSInterfaceInfo, &SCSICommandBlock, InquiryData)) != PIPE_RWSTREAM_NoError) + return ErrorCode; + + if ((ErrorCode = MS_Host_GetReturnedStatus(MSInterfaceInfo, &SCSICommandStatus)) != PIPE_RWSTREAM_NoError) + return ErrorCode; + + return PIPE_RWSTREAM_NoError; +} + +uint8_t MS_Host_TestUnitReady(USB_ClassInfo_MS_Host_t* const MSInterfaceInfo, + const uint8_t LUNIndex) +{ + if ((USB_HostState != HOST_STATE_Configured) || !(MSInterfaceInfo->State.IsActive)) + return HOST_SENDCONTROL_DeviceDisconnected; + + uint8_t ErrorCode; + + MS_CommandBlockWrapper_t SCSICommandBlock = (MS_CommandBlockWrapper_t) + { + .DataTransferLength = 0, + .Flags = COMMAND_DIRECTION_DATA_IN, + .LUN = LUNIndex, + .SCSICommandLength = 6, + .SCSICommandData = + { + SCSI_CMD_TEST_UNIT_READY, + 0x00, // Reserved + 0x00, // Reserved + 0x00, // Reserved + 0x00, // Reserved + 0x00 // Unused (control) + } + }; + + MS_CommandStatusWrapper_t SCSICommandStatus; + + if ((ErrorCode = MS_Host_SendCommand(MSInterfaceInfo, &SCSICommandBlock, NULL)) != PIPE_RWSTREAM_NoError) + return ErrorCode; + + if ((ErrorCode = MS_Host_GetReturnedStatus(MSInterfaceInfo, &SCSICommandStatus)) != PIPE_RWSTREAM_NoError) + return ErrorCode; + + return PIPE_RWSTREAM_NoError; +} + +uint8_t MS_Host_ReadDeviceCapacity(USB_ClassInfo_MS_Host_t* const MSInterfaceInfo, + const uint8_t LUNIndex, + SCSI_Capacity_t* const DeviceCapacity) +{ + if ((USB_HostState != HOST_STATE_Configured) || !(MSInterfaceInfo->State.IsActive)) + return HOST_SENDCONTROL_DeviceDisconnected; + + uint8_t ErrorCode; + + MS_CommandBlockWrapper_t SCSICommandBlock = (MS_CommandBlockWrapper_t) + { + .DataTransferLength = sizeof(SCSI_Capacity_t), + .Flags = COMMAND_DIRECTION_DATA_IN, + .LUN = LUNIndex, + .SCSICommandLength = 10, + .SCSICommandData = + { + SCSI_CMD_READ_CAPACITY_10, + 0x00, // Reserved + 0x00, // MSB of Logical block address + 0x00, + 0x00, + 0x00, // LSB of Logical block address + 0x00, // Reserved + 0x00, // Reserved + 0x00, // Partial Medium Indicator + 0x00 // Unused (control) + } + }; + + MS_CommandStatusWrapper_t SCSICommandStatus; + + if ((ErrorCode = MS_Host_SendCommand(MSInterfaceInfo, &SCSICommandBlock, DeviceCapacity)) != PIPE_RWSTREAM_NoError) + return ErrorCode; + + SwapEndian_n(&DeviceCapacity->Blocks, sizeof(DeviceCapacity->Blocks)); + SwapEndian_n(&DeviceCapacity->BlockSize, sizeof(DeviceCapacity->BlockSize)); + + if ((ErrorCode = MS_Host_GetReturnedStatus(MSInterfaceInfo, &SCSICommandStatus)) != PIPE_RWSTREAM_NoError) + return ErrorCode; + + return PIPE_RWSTREAM_NoError; +} + +uint8_t MS_Host_RequestSense(USB_ClassInfo_MS_Host_t* const MSInterfaceInfo, + const uint8_t LUNIndex, + SCSI_Request_Sense_Response_t* const SenseData) +{ + if ((USB_HostState != HOST_STATE_Configured) || !(MSInterfaceInfo->State.IsActive)) + return HOST_SENDCONTROL_DeviceDisconnected; + + uint8_t ErrorCode; + + MS_CommandBlockWrapper_t SCSICommandBlock = (MS_CommandBlockWrapper_t) + { + .DataTransferLength = sizeof(SCSI_Request_Sense_Response_t), + .Flags = COMMAND_DIRECTION_DATA_IN, + .LUN = LUNIndex, + .SCSICommandLength = 6, + .SCSICommandData = + { + SCSI_CMD_REQUEST_SENSE, + 0x00, // Reserved + 0x00, // Reserved + 0x00, // Reserved + sizeof(SCSI_Request_Sense_Response_t), // Allocation Length + 0x00 // Unused (control) + } + }; + + MS_CommandStatusWrapper_t SCSICommandStatus; + + if ((ErrorCode = MS_Host_SendCommand(MSInterfaceInfo, &SCSICommandBlock, SenseData)) != PIPE_RWSTREAM_NoError) + return ErrorCode; + + if ((ErrorCode = MS_Host_GetReturnedStatus(MSInterfaceInfo, &SCSICommandStatus)) != PIPE_RWSTREAM_NoError) + return ErrorCode; + + return PIPE_RWSTREAM_NoError; +} + +uint8_t MS_Host_PreventAllowMediumRemoval(USB_ClassInfo_MS_Host_t* const MSInterfaceInfo, + const uint8_t LUNIndex, + const bool PreventRemoval) +{ + if ((USB_HostState != HOST_STATE_Configured) || !(MSInterfaceInfo->State.IsActive)) + return HOST_SENDCONTROL_DeviceDisconnected; + + uint8_t ErrorCode; + + MS_CommandBlockWrapper_t SCSICommandBlock = (MS_CommandBlockWrapper_t) + { + .DataTransferLength = 0, + .Flags = COMMAND_DIRECTION_DATA_OUT, + .LUN = LUNIndex, + .SCSICommandLength = 6, + .SCSICommandData = + { + SCSI_CMD_PREVENT_ALLOW_MEDIUM_REMOVAL, + 0x00, // Reserved + 0x00, // Reserved + PreventRemoval, // Prevent flag + 0x00, // Reserved + 0x00 // Unused (control) + } + }; + + MS_CommandStatusWrapper_t SCSICommandStatus; + + if ((ErrorCode = MS_Host_SendCommand(MSInterfaceInfo, &SCSICommandBlock, NULL)) != PIPE_RWSTREAM_NoError) + return ErrorCode; + + if ((ErrorCode = MS_Host_GetReturnedStatus(MSInterfaceInfo, &SCSICommandStatus)) != PIPE_RWSTREAM_NoError) + return ErrorCode; + + return PIPE_RWSTREAM_NoError; +} + +uint8_t MS_Host_ReadDeviceBlocks(USB_ClassInfo_MS_Host_t* const MSInterfaceInfo, + const uint8_t LUNIndex, + const uint32_t BlockAddress, + const uint8_t Blocks, + const uint16_t BlockSize, + void* BlockBuffer) +{ + if ((USB_HostState != HOST_STATE_Configured) || !(MSInterfaceInfo->State.IsActive)) + return HOST_SENDCONTROL_DeviceDisconnected; + + uint8_t ErrorCode; + + MS_CommandBlockWrapper_t SCSICommandBlock = (MS_CommandBlockWrapper_t) + { + .DataTransferLength = ((uint32_t)Blocks * BlockSize), + .Flags = COMMAND_DIRECTION_DATA_IN, + .LUN = LUNIndex, + .SCSICommandLength = 10, + .SCSICommandData = + { + SCSI_CMD_READ_10, + 0x00, // Unused (control bits, all off) + (BlockAddress >> 24), // MSB of Block Address + (BlockAddress >> 16), + (BlockAddress >> 8), + (BlockAddress & 0xFF), // LSB of Block Address + 0x00, // Reserved + 0x00, // MSB of Total Blocks to Read + Blocks, // LSB of Total Blocks to Read + 0x00 // Unused (control) + } + }; + + MS_CommandStatusWrapper_t SCSICommandStatus; + + if ((ErrorCode = MS_Host_SendCommand(MSInterfaceInfo, &SCSICommandBlock, BlockBuffer)) != PIPE_RWSTREAM_NoError) + return ErrorCode; + + if ((ErrorCode = MS_Host_GetReturnedStatus(MSInterfaceInfo, &SCSICommandStatus)) != PIPE_RWSTREAM_NoError) + return ErrorCode; + + return PIPE_RWSTREAM_NoError; +} + +uint8_t MS_Host_WriteDeviceBlocks(USB_ClassInfo_MS_Host_t* const MSInterfaceInfo, + const uint8_t LUNIndex, + const uint32_t BlockAddress, + const uint8_t Blocks, + const uint16_t BlockSize, + const void* BlockBuffer) +{ + if ((USB_HostState != HOST_STATE_Configured) || !(MSInterfaceInfo->State.IsActive)) + return HOST_SENDCONTROL_DeviceDisconnected; + + uint8_t ErrorCode; + + MS_CommandBlockWrapper_t SCSICommandBlock = (MS_CommandBlockWrapper_t) + { + .DataTransferLength = ((uint32_t)Blocks * BlockSize), + .Flags = COMMAND_DIRECTION_DATA_OUT, + .LUN = LUNIndex, + .SCSICommandLength = 10, + .SCSICommandData = + { + SCSI_CMD_WRITE_10, + 0x00, // Unused (control bits, all off) + (BlockAddress >> 24), // MSB of Block Address + (BlockAddress >> 16), + (BlockAddress >> 8), + (BlockAddress & 0xFF), // LSB of Block Address + 0x00, // Reserved + 0x00, // MSB of Total Blocks to Write + Blocks, // LSB of Total Blocks to Write + 0x00 // Unused (control) + } + }; + + MS_CommandStatusWrapper_t SCSICommandStatus; + + if ((ErrorCode = MS_Host_SendCommand(MSInterfaceInfo, &SCSICommandBlock, BlockBuffer)) != PIPE_RWSTREAM_NoError) + return ErrorCode; + + if ((ErrorCode = MS_Host_GetReturnedStatus(MSInterfaceInfo, &SCSICommandStatus)) != PIPE_RWSTREAM_NoError) + return ErrorCode; + + return PIPE_RWSTREAM_NoError; +} + +#endif diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/MassStorage.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/MassStorage.h new file mode 100644 index 0000000000..a6b32c7918 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/MassStorage.h @@ -0,0 +1,352 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief Host mode driver for the library USB Mass Storage Class driver. + * + * Host mode driver for the library USB Mass Storage Class driver. + * + * \note This file should not be included directly. It is automatically included as needed by the class driver + * dispatch header located in LUFA/Drivers/USB/Class/MassStorage.h. + */ + +/** \ingroup Group_USBClassMS + * @defgroup Group_USBClassMassStorageHost Mass Storage Class Host Mode Driver + * + * \section Sec_Dependencies Module Source Dependencies + * The following files must be built with any user project that uses this module: + * - LUFA/Drivers/USB/Class/Host/MassStorage.c (Makefile source module name: LUFA_SRC_USBCLASS) + * + * \section Module Description + * Host Mode USB Class driver framework interface, for the Mass Storage USB Class driver. + * + * @{ + */ + +#ifndef __MS_CLASS_HOST_H__ +#define __MS_CLASS_HOST_H__ + + /* Includes: */ + #include "../../USB.h" + #include "../Common/MassStorage.h" + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_MS_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/Class/MassStorage.h instead. + #endif + + /* Public Interface - May be used in end-application: */ + /* Macros: */ + /** Error code for some Mass Storage Host functions, indicating a logical (and not hardware) error. */ + #define MS_ERROR_LOGICAL_CMD_FAILED 0x80 + + /* Type Defines: */ + /** \brief Mass Storage Class Host Mode Configuration and State Structure. + * + * Class state structure. An instance of this structure should be made within the user application, + * and passed to each of the Mass Storage class driver functions as the MSInterfaceInfo parameter. This + * stores each Mass Storage interface's configuration and state information. + */ + typedef struct + { + const struct + { + uint8_t DataINPipeNumber; /**< Pipe number of the Mass Storage interface's IN data pipe. */ + bool DataINPipeDoubleBank; /**< Indicates if the Mass Storage interface's IN data pipe should use double banking. */ + + uint8_t DataOUTPipeNumber; /**< Pipe number of the Mass Storage interface's OUT data pipe. */ + bool DataOUTPipeDoubleBank; /**< Indicates if the Mass Storage interface's OUT data pipe should use double banking. */ + } Config; /**< Config data for the USB class interface within the device. All elements in this section + * must be set or the interface will fail to enumerate and operate correctly. + */ + struct + { + bool IsActive; /**< Indicates if the current interface instance is connected to an attached device, valid + * after \ref MS_Host_ConfigurePipes() is called and the Host state machine is in the + * Configured state. + */ + uint8_t InterfaceNumber; /**< Interface index of the Mass Storage interface within the attached device. */ + + uint16_t DataINPipeSize; /**< Size in bytes of the Mass Storage interface's IN data pipe. */ + uint16_t DataOUTPipeSize; /**< Size in bytes of the Mass Storage interface's OUT data pipe. */ + + uint32_t TransactionTag; /**< Current transaction tag for data synchronizing of packets. */ + } State; /**< State data for the USB class interface within the device. All elements in this section + * may be set to initial values, but may also be ignored to default to sane values when + * the interface is enumerated. + */ + } USB_ClassInfo_MS_Host_t; + + /** \brief SCSI Device LUN Capacity Structure. + * + * SCSI capacity structure, to hold the total capacity of the device in both the number + * of blocks in the current LUN, and the size of each block. This structure is filled by + * the device when the \ref MS_Host_ReadDeviceCapacity() function is called. + */ + typedef struct + { + uint32_t Blocks; /**< Number of blocks in the addressed LUN of the device. */ + uint32_t BlockSize; /**< Number of bytes in each block in the addressed LUN. */ + } SCSI_Capacity_t; + + /* Enums: */ + enum MSHost_EnumerationFailure_ErrorCodes_t + { + MS_ENUMERROR_NoError = 0, /**< Configuration Descriptor was processed successfully. */ + MS_ENUMERROR_InvalidConfigDescriptor = 1, /**< The device returned an invalid Configuration Descriptor. */ + MS_ENUMERROR_NoMSInterfaceFound = 2, /**< A compatible Mass Storage interface was not found in the device's Configuration Descriptor. */ + MS_ENUMERROR_EndpointsNotFound = 3, /**< Compatible Mass Storage endpoints were not found in the device's interfaces. */ + }; + + /* Function Prototypes: */ + /** Host interface configuration routine, to configure a given Mass Storage host interface instance using the + * Configuration Descriptor read from an attached USB device. This function automatically updates the given Mass + * Storage Host instance's state values and configures the pipes required to communicate with the interface if it + * is found within the device. This should be called once after the stack has enumerated the attached device, while + * the host state machine is in the Addressed state. + * + * \param[in,out] MSInterfaceInfo Pointer to a structure containing an MS Class host configuration and state. + * \param[in] ConfigDescriptorSize Length of the attached device's Configuration Descriptor. + * \param[in] DeviceConfigDescriptor Pointer to a buffer containing the attached device's Configuration Descriptor. + * + * \return A value from the \ref MSHost_EnumerationFailure_ErrorCodes_t enum. + */ + uint8_t MS_Host_ConfigurePipes(USB_ClassInfo_MS_Host_t* const MSInterfaceInfo, + uint16_t ConfigDescriptorSize, + void* DeviceConfigDescriptor) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(3); + + /** Sends a MASS STORAGE RESET control request to the attached device, resetting the Mass Storage Interface + * and readying it for the next Mass Storage command. + * + * \param[in,out] MSInterfaceInfo Pointer to a structure containing a MS Class host configuration and state. + * + * \return A value from the \ref USB_Host_SendControlErrorCodes_t enum. + */ + uint8_t MS_Host_ResetMSInterface(USB_ClassInfo_MS_Host_t* const MSInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** Sends a GET MAX LUN control request to the attached device, retrieving the index of the highest LUN (Logical + * UNit, a logical drive) in the device. This value can then be used in the other functions of the Mass Storage + * Host mode Class driver to address a specific LUN within the device. + * + * \note Some devices do not support this request, and will STALL it when issued. To get around this, + * on unsupported devices the max LUN index will be reported as zero and no error will be returned + * if the device STALLs the request. + * + * \param[in,out] MSInterfaceInfo Pointer to a structure containing a MS Class host configuration and state. + * \param[out] MaxLUNIndex Pointer to a location where the highest LUN index value should be stored. + * + * \return A value from the \ref USB_Host_SendControlErrorCodes_t enum. + */ + uint8_t MS_Host_GetMaxLUN(USB_ClassInfo_MS_Host_t* const MSInterfaceInfo, + uint8_t* const MaxLUNIndex) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(2); + + /** Retrieves the Mass Storage device's inquiry data for the specified LUN, indicating the device characteristics and + * properties. + * + * \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the + * call will fail. + * + * \param[in,out] MSInterfaceInfo Pointer to a structure containing a MS Class host configuration and state. + * \param[in] LUNIndex LUN index within the device the command is being issued to. + * \param[out] InquiryData Location where the read inquiry data should be stored. + * + * \return A value from the \ref Pipe_Stream_RW_ErrorCodes_t enum or MS_ERROR_LOGICAL_CMD_FAILED. + */ + uint8_t MS_Host_GetInquiryData(USB_ClassInfo_MS_Host_t* const MSInterfaceInfo, + const uint8_t LUNIndex, + SCSI_Inquiry_Response_t* const InquiryData) ATTR_NON_NULL_PTR_ARG(1) + ATTR_NON_NULL_PTR_ARG(3); + + /** Sends a TEST UNIT READY command to the device, to determine if it is ready to accept other SCSI commands. + * + * \param[in,out] MSInterfaceInfo Pointer to a structure containing a MS Class host configuration and state. + * \param[in] LUNIndex LUN index within the device the command is being issued to. + * + * \return A value from the \ref Pipe_Stream_RW_ErrorCodes_t enum or MS_ERROR_LOGICAL_CMD_FAILED if not ready. + */ + uint8_t MS_Host_TestUnitReady(USB_ClassInfo_MS_Host_t* const MSInterfaceInfo, + const uint8_t LUNIndex) ATTR_NON_NULL_PTR_ARG(1); + + /** Retrieves the total capacity of the attached USB Mass Storage device, in blocks, and block size. + * + * \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the + * call will fail. + * + * \param[in,out] MSInterfaceInfo Pointer to a structure containing a MS Class host configuration and state. + * \param[in] LUNIndex LUN index within the device the command is being issued to. + * \param[out] DeviceCapacity Pointer to the location where the capacity information should be stored. + * + * \return A value from the \ref Pipe_Stream_RW_ErrorCodes_t enum or MS_ERROR_LOGICAL_CMD_FAILED if not ready. + */ + uint8_t MS_Host_ReadDeviceCapacity(USB_ClassInfo_MS_Host_t* const MSInterfaceInfo, + const uint8_t LUNIndex, + SCSI_Capacity_t* const DeviceCapacity) ATTR_NON_NULL_PTR_ARG(1) + ATTR_NON_NULL_PTR_ARG(3); + + /** Retrieves the device sense data, indicating the current device state and error codes for the previously + * issued command. + * + * \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the + * call will fail. + * + * \param[in,out] MSInterfaceInfo Pointer to a structure containing a MS Class host configuration and state. + * \param[in] LUNIndex LUN index within the device the command is being issued to. + * \param[out] SenseData Pointer to the location where the sense information should be stored. + * + * \return A value from the \ref Pipe_Stream_RW_ErrorCodes_t enum or MS_ERROR_LOGICAL_CMD_FAILED if not ready. + */ + uint8_t MS_Host_RequestSense(USB_ClassInfo_MS_Host_t* const MSInterfaceInfo, + const uint8_t LUNIndex, + SCSI_Request_Sense_Response_t* const SenseData) ATTR_NON_NULL_PTR_ARG(1) + ATTR_NON_NULL_PTR_ARG(3); + + /** Issues a PREVENT MEDIUM REMOVAL command, to logically (or, depending on the type of device, physically) lock + * the device from removal so that blocks of data on the medium can be read or altered. + * + * \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the + * call will fail. + * + * \param[in,out] MSInterfaceInfo Pointer to a structure containing a MS Class host configuration and state. + * \param[in] LUNIndex LUN index within the device the command is being issued to. + * \param[in] PreventRemoval Boolean true if the device should be locked from removal, false otherwise. + * + * \return A value from the \ref Pipe_Stream_RW_ErrorCodes_t enum or MS_ERROR_LOGICAL_CMD_FAILED if not ready. + */ + uint8_t MS_Host_PreventAllowMediumRemoval(USB_ClassInfo_MS_Host_t* const MSInterfaceInfo, + const uint8_t LUNIndex, + const bool PreventRemoval) ATTR_NON_NULL_PTR_ARG(1); + + /** Reads blocks of data from the attached Mass Storage device's medium. + * + * \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the + * call will fail. + * + * \param[in,out] MSInterfaceInfo Pointer to a structure containing a MS Class host configuration and state. + * \param[in] LUNIndex LUN index within the device the command is being issued to. + * \param[in] BlockAddress Starting block address within the device to read from. + * \param[in] Blocks Total number of blocks to read. + * \param[in] BlockSize Size in bytes of each block within the device. + * \param[out] BlockBuffer Pointer to where the read data from the device should be stored. + * + * \return A value from the \ref Pipe_Stream_RW_ErrorCodes_t enum or MS_ERROR_LOGICAL_CMD_FAILED if not ready. + */ + uint8_t MS_Host_ReadDeviceBlocks(USB_ClassInfo_MS_Host_t* const MSInterfaceInfo, + const uint8_t LUNIndex, + const uint32_t BlockAddress, + const uint8_t Blocks, + const uint16_t BlockSize, + void* BlockBuffer) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(6); + + /** Writes blocks of data to the attached Mass Storage device's medium. + * + * \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the + * call will fail. + * + * \param[in,out] MSInterfaceInfo Pointer to a structure containing a MS Class host configuration and state. + * \param[in] LUNIndex LUN index within the device the command is being issued to. + * \param[in] BlockAddress Starting block address within the device to write to. + * \param[in] Blocks Total number of blocks to read. + * \param[in] BlockSize Size in bytes of each block within the device. + * \param[in] BlockBuffer Pointer to where the data to write should be sourced from. + * + * \return A value from the \ref Pipe_Stream_RW_ErrorCodes_t enum or MS_ERROR_LOGICAL_CMD_FAILED if not ready. + */ + uint8_t MS_Host_WriteDeviceBlocks(USB_ClassInfo_MS_Host_t* const MSInterfaceInfo, + const uint8_t LUNIndex, + const uint32_t BlockAddress, + const uint8_t Blocks, + const uint16_t BlockSize, + const void* BlockBuffer) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(6); + + /* Inline Functions: */ + /** General management task for a given Mass Storage host class interface, required for the correct operation of + * the interface. This should be called frequently in the main program loop, before the master USB management task + * \ref USB_USBTask(). + * + * \param[in,out] MSInterfaceInfo Pointer to a structure containing an MS Class host configuration and state. + */ + static inline void MS_Host_USBTask(USB_ClassInfo_MS_Host_t* const MSInterfaceInfo); + static inline void MS_Host_USBTask(USB_ClassInfo_MS_Host_t* const MSInterfaceInfo) + { + (void)MSInterfaceInfo; + } + + /* Private Interface - For use in library only: */ + #if !defined(__DOXYGEN__) + /* Macros: */ + #define MASS_STORE_CLASS 0x08 + #define MASS_STORE_SUBCLASS 0x06 + #define MASS_STORE_PROTOCOL 0x50 + + #define REQ_MassStorageReset 0xFF + #define REQ_GetMaxLUN 0xFE + + #define CBW_SIGNATURE 0x43425355UL + #define CSW_SIGNATURE 0x53425355UL + + #define COMMAND_DIRECTION_DATA_OUT (0 << 7) + #define COMMAND_DIRECTION_DATA_IN (1 << 7) + + #define COMMAND_DATA_TIMEOUT_MS 10000 + + #define MS_FOUND_DATAPIPE_IN (1 << 0) + #define MS_FOUND_DATAPIPE_OUT (1 << 1) + + /* Function Prototypes: */ + #if defined(__INCLUDE_FROM_MS_CLASS_HOST_C) + static uint8_t DCOMP_MS_NextMSInterface(void* const CurrentDescriptor) ATTR_NON_NULL_PTR_ARG(1); + static uint8_t DCOMP_MS_NextMSInterfaceEndpoint(void* const CurrentDescriptor) ATTR_NON_NULL_PTR_ARG(1); + + static uint8_t MS_Host_SendCommand(USB_ClassInfo_MS_Host_t* const MSInterfaceInfo, + MS_CommandBlockWrapper_t* const SCSICommandBlock, + const void* const BufferPtr) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(2); + static uint8_t MS_Host_WaitForDataReceived(USB_ClassInfo_MS_Host_t* const MSInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + static uint8_t MS_Host_SendReceiveData(USB_ClassInfo_MS_Host_t* const MSInterfaceInfo, + MS_CommandBlockWrapper_t* const SCSICommandBlock, + void* BufferPtr) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(2); + static uint8_t MS_Host_GetReturnedStatus(USB_ClassInfo_MS_Host_t* const MSInterfaceInfo, + MS_CommandStatusWrapper_t* const SCSICommandStatus) + ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(2); + #endif + #endif + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/Printer.c b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/Printer.c new file mode 100644 index 0000000000..31ba6c61b2 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/Printer.c @@ -0,0 +1,256 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +#define __INCLUDE_FROM_USB_DRIVER +#include "../../HighLevel/USBMode.h" +#if defined(USB_CAN_BE_HOST) + +#define __INCLUDE_FROM_PRINTER_CLASS_HOST_C +#define __INCLUDE_FROM_PRINTER_DRIVER +#include "Printer.h" + +uint8_t PRNT_Host_ConfigurePipes(USB_ClassInfo_PRNT_Host_t* const PRNTInterfaceInfo, + uint16_t ConfigDescriptorSize, + void* DeviceConfigDescriptor) +{ + uint8_t FoundEndpoints = 0; + + memset(&PRNTInterfaceInfo->State, 0x00, sizeof(PRNTInterfaceInfo->State)); + + if (DESCRIPTOR_TYPE(DeviceConfigDescriptor) != DTYPE_Configuration) + return PRNT_ENUMERROR_InvalidConfigDescriptor; + + if (USB_GetNextDescriptorComp(&ConfigDescriptorSize, &DeviceConfigDescriptor, + DCOMP_PRNT_NextPRNTInterface) != DESCRIPTOR_SEARCH_COMP_Found) + { + return PRNT_ENUMERROR_NoPrinterInterfaceFound; + } + + USB_Descriptor_Interface_t* PrinterInterface = DESCRIPTOR_PCAST(DeviceConfigDescriptor, USB_Descriptor_Interface_t); + + PRNTInterfaceInfo->State.InterfaceNumber = PrinterInterface->InterfaceNumber; + PRNTInterfaceInfo->State.AlternateSetting = PrinterInterface->AlternateSetting; + + while (FoundEndpoints != (PRNT_FOUND_DATAPIPE_IN | PRNT_FOUND_DATAPIPE_OUT)) + { + if (USB_GetNextDescriptorComp(&ConfigDescriptorSize, &DeviceConfigDescriptor, + DCOMP_PRNT_NextPRNTInterfaceEndpoint) != DESCRIPTOR_SEARCH_COMP_Found) + { + return PRNT_ENUMERROR_EndpointsNotFound; + } + + USB_Descriptor_Endpoint_t* EndpointData = DESCRIPTOR_PCAST(DeviceConfigDescriptor, USB_Descriptor_Endpoint_t); + + if (EndpointData->EndpointAddress & ENDPOINT_DESCRIPTOR_DIR_IN) + { + Pipe_ConfigurePipe(PRNTInterfaceInfo->Config.DataINPipeNumber, EP_TYPE_BULK, PIPE_TOKEN_IN, + EndpointData->EndpointAddress, EndpointData->EndpointSize, + PRNTInterfaceInfo->Config.DataINPipeDoubleBank ? PIPE_BANK_DOUBLE : PIPE_BANK_SINGLE); + PRNTInterfaceInfo->State.DataINPipeSize = EndpointData->EndpointSize; + + FoundEndpoints |= PRNT_FOUND_DATAPIPE_IN; + } + else + { + Pipe_ConfigurePipe(PRNTInterfaceInfo->Config.DataOUTPipeNumber, EP_TYPE_BULK, PIPE_TOKEN_OUT, + EndpointData->EndpointAddress, EndpointData->EndpointSize, + PRNTInterfaceInfo->Config.DataOUTPipeDoubleBank ? PIPE_BANK_DOUBLE : PIPE_BANK_SINGLE); + PRNTInterfaceInfo->State.DataOUTPipeSize = EndpointData->EndpointSize; + + FoundEndpoints |= PRNT_FOUND_DATAPIPE_OUT; + } + } + + PRNTInterfaceInfo->State.IsActive = true; + return PRNT_ENUMERROR_NoError; +} + +static uint8_t DCOMP_PRNT_NextPRNTInterface(void* CurrentDescriptor) +{ + if (DESCRIPTOR_TYPE(CurrentDescriptor) == DTYPE_Interface) + { + if ((DESCRIPTOR_CAST(CurrentDescriptor, USB_Descriptor_Interface_t).Class == PRINTER_CLASS) && + (DESCRIPTOR_CAST(CurrentDescriptor, USB_Descriptor_Interface_t).SubClass == PRINTER_SUBCLASS) && + (DESCRIPTOR_CAST(CurrentDescriptor, USB_Descriptor_Interface_t).Protocol == PRINTER_PROTOCOL)) + { + return DESCRIPTOR_SEARCH_Found; + } + } + + return DESCRIPTOR_SEARCH_NotFound; +} + +static uint8_t DCOMP_PRNT_NextPRNTInterfaceEndpoint(void* CurrentDescriptor) +{ + if (DESCRIPTOR_TYPE(CurrentDescriptor) == DTYPE_Endpoint) + { + uint8_t EndpointType = (DESCRIPTOR_CAST(CurrentDescriptor, + USB_Descriptor_Endpoint_t).Attributes & EP_TYPE_MASK); + + if (EndpointType == EP_TYPE_BULK) + return DESCRIPTOR_SEARCH_Found; + } + else if (DESCRIPTOR_TYPE(CurrentDescriptor) == DTYPE_Interface) + { + return DESCRIPTOR_SEARCH_Fail; + } + + return DESCRIPTOR_SEARCH_NotFound; +} + +uint8_t PRNT_Host_SetBidirectionalMode(USB_ClassInfo_PRNT_Host_t* const PRNTInterfaceInfo) +{ + if (PRNTInterfaceInfo->State.AlternateSetting) + { + uint8_t ErrorCode; + + USB_ControlRequest = (USB_Request_Header_t) + { + .bmRequestType = (REQDIR_HOSTTODEVICE | REQTYPE_STANDARD | REQREC_INTERFACE), + .bRequest = REQ_SetInterface, + .wValue = PRNTInterfaceInfo->State.AlternateSetting, + .wIndex = PRNTInterfaceInfo->State.InterfaceNumber, + .wLength = 0, + }; + + Pipe_SelectPipe(PIPE_CONTROLPIPE); + + if ((ErrorCode = USB_Host_SendControlRequest(NULL)) != HOST_SENDCONTROL_Successful) + return ErrorCode; + } + + return HOST_SENDCONTROL_Successful; +} + +uint8_t PRNT_Host_GetPortStatus(USB_ClassInfo_PRNT_Host_t* const PRNTInterfaceInfo, + uint8_t* const PortStatus) +{ + USB_ControlRequest = (USB_Request_Header_t) + { + .bmRequestType = (REQDIR_DEVICETOHOST | REQTYPE_CLASS | REQREC_INTERFACE), + .bRequest = REQ_GetPortStatus, + .wValue = 0, + .wIndex = PRNTInterfaceInfo->State.InterfaceNumber, + .wLength = sizeof(uint8_t), + }; + + Pipe_SelectPipe(PIPE_CONTROLPIPE); + + return USB_Host_SendControlRequest(PortStatus); +} + +uint8_t PRNT_Host_SoftReset(USB_ClassInfo_PRNT_Host_t* const PRNTInterfaceInfo) +{ + USB_ControlRequest = (USB_Request_Header_t) + { + .bmRequestType = (REQDIR_HOSTTODEVICE | REQTYPE_CLASS | REQREC_INTERFACE), + .bRequest = REQ_SoftReset, + .wValue = 0, + .wIndex = PRNTInterfaceInfo->State.InterfaceNumber, + .wLength = 0, + }; + + Pipe_SelectPipe(PIPE_CONTROLPIPE); + + return USB_Host_SendControlRequest(NULL); +} + +uint8_t PRNT_Host_SendData(USB_ClassInfo_PRNT_Host_t* const PRNTInterfaceInfo, + void* PrinterCommands, + const uint16_t CommandSize) +{ + uint8_t ErrorCode; + + if ((USB_HostState != HOST_STATE_Configured) || !(PRNTInterfaceInfo->State.IsActive)) + return PIPE_RWSTREAM_DeviceDisconnected; + + Pipe_SelectPipe(PRNTInterfaceInfo->Config.DataOUTPipeNumber); + Pipe_Unfreeze(); + + if ((ErrorCode = Pipe_Write_Stream_LE(PrinterCommands, CommandSize, NO_STREAM_CALLBACK)) != PIPE_RWSTREAM_NoError) + return ErrorCode; + + Pipe_ClearOUT(); + while (!(Pipe_IsOUTReady())) + { + if (USB_HostState == HOST_STATE_Unattached) + return PIPE_RWSTREAM_DeviceDisconnected; + } + + Pipe_Freeze(); + + return PIPE_RWSTREAM_NoError; +} + +uint8_t PRNT_Host_GetDeviceID(USB_ClassInfo_PRNT_Host_t* const PRNTInterfaceInfo, + char* const DeviceIDString, + const uint16_t BufferSize) +{ + uint8_t ErrorCode = HOST_SENDCONTROL_Successful; + uint16_t DeviceIDStringLength = 0; + + USB_ControlRequest = (USB_Request_Header_t) + { + .bmRequestType = (REQDIR_DEVICETOHOST | REQTYPE_CLASS | REQREC_INTERFACE), + .bRequest = REQ_GetDeviceID, + .wValue = 0, + .wIndex = PRNTInterfaceInfo->State.InterfaceNumber, + .wLength = sizeof(DeviceIDStringLength), + }; + + Pipe_SelectPipe(PIPE_CONTROLPIPE); + + if ((ErrorCode = USB_Host_SendControlRequest(&DeviceIDStringLength)) != HOST_SENDCONTROL_Successful) + return ErrorCode; + + if (!(DeviceIDStringLength)) + { + DeviceIDString[0] = 0x00; + return HOST_SENDCONTROL_Successful; + } + + DeviceIDStringLength = SwapEndian_16(DeviceIDStringLength); + + if (DeviceIDStringLength > BufferSize) + DeviceIDStringLength = BufferSize; + + USB_ControlRequest.wLength = DeviceIDStringLength; + + if ((ErrorCode = USB_Host_SendControlRequest(DeviceIDString)) != HOST_SENDCONTROL_Successful) + return ErrorCode; + + memmove(&DeviceIDString[0], &DeviceIDString[2], DeviceIDStringLength - 2); + + DeviceIDString[DeviceIDStringLength - 2] = 0x00; + + return HOST_SENDCONTROL_Successful; +} + +#endif diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/Printer.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/Printer.h new file mode 100644 index 0000000000..6bb6648a19 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/Printer.h @@ -0,0 +1,237 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief Host mode driver for the library USB Printer Class driver. + * + * Host mode driver for the library USB Printer Class driver. + * + * \note This file should not be included directly. It is automatically included as needed by the class driver + * dispatch header located in LUFA/Drivers/USB/Class/Printer.h. + */ + +/** \ingroup Group_USBClassPrinter + * @defgroup Group_USBClassPrinterHost Printer Class Host Mode Driver + * + * \section Sec_Dependencies Module Source Dependencies + * The following files must be built with any user project that uses this module: + * - LUFA/Drivers/USB/Class/Host/Printer.c (Makefile source module name: LUFA_SRC_USBCLASS) + * + * \section Module Description + * Host Mode USB Class driver framework interface, for the Printer USB Class driver. + * + * @{ + */ + +#ifndef __PRINTER_CLASS_HOST_H__ +#define __PRINTER_CLASS_HOST_H__ + + /* Includes: */ + #include "../../USB.h" + #include "../Common/Printer.h" + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_PRINTER_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/Class/Printer.h instead. + #endif + + /* Public Interface - May be used in end-application: */ + /* Type Defines: */ + /** \brief Printer Class Host Mode Configuration and State Structure. + * + * Class state structure. An instance of this structure should be made within the user application, + * and passed to each of the Printer class driver functions as the PRNTInterfaceInfo parameter. This + * stores each Printer interface's configuration and state information. + */ + typedef struct + { + const struct + { + uint8_t DataINPipeNumber; /**< Pipe number of the Printer interface's IN data pipe. */ + bool DataINPipeDoubleBank; /**< Indicates if the Printer interface's IN data pipe should use double banking. */ + + uint8_t DataOUTPipeNumber; /**< Pipe number of the Printer interface's OUT data pipe. */ + bool DataOUTPipeDoubleBank; /**< Indicates if the Printer interface's OUT data pipe should use double banking. */ + } Config; /**< Config data for the USB class interface within the device. All elements in this section + * must be set or the interface will fail to enumerate and operate correctly. + */ + struct + { + bool IsActive; /**< Indicates if the current interface instance is connected to an attached device, valid + * after \ref PRNT_Host_ConfigurePipes() is called and the Host state machine is in the + * Configured state. + */ + uint8_t InterfaceNumber; /**< Interface index of the Printer interface within the attached device. */ + uint8_t AlternateSetting; /**< Alternate setting within the Printer Interface in the attached device. */ + + uint16_t DataINPipeSize; /**< Size in bytes of the Printer interface's IN data pipe. */ + uint16_t DataOUTPipeSize; /**< Size in bytes of the Printer interface's OUT data pipe. */ + } State; /**< State data for the USB class interface within the device. All elements in this section + * may be set to initial values, but may also be ignored to default to sane values when + * the interface is enumerated. + */ + } USB_ClassInfo_PRNT_Host_t; + + /* Enums: */ + enum PRNTHost_EnumerationFailure_ErrorCodes_t + { + PRNT_ENUMERROR_NoError = 0, /**< Configuration Descriptor was processed successfully. */ + PRNT_ENUMERROR_InvalidConfigDescriptor = 1, /**< The device returned an invalid Configuration Descriptor. */ + PRNT_ENUMERROR_NoPrinterInterfaceFound = 2, /**< A compatible Printer interface was not found in the device's Configuration Descriptor. */ + PRNT_ENUMERROR_EndpointsNotFound = 3, /**< Compatible Printer endpoints were not found in the device's interfaces. */ + }; + + /* Function Prototypes: */ + /** Host interface configuration routine, to configure a given Printer host interface instance using the + * Configuration Descriptor read from an attached USB device. This function automatically updates the given Printer + * instance's state values and configures the pipes required to communicate with the interface if it is found within + * the device. This should be called once after the stack has enumerated the attached device, while the host state + * machine is in the Addressed state. + * + * \param[in,out] PRNTInterfaceInfo Pointer to a structure containing a Printer Class host configuration and state. + * \param[in] ConfigDescriptorSize Length of the attached device's Configuration Descriptor. + * \param[in] DeviceConfigDescriptor Pointer to a buffer containing the attached device's Configuration Descriptor. + * + * \return A value from the \ref PRNTHost_EnumerationFailure_ErrorCodes_t enum. + */ + uint8_t PRNT_Host_ConfigurePipes(USB_ClassInfo_PRNT_Host_t* const PRNTInterfaceInfo, + uint16_t ConfigDescriptorSize, + void* DeviceConfigDescriptor) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(3); + + /** Configures the printer to enable Bidirectional mode, if it is not already in this mode. This should be called + * once the connected device's configuration has been set, to ensure the printer is ready to accept commands. + * + * \param[in,out] PRNTInterfaceInfo Pointer to a structure containing a Printer Class host configuration and state. + * + * \return A value from the \ref USB_Host_SendControlErrorCodes_t enum. + */ + uint8_t PRNT_Host_SetBidirectionalMode(USB_ClassInfo_PRNT_Host_t* const PRNTInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** Retrieves the status of the virtual Printer port's inbound status lines. The result can then be masked against the + * PRNT_PORTSTATUS_* macros to determine the printer port's status. + * + * \param[in,out] PRNTInterfaceInfo Pointer to a structure containing a Printer Class host configuration and state. + * \param[out] PortStatus Location where the retrieved port status should be stored. + * + * \return A value from the \ref USB_Host_SendControlErrorCodes_t enum. + */ + uint8_t PRNT_Host_GetPortStatus(USB_ClassInfo_PRNT_Host_t* const PRNTInterfaceInfo, + uint8_t* const PortStatus) + ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(2); + + /** Soft-resets the attached printer, readying it for new commands. + * + * \param[in,out] PRNTInterfaceInfo Pointer to a structure containing a Printer Class host configuration and state. + * + * \return A value from the \ref USB_Host_SendControlErrorCodes_t enum. + */ + uint8_t PRNT_Host_SoftReset(USB_ClassInfo_PRNT_Host_t* const PRNTInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** Sends the given raw data stream to the attached printer's input endpoint. This should contain commands that the + * printer is able to understand - for example, PCL data. Not all printers accept all printer languages; see + * \ref PRNT_Host_GetDeviceID() for details on determining acceptable languages for an attached printer. + * + * \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the + * call will fail. + * + * \param[in,out] PRNTInterfaceInfo Pointer to a structure containing a Printer Class host configuration and state. + * \param[in] PrinterCommands Pointer to a buffer containing the raw command stream to send to the printer. + * \param[in] CommandSize Size in bytes of the command stream to be sent. + * + * \return A value from the \ref Pipe_Stream_RW_ErrorCodes_t enum. + */ + uint8_t PRNT_Host_SendData(USB_ClassInfo_PRNT_Host_t* const PRNTInterfaceInfo, + void* PrinterCommands, + const uint16_t CommandSize) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(2); + + /** Retrieves the attached printer device's ID string, formatted according to IEEE 1284. This string is sent as a + * Unicode string from the device and is automatically converted to an ASCII encoded C string by this function, thus + * the maximum reportable string length is two less than the size given (to accommodate the Unicode string length + * bytes which are removed). + * + * This string, when supported, contains the model, manufacturer and acceptable printer languages for the attached device. + * + * \param[in,out] PRNTInterfaceInfo Pointer to a structure containing a Printer Class host configuration and state. + * \param[out] DeviceIDString Pointer to a buffer where the Device ID string should be stored, in ASCII format. + * \param[in] BufferSize Size in bytes of the buffer allocated for the Device ID string. + * + * \return A value from the \ref Pipe_Stream_RW_ErrorCodes_t enum. + */ + uint8_t PRNT_Host_GetDeviceID(USB_ClassInfo_PRNT_Host_t* const PRNTInterfaceInfo, + char* const DeviceIDString, + const uint16_t BufferSize) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(2); + + /* Inline Functions: */ + /** General management task for a given Printer host class interface, required for the correct operation of + * the interface. This should be called frequently in the main program loop, before the master USB management task + * \ref USB_USBTask(). + * + * \param[in,out] PRNTInterfaceInfo Pointer to a structure containing a Printer Class host configuration and state. + */ + static inline void PRNT_Host_USBTask(USB_ClassInfo_PRNT_Host_t* const PRNTInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + static inline void PRNT_Host_USBTask(USB_ClassInfo_PRNT_Host_t* const PRNTInterfaceInfo) + { + (void)PRNTInterfaceInfo; + } + + /* Private Interface - For use in library only: */ + #if !defined(__DOXYGEN__) + /* Macros: */ + #define PRINTER_CLASS 0x07 + #define PRINTER_SUBCLASS 0x01 + #define PRINTER_PROTOCOL 0x02 + + #define REQ_GetDeviceID 0 + #define REQ_GetPortStatus 1 + #define REQ_SoftReset 2 + + #define PRNT_FOUND_DATAPIPE_IN (1 << 0) + #define PRNT_FOUND_DATAPIPE_OUT (1 << 1) + + /* Function Prototypes: */ + #if defined(__INCLUDE_FROM_PRINTER_CLASS_HOST_C) + static uint8_t DCOMP_PRNT_NextPRNTInterface(void* const CurrentDescriptor) ATTR_NON_NULL_PTR_ARG(1); + static uint8_t DCOMP_PRNT_NextPRNTInterfaceEndpoint(void* const CurrentDescriptor) ATTR_NON_NULL_PTR_ARG(1); + #endif + #endif + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/RNDIS.c b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/RNDIS.c new file mode 100644 index 0000000000..cddd5cbb58 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/RNDIS.c @@ -0,0 +1,476 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +#define __INCLUDE_FROM_USB_DRIVER +#include "../../HighLevel/USBMode.h" +#if defined(USB_CAN_BE_HOST) + +#define __INCLUDE_FROM_RNDIS_CLASS_HOST_C +#define __INCLUDE_FROM_RNDIS_DRIVER +#include "RNDIS.h" + +uint8_t RNDIS_Host_ConfigurePipes(USB_ClassInfo_RNDIS_Host_t* const RNDISInterfaceInfo, + uint16_t ConfigDescriptorSize, + void* ConfigDescriptorData) +{ + uint8_t FoundEndpoints = 0; + + memset(&RNDISInterfaceInfo->State, 0x00, sizeof(RNDISInterfaceInfo->State)); + + if (DESCRIPTOR_TYPE(ConfigDescriptorData) != DTYPE_Configuration) + return RNDIS_ENUMERROR_InvalidConfigDescriptor; + + if (USB_GetNextDescriptorComp(&ConfigDescriptorSize, &ConfigDescriptorData, + DCOMP_RNDIS_Host_NextRNDISControlInterface) != DESCRIPTOR_SEARCH_COMP_Found) + { + return RNDIS_ENUMERROR_NoRNDISInterfaceFound; + } + + RNDISInterfaceInfo->State.ControlInterfaceNumber = DESCRIPTOR_CAST(ConfigDescriptorData, USB_Descriptor_Interface_t).InterfaceNumber; + + while (FoundEndpoints != (RNDIS_FOUND_NOTIFICATION_IN | RNDIS_FOUND_DATAPIPE_IN | RNDIS_FOUND_DATAPIPE_OUT)) + { + if (USB_GetNextDescriptorComp(&ConfigDescriptorSize, &ConfigDescriptorData, + DCOMP_RNDIS_Host_NextRNDISInterfaceEndpoint) != DESCRIPTOR_SEARCH_COMP_Found) + { + if (FoundEndpoints & RNDIS_FOUND_NOTIFICATION_IN) + { + if (USB_GetNextDescriptorComp(&ConfigDescriptorSize, &ConfigDescriptorData, + DCOMP_RNDIS_Host_NextRNDISDataInterface) != DESCRIPTOR_SEARCH_COMP_Found) + { + return RNDIS_ENUMERROR_NoRNDISInterfaceFound; + } + } + else + { + FoundEndpoints = 0; + + Pipe_SelectPipe(RNDISInterfaceInfo->Config.DataINPipeNumber); + Pipe_DisablePipe(); + Pipe_SelectPipe(RNDISInterfaceInfo->Config.DataOUTPipeNumber); + Pipe_DisablePipe(); + Pipe_SelectPipe(RNDISInterfaceInfo->Config.NotificationPipeNumber); + Pipe_DisablePipe(); + + if (USB_GetNextDescriptorComp(&ConfigDescriptorSize, &ConfigDescriptorData, + DCOMP_RNDIS_Host_NextRNDISControlInterface) != DESCRIPTOR_SEARCH_COMP_Found) + { + return RNDIS_ENUMERROR_NoRNDISInterfaceFound; + } + } + + if (USB_GetNextDescriptorComp(&ConfigDescriptorSize, &ConfigDescriptorData, + DCOMP_RNDIS_Host_NextRNDISInterfaceEndpoint) != DESCRIPTOR_SEARCH_COMP_Found) + { + return RNDIS_ENUMERROR_EndpointsNotFound; + } + } + + USB_Descriptor_Endpoint_t* EndpointData = DESCRIPTOR_PCAST(ConfigDescriptorData, USB_Descriptor_Endpoint_t); + + if ((EndpointData->Attributes & EP_TYPE_MASK) == EP_TYPE_INTERRUPT) + { + if (EndpointData->EndpointAddress & ENDPOINT_DESCRIPTOR_DIR_IN) + { + Pipe_ConfigurePipe(RNDISInterfaceInfo->Config.NotificationPipeNumber, EP_TYPE_INTERRUPT, PIPE_TOKEN_IN, + EndpointData->EndpointAddress, EndpointData->EndpointSize, + RNDISInterfaceInfo->Config.NotificationPipeDoubleBank ? PIPE_BANK_DOUBLE : PIPE_BANK_SINGLE); + RNDISInterfaceInfo->State.NotificationPipeSize = EndpointData->EndpointSize; + + Pipe_SetInterruptPeriod(EndpointData->PollingIntervalMS); + + FoundEndpoints |= RNDIS_FOUND_NOTIFICATION_IN; + } + } + else + { + if (EndpointData->EndpointAddress & ENDPOINT_DESCRIPTOR_DIR_IN) + { + Pipe_ConfigurePipe(RNDISInterfaceInfo->Config.DataINPipeNumber, EP_TYPE_BULK, PIPE_TOKEN_IN, + EndpointData->EndpointAddress, EndpointData->EndpointSize, + RNDISInterfaceInfo->Config.DataINPipeDoubleBank ? PIPE_BANK_DOUBLE : PIPE_BANK_SINGLE); + RNDISInterfaceInfo->State.DataINPipeSize = EndpointData->EndpointSize; + + FoundEndpoints |= RNDIS_FOUND_DATAPIPE_IN; + } + else + { + Pipe_ConfigurePipe(RNDISInterfaceInfo->Config.DataOUTPipeNumber, EP_TYPE_BULK, PIPE_TOKEN_OUT, + EndpointData->EndpointAddress, EndpointData->EndpointSize, + RNDISInterfaceInfo->Config.DataOUTPipeDoubleBank ? PIPE_BANK_DOUBLE : PIPE_BANK_SINGLE); + RNDISInterfaceInfo->State.DataOUTPipeSize = EndpointData->EndpointSize; + + FoundEndpoints |= RNDIS_FOUND_DATAPIPE_OUT; + } + } + } + + RNDISInterfaceInfo->State.IsActive = true; + return RNDIS_ENUMERROR_NoError; +} + +static uint8_t DCOMP_RNDIS_Host_NextRNDISControlInterface(void* const CurrentDescriptor) +{ + if (DESCRIPTOR_TYPE(CurrentDescriptor) == DTYPE_Interface) + { + USB_Descriptor_Interface_t* CurrentInterface = DESCRIPTOR_PCAST(CurrentDescriptor, + USB_Descriptor_Interface_t); + + if ((CurrentInterface->Class == RNDIS_CONTROL_CLASS) && + (CurrentInterface->SubClass == RNDIS_CONTROL_SUBCLASS) && + (CurrentInterface->Protocol == RNDIS_CONTROL_PROTOCOL)) + { + return DESCRIPTOR_SEARCH_Found; + } + } + + return DESCRIPTOR_SEARCH_NotFound; +} + +static uint8_t DCOMP_RNDIS_Host_NextRNDISDataInterface(void* const CurrentDescriptor) +{ + if (DESCRIPTOR_TYPE(CurrentDescriptor) == DTYPE_Interface) + { + USB_Descriptor_Interface_t* CurrentInterface = DESCRIPTOR_PCAST(CurrentDescriptor, + USB_Descriptor_Interface_t); + + if ((CurrentInterface->Class == RNDIS_DATA_CLASS) && + (CurrentInterface->SubClass == RNDIS_DATA_SUBCLASS) && + (CurrentInterface->Protocol == RNDIS_DATA_PROTOCOL)) + { + return DESCRIPTOR_SEARCH_Found; + } + } + + return DESCRIPTOR_SEARCH_NotFound; +} + +static uint8_t DCOMP_RNDIS_Host_NextRNDISInterfaceEndpoint(void* const CurrentDescriptor) +{ + if (DESCRIPTOR_TYPE(CurrentDescriptor) == DTYPE_Endpoint) + { + USB_Descriptor_Endpoint_t* CurrentEndpoint = DESCRIPTOR_PCAST(CurrentDescriptor, + USB_Descriptor_Endpoint_t); + + uint8_t EndpointType = (CurrentEndpoint->Attributes & EP_TYPE_MASK); + + if (((EndpointType == EP_TYPE_BULK) || (EndpointType == EP_TYPE_INTERRUPT)) && + !(Pipe_IsEndpointBound(CurrentEndpoint->EndpointAddress))) + { + return DESCRIPTOR_SEARCH_Found; + } + } + else if (DESCRIPTOR_TYPE(CurrentDescriptor) == DTYPE_Interface) + { + return DESCRIPTOR_SEARCH_Fail; + } + + return DESCRIPTOR_SEARCH_NotFound; +} + +static uint8_t RNDIS_SendEncapsulatedCommand(USB_ClassInfo_RNDIS_Host_t* const RNDISInterfaceInfo, + void* Buffer, + const uint16_t Length) +{ + USB_ControlRequest = (USB_Request_Header_t) + { + .bmRequestType = (REQDIR_HOSTTODEVICE | REQTYPE_CLASS | REQREC_INTERFACE), + .bRequest = REQ_SendEncapsulatedCommand, + .wValue = 0, + .wIndex = RNDISInterfaceInfo->State.ControlInterfaceNumber, + .wLength = Length, + }; + + Pipe_SelectPipe(PIPE_CONTROLPIPE); + return USB_Host_SendControlRequest(Buffer); +} + +static uint8_t RNDIS_GetEncapsulatedResponse(USB_ClassInfo_RNDIS_Host_t* const RNDISInterfaceInfo, + void* Buffer, + const uint16_t Length) +{ + USB_ControlRequest = (USB_Request_Header_t) + { + .bmRequestType = (REQDIR_DEVICETOHOST | REQTYPE_CLASS | REQREC_INTERFACE), + .bRequest = REQ_GetEncapsulatedResponse, + .wValue = 0, + .wIndex = RNDISInterfaceInfo->State.ControlInterfaceNumber, + .wLength = Length, + }; + + Pipe_SelectPipe(PIPE_CONTROLPIPE); + return USB_Host_SendControlRequest(Buffer); +} + +uint8_t RNDIS_Host_SendKeepAlive(USB_ClassInfo_RNDIS_Host_t* const RNDISInterfaceInfo) +{ + uint8_t ErrorCode; + + RNDIS_KeepAlive_Message_t KeepAliveMessage; + RNDIS_KeepAlive_Complete_t KeepAliveMessageResponse; + + KeepAliveMessage.MessageType = REMOTE_NDIS_KEEPALIVE_MSG; + KeepAliveMessage.MessageLength = sizeof(RNDIS_KeepAlive_Message_t); + KeepAliveMessage.RequestId = RNDISInterfaceInfo->State.RequestID++; + + if ((ErrorCode = RNDIS_SendEncapsulatedCommand(RNDISInterfaceInfo, &KeepAliveMessage, + sizeof(RNDIS_KeepAlive_Message_t))) != HOST_SENDCONTROL_Successful) + { + return ErrorCode; + } + + if ((ErrorCode = RNDIS_GetEncapsulatedResponse(RNDISInterfaceInfo, &KeepAliveMessageResponse, + sizeof(RNDIS_KeepAlive_Complete_t))) != HOST_SENDCONTROL_Successful) + { + return ErrorCode; + } + + return HOST_SENDCONTROL_Successful; +} + +uint8_t RNDIS_Host_InitializeDevice(USB_ClassInfo_RNDIS_Host_t* const RNDISInterfaceInfo) +{ + uint8_t ErrorCode; + + RNDIS_Initialize_Message_t InitMessage; + RNDIS_Initialize_Complete_t InitMessageResponse; + + InitMessage.MessageType = REMOTE_NDIS_INITIALIZE_MSG; + InitMessage.MessageLength = sizeof(RNDIS_Initialize_Message_t); + InitMessage.RequestId = RNDISInterfaceInfo->State.RequestID++; + + InitMessage.MajorVersion = REMOTE_NDIS_VERSION_MAJOR; + InitMessage.MinorVersion = REMOTE_NDIS_VERSION_MINOR; + InitMessage.MaxTransferSize = RNDISInterfaceInfo->Config.HostMaxPacketSize; + + if ((ErrorCode = RNDIS_SendEncapsulatedCommand(RNDISInterfaceInfo, &InitMessage, + sizeof(RNDIS_Initialize_Message_t))) != HOST_SENDCONTROL_Successful) + { + return ErrorCode; + } + + if ((ErrorCode = RNDIS_GetEncapsulatedResponse(RNDISInterfaceInfo, &InitMessageResponse, + sizeof(RNDIS_Initialize_Complete_t))) != HOST_SENDCONTROL_Successful) + { + return ErrorCode; + } + + if (InitMessageResponse.Status != REMOTE_NDIS_STATUS_SUCCESS) + return RNDIS_COMMAND_FAILED; + + RNDISInterfaceInfo->State.DeviceMaxPacketSize = InitMessageResponse.MaxTransferSize; + + return HOST_SENDCONTROL_Successful; +} + +uint8_t RNDIS_Host_SetRNDISProperty(USB_ClassInfo_RNDIS_Host_t* const RNDISInterfaceInfo, + const uint32_t Oid, + void* Buffer, + const uint16_t Length) +{ + uint8_t ErrorCode; + + struct + { + RNDIS_Set_Message_t SetMessage; + uint8_t ContiguousBuffer[Length]; + } SetMessageData; + + RNDIS_Set_Complete_t SetMessageResponse; + + SetMessageData.SetMessage.MessageType = REMOTE_NDIS_SET_MSG; + SetMessageData.SetMessage.MessageLength = sizeof(RNDIS_Set_Message_t) + Length; + SetMessageData.SetMessage.RequestId = RNDISInterfaceInfo->State.RequestID++; + + SetMessageData.SetMessage.Oid = Oid; + SetMessageData.SetMessage.InformationBufferLength = Length; + SetMessageData.SetMessage.InformationBufferOffset = (sizeof(RNDIS_Set_Message_t) - sizeof(RNDIS_Message_Header_t)); + SetMessageData.SetMessage.DeviceVcHandle = 0; + + memcpy(&SetMessageData.ContiguousBuffer, Buffer, Length); + + if ((ErrorCode = RNDIS_SendEncapsulatedCommand(RNDISInterfaceInfo, &SetMessageData, + SetMessageData.SetMessage.MessageLength)) != HOST_SENDCONTROL_Successful) + { + return ErrorCode; + } + + if ((ErrorCode = RNDIS_GetEncapsulatedResponse(RNDISInterfaceInfo, &SetMessageResponse, + sizeof(RNDIS_Set_Complete_t))) != HOST_SENDCONTROL_Successful) + { + return ErrorCode; + } + + if (SetMessageResponse.Status != REMOTE_NDIS_STATUS_SUCCESS) + return RNDIS_COMMAND_FAILED; + + return HOST_SENDCONTROL_Successful; +} + +uint8_t RNDIS_Host_QueryRNDISProperty(USB_ClassInfo_RNDIS_Host_t* const RNDISInterfaceInfo, + const uint32_t Oid, + void* Buffer, + const uint16_t MaxLength) +{ + uint8_t ErrorCode; + + RNDIS_Query_Message_t QueryMessage; + + struct + { + RNDIS_Query_Complete_t QueryMessageResponse; + uint8_t ContiguousBuffer[MaxLength]; + } QueryMessageResponseData; + + QueryMessage.MessageType = REMOTE_NDIS_QUERY_MSG; + QueryMessage.MessageLength = sizeof(RNDIS_Query_Message_t); + QueryMessage.RequestId = RNDISInterfaceInfo->State.RequestID++; + + QueryMessage.Oid = Oid; + QueryMessage.InformationBufferLength = 0; + QueryMessage.InformationBufferOffset = 0; + QueryMessage.DeviceVcHandle = 0; + + if ((ErrorCode = RNDIS_SendEncapsulatedCommand(RNDISInterfaceInfo, &QueryMessage, + sizeof(RNDIS_Query_Message_t))) != HOST_SENDCONTROL_Successful) + { + return ErrorCode; + } + + if ((ErrorCode = RNDIS_GetEncapsulatedResponse(RNDISInterfaceInfo, &QueryMessageResponseData, + sizeof(QueryMessageResponseData))) != HOST_SENDCONTROL_Successful) + { + return ErrorCode; + } + + if (QueryMessageResponseData.QueryMessageResponse.Status != REMOTE_NDIS_STATUS_SUCCESS) + return RNDIS_COMMAND_FAILED; + + memcpy(Buffer, &QueryMessageResponseData.ContiguousBuffer, MaxLength); + + return HOST_SENDCONTROL_Successful; +} + +bool RNDIS_Host_IsPacketReceived(USB_ClassInfo_RNDIS_Host_t* const RNDISInterfaceInfo) +{ + bool PacketWaiting; + + if ((USB_HostState != HOST_STATE_Configured) || !(RNDISInterfaceInfo->State.IsActive)) + return false; + + Pipe_SelectPipe(RNDISInterfaceInfo->Config.DataINPipeNumber); + + Pipe_Unfreeze(); + PacketWaiting = Pipe_IsINReceived(); + Pipe_Freeze(); + + return PacketWaiting; +} + +uint8_t RNDIS_Host_ReadPacket(USB_ClassInfo_RNDIS_Host_t* const RNDISInterfaceInfo, + void* Buffer, + uint16_t* const PacketLength) +{ + uint8_t ErrorCode; + + if ((USB_HostState != HOST_STATE_Configured) || !(RNDISInterfaceInfo->State.IsActive)) + return PIPE_READYWAIT_DeviceDisconnected; + + Pipe_SelectPipe(RNDISInterfaceInfo->Config.DataINPipeNumber); + Pipe_Unfreeze(); + + if (!(Pipe_IsReadWriteAllowed())) + { + if (Pipe_IsINReceived()) + Pipe_ClearIN(); + + *PacketLength = 0; + Pipe_Freeze(); + return PIPE_RWSTREAM_NoError; + } + + RNDIS_Packet_Message_t DeviceMessage; + + if ((ErrorCode = Pipe_Read_Stream_LE(&DeviceMessage, sizeof(RNDIS_Packet_Message_t), + NO_STREAM_CALLBACK)) != PIPE_RWSTREAM_NoError) + { + return ErrorCode; + } + + *PacketLength = (uint16_t)DeviceMessage.DataLength; + + Pipe_Discard_Stream(DeviceMessage.DataOffset - (sizeof(RNDIS_Packet_Message_t) - sizeof(RNDIS_Message_Header_t)), + NO_STREAM_CALLBACK); + + Pipe_Read_Stream_LE(Buffer, *PacketLength, NO_STREAM_CALLBACK); + + if (!(Pipe_BytesInPipe())) + Pipe_ClearIN(); + + Pipe_Freeze(); + + return PIPE_RWSTREAM_NoError; +} + +uint8_t RNDIS_Host_SendPacket(USB_ClassInfo_RNDIS_Host_t* const RNDISInterfaceInfo, + void* Buffer, + const uint16_t PacketLength) +{ + uint8_t ErrorCode; + + if ((USB_HostState != HOST_STATE_Configured) || !(RNDISInterfaceInfo->State.IsActive)) + return PIPE_READYWAIT_DeviceDisconnected; + + RNDIS_Packet_Message_t DeviceMessage; + + memset(&DeviceMessage, 0, sizeof(RNDIS_Packet_Message_t)); + DeviceMessage.MessageType = REMOTE_NDIS_PACKET_MSG; + DeviceMessage.MessageLength = (sizeof(RNDIS_Packet_Message_t) + PacketLength); + DeviceMessage.DataOffset = (sizeof(RNDIS_Packet_Message_t) - sizeof(RNDIS_Message_Header_t)); + DeviceMessage.DataLength = PacketLength; + + Pipe_SelectPipe(RNDISInterfaceInfo->Config.DataOUTPipeNumber); + Pipe_Unfreeze(); + + if ((ErrorCode = Pipe_Write_Stream_LE(&DeviceMessage, sizeof(RNDIS_Packet_Message_t), + NO_STREAM_CALLBACK)) != PIPE_RWSTREAM_NoError) + { + return ErrorCode; + } + + Pipe_Write_Stream_LE(Buffer, PacketLength, NO_STREAM_CALLBACK); + Pipe_ClearOUT(); + + Pipe_Freeze(); + + return PIPE_RWSTREAM_NoError; +} + +#endif diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/RNDIS.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/RNDIS.h new file mode 100644 index 0000000000..b1518ffed3 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/RNDIS.h @@ -0,0 +1,294 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief Host mode driver for the library USB RNDIS Class driver. + * + * Host mode driver for the library USB RNDIS Class driver. + * + * \note This file should not be included directly. It is automatically included as needed by the class driver + * dispatch header located in LUFA/Drivers/USB/Class/RNDIS.h. + */ + +/** \ingroup Group_USBClassRNDIS + * @defgroup Group_USBClassRNDISHost RNDIS Class Host Mode Driver + * + * \section Sec_Dependencies Module Source Dependencies + * The following files must be built with any user project that uses this module: + * - LUFA/Drivers/USB/Class/Host/RNDIS.c (Makefile source module name: LUFA_SRC_USBCLASS) + * + * \section Module Description + * Host Mode USB Class driver framework interface, for the Microsoft RNDIS Ethernet + * USB Class driver. + * + * @{ + */ + +#ifndef __RNDIS_CLASS_HOST_H__ +#define __RNDIS_CLASS_HOST_H__ + + /* Includes: */ + #include "../../USB.h" + #include "../Common/RNDIS.h" + + #include + #include + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_RNDIS_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/Class/RNDIS.h instead. + #endif + + /* Public Interface - May be used in end-application: */ + /* Type Defines: */ + /** \brief RNDIS Class Host Mode Configuration and State Structure. + * + * Class state structure. An instance of this structure should be made within the user application, + * and passed to each of the RNDIS class driver functions as the RNDISInterfaceInfo parameter. This + * stores each RNDIS interface's configuration and state information. + */ + typedef struct + { + const struct + { + uint8_t DataINPipeNumber; /**< Pipe number of the RNDIS interface's IN data pipe. */ + bool DataINPipeDoubleBank; /**< Indicates if the RNDIS interface's IN data pipe should use double banking. */ + + uint8_t DataOUTPipeNumber; /**< Pipe number of the RNDIS interface's OUT data pipe. */ + bool DataOUTPipeDoubleBank; /**< Indicates if the RNDIS interface's OUT data pipe should use double banking. */ + + uint8_t NotificationPipeNumber; /**< Pipe number of the RNDIS interface's IN notification endpoint, if used. */ + bool NotificationPipeDoubleBank; /**< Indicates if the RNDIS interface's notification pipe should use double banking. */ + + uint32_t HostMaxPacketSize; /**< Maximum size of a packet which can be buffered by the host. */ + } Config; /**< Config data for the USB class interface within the device. All elements in this section + * must be set or the interface will fail to enumerate and operate correctly. + */ + struct + { + bool IsActive; /**< Indicates if the current interface instance is connected to an attached device, valid + * after \ref RNDIS_Host_ConfigurePipes() is called and the Host state machine is in the + * Configured state. + */ + uint8_t ControlInterfaceNumber; /**< Interface index of the RNDIS control interface within the attached device. */ + + uint16_t DataINPipeSize; /**< Size in bytes of the RNDIS interface's IN data pipe. */ + uint16_t DataOUTPipeSize; /**< Size in bytes of the RNDIS interface's OUT data pipe. */ + uint16_t NotificationPipeSize; /**< Size in bytes of the RNDIS interface's IN notification pipe, if used. */ + + uint32_t DeviceMaxPacketSize; /**< Maximum size of a packet which can be buffered by the attached RNDIS device. */ + + uint32_t RequestID; /**< Request ID counter to give a unique ID for each command/response pair. */ + } State; /**< State data for the USB class interface within the device. All elements in this section + * may be set to initial values, but may also be ignored to default to sane values when + * the interface is enumerated. + */ + } USB_ClassInfo_RNDIS_Host_t; + + /* Enums: */ + /** Enum for the possible error codes returned by the \ref RNDIS_Host_ConfigurePipes() function. */ + enum RNDISHost_EnumerationFailure_ErrorCodes_t + { + RNDIS_ENUMERROR_NoError = 0, /**< Configuration Descriptor was processed successfully. */ + RNDIS_ENUMERROR_InvalidConfigDescriptor = 1, /**< The device returned an invalid Configuration Descriptor. */ + RNDIS_ENUMERROR_NoRNDISInterfaceFound = 2, /**< A compatible RNDIS interface was not found in the device's Configuration Descriptor. */ + RNDIS_ENUMERROR_EndpointsNotFound = 3, /**< Compatible RNDIS endpoints were not found in the device's RNDIS interface. */ + }; + + /* Macros: */ + /** Additional error code for RNDIS functions when a device returns a logical command failure. */ + #define RNDIS_COMMAND_FAILED 0xC0 + + /* Function Prototypes: */ + /** Host interface configuration routine, to configure a given RNDIS host interface instance using the Configuration + * Descriptor read from an attached USB device. This function automatically updates the given RNDIS Host instance's + * state values and configures the pipes required to communicate with the interface if it is found within the device. + * This should be called once after the stack has enumerated the attached device, while the host state machine is in + * the Addressed state. + * + * \param[in,out] RNDISInterfaceInfo Pointer to a structure containing an RNDIS Class host configuration and state. + * \param[in] ConfigDescriptorSize Length of the attached device's Configuration Descriptor. + * \param[in] DeviceConfigDescriptor Pointer to a buffer containing the attached device's Configuration Descriptor. + * + * \return A value from the \ref RNDISHost_EnumerationFailure_ErrorCodes_t enum. + */ + uint8_t RNDIS_Host_ConfigurePipes(USB_ClassInfo_RNDIS_Host_t* const RNDISInterfaceInfo, + uint16_t ConfigDescriptorSize, + void* DeviceConfigDescriptor) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(3); + + /** Sends a RNDIS KEEPALIVE command to the device, to ensure that it does not enter standby mode after periods + * of long inactivity. + * + * \param[in,out] RNDISInterfaceInfo Pointer to a structure containing an RNDIS Class host configuration and state. + * + * \return A value from the USB_Host_SendControlErrorCodes_t enum or RNDIS_COMMAND_FAILED if the device returned a + * logical command failure. + */ + uint8_t RNDIS_Host_SendKeepAlive(USB_ClassInfo_RNDIS_Host_t* const RNDISInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** Initialises the attached RNDIS device's RNDIS interface. This should be called after the device's pipes have been + * configured via the call to \ref RNDIS_Host_ConfigurePipes(). + * + * \param[in,out] RNDISInterfaceInfo Pointer to a structure containing an RNDIS Class host configuration and state. + * + * \return A value from the USB_Host_SendControlErrorCodes_t enum or RNDIS_COMMAND_FAILED if the device returned a + * logical command failure. + */ + uint8_t RNDIS_Host_InitializeDevice(USB_ClassInfo_RNDIS_Host_t* const RNDISInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** Sets a given RNDIS property of an attached RNDIS device. + * + * \param[in,out] RNDISInterfaceInfo Pointer to a structure containing an RNDIS Class host configuration and state. + * \param[in] Oid OID number of the parameter to set. + * \param[in] Buffer Pointer to where the property data is to be sourced from. + * \param[in] Length Length in bytes of the property data to sent to the device. + * + * \return A value from the USB_Host_SendControlErrorCodes_t enum or RNDIS_COMMAND_FAILED if the device returned a + * logical command failure. + */ + uint8_t RNDIS_Host_SetRNDISProperty(USB_ClassInfo_RNDIS_Host_t* const RNDISInterfaceInfo, + const uint32_t Oid, + void* Buffer, + const uint16_t Length) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(3); + + /** Gets a given RNDIS property of an attached RNDIS device. + * + * \param[in,out] RNDISInterfaceInfo Pointer to a structure containing an RNDIS Class host configuration and state. + * \param[in] Oid OID number of the parameter to get. + * \param[in] Buffer Pointer to where the property data is to be written to. + * \param[in] MaxLength Length in bytes of the destination buffer size. + * + * \return A value from the USB_Host_SendControlErrorCodes_t enum or RNDIS_COMMAND_FAILED if the device returned a + * logical command failure. + */ + uint8_t RNDIS_Host_QueryRNDISProperty(USB_ClassInfo_RNDIS_Host_t* const RNDISInterfaceInfo, + const uint32_t Oid, + void* Buffer, + const uint16_t MaxLength) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(3); + + /** Determines if a packet is currently waiting for the host to read in and process. + * + * \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the + * call will fail. + * + * \param[in,out] RNDISInterfaceInfo Pointer to a structure containing an RNDIS Class host configuration and state. + * + * \return Boolean true if a packet is waiting to be read in by the host, false otherwise. + */ + bool RNDIS_Host_IsPacketReceived(USB_ClassInfo_RNDIS_Host_t* const RNDISInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** Retrieves the next pending packet from the device, discarding the remainder of the RNDIS packet header to leave + * only the packet contents for processing by the host in the nominated buffer. + * + * \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the + * call will fail. + * + * \param[in,out] RNDISInterfaceInfo Pointer to a structure containing an RNDIS Class host configuration and state. + * \param[out] Buffer Pointer to a buffer where the packer data is to be written to. + * \param[out] PacketLength Pointer to where the length in bytes of the read packet is to be stored. + * + * \return A value from the Pipe_Stream_RW_ErrorCodes_t enum. + */ + uint8_t RNDIS_Host_ReadPacket(USB_ClassInfo_RNDIS_Host_t* const RNDISInterfaceInfo, + void* Buffer, + uint16_t* const PacketLength) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(2) + ATTR_NON_NULL_PTR_ARG(3); + + /** Sends the given packet to the attached RNDIS device, after adding a RNDIS packet message header. + * + * \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the + * call will fail. + * + * \param[in,out] RNDISInterfaceInfo Pointer to a structure containing an RNDIS Class host configuration and state. + * \param[in] Buffer Pointer to a buffer where the packer data is to be read from. + * \param[in] PacketLength Length in bytes of the packet to send. + * + * \return A value from the Pipe_Stream_RW_ErrorCodes_t enum. + */ + uint8_t RNDIS_Host_SendPacket(USB_ClassInfo_RNDIS_Host_t* const RNDISInterfaceInfo, + void* Buffer, + const uint16_t PacketLength) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(2); + + /* Inline Functions: */ + /** General management task for a given RNDIS host class interface, required for the correct operation of the interface. This should + * be called frequently in the main program loop, before the master USB management task \ref USB_USBTask(). + * + * \param[in,out] RNDISInterfaceInfo Pointer to a structure containing an RNDIS Class host configuration and state. + */ + static inline void RNDIS_Host_USBTask(USB_ClassInfo_RNDIS_Host_t* const RNDISInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + static inline void RNDIS_Host_USBTask(USB_ClassInfo_RNDIS_Host_t* const RNDISInterfaceInfo) + { + (void)RNDISInterfaceInfo; + } + + /* Private Interface - For use in library only: */ + #if !defined(__DOXYGEN__) + /* Macros: */ + #define RNDIS_CONTROL_CLASS 0x02 + #define RNDIS_CONTROL_SUBCLASS 0x02 + #define RNDIS_CONTROL_PROTOCOL 0xFF + #define RNDIS_DATA_CLASS 0x0A + #define RNDIS_DATA_SUBCLASS 0x00 + #define RNDIS_DATA_PROTOCOL 0x00 + + #define RNDIS_FOUND_DATAPIPE_IN (1 << 0) + #define RNDIS_FOUND_DATAPIPE_OUT (1 << 1) + #define RNDIS_FOUND_NOTIFICATION_IN (1 << 2) + + /* Function Prototypes: */ + #if defined(__INCLUDE_FROM_RNDIS_CLASS_HOST_C) + static uint8_t RNDIS_SendEncapsulatedCommand(USB_ClassInfo_RNDIS_Host_t* const RNDISInterfaceInfo, + void* Buffer, + const uint16_t Length) ATTR_NON_NULL_PTR_ARG(1) + ATTR_NON_NULL_PTR_ARG(2); + static uint8_t RNDIS_GetEncapsulatedResponse(USB_ClassInfo_RNDIS_Host_t* const RNDISInterfaceInfo, + void* Buffer, + const uint16_t Length) ATTR_NON_NULL_PTR_ARG(1) + ATTR_NON_NULL_PTR_ARG(2); + + static uint8_t DCOMP_RNDIS_Host_NextRNDISControlInterface(void* const CurrentDescriptor) ATTR_NON_NULL_PTR_ARG(1); + static uint8_t DCOMP_RNDIS_Host_NextRNDISDataInterface(void* const CurrentDescriptor) ATTR_NON_NULL_PTR_ARG(1); + static uint8_t DCOMP_RNDIS_Host_NextRNDISInterfaceEndpoint(void* const CurrentDescriptor) ATTR_NON_NULL_PTR_ARG(1); + #endif + #endif + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/StillImage.c b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/StillImage.c new file mode 100644 index 0000000000..42c3feca62 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/StillImage.c @@ -0,0 +1,423 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +#define __INCLUDE_FROM_USB_DRIVER +#include "../../HighLevel/USBMode.h" +#if defined(USB_CAN_BE_HOST) + +#define __INCLUDE_FROM_SI_CLASS_HOST_C +#define __INCLUDE_FROM_SI_DRIVER +#include "StillImage.h" + +uint8_t SImage_Host_ConfigurePipes(USB_ClassInfo_SI_Host_t* const SIInterfaceInfo, + uint16_t ConfigDescriptorSize, + void* DeviceConfigDescriptor) +{ + uint8_t FoundEndpoints = 0; + + memset(&SIInterfaceInfo->State, 0x00, sizeof(SIInterfaceInfo->State)); + + if (DESCRIPTOR_TYPE(DeviceConfigDescriptor) != DTYPE_Configuration) + return SI_ENUMERROR_InvalidConfigDescriptor; + + if (USB_GetNextDescriptorComp(&ConfigDescriptorSize, &DeviceConfigDescriptor, + DCOMP_SI_Host_NextSIInterface) != DESCRIPTOR_SEARCH_COMP_Found) + { + return SI_ENUMERROR_NoSIInterfaceFound; + } + + while (FoundEndpoints != (SI_FOUND_EVENTS_IN | SI_FOUND_DATAPIPE_IN | SI_FOUND_DATAPIPE_OUT)) + { + if (USB_GetNextDescriptorComp(&ConfigDescriptorSize, &DeviceConfigDescriptor, + DCOMP_SI_Host_NextSIInterfaceEndpoint) != DESCRIPTOR_SEARCH_COMP_Found) + { + return SI_ENUMERROR_EndpointsNotFound; + } + + USB_Descriptor_Endpoint_t* EndpointData = DESCRIPTOR_PCAST(DeviceConfigDescriptor, USB_Descriptor_Endpoint_t); + + if ((EndpointData->Attributes & EP_TYPE_MASK) == EP_TYPE_INTERRUPT) + { + if (EndpointData->EndpointAddress & ENDPOINT_DESCRIPTOR_DIR_IN) + { + Pipe_ConfigurePipe(SIInterfaceInfo->Config.EventsPipeNumber, EP_TYPE_INTERRUPT, PIPE_TOKEN_IN, + EndpointData->EndpointAddress, EndpointData->EndpointSize, + SIInterfaceInfo->Config.EventsPipeDoubleBank ? PIPE_BANK_DOUBLE : PIPE_BANK_SINGLE); + SIInterfaceInfo->State.EventsPipeSize = EndpointData->EndpointSize; + + Pipe_SetInterruptPeriod(EndpointData->PollingIntervalMS); + + FoundEndpoints |= SI_FOUND_EVENTS_IN; + } + } + else + { + if (EndpointData->EndpointAddress & ENDPOINT_DESCRIPTOR_DIR_IN) + { + Pipe_ConfigurePipe(SIInterfaceInfo->Config.DataINPipeNumber, EP_TYPE_BULK, PIPE_TOKEN_IN, + EndpointData->EndpointAddress, EndpointData->EndpointSize, + SIInterfaceInfo->Config.DataINPipeDoubleBank ? PIPE_BANK_DOUBLE : PIPE_BANK_SINGLE); + SIInterfaceInfo->State.DataINPipeSize = EndpointData->EndpointSize; + + FoundEndpoints |= SI_FOUND_DATAPIPE_IN; + } + else + { + Pipe_ConfigurePipe(SIInterfaceInfo->Config.DataOUTPipeNumber, EP_TYPE_BULK, PIPE_TOKEN_OUT, + EndpointData->EndpointAddress, EndpointData->EndpointSize, + SIInterfaceInfo->Config.DataOUTPipeDoubleBank ? PIPE_BANK_DOUBLE : PIPE_BANK_SINGLE); + SIInterfaceInfo->State.DataOUTPipeSize = EndpointData->EndpointSize; + + FoundEndpoints |= SI_FOUND_DATAPIPE_OUT; + } + } + } + + SIInterfaceInfo->State.IsActive = true; + return SI_ENUMERROR_NoError; +} + +uint8_t DCOMP_SI_Host_NextSIInterface(void* const CurrentDescriptor) +{ + if (DESCRIPTOR_TYPE(CurrentDescriptor) == DTYPE_Interface) + { + USB_Descriptor_Interface_t* CurrentInterface = DESCRIPTOR_PCAST(CurrentDescriptor, + USB_Descriptor_Interface_t); + + if ((CurrentInterface->Class == STILL_IMAGE_CLASS) && + (CurrentInterface->SubClass == STILL_IMAGE_SUBCLASS) && + (CurrentInterface->Protocol == STILL_IMAGE_PROTOCOL)) + { + return DESCRIPTOR_SEARCH_Found; + } + } + + return DESCRIPTOR_SEARCH_NotFound; +} + +uint8_t DCOMP_SI_Host_NextSIInterfaceEndpoint(void* const CurrentDescriptor) +{ + if (DESCRIPTOR_TYPE(CurrentDescriptor) == DTYPE_Endpoint) + { + USB_Descriptor_Endpoint_t* CurrentEndpoint = DESCRIPTOR_PCAST(CurrentDescriptor, + USB_Descriptor_Endpoint_t); + + uint8_t EndpointType = (CurrentEndpoint->Attributes & EP_TYPE_MASK); + + if (((EndpointType == EP_TYPE_BULK) || (EndpointType == EP_TYPE_INTERRUPT)) && + (!(Pipe_IsEndpointBound(CurrentEndpoint->EndpointAddress)))) + { + return DESCRIPTOR_SEARCH_Found; + } + } + else if (DESCRIPTOR_TYPE(CurrentDescriptor) == DTYPE_Interface) + { + return DESCRIPTOR_SEARCH_Fail; + } + + return DESCRIPTOR_SEARCH_NotFound; +} + +uint8_t SImage_Host_SendBlockHeader(USB_ClassInfo_SI_Host_t* const SIInterfaceInfo, + SI_PIMA_Container_t* const PIMAHeader) +{ + uint8_t ErrorCode; + + if ((USB_HostState != HOST_STATE_Configured) || !(SIInterfaceInfo->State.IsActive)) + return PIPE_RWSTREAM_DeviceDisconnected; + + if (SIInterfaceInfo->State.IsSessionOpen) + PIMAHeader->TransactionID = SIInterfaceInfo->State.TransactionID++; + + Pipe_SelectPipe(SIInterfaceInfo->Config.DataOUTPipeNumber); + Pipe_Unfreeze(); + + if ((ErrorCode = Pipe_Write_Stream_LE(PIMAHeader, PIMA_COMMAND_SIZE(0), NO_STREAM_CALLBACK)) != PIPE_RWSTREAM_NoError) + return ErrorCode; + + uint8_t ParamBytes = (PIMAHeader->DataLength - PIMA_COMMAND_SIZE(0)); + + if (ParamBytes) + { + if ((ErrorCode = Pipe_Write_Stream_LE(&PIMAHeader->Params, ParamBytes, NO_STREAM_CALLBACK)) != PIPE_RWSTREAM_NoError) + return ErrorCode; + } + + Pipe_ClearOUT(); + Pipe_Freeze(); + + return PIPE_RWSTREAM_NoError; +} + +uint8_t SImage_Host_ReceiveBlockHeader(USB_ClassInfo_SI_Host_t* const SIInterfaceInfo, + SI_PIMA_Container_t* const PIMAHeader) +{ + uint16_t TimeoutMSRem = COMMAND_DATA_TIMEOUT_MS; + + if ((USB_HostState != HOST_STATE_Configured) || !(SIInterfaceInfo->State.IsActive)) + return PIPE_RWSTREAM_DeviceDisconnected; + + Pipe_SelectPipe(SIInterfaceInfo->Config.DataINPipeNumber); + Pipe_Unfreeze(); + + while (!(Pipe_IsReadWriteAllowed())) + { + if (USB_INT_HasOccurred(USB_INT_HSOFI)) + { + USB_INT_Clear(USB_INT_HSOFI); + TimeoutMSRem--; + + if (!(TimeoutMSRem)) + { + return PIPE_RWSTREAM_Timeout; + } + } + + Pipe_Freeze(); + Pipe_SelectPipe(SIInterfaceInfo->Config.DataOUTPipeNumber); + Pipe_Unfreeze(); + + if (Pipe_IsStalled()) + { + USB_Host_ClearPipeStall(SIInterfaceInfo->Config.DataOUTPipeNumber); + return PIPE_RWSTREAM_PipeStalled; + } + + Pipe_Freeze(); + Pipe_SelectPipe(SIInterfaceInfo->Config.DataINPipeNumber); + Pipe_Unfreeze(); + + if (Pipe_IsStalled()) + { + USB_Host_ClearPipeStall(SIInterfaceInfo->Config.DataINPipeNumber); + return PIPE_RWSTREAM_PipeStalled; + } + + if (USB_HostState == HOST_STATE_Unattached) + return PIPE_RWSTREAM_DeviceDisconnected; + } + + Pipe_Read_Stream_LE(PIMAHeader, PIMA_COMMAND_SIZE(0), NO_STREAM_CALLBACK); + + if (PIMAHeader->Type == CType_ResponseBlock) + { + uint8_t ParamBytes = (PIMAHeader->DataLength - PIMA_COMMAND_SIZE(0)); + + if (ParamBytes) + Pipe_Read_Stream_LE(&PIMAHeader->Params, ParamBytes, NO_STREAM_CALLBACK); + + Pipe_ClearIN(); + } + + Pipe_Freeze(); + + return PIPE_RWSTREAM_NoError; +} + +uint8_t SImage_Host_SendData(USB_ClassInfo_SI_Host_t* const SIInterfaceInfo, + void* Buffer, + const uint16_t Bytes) +{ + uint8_t ErrorCode; + + if ((USB_HostState != HOST_STATE_Configured) || !(SIInterfaceInfo->State.IsActive)) + return PIPE_RWSTREAM_DeviceDisconnected; + + Pipe_SelectPipe(SIInterfaceInfo->Config.DataOUTPipeNumber); + Pipe_Unfreeze(); + + ErrorCode = Pipe_Write_Stream_LE(Buffer, Bytes, NO_STREAM_CALLBACK); + + Pipe_ClearOUT(); + Pipe_Freeze(); + + return ErrorCode; +} + +uint8_t SImage_Host_ReadData(USB_ClassInfo_SI_Host_t* const SIInterfaceInfo, + void* Buffer, + const uint16_t Bytes) +{ + uint8_t ErrorCode; + + if ((USB_HostState != HOST_STATE_Configured) || !(SIInterfaceInfo->State.IsActive)) + return PIPE_RWSTREAM_DeviceDisconnected; + + Pipe_SelectPipe(SIInterfaceInfo->Config.DataINPipeNumber); + Pipe_Unfreeze(); + + ErrorCode = Pipe_Read_Stream_LE(Buffer, Bytes, NO_STREAM_CALLBACK); + + Pipe_Freeze(); + + return ErrorCode; +} + +bool SImage_Host_IsEventReceived(USB_ClassInfo_SI_Host_t* const SIInterfaceInfo) +{ + bool IsEventReceived = false; + + if ((USB_HostState != HOST_STATE_Configured) || !(SIInterfaceInfo->State.IsActive)) + return false; + + Pipe_SelectPipe(SIInterfaceInfo->Config.EventsPipeNumber); + Pipe_Unfreeze(); + + if (Pipe_BytesInPipe()) + IsEventReceived = true; + + Pipe_Freeze(); + + return IsEventReceived; +} + +uint8_t SImage_Host_ReceiveEventHeader(USB_ClassInfo_SI_Host_t* const SIInterfaceInfo, + SI_PIMA_Container_t* const PIMAHeader) +{ + uint8_t ErrorCode; + + if ((USB_HostState != HOST_STATE_Configured) || !(SIInterfaceInfo->State.IsActive)) + return PIPE_RWSTREAM_DeviceDisconnected; + + Pipe_SelectPipe(SIInterfaceInfo->Config.EventsPipeNumber); + Pipe_Unfreeze(); + + ErrorCode = Pipe_Read_Stream_LE(PIMAHeader, sizeof(SI_PIMA_Container_t), NO_STREAM_CALLBACK); + + Pipe_ClearIN(); + Pipe_Freeze(); + + return ErrorCode; +} + +uint8_t SImage_Host_OpenSession(USB_ClassInfo_SI_Host_t* const SIInterfaceInfo) +{ + if ((USB_HostState != HOST_STATE_Configured) || !(SIInterfaceInfo->State.IsActive)) + return HOST_SENDCONTROL_DeviceDisconnected; + + uint8_t ErrorCode; + + SIInterfaceInfo->State.TransactionID = 0; + SIInterfaceInfo->State.IsSessionOpen = false; + + SI_PIMA_Container_t PIMABlock = (SI_PIMA_Container_t) + { + .DataLength = PIMA_COMMAND_SIZE(1), + .Type = CType_CommandBlock, + .Code = 0x1002, + .Params = {1}, + }; + + if ((ErrorCode = SImage_Host_SendBlockHeader(SIInterfaceInfo, &PIMABlock)) != PIPE_RWSTREAM_NoError) + return ErrorCode; + + if ((ErrorCode = SImage_Host_ReceiveBlockHeader(SIInterfaceInfo, &PIMABlock)) != PIPE_RWSTREAM_NoError) + return ErrorCode; + + if ((PIMABlock.Type != CType_ResponseBlock) || (PIMABlock.Code != 0x2001)) + return SI_ERROR_LOGICAL_CMD_FAILED; + + SIInterfaceInfo->State.IsSessionOpen = true; + + return PIPE_RWSTREAM_NoError; +} + +uint8_t SImage_Host_CloseSession(USB_ClassInfo_SI_Host_t* const SIInterfaceInfo) +{ + if ((USB_HostState != HOST_STATE_Configured) || !(SIInterfaceInfo->State.IsActive)) + return HOST_SENDCONTROL_DeviceDisconnected; + + uint8_t ErrorCode; + + SI_PIMA_Container_t PIMABlock = (SI_PIMA_Container_t) + { + .DataLength = PIMA_COMMAND_SIZE(1), + .Type = CType_CommandBlock, + .Code = 0x1003, + .Params = {1}, + }; + + if ((ErrorCode = SImage_Host_SendBlockHeader(SIInterfaceInfo, &PIMABlock)) != PIPE_RWSTREAM_NoError) + return ErrorCode; + + if ((ErrorCode = SImage_Host_ReceiveBlockHeader(SIInterfaceInfo, &PIMABlock)) != PIPE_RWSTREAM_NoError) + return ErrorCode; + + SIInterfaceInfo->State.IsSessionOpen = false; + + if ((PIMABlock.Type != CType_ResponseBlock) || (PIMABlock.Code != 0x2001)) + return SI_ERROR_LOGICAL_CMD_FAILED; + + return PIPE_RWSTREAM_NoError; +} + +uint8_t SImage_Host_SendCommand(USB_ClassInfo_SI_Host_t* const SIInterfaceInfo, + const uint16_t Operation, + const uint8_t TotalParams, + uint32_t* const Params) +{ + if ((USB_HostState != HOST_STATE_Configured) || !(SIInterfaceInfo->State.IsActive)) + return HOST_SENDCONTROL_DeviceDisconnected; + + uint8_t ErrorCode; + + SI_PIMA_Container_t PIMABlock = (SI_PIMA_Container_t) + { + .DataLength = PIMA_COMMAND_SIZE(TotalParams), + .Type = CType_CommandBlock, + .Code = Operation, + }; + + memcpy(&PIMABlock.Params, Params, sizeof(uint32_t) * TotalParams); + + if ((ErrorCode = SImage_Host_SendBlockHeader(SIInterfaceInfo, &PIMABlock)) != PIPE_RWSTREAM_NoError) + return ErrorCode; + + return PIPE_RWSTREAM_NoError; +} + +uint8_t SImage_Host_ReceiveResponse(USB_ClassInfo_SI_Host_t* const SIInterfaceInfo) +{ + uint8_t ErrorCode; + SI_PIMA_Container_t PIMABlock; + + if ((USB_HostState != HOST_STATE_Configured) || !(SIInterfaceInfo->State.IsActive)) + return HOST_SENDCONTROL_DeviceDisconnected; + + if ((ErrorCode = SImage_Host_ReceiveBlockHeader(SIInterfaceInfo, &PIMABlock)) != PIPE_RWSTREAM_NoError) + return ErrorCode; + + if ((PIMABlock.Type != CType_ResponseBlock) || (PIMABlock.Code != 0x2001)) + return SI_ERROR_LOGICAL_CMD_FAILED; + + return PIPE_RWSTREAM_NoError; +} + +#endif diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/StillImage.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/StillImage.h new file mode 100644 index 0000000000..a15091b6a8 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Host/StillImage.h @@ -0,0 +1,332 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief Host mode driver for the library USB Still Image Class driver. + * + * Host mode driver for the library USB Still Image Class driver. + * + * \note This file should not be included directly. It is automatically included as needed by the class driver + * dispatch header located in LUFA/Drivers/USB/Class/StillImage.h. + */ + +/** \ingroup Group_USBClassSI + * @defgroup Group_USBClassStillImageHost Still Image Class Host Mode Driver + * + * \section Sec_Dependencies Module Source Dependencies + * The following files must be built with any user project that uses this module: + * - LUFA/Drivers/USB/Class/Host/StillImage.c (Makefile source module name: LUFA_SRC_USBCLASS) + * + * \section Module Description + * Host Mode USB Class driver framework interface, for the Still Image USB Class driver. + * + * @{ + */ + +#ifndef __SI_CLASS_HOST_H__ +#define __SI_CLASS_HOST_H__ + + /* Includes: */ + #include "../../USB.h" + #include "../Common/StillImage.h" + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_SI_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/Class/StillImage.h instead. + #endif + + /* Public Interface - May be used in end-application: */ + /* Macros: */ + /** Error code for some Still Image Host functions, indicating a logical (and not hardware) error. */ + #define SI_ERROR_LOGICAL_CMD_FAILED 0x80 + + /* Type Defines: */ + /** \brief Still Image Class Host Mode Configuration and State Structure. + * + * Class state structure. An instance of this structure should be made within the user application, + * and passed to each of the Still Image class driver functions as the SIInterfaceInfo parameter. This + * stores each Still Image interface's configuration and state information. + */ + typedef struct + { + const struct + { + uint8_t DataINPipeNumber; /**< Pipe number of the Still Image interface's IN data pipe. */ + bool DataINPipeDoubleBank; /**< Indicates if the Still Image interface's IN data pipe should use double banking. */ + + uint8_t DataOUTPipeNumber; /**< Pipe number of the Still Image interface's OUT data pipe. */ + bool DataOUTPipeDoubleBank; /**< Indicates if the Still Image interface's OUT data pipe should use double banking. */ + + uint8_t EventsPipeNumber; /**< Pipe number of the Still Image interface's IN events endpoint, if used. */ + bool EventsPipeDoubleBank; /**< Indicates if the Still Image interface's events data pipe should use double banking. */ + } Config; /**< Config data for the USB class interface within the device. All elements in this section + * must be set or the interface will fail to enumerate and operate correctly. + */ + struct + { + bool IsActive; /**< Indicates if the current interface instance is connected to an attached device, valid + * after \ref SImage_Host_ConfigurePipes() is called and the Host state machine is in the + * Configured state. + */ + + uint16_t DataINPipeSize; /**< Size in bytes of the Still Image interface's IN data pipe. */ + uint16_t DataOUTPipeSize; /**< Size in bytes of the Still Image interface's OUT data pipe. */ + uint16_t EventsPipeSize; /**< Size in bytes of the Still Image interface's IN events pipe. */ + + bool IsSessionOpen; /**< Indicates if a PIMA session is currently open with the attached device. */ + uint32_t TransactionID; /**< Transaction ID for the next transaction to send to the device. */ + } State; /**< State data for the USB class interface within the device. All elements in this section + * may be set to initial values, but may also be ignored to default to sane values when + * the interface is enumerated. + */ + } USB_ClassInfo_SI_Host_t; + + /* Enums: */ + /** Enum for the possible error codes returned by the \ref SImage_Host_ConfigurePipes() function. */ + enum SIHost_EnumerationFailure_ErrorCodes_t + { + SI_ENUMERROR_NoError = 0, /**< Configuration Descriptor was processed successfully. */ + SI_ENUMERROR_InvalidConfigDescriptor = 1, /**< The device returned an invalid Configuration Descriptor. */ + SI_ENUMERROR_NoSIInterfaceFound = 2, /**< A compatible Still Image interface was not found in the device's + * Configuration Descriptor. + */ + SI_ENUMERROR_EndpointsNotFound = 3, /**< Compatible Still Image data endpoints were not found in the + * device's Still Image interface. + */ + }; + + /* Function Prototypes: */ + /** Host interface configuration routine, to configure a given Still Image host interface instance using the + * Configuration Descriptor read from an attached USB device. This function automatically updates the given Still + * Image Host instance's state values and configures the pipes required to communicate with the interface if it is + * found within the device. This should be called once after the stack has enumerated the attached device, while + * the host state machine is in the Addressed state. + * + * \param[in,out] SIInterfaceInfo Pointer to a structure containing a Still Image Class host configuration and state. + * \param[in] ConfigDescriptorSize Length of the attached device's Configuration Descriptor. + * \param[in] DeviceConfigDescriptor Pointer to a buffer containing the attached device's Configuration Descriptor. + * + * \return A value from the \ref SIHost_EnumerationFailure_ErrorCodes_t enum. + */ + uint8_t SImage_Host_ConfigurePipes(USB_ClassInfo_SI_Host_t* const SIInterfaceInfo, + uint16_t ConfigDescriptorSize, + void* DeviceConfigDescriptor) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(3); + + /** Opens a new PIMA session with the attached device. This should be used before any session-orientated PIMA commands + * are issued to the device. Only one session can be open at the one time. + * + * \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the + * call will fail. + * + * \param[in,out] SIInterfaceInfo Pointer to a structure containing a Still Image Class host configuration and state. + * + * \return A value from the \ref Pipe_Stream_RW_ErrorCodes_t enum, or \ref SI_ERROR_LOGICAL_CMD_FAILED if the device + * returned a logical command failure. + */ + uint8_t SImage_Host_OpenSession(USB_ClassInfo_SI_Host_t* const SIInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** Closes an already opened PIMA session with the attached device. This should be used after all session-orientated + * PIMA commands have been issued to the device. + * + * \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the + * call will fail. + * + * \param[in,out] SIInterfaceInfo Pointer to a structure containing a Still Image Class host configuration and state. + * + * \return A value from the \ref Pipe_Stream_RW_ErrorCodes_t enum, or \ref SI_ERROR_LOGICAL_CMD_FAILED if the device + * returned a logical command failure. + */ + uint8_t SImage_Host_CloseSession(USB_ClassInfo_SI_Host_t* const SIInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** Sends a raw PIMA block header to the device, filling out the transaction ID automatically. This can be used to send + * arbitrary PIMA blocks to the device with or without parameters. + * + * \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the + * call will fail. + * + * \param[in,out] SIInterfaceInfo Pointer to a structure containing a Still Image Class host configuration and state. + * \param[in] PIMAHeader Pointer to a PIMA container structure that is to be sent. + * + * \return A value from the \ref Pipe_Stream_RW_ErrorCodes_t enum. + */ + uint8_t SImage_Host_SendBlockHeader(USB_ClassInfo_SI_Host_t* const SIInterfaceInfo, + SI_PIMA_Container_t* const PIMAHeader) ATTR_NON_NULL_PTR_ARG(1) + ATTR_NON_NULL_PTR_ARG(2); + + /** Receives a raw PIMA block header to the device. This can be used to receive arbitrary PIMA blocks from the device with + * or without parameters. + * + * \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the + * call will fail. + * + * \param[in,out] SIInterfaceInfo Pointer to a structure containing a Still Image Class host configuration and state. + * \param[out] PIMAHeader Pointer to a PIMA container structure where the received block is to be stored. + * + * \return A value from the \ref Pipe_Stream_RW_ErrorCodes_t enum. + */ + uint8_t SImage_Host_ReceiveBlockHeader(USB_ClassInfo_SI_Host_t* const SIInterfaceInfo, + SI_PIMA_Container_t* const PIMAHeader) ATTR_NON_NULL_PTR_ARG(1) + ATTR_NON_NULL_PTR_ARG(2); + + /** Sends a given PIMA command to the attached device, filling out the PIMA command header's Transaction ID automatically. + * + * \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the + * call will fail. + * + * \param[in,out] SIInterfaceInfo Pointer to a structure containing a Still Image Class host configuration and state. + * \param[in] Operation PIMA operation code to issue to the device. + * \param[in] TotalParams Total number of 32-bit parameters to send to the device in the issued command block. + * \param[in] Params Pointer to an array of 32-bit values containing the parameters to send in the command block. + * + * \return A value from the \ref Pipe_Stream_RW_ErrorCodes_t enum, or \ref SI_ERROR_LOGICAL_CMD_FAILED if the device + * returned a logical command failure. + */ + uint8_t SImage_Host_SendCommand(USB_ClassInfo_SI_Host_t* const SIInterfaceInfo, + const uint16_t Operation, + const uint8_t TotalParams, + uint32_t* const Params) ATTR_NON_NULL_PTR_ARG(1); + + /** Receives and checks a response block from the attached PIMA device, once a command has been issued and all data + * associated with the command has been transferred. + * + * \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the + * call will fail. + * + * \param[in,out] SIInterfaceInfo Pointer to a structure containing a Still Image Class host configuration and state. + * + * \return A value from the \ref Pipe_Stream_RW_ErrorCodes_t enum, or \ref SI_ERROR_LOGICAL_CMD_FAILED if the device + * returned a logical command failure. + */ + uint8_t SImage_Host_ReceiveResponse(USB_ClassInfo_SI_Host_t* const SIInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** Indicates if the device has issued a PIMA event block to the host via the asynchronous events pipe. + * + * \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the + * call will fail. + * + * \param[in,out] SIInterfaceInfo Pointer to a structure containing a Still Image Class host configuration and state. + * + * \return Boolean true if an event is waiting to be read, false otherwise. + */ + bool SImage_Host_IsEventReceived(USB_ClassInfo_SI_Host_t* const SIInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + + /** Receives an asynchronous event block from the device via the asynchronous events pipe. + * + * \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the + * call will fail. + * + * \param[in,out] SIInterfaceInfo Pointer to a structure containing a Still Image Class host configuration and state. + * \param[out] PIMAHeader Pointer to a PIMA container structure where the event should be stored. + * + * \return A value from the \ref Pipe_Stream_RW_ErrorCodes_t enum, or \ref SI_ERROR_LOGICAL_CMD_FAILED if the device + * returned a logical command failure. + */ + uint8_t SImage_Host_ReceiveEventHeader(USB_ClassInfo_SI_Host_t* const SIInterfaceInfo, + SI_PIMA_Container_t* const PIMAHeader) ATTR_NON_NULL_PTR_ARG(1) + ATTR_NON_NULL_PTR_ARG(2); + + /** Sends arbitrary data to the attached device, for use in the data phase of PIMA commands which require data + * transfer beyond the regular PIMA command block parameters. + * + * \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the + * call will fail. + * + * \param[in,out] SIInterfaceInfo Pointer to a structure containing a Still Image Class host configuration and state. + * \param[in] Buffer Pointer to a buffer where the data to send has been stored. + * \param[in] Bytes Length in bytes of the data in the buffer to send to the attached device. + * + * \return A value from the \ref Pipe_Stream_RW_ErrorCodes_t enum. + */ + uint8_t SImage_Host_SendData(USB_ClassInfo_SI_Host_t* const SIInterfaceInfo, + void* Buffer, + const uint16_t Bytes) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(2); + + /** Receives arbitrary data from the attached device, for use in the data phase of PIMA commands which require data + * transfer beyond the regular PIMA command block parameters. + * + * \pre This function must only be called when the Host state machine is in the HOST_STATE_Configured state or the + * call will fail. + * + * \param[in,out] SIInterfaceInfo Pointer to a structure containing a Still Image Class host configuration and state. + * \param[out] Buffer Pointer to a buffer where the received data is to be stored. + * \param[in] Bytes Length in bytes of the data to read. + * + * \return A value from the \ref Pipe_Stream_RW_ErrorCodes_t enum. + */ + uint8_t SImage_Host_ReadData(USB_ClassInfo_SI_Host_t* const SIInterfaceInfo, + void* Buffer, + const uint16_t Bytes) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(2); + + /* Inline Functions: */ + /** General management task for a given Still Image host class interface, required for the correct operation of the + * interface. This should be called frequently in the main program loop, before the master USB management task + * \ref USB_USBTask(). + * + * \param[in,out] SIInterfaceInfo Pointer to a structure containing a Still Image Class host configuration and state. + */ + static inline void SImage_Host_USBTask(USB_ClassInfo_SI_Host_t* const SIInterfaceInfo) ATTR_NON_NULL_PTR_ARG(1); + static inline void SImage_Host_USBTask(USB_ClassInfo_SI_Host_t* const SIInterfaceInfo) + { + (void)SIInterfaceInfo; + } + + /* Private Interface - For use in library only: */ + #if !defined(__DOXYGEN__) + /* Macros: */ + #define STILL_IMAGE_CLASS 0x06 + #define STILL_IMAGE_SUBCLASS 0x01 + #define STILL_IMAGE_PROTOCOL 0x01 + + #define SI_FOUND_EVENTS_IN (1 << 0) + #define SI_FOUND_DATAPIPE_IN (1 << 1) + #define SI_FOUND_DATAPIPE_OUT (1 << 2) + + #define COMMAND_DATA_TIMEOUT_MS 10000 + + /* Function Prototypes: */ + #if defined(__INCLUDE_FROM_SI_CLASS_HOST_C) + static uint8_t DCOMP_SI_Host_NextSIInterface(void* const CurrentDescriptor) ATTR_NON_NULL_PTR_ARG(1); + static uint8_t DCOMP_SI_Host_NextSIInterfaceEndpoint(void* const CurrentDescriptor) ATTR_NON_NULL_PTR_ARG(1); + #endif + #endif + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/MIDI.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/MIDI.h new file mode 100644 index 0000000000..33be2b793e --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/MIDI.h @@ -0,0 +1,86 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief Master include file for the library USB MIDI Class driver. + * + * Master include file for the library USB MIDI Class driver, for both host and device modes, where available. + * + * This file should be included in all user projects making use of this optional class driver, instead of + * including any headers in the USB/ClassDriver/Device, USB/ClassDriver/Host or USB/ClassDriver/Common subdirectories. + */ + +/** \ingroup Group_USBClassDrivers + * @defgroup Group_USBClassMIDI MIDI Class Driver - LUFA/Drivers/Class/MIDI.h + * + * \section Sec_Dependencies Module Source Dependencies + * The following files must be built with any user project that uses this module: + * - LUFA/Drivers/USB/Class/Device/MIDI.c (Makefile source module name: LUFA_SRC_USBCLASS) + * - LUFA/Drivers/USB/Class/Host/MIDI.c (Makefile source module name: LUFA_SRC_USBCLASS) + * + * \section Module Description + * MIDI Class Driver module. This module contains an internal implementation of the USB MIDI Class, for both Device + * and Host USB modes. User applications can use this class driver instead of implementing the MIDI class manually + * via the low-level LUFA APIs. + * + * This module is designed to simplify the user code by exposing only the required interface needed to interface with + * Hosts or Devices using the USB MIDI Class. + * + * \note The USB MIDI class is actually a special case of the regular Audio class, thus this module depends on + * structure definitions from the \ref Group_USBClassAudioDevice class driver module. + * + * @{ + */ + +#ifndef _MIDI_CLASS_H_ +#define _MIDI_CLASS_H_ + + /* Macros: */ + #define __INCLUDE_FROM_MIDI_DRIVER + #define __INCLUDE_FROM_USB_DRIVER + + /* Includes: */ + #include "../HighLevel/USBMode.h" + + #if defined(NO_STREAM_CALLBACKS) + #error The NO_STREAM_CALLBACKS compile time option cannot be used in projects using the library Class drivers. + #endif + + #if defined(USB_CAN_BE_DEVICE) + #include "Device/MIDI.h" + #endif + + #if defined(USB_CAN_BE_HOST) + #include "Host/MIDI.h" + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/MassStorage.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/MassStorage.h new file mode 100644 index 0000000000..9d61d380d9 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/MassStorage.h @@ -0,0 +1,83 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief Master include file for the library USB Mass Storage Class driver. + * + * Master include file for the library USB Mass Storage Class driver, for both host and device modes, where available. + * + * This file should be included in all user projects making use of this optional class driver, instead of + * including any headers in the USB/ClassDriver/Device, USB/ClassDriver/Host or USB/ClassDriver/Common subdirectories. + */ + +/** \ingroup Group_USBClassDrivers + * @defgroup Group_USBClassMS Mass Storage Class Driver - LUFA/Drivers/Class/MassStorage.h + * + * \section Sec_Dependencies Module Source Dependencies + * The following files must be built with any user project that uses this module: + * - LUFA/Drivers/USB/Class/Device/MassStorage.c (Makefile source module name: LUFA_SRC_USBCLASS) + * - LUFA/Drivers/USB/Class/Host/MassStorage.c (Makefile source module name: LUFA_SRC_USBCLASS) + * + * \section Module Description + * Mass Storage Class Driver module. This module contains an internal implementation of the USB Mass Storage Class, for both + * Device and Host USB modes. User applications can use this class driver instead of implementing the Mass Storage class + * manually via the low-level LUFA APIs. + * + * This module is designed to simplify the user code by exposing only the required interface needed to interface with + * Hosts or Devices using the USB Mass Storage Class. + * + * @{ + */ + +#ifndef _MS_CLASS_H_ +#define _MS_CLASS_H_ + + /* Macros: */ + #define __INCLUDE_FROM_MS_DRIVER + #define __INCLUDE_FROM_USB_DRIVER + + /* Includes: */ + #include "../HighLevel/USBMode.h" + + #if defined(NO_STREAM_CALLBACKS) + #error The NO_STREAM_CALLBACKS compile time option cannot be used in projects using the library Class drivers. + #endif + + #if defined(USB_CAN_BE_DEVICE) + #include "Device/MassStorage.h" + #endif + + #if defined(USB_CAN_BE_HOST) + #include "Host/MassStorage.h" + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Printer.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Printer.h new file mode 100644 index 0000000000..74ee6e613e --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/Printer.h @@ -0,0 +1,80 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief Master include file for the library USB Printer Class driver. + * + * Master include file for the library USB Printer Class driver, for both host and device modes, where available. + * + * This file should be included in all user projects making use of this optional class driver, instead of + * including any headers in the USB/ClassDriver/Device, USB/ClassDriver/Host or USB/ClassDriver/Common subdirectories. + */ + +/** \ingroup Group_USBClassDrivers + * @defgroup Group_USBClassPrinter Printer Class Driver - LUFA/Drivers/Class/Printer.h + * + * \section Sec_Dependencies Module Source Dependencies + * The following files must be built with any user project that uses this module: + * - LUFA/Drivers/USB/Class/Host/Printer.c (Makefile source module name: LUFA_SRC_USBCLASS) + * + * \section Module Description + * Printer Class Driver module. This module contains an internal implementation of the USB Printer Class, for the base + * USB Printer transport layer for USB Host mode only. Note that printers are free to implement whatever printer language + * they choose on top of this (e.g. Postscript), and so this driver exposes low level data transport functions only rather + * than high level raster or text functions. User applications can use this class driver instead of implementing the Printer + * class manually via the low-level LUFA APIs. + * + * This module is designed to simplify the user code by exposing only the required interface needed to interface with + * Devices using the USB Printer Class. + * + * @{ + */ + +#ifndef _PRINTER_CLASS_H_ +#define _PRINTER_CLASS_H_ + + /* Macros: */ + #define __INCLUDE_FROM_PRINTER_DRIVER + #define __INCLUDE_FROM_USB_DRIVER + + /* Includes: */ + #include "../HighLevel/USBMode.h" + + #if defined(NO_STREAM_CALLBACKS) + #error The NO_STREAM_CALLBACKS compile time option cannot be used in projects using the library Class drivers. + #endif + + #if defined(USB_CAN_BE_HOST) + #include "Host/Printer.h" + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/RNDIS.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/RNDIS.h new file mode 100644 index 0000000000..5f3bb56845 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/RNDIS.h @@ -0,0 +1,83 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief Master include file for the library USB RNDIS Class driver. + * + * Master include file for the library USB RNDIS Class driver, for both host and device modes, where available. + * + * This file should be included in all user projects making use of this optional class driver, instead of + * including any headers in the USB/ClassDriver/Device, USB/ClassDriver/Host or USB/ClassDriver/Common subdirectories. + */ + +/** \ingroup Group_USBClassDrivers + * @defgroup Group_USBClassRNDIS RNDIS (Networking) Class Driver - LUFA/Drivers/Class/RNDIS.h + * + * \section Sec_Dependencies Module Source Dependencies + * The following files must be built with any user project that uses this module: + * - LUFA/Drivers/USB/Class/Device/RNDIS.c (Makefile source module name: LUFA_SRC_USBCLASS) + * - LUFA/Drivers/USB/Class/Host/RNDIS.c (Makefile source module name: LUFA_SRC_USBCLASS) + * + * \section Module Description + * RNDIS Class Driver module. This module contains an internal implementation of the Microsoft USB RNDIS Networking + * Class, for both Device and Host USB modes. User applications can use this class driver instead of implementing the + * RNDIS class manually via the low-level LUFA APIs. + * + * This module is designed to simplify the user code by exposing only the required interface needed to interface with + * Hosts using the USB RNDIS Class. + * + * @{ + */ + +#ifndef _RNDIS_CLASS_H_ +#define _RNDIS_CLASS_H_ + + /* Macros: */ + #define __INCLUDE_FROM_RNDIS_DRIVER + #define __INCLUDE_FROM_USB_DRIVER + + /* Includes: */ + #include "../HighLevel/USBMode.h" + + #if defined(NO_STREAM_CALLBACKS) + #error The NO_STREAM_CALLBACKS compile time option cannot be used in projects using the library Class drivers. + #endif + + #if defined(USB_CAN_BE_DEVICE) + #include "Device/RNDIS.h" + #endif + + #if defined(USB_CAN_BE_HOST) + #include "Host/RNDIS.h" + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/StillImage.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/StillImage.h new file mode 100644 index 0000000000..4c64e2d897 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/Class/StillImage.h @@ -0,0 +1,78 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief Master include file for the library USB Still Image Class driver. + * + * Master include file for the library USB Still Image Class driver, for both host and device modes, where available. + * + * This file should be included in all user projects making use of this optional class driver, instead of + * including any headers in the USB/ClassDriver/Device, USB/ClassDriver/Host or USB/ClassDriver/Common subdirectories. + */ + +/** \ingroup Group_USBClassDrivers + * @defgroup Group_USBClassSI Still Image Class Driver - LUFA/Drivers/Class/StillImage.h + * + * \section Sec_Dependencies Module Source Dependencies + * The following files must be built with any user project that uses this module: + * - LUFA/Drivers/USB/Class/Host/StillImage.c (Makefile source module name: LUFA_SRC_USBCLASS) + * + * \section Module Description + * Still Image Class Driver module. This module contains an internal implementation of the USB Still Image Class, + * for USB Host mode only. User applications can use this class driver instead of implementing the Still Image class + * manually via the low-level LUFA APIs. + * + * This module is designed to simplify the user code by exposing only the required interface needed to interface with + * Devices using the USB Still Image Class. + * + * @{ + */ + +#ifndef _SI_CLASS_H_ +#define _SI_CLASS_H_ + + /* Macros: */ + #define __INCLUDE_FROM_SI_DRIVER + #define __INCLUDE_FROM_USB_DRIVER + + /* Includes: */ + #include "../HighLevel/USBMode.h" + + #if defined(NO_STREAM_CALLBACKS) + #error The NO_STREAM_CALLBACKS compile time option cannot be used in projects using the library Class drivers. + #endif + + #if defined(USB_CAN_BE_HOST) + #include "Host/StillImage.h" + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/ConfigDescriptor.c b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/ConfigDescriptor.c new file mode 100644 index 0000000000..78290d73c1 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/ConfigDescriptor.c @@ -0,0 +1,141 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +#define __INCLUDE_FROM_USB_DRIVER +#include "ConfigDescriptor.h" + +#if defined(USB_CAN_BE_HOST) +uint8_t USB_Host_GetDeviceConfigDescriptor(uint8_t ConfigNumber, uint16_t* const ConfigSizePtr, + void* BufferPtr, uint16_t BufferSize) +{ + uint8_t ErrorCode; + uint8_t ConfigHeader[sizeof(USB_Descriptor_Configuration_Header_t)]; + + USB_ControlRequest = (USB_Request_Header_t) + { + .bmRequestType = (REQDIR_DEVICETOHOST | REQTYPE_STANDARD | REQREC_DEVICE), + .bRequest = REQ_GetDescriptor, + .wValue = ((DTYPE_Configuration << 8) | (ConfigNumber - 1)), + .wIndex = 0, + .wLength = sizeof(USB_Descriptor_Configuration_Header_t), + }; + + Pipe_SelectPipe(PIPE_CONTROLPIPE); + + if ((ErrorCode = USB_Host_SendControlRequest(ConfigHeader)) != HOST_SENDCONTROL_Successful) + return ErrorCode; + + *ConfigSizePtr = DESCRIPTOR_CAST(ConfigHeader, USB_Descriptor_Configuration_Header_t).TotalConfigurationSize; + + if (*ConfigSizePtr > BufferSize) + return HOST_GETCONFIG_BuffOverflow; + + USB_ControlRequest.wLength = *ConfigSizePtr; + + if ((ErrorCode = USB_Host_SendControlRequest(BufferPtr)) != HOST_SENDCONTROL_Successful) + return ErrorCode; + + if (DESCRIPTOR_TYPE(BufferPtr) != DTYPE_Configuration) + return HOST_GETCONFIG_InvalidData; + + return HOST_GETCONFIG_Successful; +} +#endif + +void USB_GetNextDescriptorOfType(uint16_t* const BytesRem, + void** const CurrConfigLoc, + const uint8_t Type) +{ + while (*BytesRem) + { + USB_GetNextDescriptor(BytesRem, CurrConfigLoc); + + if (DESCRIPTOR_TYPE(*CurrConfigLoc) == Type) + return; + } +} + +void USB_GetNextDescriptorOfTypeBefore(uint16_t* const BytesRem, + void** const CurrConfigLoc, + const uint8_t Type, + const uint8_t BeforeType) +{ + while (*BytesRem) + { + USB_GetNextDescriptor(BytesRem, CurrConfigLoc); + + if (DESCRIPTOR_TYPE(*CurrConfigLoc) == Type) + { + return; + } + else if (DESCRIPTOR_TYPE(*CurrConfigLoc) == BeforeType) + { + *BytesRem = 0; + return; + } + } +} + +void USB_GetNextDescriptorOfTypeAfter(uint16_t* const BytesRem, + void** const CurrConfigLoc, + const uint8_t Type, + const uint8_t AfterType) +{ + USB_GetNextDescriptorOfType(BytesRem, CurrConfigLoc, AfterType); + + if (*BytesRem) + USB_GetNextDescriptorOfType(BytesRem, CurrConfigLoc, Type); +} + +uint8_t USB_GetNextDescriptorComp(uint16_t* const BytesRem, void** const CurrConfigLoc, ConfigComparatorPtr_t const ComparatorRoutine) +{ + uint8_t ErrorCode; + + while (*BytesRem) + { + uint8_t* PrevDescLoc = *CurrConfigLoc; + uint16_t PrevBytesRem = *BytesRem; + + USB_GetNextDescriptor(BytesRem, CurrConfigLoc); + + if ((ErrorCode = ComparatorRoutine(*CurrConfigLoc)) != DESCRIPTOR_SEARCH_NotFound) + { + if (ErrorCode == DESCRIPTOR_SEARCH_Fail) + { + *CurrConfigLoc = PrevDescLoc; + *BytesRem = PrevBytesRem; + } + + return ErrorCode; + } + } + + return DESCRIPTOR_SEARCH_COMP_EndOfDescriptor; +} diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/ConfigDescriptor.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/ConfigDescriptor.h new file mode 100644 index 0000000000..001653b522 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/ConfigDescriptor.h @@ -0,0 +1,286 @@ +/* + 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 Configuration descriptor parser API. + * + * This section of the library gives a friendly API which can be used in host applications to easily + * parse an attached device's configuration descriptor so that endpoint, interface and other descriptor + * data can be extracted and used as needed. + * + * \note This file should not be included directly. It is automatically included as needed by the USB driver + * dispatch header located in LUFA/Drivers/USB/USB.h. + */ + +/** \ingroup Group_Descriptors + * @defgroup Group_ConfigDescriptorParser Configuration Descriptor Parser + * + * Functions, macros, variables, enums and types related to the parsing of Configuration Descriptors. + * + * @{ + */ + +#ifndef __CONFIGDESCRIPTOR_H__ +#define __CONFIGDESCRIPTOR_H__ + + /* Includes: */ + #include + + #include "../../../Common/Common.h" + #include "HostStandardReq.h" + #include "USBMode.h" + #include "StdDescriptors.h" + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_USB_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/USB/USB.h instead. + #endif + + /* Public Interface - May be used in end-application: */ + /* Macros: */ + /** Mask for determining the type of an endpoint from an endpoint descriptor. This should then be compared + * with the EP_TYPE_* masks to determine the exact type of the endpoint. + */ + #define EP_TYPE_MASK 0x03 + + /** Casts a pointer to a descriptor inside the configuration descriptor into a pointer to the given + * descriptor type. + * + * Usage Example: + * \code + * uint8_t* CurrDescriptor = &ConfigDescriptor[0]; // Pointing to the configuration header + * USB_Descriptor_Configuration_Header_t* ConfigHeaderPtr = DESCRIPTOR_PCAST(CurrDescriptor, + * USB_Descriptor_Configuration_Header_t); + * + * // Can now access elements of the configuration header struct using the -> indirection operator + * \endcode + */ + #define DESCRIPTOR_PCAST(DescriptorPtr, Type) ((Type*)(DescriptorPtr)) + + /** Casts a pointer to a descriptor inside the configuration descriptor into the given descriptor + * type (as an actual struct instance rather than a pointer to a struct). + * + * Usage Example: + * \code + * uint8_t* CurrDescriptor = &ConfigDescriptor[0]; // Pointing to the configuration header + * USB_Descriptor_Configuration_Header_t ConfigHeader = DESCRIPTOR_CAST(CurrDescriptor, + * USB_Descriptor_Configuration_Header_t); + * + * // Can now access elements of the configuration header struct using the . operator + * \endcode + */ + #define DESCRIPTOR_CAST(DescriptorPtr, Type) (*DESCRIPTOR_PCAST(DescriptorPtr, Type)) + + /** Returns the descriptor's type, expressed as the 8-bit type value in the header of the descriptor. + * This value's meaning depends on the descriptor's placement in the descriptor, but standard type + * values can be accessed in the \ref USB_DescriptorTypes_t enum. + */ + #define DESCRIPTOR_TYPE(DescriptorPtr) DESCRIPTOR_CAST(DescriptorPtr, USB_Descriptor_Header_t).Type + + /** Returns the descriptor's size, expressed as the 8-bit value indicating the number of bytes. */ + #define DESCRIPTOR_SIZE(DescriptorPtr) DESCRIPTOR_CAST(DescriptorPtr, USB_Descriptor_Header_t).Size + + /* Type Defines: */ + /** Type define for a Configuration Descriptor comparator function (function taking a pointer to an array + * of type void, returning a uint8_t value). + * + * \see \ref USB_GetNextDescriptorComp function for more details. + */ + typedef uint8_t (* ConfigComparatorPtr_t)(void*); + + /* Enums: */ + /** Enum for the possible return codes of the \ref USB_Host_GetDeviceConfigDescriptor() function. */ + enum USB_Host_GetConfigDescriptor_ErrorCodes_t + { + HOST_GETCONFIG_Successful = 0, /**< No error occurred while retrieving the configuration descriptor. */ + HOST_GETCONFIG_DeviceDisconnect = 1, /**< The attached device was disconnected while retrieving the configuration + * descriptor. + */ + HOST_GETCONFIG_PipeError = 2, /**< An error occurred in the pipe while sending the request. */ + HOST_GETCONFIG_SetupStalled = 3, /**< The attached device stalled the request to retrieve the configuration + * descriptor. + */ + HOST_GETCONFIG_SoftwareTimeOut = 4, /**< The request or data transfer timed out. */ + HOST_GETCONFIG_BuffOverflow = 5, /**< The device's configuration descriptor is too large to fit into the allocated + * buffer. + */ + HOST_GETCONFIG_InvalidData = 6, /**< The device returned invalid configuration descriptor data. */ + }; + + /** Enum for return values of a descriptor comparator function. */ + enum DSearch_Return_ErrorCodes_t + { + DESCRIPTOR_SEARCH_Found = 0, /**< Current descriptor matches comparator criteria. */ + DESCRIPTOR_SEARCH_Fail = 1, /**< No further descriptor could possibly match criteria, fail the search. */ + DESCRIPTOR_SEARCH_NotFound = 2, /**< Current descriptor does not match comparator criteria. */ + }; + + /** Enum for return values of \ref USB_GetNextDescriptorComp(). */ + enum DSearch_Comp_Return_ErrorCodes_t + { + DESCRIPTOR_SEARCH_COMP_Found = 0, /**< Configuration descriptor now points to descriptor which matches + * search criteria of the given comparator function. */ + DESCRIPTOR_SEARCH_COMP_Fail = 1, /**< Comparator function returned Descriptor_Search_Fail. */ + DESCRIPTOR_SEARCH_COMP_EndOfDescriptor = 2, /**< End of configuration descriptor reached before match found. */ + }; + + /* Function Prototypes: */ + /** Retrieves the configuration descriptor data from an attached device via a standard request into a buffer, + * including validity and size checking to prevent a buffer overflow. + * + * \param[in] ConfigNumber Device configuration descriptor number to fetch from the device (usually set to 1 for + * single configuration devices). + * \param[in,out] ConfigSizePtr Pointer to a uint16_t for storing the retrieved configuration descriptor size. + * \param[out] BufferPtr Pointer to the buffer for storing the configuration descriptor data. + * \param[out] BufferSize Size of the allocated buffer where the configuration descriptor is to be stored. + * + * \return A value from the \ref USB_Host_GetConfigDescriptor_ErrorCodes_t enum. + */ + uint8_t USB_Host_GetDeviceConfigDescriptor(uint8_t ConfigNumber, uint16_t* const ConfigSizePtr, void* BufferPtr, + uint16_t BufferSize) ATTR_NON_NULL_PTR_ARG(2) ATTR_NON_NULL_PTR_ARG(3); + + /** Skips to the next sub-descriptor inside the configuration descriptor of the specified type value. + * The bytes remaining value is automatically decremented. + * + * \param[in,out] BytesRem Pointer to the number of bytes remaining of the configuration descriptor. + * \param[in,out] CurrConfigLoc Pointer to the current descriptor inside the configuration descriptor. + * \param[in] Type Descriptor type value to search for. + */ + void USB_GetNextDescriptorOfType(uint16_t* const BytesRem, + void** const CurrConfigLoc, + const uint8_t Type) + ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(2); + + /** Skips to the next sub-descriptor inside the configuration descriptor of the specified type value, + * which must come before a descriptor of the second given type value. If the BeforeType type + * descriptor is reached first, the number of bytes remaining to process is set to zero and the + * function exits. The bytes remaining value is automatically decremented. + * + * \param[in,out] BytesRem Pointer to the number of bytes remaining of the configuration descriptor. + * \param[in,out] CurrConfigLoc Pointer to the current descriptor inside the configuration descriptor. + * \param[in] Type Descriptor type value to search for. + * \param[in] BeforeType Descriptor type value which must not be reached before the given Type descriptor. + */ + void USB_GetNextDescriptorOfTypeBefore(uint16_t* const BytesRem, + void** const CurrConfigLoc, + const uint8_t Type, + const uint8_t BeforeType) + ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(2); + + /** Skips to the next sub-descriptor inside the configuration descriptor of the specified type value, + * which must come after a descriptor of the second given type value. The bytes remaining value is + * automatically decremented. + * + * \param[in,out] BytesRem Pointer to the number of bytes remaining of the configuration descriptor. + * \param[in,out] CurrConfigLoc Pointer to the current descriptor inside the configuration descriptor. + * \param[in] Type Descriptor type value to search for. + * \param[in] AfterType Descriptor type value which must be reached before the given Type descriptor. + */ + void USB_GetNextDescriptorOfTypeAfter(uint16_t* const BytesRem, + void** const CurrConfigLoc, + const uint8_t Type, + const uint8_t AfterType) + ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(2); + + /** Searches for the next descriptor in the given configuration descriptor using a pre-made comparator + * function. The routine updates the position and remaining configuration descriptor bytes values + * automatically. If a comparator routine fails a search, the descriptor pointer is retreated back + * so that the next descriptor search invocation will start from the descriptor which first caused the + * original search to fail. This behaviour allows for one comparator to be used immediately after another + * has failed, starting the second search from the descriptor which failed the first. + * + * Comparator functions should be standard functions which accept a pointer to the header of the current + * descriptor inside the configuration descriptor which is being compared, and should return a value from + * the \ref DSearch_Return_ErrorCodes_t enum as a uint8_t value. + * + * \note This function is available in USB Host mode only. + * + * \param[in,out] BytesRem Pointer to an int storing the remaining bytes in the configuration descriptor. + * \param[in,out] CurrConfigLoc Pointer to the current position in the configuration descriptor. + * \param[in] ComparatorRoutine Name of the comparator search function to use on the configuration descriptor. + * + * \return Value of one of the members of the \ref DSearch_Comp_Return_ErrorCodes_t enum. + * + * Usage Example: + * \code + * uint8_t EndpointSearcher(void* CurrentDescriptor); // Comparator Prototype + * + * uint8_t EndpointSearcher(void* CurrentDescriptor) + * { + * if (DESCRIPTOR_TYPE(CurrentDescriptor) == DTYPE_Endpoint) + * return DESCRIPTOR_SEARCH_Found; + * else + * return DESCRIPTOR_SEARCH_NotFound; + * } + * + * //... + * // After retrieving configuration descriptor: + * if (USB_Host_GetNextDescriptorComp(&BytesRemaining, &CurrentConfigLoc, EndpointSearcher) == + * Descriptor_Search_Comp_Found) + * { + * // Do something with the endpoint descriptor + * } + * \endcode + */ + uint8_t USB_GetNextDescriptorComp(uint16_t* const BytesRem, + void** const CurrConfigLoc, + ConfigComparatorPtr_t const ComparatorRoutine); + + /* Inline Functions: */ + /** Skips over the current sub-descriptor inside the configuration descriptor, so that the pointer then + points to the next sub-descriptor. The bytes remaining value is automatically decremented. + * + * \param[in,out] BytesRem Pointer to the number of bytes remaining of the configuration descriptor. + * \param[in,out] CurrConfigLoc Pointer to the current descriptor inside the configuration descriptor. + */ + static inline void USB_GetNextDescriptor(uint16_t* const BytesRem, + void** CurrConfigLoc) ATTR_NON_NULL_PTR_ARG(1) ATTR_NON_NULL_PTR_ARG(2); + static inline void USB_GetNextDescriptor(uint16_t* const BytesRem, + void** CurrConfigLoc) + { + uint16_t CurrDescriptorSize = DESCRIPTOR_CAST(*CurrConfigLoc, USB_Descriptor_Header_t).Size; + + *CurrConfigLoc = ((uint8_t*)*CurrConfigLoc) + CurrDescriptorSize; + *BytesRem -= CurrDescriptorSize; + } + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/DeviceStandardReq.c b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/DeviceStandardReq.c new file mode 100644 index 0000000000..64af1406ba --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/DeviceStandardReq.c @@ -0,0 +1,395 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +#define __INCLUDE_FROM_USB_DRIVER +#include "USBMode.h" + +#if defined(USB_CAN_BE_DEVICE) + +#define __INCLUDE_FROM_DEVICESTDREQ_C +#include "DeviceStandardReq.h" + +uint8_t USB_ConfigurationNumber; + +#if !defined(NO_DEVICE_SELF_POWER) +bool USB_CurrentlySelfPowered; +#endif + +#if !defined(NO_DEVICE_REMOTE_WAKEUP) +bool USB_RemoteWakeupEnabled; +#endif + +void USB_Device_ProcessControlRequest(void) +{ + bool RequestHandled = false; + uint8_t* RequestHeader = (uint8_t*)&USB_ControlRequest; + + for (uint8_t RequestHeaderByte = 0; RequestHeaderByte < sizeof(USB_Request_Header_t); RequestHeaderByte++) + *(RequestHeader++) = Endpoint_Read_Byte(); + + uint8_t bmRequestType = USB_ControlRequest.bmRequestType; + + switch (USB_ControlRequest.bRequest) + { + case REQ_GetStatus: + if ((bmRequestType == (REQDIR_DEVICETOHOST | REQTYPE_STANDARD | REQREC_DEVICE)) || + (bmRequestType == (REQDIR_DEVICETOHOST | REQTYPE_STANDARD | REQREC_ENDPOINT))) + { + USB_Device_GetStatus(); + RequestHandled = true; + } + + break; + case REQ_ClearFeature: + case REQ_SetFeature: + if ((bmRequestType == (REQDIR_HOSTTODEVICE | REQTYPE_STANDARD | REQREC_DEVICE)) || + (bmRequestType == (REQDIR_HOSTTODEVICE | REQTYPE_STANDARD | REQREC_ENDPOINT))) + { + USB_Device_ClearSetFeature(); + RequestHandled = true; + } + + break; + case REQ_SetAddress: + if (bmRequestType == (REQDIR_HOSTTODEVICE | REQTYPE_STANDARD | REQREC_DEVICE)) + { + USB_Device_SetAddress(); + RequestHandled = true; + } + + break; + case REQ_GetDescriptor: + if ((bmRequestType == (REQDIR_DEVICETOHOST | REQTYPE_STANDARD | REQREC_DEVICE)) || + (bmRequestType == (REQDIR_DEVICETOHOST | REQTYPE_STANDARD | REQREC_INTERFACE))) + { + USB_Device_GetDescriptor(); + RequestHandled = true; + } + + break; + case REQ_GetConfiguration: + if (bmRequestType == (REQDIR_DEVICETOHOST | REQTYPE_STANDARD | REQREC_DEVICE)) + { + USB_Device_GetConfiguration(); + RequestHandled = true; + } + + break; + case REQ_SetConfiguration: + if (bmRequestType == (REQDIR_HOSTTODEVICE | REQTYPE_STANDARD | REQREC_DEVICE)) + { + USB_Device_SetConfiguration(); + RequestHandled = true; + } + + break; + } + + if (!(RequestHandled)) + EVENT_USB_Device_UnhandledControlRequest(); + + if (Endpoint_IsSETUPReceived()) + { + Endpoint_StallTransaction(); + Endpoint_ClearSETUP(); + } +} + +static void USB_Device_SetAddress(void) +{ + uint8_t DeviceAddress = (USB_ControlRequest.wValue & 0x7F); + + Endpoint_ClearSETUP(); + + Endpoint_ClearStatusStage(); + + while (!(Endpoint_IsINReady())) + { + if (USB_DeviceState == DEVICE_STATE_Unattached) + return; + } + + USB_DeviceState = (DeviceAddress) ? DEVICE_STATE_Addressed : DEVICE_STATE_Default; + + USB_Device_SetDeviceAddress(DeviceAddress); + + return; +} + +static void USB_Device_SetConfiguration(void) +{ +#if defined(FIXED_NUM_CONFIGURATIONS) + if ((uint8_t)USB_ControlRequest.wValue > FIXED_NUM_CONFIGURATIONS) + return; +#else + #if defined(USE_FLASH_DESCRIPTORS) + #define MemoryAddressSpace MEMSPACE_FLASH + #elif defined(USE_EEPROM_DESCRIPTORS) + #define MemoryAddressSpace MEMSPACE_EEPROM + #elif defined(USE_SRAM_DESCRIPTORS) + #define MemoryAddressSpace MEMSPACE_SRAM + #else + uint8_t MemoryAddressSpace; + #endif + + USB_Descriptor_Device_t* DevDescriptorPtr; + + if (CALLBACK_USB_GetDescriptor((DTYPE_Device << 8), 0, (void*)&DevDescriptorPtr + #if !defined(USE_FLASH_DESCRIPTORS) && !defined(USE_EEPROM_DESCRIPTORS) && !defined(USE_RAM_DESCRIPTORS) + , &MemoryAddressSpace + #endif + ) == NO_DESCRIPTOR) + { + return; + } + + if (MemoryAddressSpace == MEMSPACE_FLASH) + { + if (((uint8_t)USB_ControlRequest.wValue > pgm_read_byte(&DevDescriptorPtr->NumberOfConfigurations))) + return; + } + else if (MemoryAddressSpace == MEMSPACE_EEPROM) + { + if (((uint8_t)USB_ControlRequest.wValue > eeprom_read_byte(&DevDescriptorPtr->NumberOfConfigurations))) + return; + } + else + { + if ((uint8_t)USB_ControlRequest.wValue > DevDescriptorPtr->NumberOfConfigurations) + return; + } +#endif + + Endpoint_ClearSETUP(); + + USB_ConfigurationNumber = (uint8_t)USB_ControlRequest.wValue; + + Endpoint_ClearStatusStage(); + + USB_DeviceState = (USB_ConfigurationNumber) ? DEVICE_STATE_Configured : DEVICE_STATE_Addressed; + + EVENT_USB_Device_ConfigurationChanged(); +} + +void USB_Device_GetConfiguration(void) +{ + Endpoint_ClearSETUP(); + + Endpoint_Write_Byte(USB_ConfigurationNumber); + Endpoint_ClearIN(); + + Endpoint_ClearStatusStage(); +} + +#if !defined(NO_INTERNAL_SERIAL) && (USE_INTERNAL_SERIAL != NO_DESCRIPTOR) +static char USB_Device_NibbleToASCII(uint8_t Nibble) +{ + Nibble = ((Nibble & 0x0F) + '0'); + return (Nibble > '9') ? (Nibble + ('A' - '9' - 1)) : Nibble; +} + +static void USB_Device_GetInternalSerialDescriptor(void) +{ + struct + { + USB_Descriptor_Header_t Header; + int16_t UnicodeString[20]; + } SignatureDescriptor; + + SignatureDescriptor.Header.Type = DTYPE_String; + SignatureDescriptor.Header.Size = sizeof(SignatureDescriptor); + + uint8_t SigReadAddress = 0x0E; + + ATOMIC_BLOCK(ATOMIC_RESTORESTATE) + { + for (uint8_t SerialCharNum = 0; SerialCharNum < 20; SerialCharNum++) + { + uint8_t SerialByte = boot_signature_byte_get(SigReadAddress); + + if (SerialCharNum & 0x01) + { + SerialByte >>= 4; + SigReadAddress++; + } + + SignatureDescriptor.UnicodeString[SerialCharNum] = USB_Device_NibbleToASCII(SerialByte); + } + } + + Endpoint_ClearSETUP(); + + Endpoint_Write_Control_Stream_LE(&SignatureDescriptor, sizeof(SignatureDescriptor)); + + Endpoint_ClearOUT(); +} +#endif + +static void USB_Device_GetDescriptor(void) +{ + void* DescriptorPointer; + uint16_t DescriptorSize; + + #if !defined(USE_FLASH_DESCRIPTORS) && !defined(USE_EEPROM_DESCRIPTORS) && !defined(USE_RAM_DESCRIPTORS) + uint8_t DescriptorAddressSpace; + #endif + + #if !defined(NO_INTERNAL_SERIAL) && (USE_INTERNAL_SERIAL != NO_DESCRIPTOR) + if (USB_ControlRequest.wValue == ((DTYPE_String << 8) | USE_INTERNAL_SERIAL)) + { + USB_Device_GetInternalSerialDescriptor(); + return; + } + #endif + + if ((DescriptorSize = CALLBACK_USB_GetDescriptor(USB_ControlRequest.wValue, USB_ControlRequest.wIndex, + &DescriptorPointer + #if !defined(USE_FLASH_DESCRIPTORS) && !defined(USE_EEPROM_DESCRIPTORS) && !defined(USE_RAM_DESCRIPTORS) + , &DescriptorAddressSpace + #endif + )) == NO_DESCRIPTOR) + { + return; + } + + Endpoint_ClearSETUP(); + + #if defined(USE_RAM_DESCRIPTORS) + Endpoint_Write_Control_Stream_LE(DescriptorPointer, DescriptorSize); + #elif defined(USE_EEPROM_DESCRIPTORS) + Endpoint_Write_Control_EStream_LE(DescriptorPointer, DescriptorSize); + #elif defined(USE_FLASH_DESCRIPTORS) + Endpoint_Write_Control_PStream_LE(DescriptorPointer, DescriptorSize); + #else + if (DescriptorAddressSpace == MEMSPACE_FLASH) + Endpoint_Write_Control_PStream_LE(DescriptorPointer, DescriptorSize); + else if (DescriptorAddressSpace == MEMSPACE_EEPROM) + Endpoint_Write_Control_EStream_LE(DescriptorPointer, DescriptorSize); + else + Endpoint_Write_Control_Stream_LE(DescriptorPointer, DescriptorSize); + #endif + + Endpoint_ClearOUT(); +} + +static void USB_Device_GetStatus(void) +{ + uint8_t CurrentStatus = 0; + + switch (USB_ControlRequest.bmRequestType) + { +#if !defined(NO_DEVICE_SELF_POWER) || !defined(NO_DEVICE_REMOTE_WAKEUP) + case (REQDIR_DEVICETOHOST | REQTYPE_STANDARD | REQREC_DEVICE): + #if !defined(NO_DEVICE_SELF_POWER) + if (USB_CurrentlySelfPowered) + CurrentStatus |= FEATURE_SELFPOWERED_ENABLED; + #endif + + #if !defined(NO_DEVICE_REMOTE_WAKEUP) + if (USB_RemoteWakeupEnabled) + CurrentStatus |= FEATURE_REMOTE_WAKEUP_ENABLED; + #endif + break; +#endif +#if !defined(CONTROL_ONLY_DEVICE) + case (REQDIR_DEVICETOHOST | REQTYPE_STANDARD | REQREC_ENDPOINT): + Endpoint_SelectEndpoint((uint8_t)USB_ControlRequest.wIndex & ENDPOINT_EPNUM_MASK); + + CurrentStatus = Endpoint_IsStalled(); + + Endpoint_SelectEndpoint(ENDPOINT_CONTROLEP); + + break; +#endif + default: + return; + } + + Endpoint_ClearSETUP(); + + Endpoint_Write_Word_LE(CurrentStatus); + Endpoint_ClearIN(); + + Endpoint_ClearStatusStage(); +} + +static void USB_Device_ClearSetFeature(void) +{ + switch (USB_ControlRequest.bmRequestType & CONTROL_REQTYPE_RECIPIENT) + { +#if !defined(NO_DEVICE_REMOTE_WAKEUP) + case REQREC_DEVICE: + if ((uint8_t)USB_ControlRequest.wValue == FEATURE_REMOTE_WAKEUP) + USB_RemoteWakeupEnabled = (USB_ControlRequest.bRequest == REQ_SetFeature); + else + return; + + break; +#endif +#if !defined(CONTROL_ONLY_DEVICE) + case REQREC_ENDPOINT: + if ((uint8_t)USB_ControlRequest.wValue == FEATURE_ENDPOINT_HALT) + { + uint8_t EndpointIndex = ((uint8_t)USB_ControlRequest.wIndex & ENDPOINT_EPNUM_MASK); + + if (EndpointIndex == ENDPOINT_CONTROLEP) + return; + + Endpoint_SelectEndpoint(EndpointIndex); + + if (!(Endpoint_IsEnabled())) + return; + + if (USB_ControlRequest.bRequest == REQ_SetFeature) + { + Endpoint_StallTransaction(); + } + else + { + Endpoint_ClearStall(); + Endpoint_ResetFIFO(EndpointIndex); + Endpoint_ResetDataToggle(); + } + } + + break; +#endif + default: + return; + } + + Endpoint_SelectEndpoint(ENDPOINT_CONTROLEP); + + Endpoint_ClearSETUP(); + + Endpoint_ClearStatusStage(); +} + +#endif diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/DeviceStandardReq.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/DeviceStandardReq.h new file mode 100644 index 0000000000..a65b93b62c --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/DeviceStandardReq.h @@ -0,0 +1,165 @@ +/* + 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 USB device standard request management. + * + * This file contains the function prototypes necessary for the processing of incoming standard control requests + * when the library is in USB device mode. + * + * \note This file should not be included directly. It is automatically included as needed by the USB driver + * dispatch header located in LUFA/Drivers/USB/USB.h. + */ + +#ifndef __DEVICESTDREQ_H__ +#define __DEVICESTDREQ_H__ + + /* Includes: */ + #include + #include + #include + #include + #include + #include + + #include "StdDescriptors.h" + #include "Events.h" + #include "StdRequestType.h" + #include "USBTask.h" + #include "../LowLevel/USBController.h" + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_USB_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/USB/USB.h instead. + #endif + + /* Public Interface - May be used in end-application: */ + /* Macros: */ + #if defined(USE_SINGLE_DEVICE_CONFIGURATION) + #define FIXED_NUM_CONFIGURATIONS 1 + #endif + + /* Enums: */ + #if !defined(USE_FLASH_DESCRIPTORS) && !defined(USE_EEPROM_DESCRIPTORS) && !defined(USE_RAM_DESCRIPTORS) + /** Enum for the possible descriptor memory spaces, for the MemoryAddressSpace of the + * \ref CALLBACK_USB_GetDescriptor() function. This can be used when none of the USE_*_DESCRIPTORS + * compile time options are used, to indicate in which memory space the descriptor is stored. + * + * \ingroup Group_Device + */ + enum USB_DescriptorMemorySpaces_t + { + MEMSPACE_FLASH = 0, /**< Indicates the requested descriptor is located in FLASH memory. */ + MEMSPACE_EEPROM = 1, /**< Indicates the requested descriptor is located in EEPROM memory. */ + MEMSPACE_RAM = 2, /**< Indicates the requested descriptor is located in RAM memory. */ + }; + #endif + + /* Global Variables: */ + /** Indicates the currently set configuration number of the device. USB devices may have several + * different configurations which the host can select between; this indicates the currently selected + * value, or 0 if no configuration has been selected. + * + * \note This variable should be treated as read-only in the user application, and never manually + * changed in value. + * + * \ingroup Group_Device + */ + extern uint8_t USB_ConfigurationNumber; + + #if !defined(NO_DEVICE_REMOTE_WAKEUP) + /** Indicates if the host is currently allowing the device to issue remote wakeup events. If this + * flag is cleared, the device should not issue remote wakeup events to the host. + * + * \note This variable should be treated as read-only in the user application, and never manually + * changed in value. + * \n\n + * + * \note To reduce FLASH usage of the compiled applications where Remote Wakeup is not supported, + * this global and the underlying management code can be disabled by defining the + * NO_DEVICE_REMOTE_WAKEUP token in the project makefile and passing it to the compiler via + * the -D switch. + * + * \ingroup Group_Device + */ + extern bool USB_RemoteWakeupEnabled; + #endif + + #if !defined(NO_DEVICE_SELF_POWER) + /** Indicates if the device is currently being powered by its own power supply, rather than being + * powered by the host's USB supply. This flag should remain cleared if the device does not + * support self powered mode, as indicated in the device descriptors. + * + * \ingroup Group_Device + */ + extern bool USB_CurrentlySelfPowered; + #endif + + /* Private Interface - For use in library only: */ + #if !defined(__DOXYGEN__) + #if defined(USE_RAM_DESCRIPTORS) && defined(USE_EEPROM_DESCRIPTORS) + #error USE_RAM_DESCRIPTORS and USE_EEPROM_DESCRIPTORS are mutually exclusive. + #elif defined(USE_RAM_DESCRIPTORS) && defined(USE_FLASH_DESCRIPTORS) + #error USE_RAM_DESCRIPTORS and USE_FLASH_DESCRIPTORS are mutually exclusive. + #elif defined(USE_FLASH_DESCRIPTORS) && defined(USE_EEPROM_DESCRIPTORS) + #error USE_FLASH_DESCRIPTORS and USE_EEPROM_DESCRIPTORS are mutually exclusive. + #elif defined(USE_FLASH_DESCRIPTORS) && defined(USE_EEPROM_DESCRIPTORS) && defined(USE_RAM_DESCRIPTORS) + #error Only one of the USE_*_DESCRIPTORS modes should be selected. + #endif + + /* Function Prototypes: */ + void USB_Device_ProcessControlRequest(void); + + #if defined(__INCLUDE_FROM_DEVICESTDREQ_C) + static void USB_Device_SetAddress(void); + static void USB_Device_SetConfiguration(void); + static void USB_Device_GetConfiguration(void); + static void USB_Device_GetDescriptor(void); + static void USB_Device_GetStatus(void); + static void USB_Device_ClearSetFeature(void); + + #if !defined(NO_INTERNAL_SERIAL) && (USE_INTERNAL_SERIAL != NO_DESCRIPTOR) + static char USB_Device_NibbleToASCII(uint8_t Nibble) ATTR_ALWAYS_INLINE; + static void USB_Device_GetInternalSerialDescriptor(void); + #endif + #endif + #endif + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/Events.c b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/Events.c new file mode 100644 index 0000000000..ee2030e1a4 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/Events.c @@ -0,0 +1,38 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +#define __INCLUDE_FROM_EVENTS_C +#define __INCLUDE_FROM_USB_DRIVER +#include "Events.h" + +void USB_Event_Stub(void) +{ + +} diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/Events.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/Events.h new file mode 100644 index 0000000000..5c295b61fc --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/Events.h @@ -0,0 +1,364 @@ +/* + 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 USB controller events manager. + * + * This file contains macros and functions relating to the management of library events, which are small + * pieces of code similar to ISRs which are run when a given condition is met. Each event can be fired from + * multiple places in the user or library code, which may or may not be inside an ISR, thus each handler + * should be written to be as small and fast as possible to prevent possible problems. + * + * Events can be hooked by the user application by declaring a handler function with the same name and parameters + * listed here. If an event with no user-associated handler is fired within the library, it by default maps to an + * internal empty stub function. + * + * Each event must only have one associated event handler, but can be raised by multiple sources by calling the + * event handler function (with any required event parameters). + * + * \note This file should not be included directly. It is automatically included as needed by the USB driver + * dispatch header located in LUFA/Drivers/USB/USB.h. + */ + +/** \ingroup Group_USB + * @defgroup Group_Events USB Events + * + * This module contains macros and functions relating to the management of library events, which are small + * pieces of code similar to ISRs which are run when a given condition is met. Each event can be fired from + * multiple places in the user or library code, which may or may not be inside an ISR, thus each handler + * should be written to be as small and fast as possible to prevent possible problems. + * + * Events can be hooked by the user application by declaring a handler function with the same name and parameters + * listed here. If an event with no user-associated handler is fired within the library, it by default maps to an + * internal empty stub function. + * + * Each event must only have one associated event handler, but can be raised by multiple sources by calling the + * event handler function (with any required event parameters). + * + * @{ + */ + +#ifndef __USBEVENTS_H__ +#define __USBEVENTS_H__ + + /* Includes: */ + #include + + #include "../../../Common/Common.h" + #include "USBMode.h" + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_USB_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/USB/USB.h instead. + #endif + + /* Public Interface - May be used in end-application: */ + /* Pseudo-Functions for Doxygen: */ + #if !defined(__INCLUDE_FROM_EVENTS_C) || defined(__DOXYGEN__) + /** Event for USB stack initialization failure. This event fires when the USB interface fails to + * initialize correctly due to a hardware or software fault. + * + * \note This event only exists on USB AVR models which support dual role modes. + * + * \param[in] ErrorCode Error code indicating the failure reason, a value in \ref USB_InitErrorCodes_t. + */ + void EVENT_USB_InitFailure(const uint8_t ErrorCode); + + /** Event for USB mode pin level change. This event fires when the USB interface is set to dual role + * mode, and the UID pin level has changed to indicate a new mode (device or host). This event fires + * before the mode is switched to the newly indicated mode but after the \ref EVENT_USB_Device_Disconnect + * event has fired (if connected before the role change). + * + * \note This event only exists on USB AVR models which support dual role modes. + * \n\n + * + * \note This event does not exist if the USB_DEVICE_ONLY or USB_HOST_ONLY tokens have been supplied + * to the compiler (see \ref Group_USBManagement documentation). + */ + void EVENT_USB_UIDChange(void); + + /** Event for USB host error. This event fires when a hardware fault has occurred whilst the USB + * interface is in host mode. + * + * \param[in] ErrorCode Error code indicating the failure reason, a value in \ref USB_Host_ErrorCodes_t. + * + * \note This event only exists on USB AVR models which supports host mode. + * \n\n + * + * \note This event does not exist if the USB_DEVICE_ONLY token is supplied to the compiler (see + * \ref Group_USBManagement documentation). + */ + void EVENT_USB_Host_HostError(const uint8_t ErrorCode); + + /** Event for USB device attachment. This event fires when a the USB interface is in host mode, and + * a USB device has been connected to the USB interface. This is interrupt driven, thus fires before + * the standard \ref EVENT_USB_Device_Connect() event and so can be used to programmatically start the USB + * management task to reduce CPU consumption. + * + * \note This event only exists on USB AVR models which supports host mode. + * \n\n + * + * \note This event does not exist if the USB_DEVICE_ONLY token is supplied to the compiler (see + * \ref Group_USBManagement documentation). + * + * \see \ref USB_USBTask() for more information on the USB management task and reducing CPU usage. + */ + void EVENT_USB_Host_DeviceAttached(void); + + /** Event for USB device removal. This event fires when a the USB interface is in host mode, and + * a USB device has been removed the USB interface whether or not it has been enumerated. This + * can be used to programmatically stop the USB management task to reduce CPU consumption. + * + * \note This event only exists on USB AVR models which supports host mode. + * \n\n + * + * \note This event does not exist if the USB_DEVICE_ONLY token is supplied to the compiler (see + * \ref Group_USBManagement documentation). + * + * \see \ref USB_USBTask() for more information on the USB management task and reducing CPU usage. + */ + void EVENT_USB_Host_DeviceUnattached(void); + + /** Event for USB device enumeration failure. This event fires when a the USB interface is + * in host mode, and an attached USB device has failed to enumerate completely. + * + * \param[in] ErrorCode Error code indicating the failure reason, a value in + * \ref USB_Host_EnumerationErrorCodes_t. + * + * \param[in] SubErrorCode Sub error code indicating the reason for failure - for example, if the + * ErrorCode parameter indicates a control error, this will give the error + * code returned by the \ref USB_Host_SendControlRequest() function. + * + * \note This event only exists on USB AVR models which supports host mode. + * \n\n + * + * \note This event does not exist if the USB_DEVICE_ONLY token is supplied to the compiler (see + * \ref Group_USBManagement documentation). + */ + void EVENT_USB_Host_DeviceEnumerationFailed(const uint8_t ErrorCode, + const uint8_t SubErrorCode); + + /** Event for USB device enumeration completion. This event fires when a the USB interface is + * in host mode and an attached USB device has been completely enumerated and is ready to be + * controlled by the user application. + * + * This event is time-critical; exceeding OS-specific delays within this event handler (typically of around + * 1 second) when a transaction is waiting to be processed by the device will prevent break communications + * and cause the host to reset the USB bus. + */ + void EVENT_USB_Host_DeviceEnumerationComplete(void); + + /** Event for USB device connection. This event fires when the AVR in device mode and the device is connected + * to a host, beginning the enumeration process, measured by a rising level on the AVR's VBUS pin. + * + * This event is time-critical; exceeding OS-specific delays within this event handler (typically of around + * two seconds) will prevent the device from enumerating correctly. + * + * \note For the smaller series 2 USB AVRs with limited USB controllers, VBUS is not available to the USB controller. + * this means that the current connection state is derived from the bus suspension and wake up events by default, + * which is not always accurate (host may suspend the bus while still connected). If the actual connection state + * needs to be determined, VBUS should be routed to an external pin, and the auto-detect behaviour turned off by + * passing the NO_LIMITED_CONTROLLER_CONNECT token to the compiler via the -D switch at compile time. The connection + * and disconnection events may be manually fired, and the \ref USB_DeviceState global changed manually. + * \n\n + * + * \note This event may fire multiple times during device enumeration on the series 2 USB AVRs with limited USB controllers + * if NO_LIMITED_CONTROLLER_CONNECT is not defined. + * + * \see USBTask.h for more information on the USB management task and reducing CPU usage. + */ + void EVENT_USB_Device_Connect(void); + + /** Event for USB device disconnection. This event fires when the AVR in device mode and the device is disconnected + * from a host, measured by a falling level on the AVR's VBUS pin. + * + * \note For the smaller series 2 USB AVRs with limited USB controllers, VBUS is not available to the USB controller. + * this means that the current connection state is derived from the bus suspension and wake up events by default, + * which is not always accurate (host may suspend the bus while still connected). If the actual connection state + * needs to be determined, VBUS should be routed to an external pin, and the auto-detect behaviour turned off by + * passing the NO_LIMITED_CONTROLLER_CONNECT token to the compiler via the -D switch at compile time. The connection + * and disconnection events may be manually fired, and the \ref USB_DeviceState global changed manually. + * \n\n + * + * \note This event may fire multiple times during device enumeration on the series 2 USB AVRs with limited USB controllers + * if NO_LIMITED_CONTROLLER_CONNECT is not defined. + * + * \see USBTask.h for more information on the USB management task and reducing CPU usage. + */ + void EVENT_USB_Device_Disconnect(void); + + /** Event for unhandled control requests. This event fires when a the USB host issues a control + * request to the control endpoint (address 0) that the library does not handle. This may either + * be a standard request that the library has no handler code for, or a class specific request + * issued to the device which must be handled appropriately. + * + * This event is time-critical; each packet within the request transaction must be acknowledged or + * sent within 50ms or the host will abort the transfer. + * + * The library internally handles all standard control requests with the exceptions of SYNC FRAME, + * SET DESCRIPTOR and SET INTERFACE. These and all other non-standard control requests will be left + * for the user to process via this event if desired. If not handled in the user application, requests + * are automatically STALLed. + * + * \note This event does not exist if the USB_HOST_ONLY token is supplied to the compiler (see + * \ref Group_USBManagement documentation). + * \n\n + * + * \note Requests should be handled in the same manner as described in the USB 2.0 Specification, + * or appropriate class specification. In all instances, the library has already read the + * request SETUP parameters into the \ref USB_ControlRequest structure which should then be used + * by the application to determine how to handle the issued request. + */ + void EVENT_USB_Device_UnhandledControlRequest(void); + + /** Event for USB configuration number changed. This event fires when a the USB host changes the + * selected configuration number while in device mode. This event should be hooked in device + * applications to create the endpoints and configure the device for the selected configuration. + * + * This event is time-critical; exceeding OS-specific delays within this event handler (typically of around + * one second) will prevent the device from enumerating correctly. + * + * This event fires after the value of \ref USB_ConfigurationNumber has been changed. + * + * \note This event does not exist if the USB_HOST_ONLY token is supplied to the compiler (see + * \ref Group_USBManagement documentation). + */ + void EVENT_USB_Device_ConfigurationChanged(void); + + /** Event for USB suspend. This event fires when a the USB host suspends the device by halting its + * transmission of Start Of Frame pulses to the device. This is generally hooked in order to move + * the device over to a low power state until the host wakes up the device. If the USB interface is + * enumerated with the \ref USB_OPT_AUTO_PLL option set, the library will automatically suspend the + * USB PLL before the event is fired to save power. + * + * \note This event does not exist if the USB_HOST_ONLY token is supplied to the compiler (see + * \ref Group_USBManagement documentation). + * \n\n + * + * \note This event does not exist on the series 2 USB AVRs when the NO_LIMITED_CONTROLLER_CONNECT + * compile time token is not set - see \ref EVENT_USB_Device_Disconnect. + * + * \see \ref EVENT_USB_Device_WakeUp() event for accompanying Wake Up event. + */ + void EVENT_USB_Device_Suspend(void); + + /** Event for USB wake up. This event fires when a the USB interface is suspended while in device + * mode, and the host wakes up the device by supplying Start Of Frame pulses. This is generally + * hooked to pull the user application out of a low power state and back into normal operating + * mode. If the USB interface is enumerated with the \ref USB_OPT_AUTO_PLL option set, the library + * will automatically restart the USB PLL before the event is fired. + * + * \note This event does not exist if the USB_HOST_ONLY token is supplied to the compiler (see + * \ref Group_USBManagement documentation). + * \n\n + * + * \note This event does not exist on the series 2 USB AVRs when the NO_LIMITED_CONTROLLER_CONNECT + * compile time token is not set - see \ref EVENT_USB_Device_Connect. + * + * \see \ref EVENT_USB_Device_Suspend() event for accompanying Suspend event. + */ + void EVENT_USB_Device_WakeUp(void); + + /** Event for USB interface reset. This event fires when the USB interface is in device mode, and + * a the USB host requests that the device reset its interface. This event fires after the control + * endpoint has been automatically configured by the library. + * + * This event is time-critical; exceeding OS-specific delays within this event handler (typically of around + * two seconds) will prevent the device from enumerating correctly. + * + * \note This event does not exist if the USB_HOST_ONLY token is supplied to the compiler (see + * \ref Group_USBManagement documentation). + */ + void EVENT_USB_Device_Reset(void); + + /** Event for USB Start Of Frame detection, when enabled. This event fires at the start of each USB + * frame, once per millisecond, and is synchronized to the USB bus. This can be used as an accurate + * millisecond timer source when the USB bus is enumerated in device mode to a USB host. + * + * This event is time-critical; it is run once per millisecond and thus long handlers will significantly + * degrade device performance. This event should only be enabled when needed to reduce device wake-ups. + * + * \note This event is not normally active - it must be manually enabled and disabled via the + * \ref USB_Device_EnableSOFEvents() and \ref USB_Device_DisableSOFEvents() commands after enumeration. + * \n\n + * + * \note This event does not exist if the USB_HOST_ONLY token is supplied to the compiler (see + * \ref Group_USBManagement documentation). + */ + void EVENT_USB_Device_StartOfFrame(void); + #endif + + /* Private Interface - For use in library only: */ + #if !defined(__DOXYGEN__) + /* Function Prototypes: */ + #if defined(__INCLUDE_FROM_EVENTS_C) + void USB_Event_Stub(void) ATTR_CONST; + + #if defined(USB_CAN_BE_BOTH) + void EVENT_USB_InitFailure(const uint8_t ErrorCode) ATTR_WEAK ATTR_ALIAS(USB_Event_Stub); + void EVENT_USB_UIDChange(void) ATTR_WEAK ATTR_ALIAS(USB_Event_Stub); + #endif + + #if defined(USB_CAN_BE_HOST) + void EVENT_USB_Host_HostError(const uint8_t ErrorCode) ATTR_WEAK ATTR_ALIAS(USB_Event_Stub); + void EVENT_USB_Host_DeviceAttached(void) ATTR_WEAK ATTR_ALIAS(USB_Event_Stub); + void EVENT_USB_Host_DeviceUnattached(void) ATTR_WEAK ATTR_ALIAS(USB_Event_Stub); + void EVENT_USB_Host_DeviceEnumerationComplete(void) ATTR_WEAK ATTR_ALIAS(USB_Event_Stub); + void EVENT_USB_Host_DeviceEnumerationFailed(const uint8_t ErrorCode, + const uint8_t SubErrorCode) + ATTR_WEAK ATTR_ALIAS(USB_Event_Stub); + #endif + + #if defined(USB_CAN_BE_DEVICE) + void EVENT_USB_Device_Connect(void) ATTR_WEAK ATTR_ALIAS(USB_Event_Stub); + void EVENT_USB_Device_Disconnect(void) ATTR_WEAK ATTR_ALIAS(USB_Event_Stub); + void EVENT_USB_Device_UnhandledControlRequest(void) ATTR_WEAK ATTR_ALIAS(USB_Event_Stub); + void EVENT_USB_Device_ConfigurationChanged(void) ATTR_WEAK ATTR_ALIAS(USB_Event_Stub); + void EVENT_USB_Device_Suspend(void) ATTR_WEAK ATTR_ALIAS(USB_Event_Stub); + void EVENT_USB_Device_WakeUp(void) ATTR_WEAK ATTR_ALIAS(USB_Event_Stub); + void EVENT_USB_Device_Reset(void) ATTR_WEAK ATTR_ALIAS(USB_Event_Stub); + void EVENT_USB_Device_StartOfFrame(void) ATTR_WEAK ATTR_ALIAS(USB_Event_Stub); + #endif + #endif + #endif + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/HostStandardReq.c b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/HostStandardReq.c new file mode 100644 index 0000000000..182cd69795 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/HostStandardReq.c @@ -0,0 +1,179 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +#define __INCLUDE_FROM_USB_DRIVER +#include "USBMode.h" + +#if defined(USB_CAN_BE_HOST) + +#define __INCLUDE_FROM_HOSTSTDREQ_C +#include "HostStandardReq.h" + +uint8_t USB_Host_SendControlRequest(void* const BufferPtr) +{ + uint8_t* HeaderStream = (uint8_t*)&USB_ControlRequest; + uint8_t* DataStream = (uint8_t*)BufferPtr; + bool BusSuspended = USB_Host_IsBusSuspended(); + uint8_t ReturnStatus = HOST_SENDCONTROL_Successful; + uint16_t DataLen = USB_ControlRequest.wLength; + + USB_Host_ResumeBus(); + + if ((ReturnStatus = USB_Host_WaitMS(1)) != HOST_WAITERROR_Successful) + goto End_Of_Control_Send; + + Pipe_SetPipeToken(PIPE_TOKEN_SETUP); + Pipe_ClearErrorFlags(); + + Pipe_Unfreeze(); + + for (uint8_t HeaderByte = 0; HeaderByte < sizeof(USB_Request_Header_t); HeaderByte++) + Pipe_Write_Byte(*(HeaderStream++)); + + Pipe_ClearSETUP(); + + if ((ReturnStatus = USB_Host_WaitForIOS(USB_HOST_WAITFOR_SetupSent)) != HOST_SENDCONTROL_Successful) + goto End_Of_Control_Send; + + Pipe_Freeze(); + + if ((ReturnStatus = USB_Host_WaitMS(1)) != HOST_WAITERROR_Successful) + goto End_Of_Control_Send; + + if ((USB_ControlRequest.bmRequestType & CONTROL_REQTYPE_DIRECTION) == REQDIR_DEVICETOHOST) + { + Pipe_SetPipeToken(PIPE_TOKEN_IN); + + if (DataStream != NULL) + { + while (DataLen) + { + Pipe_Unfreeze(); + + if ((ReturnStatus = USB_Host_WaitForIOS(USB_HOST_WAITFOR_InReceived)) != HOST_SENDCONTROL_Successful) + goto End_Of_Control_Send; + + if (!(Pipe_BytesInPipe())) + DataLen = 0; + + while (Pipe_BytesInPipe() && DataLen) + { + *(DataStream++) = Pipe_Read_Byte(); + DataLen--; + } + + Pipe_Freeze(); + Pipe_ClearIN(); + } + } + + Pipe_SetPipeToken(PIPE_TOKEN_OUT); + Pipe_Unfreeze(); + + if ((ReturnStatus = USB_Host_WaitForIOS(USB_HOST_WAITFOR_OutReady)) != HOST_SENDCONTROL_Successful) + goto End_Of_Control_Send; + + Pipe_ClearOUT(); + + if ((ReturnStatus = USB_Host_WaitForIOS(USB_HOST_WAITFOR_OutReady)) != HOST_SENDCONTROL_Successful) + goto End_Of_Control_Send; + } + else + { + if (DataStream != NULL) + { + Pipe_SetPipeToken(PIPE_TOKEN_OUT); + Pipe_Unfreeze(); + + while (DataLen) + { + if ((ReturnStatus = USB_Host_WaitForIOS(USB_HOST_WAITFOR_OutReady)) != HOST_SENDCONTROL_Successful) + goto End_Of_Control_Send; + + while (DataLen && (Pipe_BytesInPipe() < USB_ControlPipeSize)) + { + Pipe_Write_Byte(*(DataStream++)); + DataLen--; + } + + Pipe_ClearOUT(); + } + + if ((ReturnStatus = USB_Host_WaitForIOS(USB_HOST_WAITFOR_OutReady)) != HOST_SENDCONTROL_Successful) + goto End_Of_Control_Send; + + Pipe_Freeze(); + } + + Pipe_SetPipeToken(PIPE_TOKEN_IN); + Pipe_Unfreeze(); + + if ((ReturnStatus = USB_Host_WaitForIOS(USB_HOST_WAITFOR_InReceived)) != HOST_SENDCONTROL_Successful) + goto End_Of_Control_Send; + + Pipe_ClearIN(); + } + +End_Of_Control_Send: + Pipe_Freeze(); + + if (BusSuspended) + USB_Host_SuspendBus(); + + Pipe_ResetPipe(PIPE_CONTROLPIPE); + + return ReturnStatus; +} + +static uint8_t USB_Host_WaitForIOS(const uint8_t WaitType) +{ + #if (USB_HOST_TIMEOUT_MS < 0xFF) + uint8_t TimeoutCounter = USB_HOST_TIMEOUT_MS; + #else + uint16_t TimeoutCounter = USB_HOST_TIMEOUT_MS; + #endif + + while (!(((WaitType == USB_HOST_WAITFOR_SetupSent) && Pipe_IsSETUPSent()) || + ((WaitType == USB_HOST_WAITFOR_InReceived) && Pipe_IsINReceived()) || + ((WaitType == USB_HOST_WAITFOR_OutReady) && Pipe_IsOUTReady()))) + { + uint8_t ErrorCode; + + if ((ErrorCode = USB_Host_WaitMS(1)) != HOST_WAITERROR_Successful) + return ErrorCode; + + if (!(TimeoutCounter--)) + return HOST_SENDCONTROL_SoftwareTimeOut; + } + + return HOST_SENDCONTROL_Successful; +} + +#endif diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/HostStandardReq.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/HostStandardReq.h new file mode 100644 index 0000000000..358f3d3ad6 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/HostStandardReq.h @@ -0,0 +1,117 @@ +/* + 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 USB host standard request management. + * + * This file contains the function prototypes necessary for the issuing of outgoing standard control requests + * when the library is in USB host mode. + * + * \note This file should not be included directly. It is automatically included as needed by the USB driver + * dispatch header located in LUFA/Drivers/USB/USB.h. + */ + +#ifndef __HOSTSTDREQ_H__ +#define __HOSTSTDREQ_H__ + + /* Includes: */ + #include + #include + + #include "USBMode.h" + #include "StdRequestType.h" + #include "../LowLevel/USBController.h" + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_USB_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/USB/USB.h instead. + #endif + + /* Public Interface - May be used in end-application: */ + /* Enums: */ + /** Enum for the \ref USB_Host_SendControlRequest() return code, indicating the reason for the error + * if the transfer of the request is unsuccessful. + * + * \ingroup Group_PipeControlReq + */ + enum USB_Host_SendControlErrorCodes_t + { + HOST_SENDCONTROL_Successful = 0, /**< No error occurred in the request transfer. */ + HOST_SENDCONTROL_DeviceDisconnected = 1, /**< The attached device was disconnected during the + * request transfer. + */ + HOST_SENDCONTROL_PipeError = 2, /**< An error occurred in the pipe while sending the request. */ + HOST_SENDCONTROL_SetupStalled = 3, /**< The attached device stalled the request, usually + * indicating that the request is unsupported on the device. + */ + HOST_SENDCONTROL_SoftwareTimeOut = 4, /**< The request or data transfer timed out. */ + }; + + /* Function Prototypes: */ + /** Sends the request stored in the \ref USB_ControlRequest global structure to the attached device, + * and transfers the data stored in the buffer to the device, or from the device to the buffer + * as requested. The transfer is made on the currently selected pipe. + * + * \ingroup Group_PipeControlReq + * + * \param[in] BufferPtr Pointer to the start of the data buffer if the request has a data stage, or + * NULL if the request transfers no data to or from the device. + * + * \return A value from the \ref USB_Host_SendControlErrorCodes_t enum to indicate the result. + */ + uint8_t USB_Host_SendControlRequest(void* const BufferPtr); + + /* Private Interface - For use in library only: */ + #if !defined(__DOXYGEN__) + /* Enums: */ + enum USB_WaitForTypes_t + { + USB_HOST_WAITFOR_SetupSent, + USB_HOST_WAITFOR_InReceived, + USB_HOST_WAITFOR_OutReady, + }; + + /* Function Prototypes: */ + #if defined(__INCLUDE_FROM_HOSTSTDREQ_C) + static uint8_t USB_Host_WaitForIOS(const uint8_t WaitType); + #endif + #endif + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/StdDescriptors.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/StdDescriptors.h new file mode 100644 index 0000000000..94c7f291fe --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/StdDescriptors.h @@ -0,0 +1,645 @@ +/* + 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 USB standard descriptor definitions. + * + * This file contains structures and macros for the easy creation of standard USB descriptors in USB device projects. + * + * \note This file should not be included directly. It is automatically included as needed by the USB driver + * dispatch header located in LUFA/Drivers/USB/USB.h. + */ + +/** \ingroup Group_USB + * @defgroup Group_Descriptors USB Descriptors + * + * Standard USB device descriptor defines and retrieval routines, for USB devices. This module contains + * structures and macros for the easy creation of standard USB descriptors in USB device projects. + * + * @{ + */ + +#ifndef __USBDESCRIPTORS_H__ +#define __USBDESCRIPTORS_H__ + + /* Includes: */ + #include + #include + #include + #include + + #include "../../../Common/Common.h" + #include "USBMode.h" + #include "Events.h" + + #if defined(USB_CAN_BE_DEVICE) + #include "../LowLevel/Device.h" + #endif + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_USB_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/USB/USB.h instead. + #endif + + /* Public Interface - May be used in end-application: */ + /* Macros: */ + /** Indicates that a given descriptor does not exist in the device. This can be used inside descriptors + * for string descriptor indexes, or may be use as a return value for GetDescriptor when the specified + * descriptor does not exist. + */ + #define NO_DESCRIPTOR 0 + + #if (!defined(NO_INTERNAL_SERIAL) && \ + (defined(__AVR_AT90USB647__) || defined(__AVR_AT90USB1287__) || \ + defined(__AVR_ATmega32U6__) || defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB1286__) || \ + defined(__AVR_ATmega32U2__) || defined(__AVR_ATmega16U2__) || defined(__AVR_ATmega8U2__))) + /** String descriptor index for the device's unique serial number string descriptor within the device. + * This unique serial number is used by the host to associate resources to the device (such as drivers or COM port + * number allocations) to a device regardless of the port it is plugged in to on the host. Some USB AVRs contain + * a unique serial number internally, and setting the device descriptors serial number string index to this value + * will cause it to use the internal serial number. + * + * On unsupported devices, this will evaluate to NO_DESCRIPTOR and so will force the host to create a pseudo-serial + * number for the device. + */ + #define USE_INTERNAL_SERIAL 0xDC + #else + #define USE_INTERNAL_SERIAL NO_DESCRIPTOR + #endif + + /** Macro to calculate the power value for the configuration descriptor, from a given number of milliamperes. */ + #define USB_CONFIG_POWER_MA(mA) ((mA) >> 1) + + /** Macro to calculate the Unicode length of a string with a given number of Unicode characters. + * Should be used in string descriptor's headers for giving the string descriptor's byte length. + */ + #define USB_STRING_LEN(str) (sizeof(USB_Descriptor_Header_t) + ((str) << 1)) + + /** Macro to encode a given four digit floating point version number (e.g. 01.23) into Binary Coded + * Decimal format for descriptor fields requiring BCD encoding, such as the USB version number in the + * standard device descriptor. + */ + #define VERSION_BCD(x) ((((VERSION_TENS(x) << 4) | VERSION_ONES(x)) << 8) | \ + ((VERSION_TENTHS(x) << 4) | VERSION_HUNDREDTHS(x))) + + /** String language ID for the English language. Should be used in \ref USB_Descriptor_String_t descriptors + * to indicate that the English language is supported by the device in its string descriptors. + */ + #define LANGUAGE_ID_ENG 0x0409 + + /** Can be masked with an endpoint address for a \ref USB_Descriptor_Endpoint_t endpoint descriptor's + * EndpointAddress value to indicate to the host that the endpoint is of the IN direction (i.e, from + * device to host). + */ + #define ENDPOINT_DESCRIPTOR_DIR_IN 0x80 + + /** Can be masked with an endpoint address for a \ref USB_Descriptor_Endpoint_t endpoint descriptor's + * EndpointAddress value to indicate to the host that the endpoint is of the OUT direction (i.e, from + * host to device). + */ + #define ENDPOINT_DESCRIPTOR_DIR_OUT 0x00 + + /** Can be masked with other configuration descriptor attributes for a \ref USB_Descriptor_Configuration_Header_t + * descriptor's ConfigAttributes value to indicate that the specified configuration can draw its power + * from the host's VBUS line. + */ + #define USB_CONFIG_ATTR_BUSPOWERED 0x80 + + /** Can be masked with other configuration descriptor attributes for a \ref USB_Descriptor_Configuration_Header_t + * descriptor's ConfigAttributes value to indicate that the specified configuration can draw its power + * from the device's own power source. + */ + #define USB_CONFIG_ATTR_SELFPOWERED 0x40 + + /** Can be masked with other configuration descriptor attributes for a \ref USB_Descriptor_Configuration_Header_t + * descriptor's ConfigAttributes value to indicate that the specified configuration supports the + * remote wakeup feature of the USB standard, allowing a suspended USB device to wake up the host upon + * request. + */ + #define USB_CONFIG_ATTR_REMOTEWAKEUP 0x20 + + /** Can be masked with other endpoint descriptor attributes for a \ref USB_Descriptor_Endpoint_t descriptor's + * Attributes value to indicate that the specified endpoint is not synchronized. + * + * \see The USB specification for more details on the possible Endpoint attributes. + */ + #define ENDPOINT_ATTR_NO_SYNC (0 << 2) + + /** Can be masked with other endpoint descriptor attributes for a \ref USB_Descriptor_Endpoint_t descriptor's + * Attributes value to indicate that the specified endpoint is asynchronous. + * + * \see The USB specification for more details on the possible Endpoint attributes. + */ + #define ENDPOINT_ATTR_ASYNC (1 << 2) + + /** Can be masked with other endpoint descriptor attributes for a \ref USB_Descriptor_Endpoint_t descriptor's + * Attributes value to indicate that the specified endpoint is adaptive. + * + * \see The USB specification for more details on the possible Endpoint attributes. + */ + #define ENDPOINT_ATTR_ADAPTIVE (2 << 2) + + /** Can be masked with other endpoint descriptor attributes for a \ref USB_Descriptor_Endpoint_t descriptor's + * Attributes value to indicate that the specified endpoint is synchronized. + * + * \see The USB specification for more details on the possible Endpoint attributes. + */ + #define ENDPOINT_ATTR_SYNC (3 << 2) + + /** Can be masked with other endpoint descriptor attributes for a \ref USB_Descriptor_Endpoint_t descriptor's + * Attributes value to indicate that the specified endpoint is used for data transfers. + * + * \see The USB specification for more details on the possible Endpoint usage attributes. + */ + #define ENDPOINT_USAGE_DATA (0 << 4) + + /** Can be masked with other endpoint descriptor attributes for a \ref USB_Descriptor_Endpoint_t descriptor's + * Attributes value to indicate that the specified endpoint is used for feedback. + * + * \see The USB specification for more details on the possible Endpoint usage attributes. + */ + #define ENDPOINT_USAGE_FEEDBACK (1 << 4) + + /** Can be masked with other endpoint descriptor attributes for a \ref USB_Descriptor_Endpoint_t descriptor's + * Attributes value to indicate that the specified endpoint is used for implicit feedback. + * + * \see The USB specification for more details on the possible Endpoint usage attributes. + */ + #define ENDPOINT_USAGE_IMPLICIT_FEEDBACK (2 << 4) + + /* Enums: */ + /** Enum for the possible standard descriptor types, as given in each descriptor's header. */ + enum USB_DescriptorTypes_t + { + DTYPE_Device = 0x01, /**< Indicates that the descriptor is a device descriptor. */ + DTYPE_Configuration = 0x02, /**< Indicates that the descriptor is a configuration descriptor. */ + DTYPE_String = 0x03, /**< Indicates that the descriptor is a string descriptor. */ + DTYPE_Interface = 0x04, /**< Indicates that the descriptor is an interface descriptor. */ + DTYPE_Endpoint = 0x05, /**< Indicates that the descriptor is an endpoint descriptor. */ + DTYPE_DeviceQualifier = 0x06, /**< Indicates that the descriptor is a device qualifier descriptor. */ + DTYPE_Other = 0x07, /**< Indicates that the descriptor is of other type. */ + DTYPE_InterfacePower = 0x08, /**< Indicates that the descriptor is an interface power descriptor. */ + DTYPE_InterfaceAssociation = 0x0B, /**< Indicates that the descriptor is an interface association descriptor. */ + }; + + /* Type Defines: */ + /** \brief Standard USB Descriptor Header (LUFA naming conventions). + * + * Type define for all descriptors' standard header, indicating the descriptor's length and type. This structure + * uses LUFA-specific element names to make each element's purpose clearer. + * + * \see \ref USB_StdDescriptor_Header_t for the version of this define with standard element names. + */ + typedef struct + { + uint8_t Size; /**< Size of the descriptor, in bytes. */ + uint8_t Type; /**< Type of the descriptor, either a value in \ref USB_DescriptorTypes_t or a value + * given by the specific class. + */ + } USB_Descriptor_Header_t; + + /** \brief Standard USB Descriptor Header (USB-IF naming conventions). + * + * Type define for all descriptors' standard header, indicating the descriptor's length and type. This structure + * uses the relevant standard's given element names to ensure compatibility with the standard. + * + * \see \ref USB_Descriptor_Header_t for the version of this define with non-standard LUFA specific element names. + */ + typedef struct + { + uint8_t bLength; /**< Size of the descriptor, in bytes. */ + uint8_t bDescriptorType; /**< Type of the descriptor, either a value in \ref USB_DescriptorTypes_t or a value + * given by the specific class. + */ + } USB_StdDescriptor_Header_t; + + /** \brief Standard USB Device Descriptor (LUFA naming conventions). + * + * Type define for a standard Device Descriptor. This structure uses LUFA-specific element names to make each + * element's purpose clearer. + * + * \see \ref USB_StdDescriptor_Device_t for the version of this define with standard element names. + */ + typedef struct + { + USB_Descriptor_Header_t Header; /**< Descriptor header, including type and size. */ + + uint16_t USBSpecification; /**< BCD of the supported USB specification. */ + uint8_t Class; /**< USB device class. */ + uint8_t SubClass; /**< USB device subclass. */ + uint8_t Protocol; /**< USB device protocol. */ + + uint8_t Endpoint0Size; /**< Size of the control (address 0) endpoint's bank in bytes. */ + + uint16_t VendorID; /**< Vendor ID for the USB product. */ + uint16_t ProductID; /**< Unique product ID for the USB product. */ + uint16_t ReleaseNumber; /**< Product release (version) number. */ + + uint8_t ManufacturerStrIndex; /**< String index for the manufacturer's name. The + * host will request this string via a separate + * control request for the string descriptor. + * + * \note If no string supplied, use \ref NO_DESCRIPTOR. + */ + uint8_t ProductStrIndex; /**< String index for the product name/details. + * + * \see ManufacturerStrIndex structure entry. + */ + uint8_t SerialNumStrIndex; /**< String index for the product's globally unique hexadecimal + * serial number, in uppercase Unicode ASCII. + * + * \note On some AVR models, there is an embedded serial number + * in the chip which can be used for the device serial number. + * To use this serial number, set this to USE_INTERNAL_SERIAL. + * On unsupported devices, this will evaluate to 0 and will cause + * the host to generate a pseudo-unique value for the device upon + * insertion. + * + * \see ManufacturerStrIndex structure entry. + */ + uint8_t NumberOfConfigurations; /**< Total number of configurations supported by + * the device. + */ + } USB_Descriptor_Device_t; + + /** \brief Standard USB Device Descriptor (USB-IF naming conventions). + * + * Type define for a standard Device Descriptor. This structure uses the relevant standard's given element names + * to ensure compatibility with the standard. + * + * \see \ref USB_Descriptor_Device_t for the version of this define with non-standard LUFA specific element names. + */ + typedef struct + { + uint8_t bLength; /**< Size of the descriptor, in bytes. */ + uint8_t bDescriptorType; /**< Type of the descriptor, either a value in \ref USB_DescriptorTypes_t or a value + * given by the specific class. + */ + uint16_t bcdUSB; /**< BCD of the supported USB specification. */ + uint8_t bDeviceClass; /**< USB device class. */ + uint8_t bDeviceSubClass; /**< USB device subclass. */ + uint8_t bDeviceProtocol; /**< USB device protocol. */ + uint8_t bMaxPacketSize0; /**< Size of the control (address 0) endpoint's bank in bytes. */ + uint16_t idVendor; /**< Vendor ID for the USB product. */ + uint16_t idProduct; /**< Unique product ID for the USB product. */ + uint16_t bcdDevice; /**< Product release (version) number. */ + uint8_t iManufacturer; /**< String index for the manufacturer's name. The + * host will request this string via a separate + * control request for the string descriptor. + * + * \note If no string supplied, use \ref NO_DESCRIPTOR. + */ + uint8_t iProduct; /**< String index for the product name/details. + * + * \see ManufacturerStrIndex structure entry. + */ + uint8_t iSerialNumber; /**< String index for the product's globally unique hexadecimal + * serial number, in uppercase Unicode ASCII. + * + * \note On some AVR models, there is an embedded serial number + * in the chip which can be used for the device serial number. + * To use this serial number, set this to USE_INTERNAL_SERIAL. + * On unsupported devices, this will evaluate to 0 and will cause + * the host to generate a pseudo-unique value for the device upon + * insertion. + * + * \see ManufacturerStrIndex structure entry. + */ + uint8_t bNumConfigurations; /**< Total number of configurations supported by + * the device. + */ + } USB_StdDescriptor_Device_t; + + /** \brief Standard USB Configuration Descriptor (LUFA naming conventions). + * + * Type define for a standard Configuration Descriptor header. This structure uses LUFA-specific element names + * to make each element's purpose clearer. + * + * \see \ref USB_StdDescriptor_Configuration_Header_t for the version of this define with standard element names. + */ + typedef struct + { + USB_Descriptor_Header_t Header; /**< Descriptor header, including type and size. */ + + uint16_t TotalConfigurationSize; /**< Size of the configuration descriptor header, + * and all sub descriptors inside the configuration. + */ + uint8_t TotalInterfaces; /**< Total number of interfaces in the configuration. */ + + uint8_t ConfigurationNumber; /**< Configuration index of the current configuration. */ + uint8_t ConfigurationStrIndex; /**< Index of a string descriptor describing the configuration. */ + + uint8_t ConfigAttributes; /**< Configuration attributes, comprised of a mask of zero or + * more USB_CONFIG_ATTR_* masks. + */ + + uint8_t MaxPowerConsumption; /**< Maximum power consumption of the device while in the + * current configuration, calculated by the \ref USB_CONFIG_POWER_MA() + * macro. + */ + } USB_Descriptor_Configuration_Header_t; + + /** \brief Standard USB Configuration Descriptor (USB-IF naming conventions). + * + * Type define for a standard Configuration Descriptor header. This structure uses the relevant standard's given element names + * to ensure compatibility with the standard. + * + * \see \ref USB_Descriptor_Device_t for the version of this define with non-standard LUFA specific element names. + */ + typedef struct + { + uint8_t bLength; /**< Size of the descriptor, in bytes. */ + uint8_t bDescriptorType; /**< Type of the descriptor, either a value in \ref USB_DescriptorTypes_t or a value + * given by the specific class. + */ + uint16_t wTotalLength; /**< Size of the configuration descriptor header, + * and all sub descriptors inside the configuration. + */ + uint8_t bNumInterfaces; /**< Total number of interfaces in the configuration. */ + uint8_t bConfigurationValue; /**< Configuration index of the current configuration. */ + uint8_t iConfiguration; /**< Index of a string descriptor describing the configuration. */ + uint8_t bmAttributes; /**< Configuration attributes, comprised of a mask of zero or + * more USB_CONFIG_ATTR_* masks. + */ + uint8_t bMaxPower; /**< Maximum power consumption of the device while in the + * current configuration, calculated by the \ref USB_CONFIG_POWER_MA() + * macro. + */ + } USB_StdDescriptor_Configuration_Header_t; + + /** \brief Standard USB Interface Descriptor (LUFA naming conventions). + * + * Type define for a standard Interface Descriptor. This structure uses LUFA-specific element names + * to make each element's purpose clearer. + * + * \see \ref USB_StdDescriptor_Interface_t for the version of this define with standard element names. + */ + typedef struct + { + USB_Descriptor_Header_t Header; /**< Descriptor header, including type and size. */ + + uint8_t InterfaceNumber; /**< Index of the interface in the current configuration. */ + uint8_t AlternateSetting; /**< Alternate setting for the interface number. The same + * interface number can have multiple alternate settings + * with different endpoint configurations, which can be + * selected by the host. + */ + uint8_t TotalEndpoints; /**< Total number of endpoints in the interface. */ + + uint8_t Class; /**< Interface class ID. */ + uint8_t SubClass; /**< Interface subclass ID. */ + uint8_t Protocol; /**< Interface protocol ID. */ + + uint8_t InterfaceStrIndex; /**< Index of the string descriptor describing the interface. */ + } USB_Descriptor_Interface_t; + + /** \brief Standard USB Interface Descriptor (USB-IF naming conventions). + * + * Type define for a standard Interface Descriptor. This structure uses the relevant standard's given element names + * to ensure compatibility with the standard. + * + * \see \ref USB_Descriptor_Interface_t for the version of this define with non-standard LUFA specific element names. + */ + typedef struct + { + uint8_t bLength; /**< Size of the descriptor, in bytes. */ + uint8_t bDescriptorType; /**< Type of the descriptor, either a value in \ref USB_DescriptorTypes_t or a value + * given by the specific class. + */ + uint8_t bInterfaceNumber; /**< Index of the interface in the current configuration. */ + uint8_t bAlternateSetting; /**< Alternate setting for the interface number. The same + * interface number can have multiple alternate settings + * with different endpoint configurations, which can be + * selected by the host. + */ + uint8_t bNumEndpoints; /**< Total number of endpoints in the interface. */ + uint8_t bInterfaceClass; /**< Interface class ID. */ + uint8_t bInterfaceSubClass; /**< Interface subclass ID. */ + uint8_t bInterfaceProtocol; /**< Interface protocol ID. */ + uint8_t iInterface; /**< Index of the string descriptor describing the + * interface. + */ + } USB_StdDescriptor_Interface_t; + + /** \brief Standard USB Interface Association Descriptor (LUFA naming conventions). + * + * Type define for a standard Interface Association Descriptor. This structure uses LUFA-specific element names + * to make each element's purpose clearer. + * + * This descriptor has been added as a supplement to the USB2.0 standard, in the ECN located at + * http://www.usb.org/developers/docs/InterfaceAssociationDescriptor_ecn.pdf. It allows compound + * devices with multiple interfaces related to the same function to have the multiple interfaces bound + * together at the point of enumeration, loading one generic driver for all the interfaces in the single + * function. Read the ECN for more information. + * + * \see \ref USB_StdDescriptor_Interface_Association_t for the version of this define with standard element names. + */ + typedef struct + { + USB_Descriptor_Header_t Header; /**< Descriptor header, including type and size. */ + + uint8_t FirstInterfaceIndex; /**< Index of the first associated interface. */ + uint8_t TotalInterfaces; /**< Total number of associated interfaces. */ + + uint8_t Class; /**< Interface class ID. */ + uint8_t SubClass; /**< Interface subclass ID. */ + uint8_t Protocol; /**< Interface protocol ID. */ + + uint8_t IADStrIndex; /**< Index of the string descriptor describing the + * interface association. + */ + } USB_Descriptor_Interface_Association_t; + + /** \brief Standard USB Interface Association Descriptor (USB-IF naming conventions). + * + * Type define for a standard Interface Association Descriptor. This structure uses the relevant standard's given + * element names to ensure compatibility with the standard. + * + * This descriptor has been added as a supplement to the USB2.0 standard, in the ECN located at + * http://www.usb.org/developers/docs/InterfaceAssociationDescriptor_ecn.pdf. It allows compound + * devices with multiple interfaces related to the same function to have the multiple interfaces bound + * together at the point of enumeration, loading one generic driver for all the interfaces in the single + * function. Read the ECN for more information. + * + * \see \ref USB_Descriptor_Interface_Association_t for the version of this define with non-standard LUFA specific + * element names. + */ + typedef struct + { + uint8_t bLength; /**< Size of the descriptor, in bytes. */ + uint8_t bDescriptorType; /**< Type of the descriptor, either a value in \ref USB_DescriptorTypes_t or a value + * given by the specific class. + */ + uint8_t bFirstInterface; /**< Index of the first associated interface. */ + uint8_t bInterfaceCount; /**< Total number of associated interfaces. */ + uint8_t bFunctionClass; /**< Interface class ID. */ + uint8_t bFunctionSubClass; /**< Interface subclass ID. */ + uint8_t bFunctionProtocol; /**< Interface protocol ID. */ + uint8_t iFunction; /**< Index of the string descriptor describing the + * interface association. + */ + } USB_StdDescriptor_Interface_Association_t; + + /** \brief Standard USB Endpoint Descriptor (LUFA naming conventions). + * + * Type define for a standard Endpoint Descriptor. This structure uses LUFA-specific element names + * to make each element's purpose clearer. + * + * \see \ref USB_StdDescriptor_Endpoint_t for the version of this define with standard element names. + */ + typedef struct + { + USB_Descriptor_Header_t Header; /**< Descriptor header, including type and size. */ + + uint8_t EndpointAddress; /**< Logical address of the endpoint within the device for the current + * configuration, including direction mask. + */ + uint8_t Attributes; /**< Endpoint attributes, comprised of a mask of the endpoint type (EP_TYPE_*) + * and attributes (ENDPOINT_ATTR_*) masks. + */ + uint16_t EndpointSize; /**< Size of the endpoint bank, in bytes. This indicates the maximum packet + * size that the endpoint can receive at a time. + */ + uint8_t PollingIntervalMS; /**< Polling interval in milliseconds for the endpoint if it is an INTERRUPT + * or ISOCHRONOUS type. + */ + } USB_Descriptor_Endpoint_t; + + /** \brief Standard USB Endpoint Descriptor (USB-IF naming conventions). + * + * Type define for a standard Endpoint Descriptor. This structure uses the relevant standard's given + * element names to ensure compatibility with the standard. + * + * \see \ref USB_Descriptor_Endpoint_t for the version of this define with non-standard LUFA specific + * element names. + */ + typedef struct + { + uint8_t bLength; /**< Size of the descriptor, in bytes. */ + uint8_t bDescriptorType; /**< Type of the descriptor, either a value in \ref USB_DescriptorTypes_t or a + * value given by the specific class. + */ + uint8_t bEndpointAddress; /**< Logical address of the endpoint within the device for the current + * configuration, including direction mask. + */ + uint8_t bmAttributes; /**< Endpoint attributes, comprised of a mask of the endpoint type (EP_TYPE_*) + * and attributes (ENDPOINT_ATTR_*) masks. + */ + uint16_t wMaxPacketSize; /**< Size of the endpoint bank, in bytes. This indicates the maximum packet size + * that the endpoint can receive at a time. + */ + uint8_t bInterval; /**< Polling interval in milliseconds for the endpoint if it is an INTERRUPT or + * ISOCHRONOUS type. + */ + } USB_StdDescriptor_Endpoint_t; + + /** \brief Standard USB String Descriptor (LUFA naming conventions). + * + * Type define for a standard string descriptor. Unlike other standard descriptors, the length + * of the descriptor for placement in the descriptor header must be determined by the \ref USB_STRING_LEN() + * macro rather than by the size of the descriptor structure, as the length is not fixed. + * + * This structure should also be used for string index 0, which contains the supported language IDs for + * the device as an array. + * + * This structure uses LUFA-specific element names to make each element's purpose clearer. + * + * \see \ref USB_StdDescriptor_String_t for the version of this define with standard element names. + */ + typedef struct + { + USB_Descriptor_Header_t Header; /**< Descriptor header, including type and size. */ + + wchar_t UnicodeString[]; /**< String data, as unicode characters (alternatively, + * string language IDs). If normal ASCII characters are + * to be used, they must be added as an array of characters + * rather than a normal C string so that they are widened to + * Unicode size. + * + * Under GCC, strings prefixed with the "L" character (before + * the opening string quotation mark) are considered to be + * Unicode strings, and may be used instead of an explicit + * array of ASCII characters. + */ + } USB_Descriptor_String_t; + + /** \brief Standard USB String Descriptor (USB-IF naming conventions). + * + * Type define for a standard string descriptor. Unlike other standard descriptors, the length + * of the descriptor for placement in the descriptor header must be determined by the \ref USB_STRING_LEN() + * macro rather than by the size of the descriptor structure, as the length is not fixed. + * + * This structure should also be used for string index 0, which contains the supported language IDs for + * the device as an array. + * + * This structure uses the relevant standard's given element names to ensure compatibility with the standard. + * + * \see \ref USB_Descriptor_String_t for the version of this define with with non-standard LUFA specific + * element names. + */ + typedef struct + { + uint8_t bLength; /**< Size of the descriptor, in bytes. */ + uint8_t bDescriptorType; /**< Type of the descriptor, either a value in \ref USB_DescriptorTypes_t + * or a value given by the specific class. + */ + int16_t bString[]; /**< String data, as unicode characters (alternatively, string language IDs). + * If normal ASCII characters are to be used, they must be added as an array + * of characters rather than a normal C string so that they are widened to + * Unicode size. + * + * Under GCC, strings prefixed with the "L" character (before the opening string + * quotation mark) are considered to be Unicode strings, and may be used instead + * of an explicit array of ASCII characters. + */ + } USB_StdDescriptor_String_t; + + /* Private Interface - For use in library only: */ + #if !defined(__DOXYGEN__) + /* Macros: */ + #define VERSION_TENS(x) (int)((x) / 10) + #define VERSION_ONES(x) (int)((x) - (10 * VERSION_TENS(x))) + #define VERSION_TENTHS(x) (int)(((x) - (int)(x)) * 10) + #define VERSION_HUNDREDTHS(x) (int)((((x) - (int)(x)) * 100) - (10 * VERSION_TENTHS(x))) + #endif + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/StdRequestType.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/StdRequestType.h new file mode 100644 index 0000000000..f8e4f45f44 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/StdRequestType.h @@ -0,0 +1,229 @@ +/* + 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 USB control endpoint request definitions. + * + * This file contains structures and macros for the easy creation and parsing of standard USB control requests. + * + * \note This file should not be included directly. It is automatically included as needed by the USB driver + * dispatch header located in LUFA/Drivers/USB/USB.h. + */ + +/** \ingroup Group_USB + * @defgroup Group_StdRequest Standard USB Requests + * + * This module contains definitions for the various control request parameters, so that the request + * details (such as data direction, request recipient, etc.) can be extracted via masking. + * + * @{ + */ + +#ifndef __STDREQTYPE_H__ +#define __STDREQTYPE_H__ + + /* Includes: */ + #include + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_USB_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/USB/USB.h instead. + #endif + + /* Public Interface - May be used in end-application: */ + /* Macros: */ + /** Mask for the request type parameter, to indicate the direction of the request data (Host to Device + * or Device to Host). The result of this mask should then be compared to the request direction masks. + * + * \see REQDIR_* macros for masks indicating the request data direction. + */ + #define CONTROL_REQTYPE_DIRECTION 0x80 + + /** Mask for the request type parameter, to indicate the type of request (Device, Class or Vendor + * Specific). The result of this mask should then be compared to the request type masks. + * + * \see REQTYPE_* macros for masks indicating the request type. + */ + #define CONTROL_REQTYPE_TYPE 0x60 + + /** Mask for the request type parameter, to indicate the recipient of the request (Standard, Class + * or Vendor Specific). The result of this mask should then be compared to the request recipient + * masks. + * + * \see REQREC_* macros for masks indicating the request recipient. + */ + #define CONTROL_REQTYPE_RECIPIENT 0x1F + + /** Request data direction mask, indicating that the request data will flow from host to device. + * + * \see \ref CONTROL_REQTYPE_DIRECTION macro. + */ + #define REQDIR_HOSTTODEVICE (0 << 7) + + /** Request data direction mask, indicating that the request data will flow from device to host. + * + * \see \ref CONTROL_REQTYPE_DIRECTION macro. + */ + #define REQDIR_DEVICETOHOST (1 << 7) + + /** Request type mask, indicating that the request is a standard request. + * + * \see \ref CONTROL_REQTYPE_TYPE macro. + */ + #define REQTYPE_STANDARD (0 << 5) + + /** Request type mask, indicating that the request is a class-specific request. + * + * \see \ref CONTROL_REQTYPE_TYPE macro. + */ + #define REQTYPE_CLASS (1 << 5) + + /** Request type mask, indicating that the request is a vendor specific request. + * + * \see \ref CONTROL_REQTYPE_TYPE macro. + */ + #define REQTYPE_VENDOR (2 << 5) + + /** Request recipient mask, indicating that the request is to be issued to the device as a whole. + * + * \see \ref CONTROL_REQTYPE_RECIPIENT macro. + */ + #define REQREC_DEVICE (0 << 0) + + /** Request recipient mask, indicating that the request is to be issued to an interface in the + * currently selected configuration. + * + * \see \ref CONTROL_REQTYPE_RECIPIENT macro. + */ + #define REQREC_INTERFACE (1 << 0) + + /** Request recipient mask, indicating that the request is to be issued to an endpoint in the + * currently selected configuration. + * + * \see \ref CONTROL_REQTYPE_RECIPIENT macro. + */ + #define REQREC_ENDPOINT (2 << 0) + + /** Request recipient mask, indicating that the request is to be issued to an unspecified element + * in the currently selected configuration. + * + * \see \ref CONTROL_REQTYPE_RECIPIENT macro. + */ + #define REQREC_OTHER (3 << 0) + + /** Feature indicator for Clear Feature or Set Feature commands. When used in a Clear Feature + * request this indicates that an endpoint (whose address is given elsewhere in the request + * should have its stall condition cleared. If used in a similar manner inside a Set Feature + * request, this stalls an endpoint. + */ + #define FEATURE_ENDPOINT_HALT 0x00 + + /** Feature indicator for Clear Feature or Set Feature commands. When used in a Clear Feature + * request this indicates that the remote wakeup enabled device should not issue remote + * wakeup requests until further notice. If used in a similar manner inside a Set Feature + * request, this re-enabled the remote wakeup feature on the device. + */ + #define FEATURE_REMOTE_WAKEUP 0x01 + + /* Type Defines: */ + /** \brief Standard USB Control Request + * + * Type define for a standard USB control request. + * + * \see The USB 2.0 specification for more information on standard control requests. + */ + typedef struct + { + uint8_t bmRequestType; /**< Type of the request. */ + uint8_t bRequest; /**< Request command code. */ + uint16_t wValue; /**< wValue parameter of the request. */ + uint16_t wIndex; /**< wIndex parameter of the request. */ + uint16_t wLength; /**< Length of the data to transfer in bytes. */ + } USB_Request_Header_t; + + /* Enums: */ + /** Enumeration for the various standard request commands. These commands are applicable when the + * request type is \ref REQTYPE_STANDARD (with the exception of \ref REQ_GetDescriptor, which is always + * handled regardless of the request type value). + * + * \see Chapter 9 of the USB 2.0 Specification. + */ + enum USB_Control_Request_t + { + REQ_GetStatus = 0, /**< Implemented in the library for device, endpoint and interface + * recipients. Passed to the user application for other recipients + * via the \ref EVENT_USB_Device_UnhandledControlRequest() event when received in + * device mode. */ + REQ_ClearFeature = 1, /**< Implemented in the library for device, endpoint and interface + * recipients. Passed to the user application for other recipients + * via the \ref EVENT_USB_Device_UnhandledControlRequest() event when received in + * device mode. */ + REQ_SetFeature = 3, /**< Implemented in the library for device, endpoint and interface + * recipients. Passed to the user application for other recipients + * via the \ref EVENT_USB_Device_UnhandledControlRequest() event when received in + * device mode. */ + REQ_SetAddress = 5, /**< Implemented in the library for the device recipient. Passed + * to the user application for other recipients via the + * \ref EVENT_USB_Device_UnhandledControlRequest() event when received in + * device mode. */ + REQ_GetDescriptor = 6, /**< Implemented in the library for all recipients and all request + * types. */ + REQ_SetDescriptor = 7, /**< Not implemented in the library, passed to the user application + * via the \ref EVENT_USB_Device_UnhandledControlRequest() event when received in + * device mode. */ + REQ_GetConfiguration = 8, /**< Implemented in the library for the device recipient. Passed + * to the user application for other recipients via the + * \ref EVENT_USB_Device_UnhandledControlRequest() event when received in + * device mode. */ + REQ_SetConfiguration = 9, /**< Implemented in the library for the device recipient. Passed + * to the user application for other recipients via the + * \ref EVENT_USB_Device_UnhandledControlRequest() event when received in + * device mode. */ + REQ_GetInterface = 10, /**< Not implemented in the library, passed to the user application + * via the \ref EVENT_USB_Device_UnhandledControlRequest() event when received in + * device mode. */ + REQ_SetInterface = 11, /**< Not implemented in the library, passed to the user application + * via the \ref EVENT_USB_Device_UnhandledControlRequest() event when received in + * device mode. */ + REQ_SynchFrame = 12, /**< Not implemented in the library, passed to the user application + * via the \ref EVENT_USB_Device_UnhandledControlRequest() event when received in + * device mode. */ + }; + + /* Private Interface - For use in library only: */ + #if !defined(__DOXYGEN__) + /* Macros: */ + #define FEATURE_SELFPOWERED_ENABLED (1 << 0) + #define FEATURE_REMOTE_WAKEUP_ENABLED (1 << 1) + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/StreamCallbacks.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/StreamCallbacks.h new file mode 100644 index 0000000000..dc34952856 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/StreamCallbacks.h @@ -0,0 +1,86 @@ +/* + 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 USB endpoint/pipe stream callback management. + * + * This file contains definitions for the creation of optional callback routines which can be passed to the + * endpoint and/or pipe stream APIs, to abort the transfer currently in progress when a condition is met. + * + * \note This file should not be included directly. It is automatically included as needed by the USB driver + * dispatch header located in LUFA/Drivers/USB/USB.h. + */ + +/** \ingroup Group_USB + * @defgroup Group_StreamCallbacks Endpoint and Pipe Stream Callbacks + * + * Macros and enums for the stream callback routines. This module contains the code required to easily set up + * stream callback functions which can be used to force early abort of a stream read/write process. Each callback + * should take no arguments, and return a value from the \ref StreamCallback_Return_ErrorCodes_t enum. + * + * @{ + */ + +#ifndef __STREAMCALLBACK_H__ +#define __STREAMCALLBACK_H__ + + /* Includes: */ + #include + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_USB_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/USB/USB.h instead. + #endif + + /* Public Interface - May be used in end-application: */ + /* Macros: */ + /** Used with the Endpoint and Pipe stream functions as the callback function parameter, indicating that the stream + * call has no callback function to be called between USB packets. + */ + #define NO_STREAM_CALLBACK NULL + + /* Enums: */ + /** Enum for the possible error return codes of a stream callback function. */ + enum StreamCallback_Return_ErrorCodes_t + { + STREAMCALLBACK_Continue = 0, /**< Continue sending or receiving the stream. */ + STREAMCALLBACK_Abort = 1, /**< Abort the stream send or receiving process. */ + }; + + /* Type Defines: */ + /** Type define for a Stream Callback function (function taking no arguments and retuning a + * uint8_t value). Stream callback functions should have an identical function signature if they + * are to be used as the callback parameter of the stream functions. + */ + typedef uint8_t (* const StreamCallbackPtr_t)(void); + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/USBMode.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/USBMode.h new file mode 100644 index 0000000000..1de2ef9bb8 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/USBMode.h @@ -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 USB mode and capability macros. + * + * This file defines macros indicating the type of USB controller the library is being compiled for, and its + * capabilities. These macros may then be referenced in the user application to selectively enable or disable + * code sections depending on if they are defined or not. + * + * \note This file should not be included directly. It is automatically included as needed by the USB driver + * dispatch header located in LUFA/Drivers/USB/USB.h. + */ + +/** \ingroup Group_USB + * @defgroup Group_USBMode USB Mode Tokens + * + * After the inclusion of the master USB driver header, one or more of the following + * tokens may be defined, to allow the user code to conditionally enable or disable + * code based on the USB controller family and allowable USB modes. These tokens may + * be tested against to eliminate code relating to a USB mode which is not enabled for + * the given compilation. + * + * @{ + */ + +#ifndef __USBMODE_H__ +#define __USBMODE_H__ + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_USB_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/USB/USB.h instead. + #endif + + /* Public Interface - May be used in end-application: */ + #if defined(__DOXYGEN__) + /** Indicates that the target AVR microcontroller belongs to the Series 2 USB controller + * (i.e. AT90USBXXX2 or ATMEGAXXU2) when defined. + */ + #define USB_SERIES_2_AVR + + /** Indicates that the target AVR microcontroller belongs to the Series 4 USB controller + * (i.e. ATMEGAXXU4) when defined. + */ + #define USB_SERIES_4_AVR + + /** Indicates that the target AVR microcontroller belongs to the Series 6 USB controller + * (i.e. AT90USBXXX6) when defined. + */ + #define USB_SERIES_6_AVR + + /** Indicates that the target AVR microcontroller belongs to the Series 7 USB controller + * (i.e. AT90USBXXX7) when defined. + */ + #define USB_SERIES_7_AVR + + /** Indicates that the target AVR microcontroller and compilation settings allow for the + * target to be configured in USB Device mode when defined. + */ + #define USB_CAN_BE_DEVICE + + /** Indicates that the target AVR microcontroller and compilation settings allow for the + * target to be configured in USB Host mode when defined. + */ + #define USB_CAN_BE_HOST + + /** Indicates that the target AVR microcontroller and compilation settings allow for the + * target to be configured in either USB Device or Host mode when defined. + */ + #define USB_CAN_BE_BOTH + #else + /* Macros: */ + #if (defined(__AVR_AT90USB162__) || defined(__AVR_AT90USB82__) || \ + defined(__AVR_ATmega32U2__) || defined(__AVR_ATmega16U2__) || defined(__AVR_ATmega8U2__)) + #define USB_SERIES_2_AVR + #elif (defined(__AVR_ATmega32U4__) || defined(__AVR_ATmega16U4__)) + #define USB_SERIES_4_AVR + #elif (defined(__AVR_ATmega32U6__) || defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB1286__)) + #define USB_SERIES_6_AVR + #elif (defined(__AVR_AT90USB647__) || defined(__AVR_AT90USB1287__)) + #define USB_SERIES_7_AVR + #endif + + #if !defined(USB_SERIES_7_AVR) + #if defined(USB_HOST_ONLY) + #error USB_HOST_ONLY is not available for the currently selected USB AVR model. + #endif + + #if !defined(USB_DEVICE_ONLY) + #define USB_DEVICE_ONLY + #endif + #endif + + #if (!defined(USB_DEVICE_ONLY) && !defined(USB_HOST_ONLY)) + #define USB_CAN_BE_BOTH + #define USB_CAN_BE_HOST + #define USB_CAN_BE_DEVICE + #elif defined(USB_HOST_ONLY) + #define USB_CAN_BE_HOST + #elif defined(USB_DEVICE_ONLY) + #define USB_CAN_BE_DEVICE + #endif + + #if (defined(USB_HOST_ONLY) && defined(USB_DEVICE_ONLY)) + #error USB_HOST_ONLY and USB_DEVICE_ONLY are mutually exclusive. + #endif + #endif + +#endif + +/** @} */ \ No newline at end of file diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/USBTask.c b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/USBTask.c new file mode 100644 index 0000000000..5ec1746fd3 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/USBTask.c @@ -0,0 +1,88 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +#define __INCLUDE_FROM_USBTASK_C +#define __INCLUDE_FROM_USB_DRIVER +#include "USBTask.h" + +volatile bool USB_IsInitialized; +USB_Request_Header_t USB_ControlRequest; + +#if defined(USB_CAN_BE_HOST) && !defined(HOST_STATE_AS_GPIOR) +volatile uint8_t USB_HostState; +#endif + +#if defined(USB_CAN_BE_DEVICE) && !defined(DEVICE_STATE_AS_GPIOR) +volatile uint8_t USB_DeviceState; +#endif + +void USB_USBTask(void) +{ + #if defined(USB_HOST_ONLY) + USB_HostTask(); + #elif defined(USB_DEVICE_ONLY) + USB_DeviceTask(); + #else + if (USB_CurrentMode == USB_MODE_DEVICE) + USB_DeviceTask(); + else if (USB_CurrentMode == USB_MODE_HOST) + USB_HostTask(); + #endif +} + +#if defined(USB_CAN_BE_DEVICE) +static void USB_DeviceTask(void) +{ + if (USB_DeviceState != DEVICE_STATE_Unattached) + { + uint8_t PrevEndpoint = Endpoint_GetCurrentEndpoint(); + + Endpoint_SelectEndpoint(ENDPOINT_CONTROLEP); + + if (Endpoint_IsSETUPReceived()) + USB_Device_ProcessControlRequest(); + + Endpoint_SelectEndpoint(PrevEndpoint); + } +} +#endif + +#if defined(USB_CAN_BE_HOST) +static void USB_HostTask(void) +{ + uint8_t PrevPipe = Pipe_GetCurrentPipe(); + + Pipe_SelectPipe(PIPE_CONTROLPIPE); + + USB_Host_ProcessNextHostState(); + + Pipe_SelectPipe(PrevPipe); +} +#endif diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/USBTask.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/USBTask.h new file mode 100644 index 0000000000..faff2a3bba --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/HighLevel/USBTask.h @@ -0,0 +1,204 @@ +/* + 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 Main USB service task management. + * + * This file contains the function definitions required for the main USB service task, which must be called + * from the user application to ensure that the USB connection to or from a connected USB device is maintained. + * + * \note This file should not be included directly. It is automatically included as needed by the USB driver + * dispatch header located in LUFA/Drivers/USB/USB.h. + */ + +#ifndef __USBTASK_H__ +#define __USBTASK_H__ + + /* Includes: */ + #include + #include + #include + + #include "../LowLevel/USBController.h" + #include "Events.h" + #include "StdRequestType.h" + #include "StdDescriptors.h" + #include "USBMode.h" + + #if defined(USB_CAN_BE_DEVICE) + #include "DeviceStandardReq.h" + #endif + + #if defined(USB_CAN_BE_HOST) + #include "HostStandardReq.h" + #endif + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_USB_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/USB/USB.h instead. + #endif + + /* Public Interface - May be used in end-application: */ + /* Global Variables: */ + /** Indicates if the USB interface is currently initialized but not necessarily connected to a host + * or device (i.e. if \ref USB_Init() has been run). If this is false, all other library globals are invalid. + * + * \note This variable should be treated as read-only in the user application, and never manually + * changed in value. + * + * \ingroup Group_USBManagement + */ + extern volatile bool USB_IsInitialized; + + /** Structure containing the last received Control request when in Device mode (for use in user-applications + * inside of the \ref EVENT_USB_Device_UnhandledControlRequest() event, or for filling up with a control request to issue when + * in Host mode before calling \ref USB_Host_SendControlRequest(). + * + * \ingroup Group_USBManagement + */ + extern USB_Request_Header_t USB_ControlRequest; + + #if defined(USB_CAN_BE_HOST) || defined(__DOXYGEN__) + #if !defined(HOST_STATE_AS_GPIOR) || defined(__DOXYGEN__) + /** Indicates the current host state machine state. When in host mode, this indicates the state + * via one of the values of the \ref USB_Host_States_t enum values. + * + * This value may be altered by the user application to implement the \ref HOST_STATE_Addressed, + * \ref HOST_STATE_Configured and \ref HOST_STATE_Suspended states which are not implemented by + * the library. + * + * To reduce program size and speed up checks of this global, it can be placed into one of the AVR's + * GPIOR hardware registers instead of RAM by defining the HOST_STATE_AS_GPIOR token to a value + * between 0 and 2 in the project makefile and passing it to the compiler via the -D switch. When + * defined, the corresponding GPIOR register should not be used in the user application except + * implicitly via the library APIs. + * + * \note This global is only present if the user application can be a USB host. + * + * \see \ref USB_Host_States_t for a list of possible device states. + * + * \ingroup Group_Host + */ + extern volatile uint8_t USB_HostState; + #else + #define _GET_HOST_GPIOR_NAME2(y) GPIOR ## y + #define _GET_HOST_GPIOR_NAME(x) _GET_HOST_GPIOR_NAME2(x) + #define USB_HostState _GET_HOST_GPIOR_NAME(HOST_STATE_AS_GPIOR) + #endif + #endif + + #if defined(USB_CAN_BE_DEVICE) || defined(__DOXYGEN__) + #if !defined(DEVICE_STATE_AS_GPIOR) || defined(__DOXYGEN__) + /** Indicates the current device state machine state. When in device mode, this indicates the state + * via one of the values of the \ref USB_Device_States_t enum values. + * + * This value should not be altered by the user application as it is handled automatically by the + * library. The only exception to this rule is if the NO_LIMITED_CONTROLLER_CONNECT token is used + * (see \ref EVENT_USB_Device_Connect() and \ref EVENT_USB_Device_Disconnect() events). + * + * To reduce program size and speed up checks of this global, it can be placed into one of the AVR's + * GPIOR hardware registers instead of RAM by defining the DEVICE_STATE_AS_GPIOR token to a value + * between 0 and 2 in the project makefile and passing it to the compiler via the -D switch. When + * defined, the corresponding GPIOR register should not be used in the user application except + * implicitly via the library APIs. + * + * \note This global is only present if the user application can be a USB device. + * \n\n + * + * \note This variable should be treated as read-only in the user application, and never manually + * changed in value except in the circumstances outlined above. + * + * \see \ref USB_Device_States_t for a list of possible device states. + * + * \ingroup Group_Device + */ + extern volatile uint8_t USB_DeviceState; + #else + #define _GET_DEVICE_GPIOR_NAME2(y) GPIOR ## y + #define _GET_DEVICE_GPIOR_NAME(x) _GET_DEVICE_GPIOR_NAME2(x) + #define USB_DeviceState _GET_DEVICE_GPIOR_NAME(DEVICE_STATE_AS_GPIOR) + #endif + #endif + + /* Function Prototypes: */ + /** This is the main USB management task. The USB driver requires that this task be executed + * continuously when the USB system is active (device attached in host mode, or attached to a host + * in device mode) in order to manage USB communications. This task may be executed inside an RTOS, + * fast timer ISR or the main user application loop. + * + * The USB task must be serviced within 30ms while in device mode, or within 1ms while in host mode. + * The task may be serviced at all times, or (for minimum CPU consumption): + * + * - In device mode, it may be disabled at start-up, enabled on the firing of the \ref EVENT_USB_Device_Connect() + * event and disabled again on the firing of the \ref EVENT_USB_Device_Disconnect() event. + * + * - In host mode, it may be disabled at start-up, enabled on the firing of the \ref EVENT_USB_Host_DeviceAttached() + * event and disabled again on the firing of the \ref EVENT_USB_Host_DeviceEnumerationComplete() or + * \ref EVENT_USB_Host_DeviceEnumerationFailed() events. + * + * If in device mode (only), the control endpoint can instead be managed via interrupts entirely by the library + * by defining the INTERRUPT_CONTROL_ENDPOINT token and passing it to the compiler via the -D switch. + * + * \see \ref Group_Events for more information on the USB events. + * + * \ingroup Group_USBManagement + */ + void USB_USBTask(void); + + /* Private Interface - For use in library only: */ + #if !defined(__DOXYGEN__) + /* Function Prototypes: */ + #if defined(__INCLUDE_FROM_USBTASK_C) + #if defined(USB_CAN_BE_HOST) + static void USB_HostTask(void); + #endif + + #if defined(USB_CAN_BE_DEVICE) + static void USB_DeviceTask(void); + #endif + #endif + + /* Macros: */ + #define HOST_TASK_NONBLOCK_WAIT(duration, nextstate) MACROS{ USB_HostState = HOST_STATE_WaitForDevice; \ + WaitMSRemaining = (duration); \ + PostWaitState = (nextstate); }MACROE + #endif + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/Device.c b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/Device.c new file mode 100644 index 0000000000..5355ca27ca --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/Device.c @@ -0,0 +1,52 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +#define __INCLUDE_FROM_USB_DRIVER +#include "../HighLevel/USBMode.h" + +#if defined(USB_CAN_BE_DEVICE) + +#include "Device.h" + +void USB_Device_SendRemoteWakeup(void) +{ + if (!(USB_Options & USB_OPT_MANUAL_PLL)) + { + USB_PLL_On(); + while (!(USB_PLL_IsReady())); + } + + USB_CLK_Unfreeze(); + + UDCON |= (1 << RMWKUP); + while (!(UDCON & (1 << RMWKUP))); +} + +#endif diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/Device.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/Device.h new file mode 100644 index 0000000000..ef093d64d3 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/Device.h @@ -0,0 +1,222 @@ +/* + 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 USB device mode definitions. + * + * This file contains structures, function prototypes and macros related to USB device mode. + * + * \note This file should not be included directly. It is automatically included as needed by the USB driver + * dispatch header located in LUFA/Drivers/USB/USB.h. + */ + +/** \ingroup Group_USB + * @defgroup Group_Device Device Management + * + * USB Device mode related macros and enums. This module contains macros and enums which are used when + * the USB controller is initialized in device mode. + * + * @{ + */ + +#ifndef __USBDEVICE_H__ +#define __USBDEVICE_H__ + + /* Includes: */ + #include + #include + #include + + #include "../../../Common/Common.h" + #include "../HighLevel/StdDescriptors.h" + #include "USBInterrupt.h" + #include "Endpoint.h" + + /* Preprocessor Checks: */ + #if (defined(USE_RAM_DESCRIPTORS) && defined(USE_EEPROM_DESCRIPTORS)) + #error USE_RAM_DESCRIPTORS and USE_EEPROM_DESCRIPTORS are mutually exclusive. + #endif + + #if !defined(__INCLUDE_FROM_USB_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/USB/USB.h instead. + #endif + + /* Public Interface - May be used in end-application: */ + /* Macros: */ + #if defined(USB_SERIES_4_AVR) || defined(USB_SERIES_6_AVR) || defined(USB_SERIES_7_AVR) || defined(__DOXYGEN__) + /** Mask for the Options parameter of the \ref USB_Init() function. This indicates that the + * USB interface should be initialized in low speed (1.5Mb/s) mode. + * + * \note Low Speed mode is not available on all USB AVR models. + * \n\n + * + * \note Restrictions apply on the number, size and type of endpoints which can be used + * when running in low speed mode -- refer to the USB 2.0 standard. + */ + #define USB_DEVICE_OPT_LOWSPEED (1 << 0) + #endif + + /** Mask for the Options parameter of the \ref USB_Init() function. This indicates that the + * USB interface should be initialized in full speed (12Mb/s) mode. + */ + #define USB_DEVICE_OPT_FULLSPEED (0 << 0) + + /* Function Prototypes: */ + /** Sends a Remote Wakeup request to the host. This signals to the host that the device should + * be taken out of suspended mode, and communications should resume. + * + * Typically, this is implemented so that HID devices (mice, keyboards, etc.) can wake up the + * host computer when the host has suspended all USB devices to enter a low power state. + * + * \note This macro should only be used if the device has indicated to the host that it + * supports the Remote Wakeup feature in the device descriptors, and should only be + * issued if the host is currently allowing remote wakeup events from the device (i.e., + * the \ref USB_RemoteWakeupEnabled flag is set). When the NO_DEVICE_REMOTE_WAKEUP compile + * time option is used, this macro is unavailable. + * \n + * + * \note The USB clock must be running for this function to operate. If the stack is initialized with + * the \ref USB_OPT_MANUAL_PLL option enabled, the user must ensure that the PLL is running + * before attempting to call this function. + * + * \see \ref Group_Descriptors for more information on the RMWAKEUP feature and device descriptors. + */ + void USB_Device_SendRemoteWakeup(void); + + /* Type Defines: */ + enum USB_Device_States_t + { + DEVICE_STATE_Unattached = 0, /**< Internally implemented by the library. This state indicates + * that the device is not currently connected to a host. + */ + DEVICE_STATE_Powered = 1, /**< Internally implemented by the library. This state indicates + * that the device is connected to a host, but enumeration has not + * yet begun. + */ + DEVICE_STATE_Default = 2, /**< Internally implemented by the library. This state indicates + * that the device's USB bus has been reset by the host and it is + * now waiting for the host to begin the enumeration process. + */ + DEVICE_STATE_Addressed = 3, /**< Internally implemented by the library. This state indicates + * that the device has been addressed by the USB Host, but is not + * yet configured. + */ + DEVICE_STATE_Configured = 4, /**< May be implemented by the user project. This state indicates + * that the device has been enumerated by the host and is ready + * for USB communications to begin. + */ + DEVICE_STATE_Suspended = 5, /**< May be implemented by the user project. This state indicates + * that the USB bus has been suspended by the host, and the device + * should power down to a minimal power level until the bus is + * resumed. + */ + }; + + /* Inline Functions: */ + /** Enables the device mode Start Of Frame events. When enabled, this causes the + * \ref EVENT_USB_Device_StartOfFrame() event to fire once per millisecond, synchronized to the USB bus, + * at the start of each USB frame when enumerated in device mode. + */ + static inline void USB_Device_EnableSOFEvents(void) ATTR_ALWAYS_INLINE; + static inline void USB_Device_EnableSOFEvents(void) + { + USB_INT_Enable(USB_INT_SOFI); + } + + /** Disables the device mode Start Of Frame events. When disabled, this stop the firing of the + * \ref EVENT_USB_Device_StartOfFrame() event when enumerated in device mode. + */ + static inline void USB_Device_DisableSOFEvents(void) ATTR_ALWAYS_INLINE; + static inline void USB_Device_DisableSOFEvents(void) + { + USB_INT_Disable(USB_INT_SOFI); + } + + /* Function Prototypes: */ + /** Function to retrieve a given descriptor's size and memory location from the given descriptor type value, + * index and language ID. This function MUST be overridden in the user application (added with full, identical + * prototype and name so that the library can call it to retrieve descriptor data. + * + * \param[in] wValue The type of the descriptor to retrieve in the upper byte, and the index in the + * lower byte (when more than one descriptor of the given type exists, such as the + * case of string descriptors). The type may be one of the standard types defined + * in the DescriptorTypes_t enum, or may be a class-specific descriptor type value. + * \param[in] wIndex The language ID of the string to return if the wValue type indicates DTYPE_String, + * otherwise zero for standard descriptors, or as defined in a class-specific + * standards. + * \param[out] DescriptorAddress Pointer to the descriptor in memory. This should be set by the routine to + * the address of the descriptor. + * \param[out] MemoryAddressSpace A value from the \ref USB_DescriptorMemorySpaces_t enum to indicate the memory + * space in which the descriptor is stored. This parameter does not exist when one + * of the USE_*_DESCRIPTORS compile time options is used. + * + * \note By default, the library expects all descriptors to be located in flash memory via the PROGMEM attribute. + * If descriptors should be located in RAM or EEPROM instead (to speed up access in the case of RAM, or to + * allow the descriptors to be changed dynamically at runtime) either the USE_RAM_DESCRIPTORS or the + * USE_EEPROM_DESCRIPTORS tokens may be defined in the project makefile and passed to the compiler by the -D + * switch. + * + * \return Size in bytes of the descriptor if it exists, zero or \ref NO_DESCRIPTOR otherwise. + */ + uint16_t CALLBACK_USB_GetDescriptor(const uint16_t wValue, + const uint8_t wIndex, + void** const DescriptorAddress + #if !defined(USE_FLASH_DESCRIPTORS) && !defined(USE_EEPROM_DESCRIPTORS) && !defined(USE_RAM_DESCRIPTORS) + , uint8_t* MemoryAddressSpace + #endif + ) ATTR_WARN_UNUSED_RESULT ATTR_NON_NULL_PTR_ARG(3); + + /* Private Interface - For use in library only: */ + #if !defined(__DOXYGEN__) + /* Inline Functions: */ + #if (defined(USB_SERIES_4_AVR) || defined(USB_SERIES_6_AVR) || defined(USB_SERIES_7_AVR)) + static inline void USB_Device_SetLowSpeed(void) ATTR_ALWAYS_INLINE; + static inline void USB_Device_SetLowSpeed(void) + { + UDCON |= (1 << LSM); + } + + static inline void USB_Device_SetFullSpeed(void) ATTR_ALWAYS_INLINE; + static inline void USB_Device_SetFullSpeed(void) + { + UDCON &= ~(1 << LSM); + } + #endif + + static inline void USB_Device_SetDeviceAddress(const uint8_t Address) ATTR_ALWAYS_INLINE; + static inline void USB_Device_SetDeviceAddress(const uint8_t Address) + { + UDADDR = ((1 << ADDEN) | (Address & 0x7F)); + } + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/Endpoint.c b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/Endpoint.c new file mode 100644 index 0000000000..4eecdc5759 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/Endpoint.c @@ -0,0 +1,340 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +#define __INCLUDE_FROM_USB_DRIVER +#include "../HighLevel/USBMode.h" + +#if defined(USB_CAN_BE_DEVICE) + +#define __INCLUDE_FROM_ENDPOINT_C +#include "Endpoint.h" + +#if !defined(FIXED_CONTROL_ENDPOINT_SIZE) +uint8_t USB_ControlEndpointSize = ENDPOINT_CONTROLEP_DEFAULT_SIZE; +#endif + +uint8_t Endpoint_BytesToEPSizeMaskDynamic(const uint16_t Size) +{ + return Endpoint_BytesToEPSizeMask(Size); +} + +bool Endpoint_ConfigureEndpoint_Prv(const uint8_t Number, + const uint8_t UECFG0XData, + const uint8_t UECFG1XData) +{ + Endpoint_SelectEndpoint(Number); + Endpoint_EnableEndpoint(); + + UECFG1X = 0; + + UECFG0X = UECFG0XData; + UECFG1X = UECFG1XData; + + return Endpoint_IsConfigured(); +} + +void Endpoint_ClearEndpoints(void) +{ + UEINT = 0; + + for (uint8_t EPNum = 0; EPNum < ENDPOINT_TOTAL_ENDPOINTS; EPNum++) + { + Endpoint_SelectEndpoint(EPNum); + UEIENX = 0; + UEINTX = 0; + UECFG1X = 0; + Endpoint_DisableEndpoint(); + } +} + +void Endpoint_ClearStatusStage(void) +{ + if (USB_ControlRequest.bmRequestType & REQDIR_DEVICETOHOST) + { + while (!(Endpoint_IsOUTReceived())) + { + if (USB_DeviceState == DEVICE_STATE_Unattached) + return; + } + + Endpoint_ClearOUT(); + } + else + { + while (!(Endpoint_IsINReady())) + { + if (USB_DeviceState == DEVICE_STATE_Unattached) + return; + } + + Endpoint_ClearIN(); + } +} + +#if !defined(CONTROL_ONLY_DEVICE) +uint8_t Endpoint_WaitUntilReady(void) +{ + #if (USB_STREAM_TIMEOUT_MS < 0xFF) + uint8_t TimeoutMSRem = USB_STREAM_TIMEOUT_MS; + #else + uint16_t TimeoutMSRem = USB_STREAM_TIMEOUT_MS; + #endif + + for (;;) + { + if (Endpoint_GetEndpointDirection() == ENDPOINT_DIR_IN) + { + if (Endpoint_IsINReady()) + return ENDPOINT_READYWAIT_NoError; + } + else + { + if (Endpoint_IsOUTReceived()) + return ENDPOINT_READYWAIT_NoError; + } + + if (USB_DeviceState == DEVICE_STATE_Unattached) + return ENDPOINT_READYWAIT_DeviceDisconnected; + else if (USB_DeviceState == DEVICE_STATE_Suspended) + return ENDPOINT_READYWAIT_BusSuspended; + else if (Endpoint_IsStalled()) + return ENDPOINT_READYWAIT_EndpointStalled; + + if (USB_INT_HasOccurred(USB_INT_SOFI)) + { + USB_INT_Clear(USB_INT_SOFI); + + if (!(TimeoutMSRem--)) + return ENDPOINT_READYWAIT_Timeout; + } + } +} + +uint8_t Endpoint_Discard_Stream(uint16_t Length +#if !defined(NO_STREAM_CALLBACKS) + , StreamCallbackPtr_t Callback +#endif + ) +{ + uint8_t ErrorCode; + + if ((ErrorCode = Endpoint_WaitUntilReady())) + return ErrorCode; + + #if defined(FAST_STREAM_TRANSFERS) + uint8_t BytesRemToAlignment = (Endpoint_BytesInEndpoint() & 0x07); + + if (Length >= 8) + { + Length -= BytesRemToAlignment; + + switch (BytesRemToAlignment) + { + default: + do + { + if (!(Endpoint_IsReadWriteAllowed())) + { + Endpoint_ClearOUT(); + + #if !defined(NO_STREAM_CALLBACKS) + if ((Callback != NULL) && (Callback() == STREAMCALLBACK_Abort)) + return ENDPOINT_RWSTREAM_CallbackAborted; + #endif + + if ((ErrorCode = Endpoint_WaitUntilReady())) + return ErrorCode; + } + + Length -= 8; + + Endpoint_Discard_Byte(); + case 7: Endpoint_Discard_Byte(); + case 6: Endpoint_Discard_Byte(); + case 5: Endpoint_Discard_Byte(); + case 4: Endpoint_Discard_Byte(); + case 3: Endpoint_Discard_Byte(); + case 2: Endpoint_Discard_Byte(); + case 1: Endpoint_Discard_Byte(); + } while (Length >= 8); + } + } + #endif + + while (Length) + { + if (!(Endpoint_IsReadWriteAllowed())) + { + Endpoint_ClearOUT(); + + #if !defined(NO_STREAM_CALLBACKS) + if ((Callback != NULL) && (Callback() == STREAMCALLBACK_Abort)) + return ENDPOINT_RWSTREAM_CallbackAborted; + #endif + + if ((ErrorCode = Endpoint_WaitUntilReady())) + return ErrorCode; + } + else + { + Endpoint_Discard_Byte(); + Length--; + } + } + + return ENDPOINT_RWSTREAM_NoError; +} + +/* The following abuses the C preprocessor in order to copy-past common code with slight alterations, + * so that the code needs to be written once. It is a crude form of templating to reduce code maintenance. */ + +#define TEMPLATE_FUNC_NAME Endpoint_Write_Stream_LE +#define TEMPLATE_BUFFER_TYPE const void* +#define TEMPLATE_CLEAR_ENDPOINT() Endpoint_ClearIN() +#define TEMPLATE_BUFFER_OFFSET(Length) 0 +#define TEMPLATE_TRANSFER_BYTE(BufferPtr) Endpoint_Write_Byte(*((uint8_t*)BufferPtr++)) +#include "Template/Template_Endpoint_RW.c" + +#define TEMPLATE_FUNC_NAME Endpoint_Write_PStream_LE +#define TEMPLATE_BUFFER_TYPE const void* +#define TEMPLATE_CLEAR_ENDPOINT() Endpoint_ClearIN() +#define TEMPLATE_BUFFER_OFFSET(Length) 0 +#define TEMPLATE_TRANSFER_BYTE(BufferPtr) Endpoint_Write_Byte(pgm_read_byte((uint8_t*)BufferPtr++)) +#include "Template/Template_Endpoint_RW.c" + +#define TEMPLATE_FUNC_NAME Endpoint_Write_EStream_LE +#define TEMPLATE_BUFFER_TYPE const void* +#define TEMPLATE_CLEAR_ENDPOINT() Endpoint_ClearIN() +#define TEMPLATE_BUFFER_OFFSET(Length) 0 +#define TEMPLATE_TRANSFER_BYTE(BufferPtr) Endpoint_Write_Byte(eeprom_read_byte((uint8_t*)BufferPtr++)) +#include "Template/Template_Endpoint_RW.c" + +#define TEMPLATE_FUNC_NAME Endpoint_Write_Stream_BE +#define TEMPLATE_BUFFER_TYPE const void* +#define TEMPLATE_CLEAR_ENDPOINT() Endpoint_ClearIN() +#define TEMPLATE_BUFFER_OFFSET(Length) (Length - 1) +#define TEMPLATE_TRANSFER_BYTE(BufferPtr) Endpoint_Write_Byte(*((uint8_t*)BufferPtr--)) +#include "Template/Template_Endpoint_RW.c" + +#define TEMPLATE_FUNC_NAME Endpoint_Write_EStream_BE +#define TEMPLATE_BUFFER_TYPE const void* +#define TEMPLATE_CLEAR_ENDPOINT() Endpoint_ClearIN() +#define TEMPLATE_BUFFER_OFFSET(Length) (Length - 1) +#define TEMPLATE_TRANSFER_BYTE(BufferPtr) Endpoint_Write_Byte(eeprom_read_byte((uint8_t*)BufferPtr--)) +#include "Template/Template_Endpoint_RW.c" + +#define TEMPLATE_FUNC_NAME Endpoint_Write_PStream_BE +#define TEMPLATE_BUFFER_TYPE const void* +#define TEMPLATE_CLEAR_ENDPOINT() Endpoint_ClearIN() +#define TEMPLATE_BUFFER_OFFSET(Length) (Length - 1) +#define TEMPLATE_TRANSFER_BYTE(BufferPtr) Endpoint_Write_Byte(pgm_read_byte((uint8_t*)BufferPtr--)) +#include "Template/Template_Endpoint_RW.c" + +#define TEMPLATE_FUNC_NAME Endpoint_Read_Stream_LE +#define TEMPLATE_BUFFER_TYPE void* +#define TEMPLATE_CLEAR_ENDPOINT() Endpoint_ClearOUT() +#define TEMPLATE_BUFFER_OFFSET(Length) 0 +#define TEMPLATE_TRANSFER_BYTE(BufferPtr) *((uint8_t*)BufferPtr++) = Endpoint_Read_Byte() +#include "Template/Template_Endpoint_RW.c" + +#define TEMPLATE_FUNC_NAME Endpoint_Read_EStream_LE +#define TEMPLATE_BUFFER_TYPE void* +#define TEMPLATE_CLEAR_ENDPOINT() Endpoint_ClearOUT() +#define TEMPLATE_BUFFER_OFFSET(Length) 0 +#define TEMPLATE_TRANSFER_BYTE(BufferPtr) eeprom_update_byte((uint8_t*)BufferPtr++, Endpoint_Read_Byte()) +#include "Template/Template_Endpoint_RW.c" + +#define TEMPLATE_FUNC_NAME Endpoint_Read_Stream_BE +#define TEMPLATE_BUFFER_TYPE void* +#define TEMPLATE_CLEAR_ENDPOINT() Endpoint_ClearOUT() +#define TEMPLATE_BUFFER_OFFSET(Length) (Length - 1) +#define TEMPLATE_TRANSFER_BYTE(BufferPtr) *((uint8_t*)BufferPtr--) = Endpoint_Read_Byte() +#include "Template/Template_Endpoint_RW.c" + +#define TEMPLATE_FUNC_NAME Endpoint_Read_EStream_BE +#define TEMPLATE_BUFFER_TYPE void* +#define TEMPLATE_CLEAR_ENDPOINT() Endpoint_ClearOUT() +#define TEMPLATE_BUFFER_OFFSET(Length) (Length - 1) +#define TEMPLATE_TRANSFER_BYTE(BufferPtr) eeprom_update_byte((uint8_t*)BufferPtr--, Endpoint_Read_Byte()) +#include "Template/Template_Endpoint_RW.c" + +#endif + +#define TEMPLATE_FUNC_NAME Endpoint_Write_Control_Stream_LE +#define TEMPLATE_BUFFER_OFFSET(Length) 0 +#define TEMPLATE_TRANSFER_BYTE(BufferPtr) Endpoint_Write_Byte(*((uint8_t*)BufferPtr++)) +#include "Template/Template_Endpoint_Control_W.c" + +#define TEMPLATE_FUNC_NAME Endpoint_Write_Control_PStream_LE +#define TEMPLATE_BUFFER_OFFSET(Length) 0 +#define TEMPLATE_TRANSFER_BYTE(BufferPtr) Endpoint_Write_Byte(pgm_read_byte((uint8_t*)BufferPtr++)) +#include "Template/Template_Endpoint_Control_W.c" + +#define TEMPLATE_FUNC_NAME Endpoint_Write_Control_EStream_LE +#define TEMPLATE_BUFFER_OFFSET(Length) 0 +#define TEMPLATE_TRANSFER_BYTE(BufferPtr) Endpoint_Write_Byte(eeprom_read_byte((uint8_t*)BufferPtr++)) +#include "Template/Template_Endpoint_Control_W.c" + +#define TEMPLATE_FUNC_NAME Endpoint_Write_Control_Stream_BE +#define TEMPLATE_BUFFER_OFFSET(Length) (Length - 1) +#define TEMPLATE_TRANSFER_BYTE(BufferPtr) Endpoint_Write_Byte(*((uint8_t*)BufferPtr--)) +#include "Template/Template_Endpoint_Control_W.c" + +#define TEMPLATE_FUNC_NAME Endpoint_Write_Control_PStream_BE +#define TEMPLATE_BUFFER_OFFSET(Length) (Length - 1) +#define TEMPLATE_TRANSFER_BYTE(BufferPtr) Endpoint_Write_Byte(pgm_read_byte((uint8_t*)BufferPtr--)) +#include "Template/Template_Endpoint_Control_W.c" + +#define TEMPLATE_FUNC_NAME Endpoint_Write_Control_EStream_BE +#define TEMPLATE_BUFFER_OFFSET(Length) (Length - 1) +#define TEMPLATE_TRANSFER_BYTE(BufferPtr) Endpoint_Write_Byte(eeprom_read_byte((uint8_t*)BufferPtr--)) +#include "Template/Template_Endpoint_Control_W.c" + +#define TEMPLATE_FUNC_NAME Endpoint_Read_Control_Stream_LE +#define TEMPLATE_BUFFER_OFFSET(Length) 0 +#define TEMPLATE_TRANSFER_BYTE(BufferPtr) *((uint8_t*)BufferPtr++) = Endpoint_Read_Byte() +#include "Template/Template_Endpoint_Control_R.c" + +#define TEMPLATE_FUNC_NAME Endpoint_Read_Control_EStream_LE +#define TEMPLATE_BUFFER_OFFSET(Length) 0 +#define TEMPLATE_TRANSFER_BYTE(BufferPtr) eeprom_update_byte((uint8_t*)BufferPtr++, Endpoint_Read_Byte()) +#include "Template/Template_Endpoint_Control_R.c" + +#define TEMPLATE_FUNC_NAME Endpoint_Read_Control_Stream_BE +#define TEMPLATE_BUFFER_OFFSET(Length) (Length - 1) +#define TEMPLATE_TRANSFER_BYTE(BufferPtr) *((uint8_t*)BufferPtr--) = Endpoint_Read_Byte() +#include "Template/Template_Endpoint_Control_R.c" + +#define TEMPLATE_FUNC_NAME Endpoint_Read_Control_EStream_BE +#define TEMPLATE_BUFFER_OFFSET(Length) (Length - 1) +#define TEMPLATE_TRANSFER_BYTE(BufferPtr) eeprom_update_byte((uint8_t*)BufferPtr--, Endpoint_Read_Byte()) +#include "Template/Template_Endpoint_Control_R.c" + +#endif diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/Endpoint.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/Endpoint.h new file mode 100644 index 0000000000..eb4b6161cb --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/Endpoint.h @@ -0,0 +1,1357 @@ +/* + 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 USB device endpoint management definitions. + * + * This file contains structures, function prototypes and macros related to the management of the device's + * data endpoints when the library is initialized in USB device mode. + * + * \note This file should not be included directly. It is automatically included as needed by the USB driver + * dispatch header located in LUFA/Drivers/USB/USB.h. + */ + +/** \ingroup Group_USB + * @defgroup Group_EndpointManagement Endpoint Management + * + * Functions, macros and enums related to endpoint management when in USB Device mode. This + * module contains the endpoint management macros, as well as endpoint interrupt and data + * send/receive functions for various data types. + * + * @{ + */ + +/** @defgroup Group_EndpointRW Endpoint Data Reading and Writing + * + * Functions, macros, variables, enums and types related to data reading and writing from and to endpoints. + */ + +/** \ingroup Group_EndpointRW + * @defgroup Group_EndpointPrimitiveRW Read/Write of Primitive Data Types + * + * Functions, macros, variables, enums and types related to data reading and writing of primitive data types + * from and to endpoints. + */ + +/** \ingroup Group_EndpointRW + * @defgroup Group_EndpointStreamRW Read/Write of Multi-Byte Streams + * + * Functions, macros, variables, enums and types related to data reading and writing of data streams from + * and to endpoints. + */ + +/** @defgroup Group_EndpointPacketManagement Endpoint Packet Management + * + * Functions, macros, variables, enums and types related to packet management of endpoints. + */ + +#ifndef __ENDPOINT_H__ +#define __ENDPOINT_H__ + + /* Includes: */ + #include + #include + #include + #include + + #include "../../../Common/Common.h" + #include "../HighLevel/USBTask.h" + #include "USBInterrupt.h" + + #if !defined(NO_STREAM_CALLBACKS) || defined(__DOXYGEN__) + #include "../HighLevel/StreamCallbacks.h" + #endif + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_USB_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/USB/USB.h instead. + #endif + + /* Public Interface - May be used in end-application: */ + /* Macros: */ + /** Endpoint data direction mask for \ref Endpoint_ConfigureEndpoint(). This indicates that the endpoint + * should be initialized in the OUT direction - i.e. data flows from host to device. + */ + #define ENDPOINT_DIR_OUT (0 << EPDIR) + + /** Endpoint data direction mask for \ref Endpoint_ConfigureEndpoint(). This indicates that the endpoint + * should be initialized in the IN direction - i.e. data flows from device to host. + */ + #define ENDPOINT_DIR_IN (1 << EPDIR) + + /** Mask for the bank mode selection for the \ref Endpoint_ConfigureEndpoint() macro. This indicates + * that the endpoint should have one single bank, which requires less USB FIFO memory but results + * in slower transfers as only one USB device (the AVR or the host) can access the endpoint's + * bank at the one time. + */ + #define ENDPOINT_BANK_SINGLE (0 << EPBK0) + + /** Mask for the bank mode selection for the \ref Endpoint_ConfigureEndpoint() macro. This indicates + * that the endpoint should have two banks, which requires more USB FIFO memory but results + * in faster transfers as one USB device (the AVR or the host) can access one bank while the other + * accesses the second bank. + */ + #define ENDPOINT_BANK_DOUBLE (1 << EPBK0) + + /** Endpoint address for the default control endpoint, which always resides in address 0. This is + * defined for convenience to give more readable code when used with the endpoint macros. + */ + #define ENDPOINT_CONTROLEP 0 + + #if (!defined(FIXED_CONTROL_ENDPOINT_SIZE) || defined(__DOXYGEN__)) + /** Default size of the default control endpoint's bank, until altered by the control endpoint bank size + * value in the device descriptor. Not available if the FIXED_CONTROL_ENDPOINT_SIZE token is defined. + */ + #define ENDPOINT_CONTROLEP_DEFAULT_SIZE 8 + #endif + + /** Endpoint number mask, for masking against endpoint addresses to retrieve the endpoint's + * numerical address in the device. + */ + #define ENDPOINT_EPNUM_MASK 0x07 + + /** Endpoint direction mask, for masking against endpoint addresses to retrieve the endpoint's + * direction for comparing with the ENDPOINT_DESCRIPTOR_DIR_* masks. + */ + #define ENDPOINT_EPDIR_MASK 0x80 + + /** Endpoint bank size mask, for masking against endpoint addresses to retrieve the endpoint's + * bank size in the device. + */ + #define ENDPOINT_EPSIZE_MASK 0x7F + + /** Maximum size in bytes of a given endpoint. + * + * \param[in] n Endpoint number, a value between 0 and (ENDPOINT_TOTAL_ENDPOINTS - 1) + */ + #define ENDPOINT_MAX_SIZE(n) _ENDPOINT_GET_MAXSIZE(n) + + /** Indicates if the given endpoint supports double banking. + * + * \param[in] n Endpoint number, a value between 0 and (ENDPOINT_TOTAL_ENDPOINTS - 1) + */ + #define ENDPOINT_DOUBLEBANK_SUPPORTED(n) _ENDPOINT_GET_DOUBLEBANK(n) + + #if !defined(CONTROL_ONLY_DEVICE) + #if defined(USB_SERIES_4_AVR) || defined(USB_SERIES_6_AVR) || defined(USB_SERIES_7_AVR) || defined(__DOXYGEN__) + /** Total number of endpoints (including the default control endpoint at address 0) which may + * be used in the device. Different USB AVR models support different amounts of endpoints, + * this value reflects the maximum number of endpoints for the currently selected AVR model. + */ + #define ENDPOINT_TOTAL_ENDPOINTS 7 + #else + #define ENDPOINT_TOTAL_ENDPOINTS 5 + #endif + #else + #define ENDPOINT_TOTAL_ENDPOINTS 1 + #endif + + /* Enums: */ + /** Enum for the possible error return codes of the \ref Endpoint_WaitUntilReady() function. + * + * \ingroup Group_EndpointRW + */ + enum Endpoint_WaitUntilReady_ErrorCodes_t + { + ENDPOINT_READYWAIT_NoError = 0, /**< Endpoint is ready for next packet, no error. */ + ENDPOINT_READYWAIT_EndpointStalled = 1, /**< The endpoint was stalled during the stream + * transfer by the host or device. + */ + ENDPOINT_READYWAIT_DeviceDisconnected = 2, /**< Device was disconnected from the host while + * waiting for the endpoint to become ready. + */ + ENDPOINT_READYWAIT_BusSuspended = 3, /**< The USB bus has been suspended by the host and + * no USB endpoint traffic can occur until the bus + * has resumed. + */ + ENDPOINT_READYWAIT_Timeout = 4, /**< The host failed to accept or send the next packet + * within the software timeout period set by the + * \ref USB_STREAM_TIMEOUT_MS macro. + */ + }; + + /** Enum for the possible error return codes of the Endpoint_*_Stream_* functions. + * + * \ingroup Group_EndpointStreamRW + */ + enum Endpoint_Stream_RW_ErrorCodes_t + { + ENDPOINT_RWSTREAM_NoError = 0, /**< Command completed successfully, no error. */ + ENDPOINT_RWSTREAM_EndpointStalled = 1, /**< The endpoint was stalled during the stream + * transfer by the host or device. + */ + ENDPOINT_RWSTREAM_DeviceDisconnected = 2, /**< Device was disconnected from the host during + * the transfer. + */ + ENDPOINT_RWSTREAM_BusSuspended = 3, /**< The USB bus has been suspended by the host and + * no USB endpoint traffic can occur until the bus + * has resumed. + */ + ENDPOINT_RWSTREAM_Timeout = 4, /**< The host failed to accept or send the next packet + * within the software timeout period set by the + * \ref USB_STREAM_TIMEOUT_MS macro. + */ + ENDPOINT_RWSTREAM_CallbackAborted = 5, /**< Indicates that the stream's callback function + * aborted the transfer early. + */ + }; + + /** Enum for the possible error return codes of the Endpoint_*_Control_Stream_* functions.. + * + * \ingroup Group_EndpointStreamRW + */ + enum Endpoint_ControlStream_RW_ErrorCodes_t + { + ENDPOINT_RWCSTREAM_NoError = 0, /**< Command completed successfully, no error. */ + ENDPOINT_RWCSTREAM_HostAborted = 1, /**< The aborted the transfer prematurely. */ + ENDPOINT_RWCSTREAM_DeviceDisconnected = 2, /**< Device was disconnected from the host during + * the transfer. + */ + ENDPOINT_RWCSTREAM_BusSuspended = 3, /**< The USB bus has been suspended by the host and + * no USB endpoint traffic can occur until the bus + * has resumed. + */ + }; + + /* Inline Functions: */ + /** Indicates the number of bytes currently stored in the current endpoint's selected bank. + * + * \note The return width of this function may differ, depending on the maximum endpoint bank size + * of the selected AVR model. + * + * \ingroup Group_EndpointRW + * + * \return Total number of bytes in the currently selected Endpoint's FIFO buffer. + */ + static inline uint16_t Endpoint_BytesInEndpoint(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline uint16_t Endpoint_BytesInEndpoint(void) + { + #if defined(USB_SERIES_6_AVR) || defined(USB_SERIES_7_AVR) + return UEBCX; + #elif defined(USB_SERIES_4_AVR) + return (((uint16_t)UEBCHX << 8) | UEBCLX); + #elif defined(USB_SERIES_2_AVR) + return UEBCLX; + #endif + } + + /** Get the endpoint address of the currently selected endpoint. This is typically used to save + * the currently selected endpoint number so that it can be restored after another endpoint has + * been manipulated. + * + * \return Index of the currently selected endpoint. + */ + static inline uint8_t Endpoint_GetCurrentEndpoint(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline uint8_t Endpoint_GetCurrentEndpoint(void) + { + #if !defined(CONTROL_ONLY_DEVICE) + return (UENUM & ENDPOINT_EPNUM_MASK); + #else + return ENDPOINT_CONTROLEP; + #endif + } + + /** Selects the given endpoint number. If the address from the device descriptors is used, the + * value should be masked with the \ref ENDPOINT_EPNUM_MASK constant to extract only the endpoint + * number (and discarding the endpoint direction bit). + * + * Any endpoint operations which do not require the endpoint number to be indicated will operate on + * the currently selected endpoint. + * + * \param[in] EndpointNumber Endpoint number to select. + */ + static inline void Endpoint_SelectEndpoint(const uint8_t EndpointNumber) ATTR_ALWAYS_INLINE; + static inline void Endpoint_SelectEndpoint(const uint8_t EndpointNumber) + { + #if !defined(CONTROL_ONLY_DEVICE) + UENUM = EndpointNumber; + #endif + } + + /** Resets the endpoint bank FIFO. This clears all the endpoint banks and resets the USB controller's + * In and Out pointers to the bank's contents. + * + * \param[in] EndpointNumber Endpoint number whose FIFO buffers are to be reset. + */ + static inline void Endpoint_ResetFIFO(const uint8_t EndpointNumber) ATTR_ALWAYS_INLINE; + static inline void Endpoint_ResetFIFO(const uint8_t EndpointNumber) + { + UERST = (1 << EndpointNumber); + UERST = 0; + } + + /** Enables the currently selected endpoint so that data can be sent and received through it to + * and from a host. + * + * \note Endpoints must first be configured properly via \ref Endpoint_ConfigureEndpoint(). + */ + static inline void Endpoint_EnableEndpoint(void) ATTR_ALWAYS_INLINE; + static inline void Endpoint_EnableEndpoint(void) + { + UECONX |= (1 << EPEN); + } + + /** Disables the currently selected endpoint so that data cannot be sent and received through it + * to and from a host. + */ + static inline void Endpoint_DisableEndpoint(void) ATTR_ALWAYS_INLINE; + static inline void Endpoint_DisableEndpoint(void) + { + UECONX &= ~(1 << EPEN); + } + + /** Determines if the currently selected endpoint is enabled, but not necessarily configured. + * + * \return Boolean True if the currently selected endpoint is enabled, false otherwise. + */ + static inline bool Endpoint_IsEnabled(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline bool Endpoint_IsEnabled(void) + { + return ((UECONX & (1 << EPEN)) ? true : false); + } + + /** Determines if the currently selected endpoint may be read from (if data is waiting in the endpoint + * bank and the endpoint is an OUT direction, or if the bank is not yet full if the endpoint is an IN + * direction). This function will return false if an error has occurred in the endpoint, if the endpoint + * is an OUT direction and no packet (or an empty packet) has been received, or if the endpoint is an IN + * direction and the endpoint bank is full. + * + * \ingroup Group_EndpointPacketManagement + * + * \return Boolean true if the currently selected endpoint may be read from or written to, depending on its direction. + */ + static inline bool Endpoint_IsReadWriteAllowed(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline bool Endpoint_IsReadWriteAllowed(void) + { + return ((UEINTX & (1 << RWAL)) ? true : false); + } + + /** Determines if the currently selected endpoint is configured. + * + * \return Boolean true if the currently selected endpoint has been configured, false otherwise. + */ + static inline bool Endpoint_IsConfigured(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline bool Endpoint_IsConfigured(void) + { + return ((UESTA0X & (1 << CFGOK)) ? true : false); + } + + /** Returns a mask indicating which INTERRUPT type endpoints have interrupted - i.e. their + * interrupt duration has elapsed. Which endpoints have interrupted can be determined by + * masking the return value against (1 << {Endpoint Number}). + * + * \return Mask whose bits indicate which endpoints have interrupted. + */ + static inline uint8_t Endpoint_GetEndpointInterrupts(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline uint8_t Endpoint_GetEndpointInterrupts(void) + { + return UEINT; + } + + /** Determines if the specified endpoint number has interrupted (valid only for INTERRUPT type + * endpoints). + * + * \param[in] EndpointNumber Index of the endpoint whose interrupt flag should be tested. + * + * \return Boolean true if the specified endpoint has interrupted, false otherwise. + */ + static inline bool Endpoint_HasEndpointInterrupted(const uint8_t EndpointNumber) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline bool Endpoint_HasEndpointInterrupted(const uint8_t EndpointNumber) + { + return ((UEINT & (1 << EndpointNumber)) ? true : false); + } + + /** Determines if the selected IN endpoint is ready for a new packet. + * + * \ingroup Group_EndpointPacketManagement + * + * \return Boolean true if the current endpoint is ready for an IN packet, false otherwise. + */ + static inline bool Endpoint_IsINReady(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline bool Endpoint_IsINReady(void) + { + return ((UEINTX & (1 << TXINI)) ? true : false); + } + + /** Determines if the selected OUT endpoint has received new packet. + * + * \ingroup Group_EndpointPacketManagement + * + * \return Boolean true if current endpoint is has received an OUT packet, false otherwise. + */ + static inline bool Endpoint_IsOUTReceived(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline bool Endpoint_IsOUTReceived(void) + { + return ((UEINTX & (1 << RXOUTI)) ? true : false); + } + + /** Determines if the current CONTROL type endpoint has received a SETUP packet. + * + * \ingroup Group_EndpointPacketManagement + * + * \return Boolean true if the selected endpoint has received a SETUP packet, false otherwise. + */ + static inline bool Endpoint_IsSETUPReceived(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline bool Endpoint_IsSETUPReceived(void) + { + return ((UEINTX & (1 << RXSTPI)) ? true : false); + } + + /** Clears a received SETUP packet on the currently selected CONTROL type endpoint, freeing up the + * endpoint for the next packet. + * + * \ingroup Group_EndpointPacketManagement + * + * \note This is not applicable for non CONTROL type endpoints. + */ + static inline void Endpoint_ClearSETUP(void) ATTR_ALWAYS_INLINE; + static inline void Endpoint_ClearSETUP(void) + { + UEINTX &= ~(1 << RXSTPI); + } + + /** Sends an IN packet to the host on the currently selected endpoint, freeing up the endpoint for the + * next packet and switching to the alternative endpoint bank if double banked. + * + * \ingroup Group_EndpointPacketManagement + */ + static inline void Endpoint_ClearIN(void) ATTR_ALWAYS_INLINE; + static inline void Endpoint_ClearIN(void) + { + #if !defined(CONTROL_ONLY_DEVICE) + UEINTX &= ~((1 << TXINI) | (1 << FIFOCON)); + #else + UEINTX &= ~(1 << TXINI); + #endif + } + + /** Acknowledges an OUT packet to the host on the currently selected endpoint, freeing up the endpoint + * for the next packet and switching to the alternative endpoint bank if double banked. + * + * \ingroup Group_EndpointPacketManagement + */ + static inline void Endpoint_ClearOUT(void) ATTR_ALWAYS_INLINE; + static inline void Endpoint_ClearOUT(void) + { + #if !defined(CONTROL_ONLY_DEVICE) + UEINTX &= ~((1 << RXOUTI) | (1 << FIFOCON)); + #else + UEINTX &= ~(1 << RXOUTI); + #endif + } + + /** Stalls the current endpoint, indicating to the host that a logical problem occurred with the + * indicated endpoint and that the current transfer sequence should be aborted. This provides a + * way for devices to indicate invalid commands to the host so that the current transfer can be + * aborted and the host can begin its own recovery sequence. + * + * The currently selected endpoint remains stalled until either the \ref Endpoint_ClearStall() macro + * is called, or the host issues a CLEAR FEATURE request to the device for the currently selected + * endpoint. + * + * \ingroup Group_EndpointPacketManagement + */ + static inline void Endpoint_StallTransaction(void) ATTR_ALWAYS_INLINE; + static inline void Endpoint_StallTransaction(void) + { + UECONX |= (1 << STALLRQ); + } + + /** Clears the STALL condition on the currently selected endpoint. + * + * \ingroup Group_EndpointPacketManagement + */ + static inline void Endpoint_ClearStall(void) ATTR_ALWAYS_INLINE; + static inline void Endpoint_ClearStall(void) + { + UECONX |= (1 << STALLRQC); + } + + /** Determines if the currently selected endpoint is stalled, false otherwise. + * + * \ingroup Group_EndpointPacketManagement + * + * \return Boolean true if the currently selected endpoint is stalled, false otherwise. + */ + static inline bool Endpoint_IsStalled(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline bool Endpoint_IsStalled(void) + { + return ((UECONX & (1 << STALLRQ)) ? true : false); + } + + /** Resets the data toggle of the currently selected endpoint. */ + static inline void Endpoint_ResetDataToggle(void) ATTR_ALWAYS_INLINE; + static inline void Endpoint_ResetDataToggle(void) + { + UECONX |= (1 << RSTDT); + } + + /** Determines the currently selected endpoint's direction. + * + * \return The currently selected endpoint's direction, as a ENDPOINT_DIR_* mask. + */ + static inline uint8_t Endpoint_GetEndpointDirection(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline uint8_t Endpoint_GetEndpointDirection(void) + { + return (UECFG0X & ENDPOINT_DIR_IN); + } + + /** Sets the direction of the currently selected endpoint. + * + * \param[in] DirectionMask New endpoint direction, as a ENDPOINT_DIR_* mask. + */ + static inline void Endpoint_SetEndpointDirection(const uint8_t DirectionMask) ATTR_ALWAYS_INLINE; + static inline void Endpoint_SetEndpointDirection(const uint8_t DirectionMask) + { + UECFG0X = ((UECFG0X & ~ENDPOINT_DIR_IN) | DirectionMask); + } + + /** Reads one byte from the currently selected endpoint's bank, for OUT direction endpoints. + * + * \ingroup Group_EndpointPrimitiveRW + * + * \return Next byte in the currently selected endpoint's FIFO buffer. + */ + static inline uint8_t Endpoint_Read_Byte(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline uint8_t Endpoint_Read_Byte(void) + { + return UEDATX; + } + + /** Writes one byte from the currently selected endpoint's bank, for IN direction endpoints. + * + * \ingroup Group_EndpointPrimitiveRW + * + * \param[in] Byte Next byte to write into the the currently selected endpoint's FIFO buffer. + */ + static inline void Endpoint_Write_Byte(const uint8_t Byte) ATTR_ALWAYS_INLINE; + static inline void Endpoint_Write_Byte(const uint8_t Byte) + { + UEDATX = Byte; + } + + /** Discards one byte from the currently selected endpoint's bank, for OUT direction endpoints. + * + * \ingroup Group_EndpointPrimitiveRW + */ + static inline void Endpoint_Discard_Byte(void) ATTR_ALWAYS_INLINE; + static inline void Endpoint_Discard_Byte(void) + { + uint8_t Dummy; + + Dummy = UEDATX; + } + + /** Reads two bytes from the currently selected endpoint's bank in little endian format, for OUT + * direction endpoints. + * + * \ingroup Group_EndpointPrimitiveRW + * + * \return Next word in the currently selected endpoint's FIFO buffer. + */ + static inline uint16_t Endpoint_Read_Word_LE(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline uint16_t Endpoint_Read_Word_LE(void) + { + union + { + uint16_t Word; + uint8_t Bytes[2]; + } Data; + + Data.Bytes[0] = UEDATX; + Data.Bytes[1] = UEDATX; + + return Data.Word; + } + + /** Reads two bytes from the currently selected endpoint's bank in big endian format, for OUT + * direction endpoints. + * + * \ingroup Group_EndpointPrimitiveRW + * + * \return Next word in the currently selected endpoint's FIFO buffer. + */ + static inline uint16_t Endpoint_Read_Word_BE(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline uint16_t Endpoint_Read_Word_BE(void) + { + union + { + uint16_t Word; + uint8_t Bytes[2]; + } Data; + + Data.Bytes[1] = UEDATX; + Data.Bytes[0] = UEDATX; + + return Data.Word; + } + + /** Writes two bytes to the currently selected endpoint's bank in little endian format, for IN + * direction endpoints. + * + * \ingroup Group_EndpointPrimitiveRW + * + * \param[in] Word Next word to write to the currently selected endpoint's FIFO buffer. + */ + static inline void Endpoint_Write_Word_LE(const uint16_t Word) ATTR_ALWAYS_INLINE; + static inline void Endpoint_Write_Word_LE(const uint16_t Word) + { + UEDATX = (Word & 0xFF); + UEDATX = (Word >> 8); + } + + /** Writes two bytes to the currently selected endpoint's bank in big endian format, for IN + * direction endpoints. + * + * \ingroup Group_EndpointPrimitiveRW + * + * \param[in] Word Next word to write to the currently selected endpoint's FIFO buffer. + */ + static inline void Endpoint_Write_Word_BE(const uint16_t Word) ATTR_ALWAYS_INLINE; + static inline void Endpoint_Write_Word_BE(const uint16_t Word) + { + UEDATX = (Word >> 8); + UEDATX = (Word & 0xFF); + } + + /** Discards two bytes from the currently selected endpoint's bank, for OUT direction endpoints. + * + * \ingroup Group_EndpointPrimitiveRW + */ + static inline void Endpoint_Discard_Word(void) ATTR_ALWAYS_INLINE; + static inline void Endpoint_Discard_Word(void) + { + uint8_t Dummy; + + Dummy = UEDATX; + Dummy = UEDATX; + } + + /** Reads four bytes from the currently selected endpoint's bank in little endian format, for OUT + * direction endpoints. + * + * \ingroup Group_EndpointPrimitiveRW + * + * \return Next double word in the currently selected endpoint's FIFO buffer. + */ + static inline uint32_t Endpoint_Read_DWord_LE(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline uint32_t Endpoint_Read_DWord_LE(void) + { + union + { + uint32_t DWord; + uint8_t Bytes[4]; + } Data; + + Data.Bytes[0] = UEDATX; + Data.Bytes[1] = UEDATX; + Data.Bytes[2] = UEDATX; + Data.Bytes[3] = UEDATX; + + return Data.DWord; + } + + /** Reads four bytes from the currently selected endpoint's bank in big endian format, for OUT + * direction endpoints. + * + * \ingroup Group_EndpointPrimitiveRW + * + * \return Next double word in the currently selected endpoint's FIFO buffer. + */ + static inline uint32_t Endpoint_Read_DWord_BE(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline uint32_t Endpoint_Read_DWord_BE(void) + { + union + { + uint32_t DWord; + uint8_t Bytes[4]; + } Data; + + Data.Bytes[3] = UEDATX; + Data.Bytes[2] = UEDATX; + Data.Bytes[1] = UEDATX; + Data.Bytes[0] = UEDATX; + + return Data.DWord; + } + + /** Writes four bytes to the currently selected endpoint's bank in little endian format, for IN + * direction endpoints. + * + * \ingroup Group_EndpointPrimitiveRW + * + * \param[in] DWord Next double word to write to the currently selected endpoint's FIFO buffer. + */ + static inline void Endpoint_Write_DWord_LE(const uint32_t DWord) ATTR_ALWAYS_INLINE; + static inline void Endpoint_Write_DWord_LE(const uint32_t DWord) + { + UEDATX = (DWord & 0xFF); + UEDATX = (DWord >> 8); + UEDATX = (DWord >> 16); + UEDATX = (DWord >> 24); + } + + /** Writes four bytes to the currently selected endpoint's bank in big endian format, for IN + * direction endpoints. + * + * \ingroup Group_EndpointPrimitiveRW + * + * \param[in] DWord Next double word to write to the currently selected endpoint's FIFO buffer. + */ + static inline void Endpoint_Write_DWord_BE(const uint32_t DWord) ATTR_ALWAYS_INLINE; + static inline void Endpoint_Write_DWord_BE(const uint32_t DWord) + { + UEDATX = (DWord >> 24); + UEDATX = (DWord >> 16); + UEDATX = (DWord >> 8); + UEDATX = (DWord & 0xFF); + } + + /** Discards four bytes from the currently selected endpoint's bank, for OUT direction endpoints. + * + * \ingroup Group_EndpointPrimitiveRW + */ + static inline void Endpoint_Discard_DWord(void) ATTR_ALWAYS_INLINE; + static inline void Endpoint_Discard_DWord(void) + { + uint8_t Dummy; + + Dummy = UEDATX; + Dummy = UEDATX; + Dummy = UEDATX; + Dummy = UEDATX; + } + + /* External Variables: */ + /** Global indicating the maximum packet size of the default control endpoint located at address + * 0 in the device. This value is set to the value indicated in the device descriptor in the user + * project once the USB interface is initialized into device mode. + * + * If space is an issue, it is possible to fix this to a static value by defining the control + * endpoint size in the FIXED_CONTROL_ENDPOINT_SIZE token passed to the compiler in the makefile + * via the -D switch. When a fixed control endpoint size is used, the size is no longer dynamically + * read from the descriptors at runtime and instead fixed to the given value. When used, it is + * important that the descriptor control endpoint size value matches the size given as the + * FIXED_CONTROL_ENDPOINT_SIZE token - it is recommended that the FIXED_CONTROL_ENDPOINT_SIZE token + * be used in the descriptors to ensure this. + * + * \note This variable should be treated as read-only in the user application, and never manually + * changed in value. + */ + #if (!defined(FIXED_CONTROL_ENDPOINT_SIZE) || defined(__DOXYGEN__)) + extern uint8_t USB_ControlEndpointSize; + #else + #define USB_ControlEndpointSize FIXED_CONTROL_ENDPOINT_SIZE + #endif + + /* Function Prototypes: */ + #if !defined(NO_STREAM_CALLBACKS) || defined(__DOXYGEN__) + #define __CALLBACK_PARAM , StreamCallbackPtr_t Callback + #else + #define __CALLBACK_PARAM + #endif + + /** Configures the specified endpoint number with the given endpoint type, direction, bank size + * and banking mode. Endpoints should be allocated in ascending order by their address in the + * device (i.e. endpoint 1 should be configured before endpoint 2 and so on) to prevent fragmentation + * of the USB FIFO memory. + * + * The endpoint type may be one of the EP_TYPE_* macros listed in LowLevel.h and the direction + * may be either \ref ENDPOINT_DIR_OUT or \ref ENDPOINT_DIR_IN. + * + * The bank size must indicate the maximum packet size that the endpoint can handle. Different + * endpoint numbers can handle different maximum packet sizes - refer to the chosen USB AVR's + * datasheet to determine the maximum bank size for each endpoint. + * + * The banking mode may be either \ref ENDPOINT_BANK_SINGLE or \ref ENDPOINT_BANK_DOUBLE. + * + * \note The default control endpoint should not be manually configured by the user application, as + * it is automatically configured by the library internally. + * \n\n + * + * \note This routine will select the specified endpoint, and the endpoint will remain selected + * once the routine completes regardless of if the endpoint configuration succeeds. + * + * \return Boolean true if the configuration succeeded, false otherwise. + */ + bool Endpoint_ConfigureEndpoint(const uint8_t Number, + const uint8_t Type, + const uint8_t Direction, + const uint16_t Size, + const uint8_t Banks); + + /** Spin-loops until the currently selected non-control endpoint is ready for the next packet of data + * to be read or written to it. + * + * \note This routine should not be called on CONTROL type endpoints. + * + * \ingroup Group_EndpointRW + * + * \return A value from the \ref Endpoint_WaitUntilReady_ErrorCodes_t enum. + */ + uint8_t Endpoint_WaitUntilReady(void); + + /** Completes the status stage of a control transfer on a CONTROL type endpoint automatically, + * with respect to the data direction. This is a convenience function which can be used to + * simplify user control request handling. + */ + void Endpoint_ClearStatusStage(void); + + /** Reads and discards the given number of bytes from the endpoint from the given buffer, + * discarding fully read packets from the host as needed. The last packet is not automatically + * discarded once the remaining bytes has been read; the user is responsible for manually + * discarding the last packet from the host via the \ref Endpoint_ClearOUT() macro. Between + * each USB packet, the given stream callback function is executed repeatedly until the next + * packet is ready, allowing for early aborts of stream transfers. + * + * The callback routine should be created according to the information in \ref Group_StreamCallbacks. + * If the token NO_STREAM_CALLBACKS is passed via the -D option to the compiler, stream callbacks are + * disabled and this function has the Callback parameter omitted. + * + * \note This routine should not be used on CONTROL type endpoints. + * + * \ingroup Group_EndpointStreamRW + * + * \param[in] Length Number of bytes to send via the currently selected endpoint. + * \param[in] Callback Name of a callback routine to call between successive USB packet transfers, NULL if no callback. + * + * \return A value from the \ref Endpoint_Stream_RW_ErrorCodes_t enum. + */ + uint8_t Endpoint_Discard_Stream(uint16_t Length + __CALLBACK_PARAM); + + /** Writes the given number of bytes to the endpoint from the given buffer in little endian, + * sending full packets to the host as needed. The last packet filled is not automatically sent; + * the user is responsible for manually sending the last written packet to the host via the + * \ref Endpoint_ClearIN() macro. Between each USB packet, the given stream callback function + * is executed repeatedly until the endpoint is ready to accept the next packet, allowing for early + * aborts of stream transfers. + * + * The callback routine should be created according to the information in \ref Group_StreamCallbacks. + * If the token NO_STREAM_CALLBACKS is passed via the -D option to the compiler, stream callbacks are + * disabled and this function has the Callback parameter omitted. + * + * \note This routine should not be used on CONTROL type endpoints. + * + * \ingroup Group_EndpointStreamRW + * + * \param[in] Buffer Pointer to the source data buffer to read from. + * \param[in] Length Number of bytes to read for the currently selected endpoint into the buffer. + * \param[in] Callback Name of a callback routine to call between successive USB packet transfers, NULL if no callback. + * + * \return A value from the \ref Endpoint_Stream_RW_ErrorCodes_t enum. + */ + uint8_t Endpoint_Write_Stream_LE(const void* Buffer, + uint16_t Length + __CALLBACK_PARAM) ATTR_NON_NULL_PTR_ARG(1); + + /** EEPROM buffer source version of \ref Endpoint_Write_Stream_LE(). + * + * \ingroup Group_EndpointStreamRW + * + * \param[in] Buffer Pointer to the source data buffer to read from. + * \param[in] Length Number of bytes to read for the currently selected endpoint into the buffer. + * \param[in] Callback Name of a callback routine to call between successive USB packet transfers, NULL if no callback. + * + * \return A value from the \ref Endpoint_Stream_RW_ErrorCodes_t enum. + */ + uint8_t Endpoint_Write_EStream_LE(const void* Buffer, + uint16_t Length + __CALLBACK_PARAM) ATTR_NON_NULL_PTR_ARG(1); + + /** FLASH buffer source version of \ref Endpoint_Write_Stream_LE(). + * + * \pre The FLASH data must be located in the first 64KB of FLASH for this function to work correctly. + * + * \ingroup Group_EndpointStreamRW + * + * \param[in] Buffer Pointer to the source data buffer to read from. + * \param[in] Length Number of bytes to read for the currently selected endpoint into the buffer. + * \param[in] Callback Name of a callback routine to call between successive USB packet transfers, NULL if no callback. + * + * \return A value from the \ref Endpoint_Stream_RW_ErrorCodes_t enum. + */ + uint8_t Endpoint_Write_PStream_LE(const void* Buffer, + uint16_t Length + __CALLBACK_PARAM) ATTR_NON_NULL_PTR_ARG(1); + + /** Writes the given number of bytes to the endpoint from the given buffer in big endian, + * sending full packets to the host as needed. The last packet filled is not automatically sent; + * the user is responsible for manually sending the last written packet to the host via the + * \ref Endpoint_ClearIN() macro. Between each USB packet, the given stream callback function + * is executed repeatedly until the endpoint is ready to accept the next packet, allowing for early + * aborts of stream transfers. + * + * The callback routine should be created according to the information in \ref Group_StreamCallbacks. + * If the token NO_STREAM_CALLBACKS is passed via the -D option to the compiler, stream callbacks are + * disabled and this function has the Callback parameter omitted. + * + * \note This routine should not be used on CONTROL type endpoints. + * + * \ingroup Group_EndpointStreamRW + * + * \param[in] Buffer Pointer to the source data buffer to read from. + * \param[in] Length Number of bytes to read for the currently selected endpoint into the buffer. + * \param[in] Callback Name of a callback routine to call between successive USB packet transfers, NULL if no callback. + * + * \return A value from the \ref Endpoint_Stream_RW_ErrorCodes_t enum. + */ + uint8_t Endpoint_Write_Stream_BE(const void* Buffer, + uint16_t Length + __CALLBACK_PARAM) ATTR_NON_NULL_PTR_ARG(1); + + /** EEPROM buffer source version of \ref Endpoint_Write_Stream_BE(). + * + * \ingroup Group_EndpointStreamRW + * + * \param[in] Buffer Pointer to the source data buffer to read from. + * \param[in] Length Number of bytes to read for the currently selected endpoint into the buffer. + * \param[in] Callback Name of a callback routine to call between successive USB packet transfers, NULL if no callback. + * + * \return A value from the \ref Endpoint_Stream_RW_ErrorCodes_t enum. + */ + uint8_t Endpoint_Write_EStream_BE(const void* Buffer, + uint16_t Length + __CALLBACK_PARAM) ATTR_NON_NULL_PTR_ARG(1); + + /** FLASH buffer source version of \ref Endpoint_Write_Stream_BE(). + * + * \pre The FLASH data must be located in the first 64KB of FLASH for this function to work correctly. + * + * \ingroup Group_EndpointStreamRW + * + * \param[in] Buffer Pointer to the source data buffer to read from. + * \param[in] Length Number of bytes to read for the currently selected endpoint into the buffer. + * \param[in] Callback Name of a callback routine to call between successive USB packet transfers, NULL if no callback. + * + * \return A value from the \ref Endpoint_Stream_RW_ErrorCodes_t enum. + */ + uint8_t Endpoint_Write_PStream_BE(const void* Buffer, + uint16_t Length + __CALLBACK_PARAM) ATTR_NON_NULL_PTR_ARG(1); + + /** Reads the given number of bytes from the endpoint from the given buffer in little endian, + * discarding fully read packets from the host as needed. The last packet is not automatically + * discarded once the remaining bytes has been read; the user is responsible for manually + * discarding the last packet from the host via the \ref Endpoint_ClearOUT() macro. Between + * each USB packet, the given stream callback function is executed repeatedly until the endpoint + * is ready to accept the next packet, allowing for early aborts of stream transfers. + * + * The callback routine should be created according to the information in \ref Group_StreamCallbacks. + * If the token NO_STREAM_CALLBACKS is passed via the -D option to the compiler, stream callbacks are + * disabled and this function has the Callback parameter omitted. + * + * \note This routine should not be used on CONTROL type endpoints. + * + * \ingroup Group_EndpointStreamRW + * + * \param[out] Buffer Pointer to the destination data buffer to write to. + * \param[in] Length Number of bytes to send via the currently selected endpoint. + * \param[in] Callback Name of a callback routine to call between successive USB packet transfers, NULL if no callback. + * + * \return A value from the \ref Endpoint_Stream_RW_ErrorCodes_t enum. + */ + uint8_t Endpoint_Read_Stream_LE(void* Buffer, + uint16_t Length + __CALLBACK_PARAM) ATTR_NON_NULL_PTR_ARG(1); + + /** EEPROM buffer source version of \ref Endpoint_Read_Stream_LE(). + * + * \ingroup Group_EndpointStreamRW + * + * \param[out] Buffer Pointer to the destination data buffer to write to, located in EEPROM memory space. + * \param[in] Length Number of bytes to send via the currently selected endpoint. + * \param[in] Callback Name of a callback routine to call between successive USB packet transfers, NULL if no callback. + * + * \return A value from the \ref Endpoint_Stream_RW_ErrorCodes_t enum. + */ + uint8_t Endpoint_Read_EStream_LE(void* Buffer, + uint16_t Length + __CALLBACK_PARAM) ATTR_NON_NULL_PTR_ARG(1); + + /** Reads the given number of bytes from the endpoint from the given buffer in big endian, + * discarding fully read packets from the host as needed. The last packet is not automatically + * discarded once the remaining bytes has been read; the user is responsible for manually + * discarding the last packet from the host via the \ref Endpoint_ClearOUT() macro. Between + * each USB packet, the given stream callback function is executed repeatedly until the endpoint + * is ready to accept the next packet, allowing for early aborts of stream transfers. + * + * The callback routine should be created according to the information in \ref Group_StreamCallbacks. + * If the token NO_STREAM_CALLBACKS is passed via the -D option to the compiler, stream callbacks are + * disabled and this function has the Callback parameter omitted. + * + * \note This routine should not be used on CONTROL type endpoints. + * + * \ingroup Group_EndpointStreamRW + * + * \param[out] Buffer Pointer to the destination data buffer to write to. + * \param[in] Length Number of bytes to send via the currently selected endpoint. + * \param[in] Callback Name of a callback routine to call between successive USB packet transfers, NULL if no callback. + * + * \return A value from the \ref Endpoint_Stream_RW_ErrorCodes_t enum. + */ + uint8_t Endpoint_Read_Stream_BE(void* Buffer, + uint16_t Length + __CALLBACK_PARAM) ATTR_NON_NULL_PTR_ARG(1); + + /** EEPROM buffer source version of \ref Endpoint_Read_Stream_BE(). + * + * \ingroup Group_EndpointStreamRW + * + * \param[out] Buffer Pointer to the destination data buffer to write to, located in EEPROM memory space. + * \param[in] Length Number of bytes to send via the currently selected endpoint. + * \param[in] Callback Name of a callback routine to call between successive USB packet transfers, NULL if no callback. + * + * \return A value from the \ref Endpoint_Stream_RW_ErrorCodes_t enum. + */ + uint8_t Endpoint_Read_EStream_BE(void* Buffer, + uint16_t Length + __CALLBACK_PARAM) ATTR_NON_NULL_PTR_ARG(1); + + /** Writes the given number of bytes to the CONTROL type endpoint from the given buffer in little endian, + * sending full packets to the host as needed. The host OUT acknowledgement is not automatically cleared + * in both failure and success states; the user is responsible for manually clearing the setup OUT to + * finalize the transfer via the \ref Endpoint_ClearOUT() macro. + * + * \note This function automatically clears the control transfer's status stage. Do not manually attempt + * to clear the status stage when using this routine in a control transaction. + * \n\n + * + * \note This routine should only be used on CONTROL type endpoints. + * + * \warning Unlike the standard stream read/write commands, the control stream commands cannot be chained + * together; i.e. the entire stream data must be read or written at the one time. + * + * \ingroup Group_EndpointStreamRW + * + * \param[in] Buffer Pointer to the source data buffer to read from. + * \param[in] Length Number of bytes to read for the currently selected endpoint into the buffer. + * + * \return A value from the \ref Endpoint_ControlStream_RW_ErrorCodes_t enum. + */ + uint8_t Endpoint_Write_Control_Stream_LE(const void* Buffer, + uint16_t Length) ATTR_NON_NULL_PTR_ARG(1); + + /** EEPROM buffer source version of Endpoint_Write_Control_Stream_LE. + * + * \note This function automatically clears the control transfer's status stage. Do not manually attempt + * to clear the status stage when using this routine in a control transaction. + * \n\n + * + * \note This routine should only be used on CONTROL type endpoints. + * + * \warning Unlike the standard stream read/write commands, the control stream commands cannot be chained + * together; i.e. the entire stream data must be read or written at the one time. + * + * \ingroup Group_EndpointStreamRW + * + * \param[in] Buffer Pointer to the source data buffer to read from. + * \param[in] Length Number of bytes to read for the currently selected endpoint into the buffer. + * + * \return A value from the \ref Endpoint_ControlStream_RW_ErrorCodes_t enum. + */ + uint8_t Endpoint_Write_Control_EStream_LE(const void* Buffer, + uint16_t Length) ATTR_NON_NULL_PTR_ARG(1); + + /** FLASH buffer source version of \ref Endpoint_Write_Control_Stream_LE(). + * + * \pre The FLASH data must be located in the first 64KB of FLASH for this function to work correctly. + * + * \note This function automatically clears the control transfer's status stage. Do not manually attempt + * to clear the status stage when using this routine in a control transaction. + * \n\n + * + * \note This routine should only be used on CONTROL type endpoints. + * + * \warning Unlike the standard stream read/write commands, the control stream commands cannot be chained + * together; i.e. the entire stream data must be read or written at the one time. + * + * \ingroup Group_EndpointStreamRW + * + * \param[in] Buffer Pointer to the source data buffer to read from. + * \param[in] Length Number of bytes to read for the currently selected endpoint into the buffer. + * + * \return A value from the \ref Endpoint_ControlStream_RW_ErrorCodes_t enum. + */ + uint8_t Endpoint_Write_Control_PStream_LE(const void* Buffer, + uint16_t Length) ATTR_NON_NULL_PTR_ARG(1); + + /** Writes the given number of bytes to the CONTROL type endpoint from the given buffer in big endian, + * sending full packets to the host as needed. The host OUT acknowledgement is not automatically cleared + * in both failure and success states; the user is responsible for manually clearing the setup OUT to + * finalize the transfer via the \ref Endpoint_ClearOUT() macro. + * + * \note This function automatically clears the control transfer's status stage. Do not manually attempt + * to clear the status stage when using this routine in a control transaction. + * \n\n + * + * \note This routine should only be used on CONTROL type endpoints. + * + * \warning Unlike the standard stream read/write commands, the control stream commands cannot be chained + * together; i.e. the entire stream data must be read or written at the one time. + * + * \ingroup Group_EndpointStreamRW + * + * \param[in] Buffer Pointer to the source data buffer to read from. + * \param[in] Length Number of bytes to read for the currently selected endpoint into the buffer. + * + * \return A value from the \ref Endpoint_ControlStream_RW_ErrorCodes_t enum. + */ + uint8_t Endpoint_Write_Control_Stream_BE(const void* Buffer, + uint16_t Length) ATTR_NON_NULL_PTR_ARG(1); + + /** EEPROM buffer source version of \ref Endpoint_Write_Control_Stream_BE(). + * + * \note This function automatically clears the control transfer's status stage. Do not manually attempt + * to clear the status stage when using this routine in a control transaction. + * \n\n + * + * \note This routine should only be used on CONTROL type endpoints. + * + * \warning Unlike the standard stream read/write commands, the control stream commands cannot be chained + * together; i.e. the entire stream data must be read or written at the one time. + * + * \ingroup Group_EndpointStreamRW + * + * \param[in] Buffer Pointer to the source data buffer to read from. + * \param[in] Length Number of bytes to read for the currently selected endpoint into the buffer. + * + * \return A value from the \ref Endpoint_ControlStream_RW_ErrorCodes_t enum. + */ + uint8_t Endpoint_Write_Control_EStream_BE(const void* Buffer, + uint16_t Length) ATTR_NON_NULL_PTR_ARG(1); + + /** FLASH buffer source version of \ref Endpoint_Write_Control_Stream_BE(). + * + * \pre The FLASH data must be located in the first 64KB of FLASH for this function to work correctly. + * + * \note This function automatically clears the control transfer's status stage. Do not manually attempt + * to clear the status stage when using this routine in a control transaction. + * \n\n + * + * \note This routine should only be used on CONTROL type endpoints. + * + * \warning Unlike the standard stream read/write commands, the control stream commands cannot be chained + * together; i.e. the entire stream data must be read or written at the one time. + * + * \ingroup Group_EndpointStreamRW + * + * \param[in] Buffer Pointer to the source data buffer to read from. + * \param[in] Length Number of bytes to read for the currently selected endpoint into the buffer. + * + * \return A value from the \ref Endpoint_ControlStream_RW_ErrorCodes_t enum. + */ + uint8_t Endpoint_Write_Control_PStream_BE(const void* Buffer, + uint16_t Length) ATTR_NON_NULL_PTR_ARG(1); + + /** Reads the given number of bytes from the CONTROL endpoint from the given buffer in little endian, + * discarding fully read packets from the host as needed. The device IN acknowledgement is not + * automatically sent after success or failure states; the user is responsible for manually sending the + * setup IN to finalize the transfer via the \ref Endpoint_ClearIN() macro. + * + * \note This function automatically clears the control transfer's status stage. Do not manually attempt + * to clear the status stage when using this routine in a control transaction. + * \n\n + * + * \note This routine should only be used on CONTROL type endpoints. + * + * \warning Unlike the standard stream read/write commands, the control stream commands cannot be chained + * together; i.e. the entire stream data must be read or written at the one time. + * + * \ingroup Group_EndpointStreamRW + * + * \param[out] Buffer Pointer to the destination data buffer to write to. + * \param[in] Length Number of bytes to send via the currently selected endpoint. + * + * \return A value from the \ref Endpoint_ControlStream_RW_ErrorCodes_t enum. + */ + uint8_t Endpoint_Read_Control_Stream_LE(void* Buffer, + uint16_t Length) ATTR_NON_NULL_PTR_ARG(1); + + /** EEPROM buffer source version of \ref Endpoint_Read_Control_Stream_LE(). + * + * \note This function automatically clears the control transfer's status stage. Do not manually attempt + * to clear the status stage when using this routine in a control transaction. + * \n\n + * + * \note This routine should only be used on CONTROL type endpoints. + * + * \warning Unlike the standard stream read/write commands, the control stream commands cannot be chained + * together; i.e. the entire stream data must be read or written at the one time. + * + * \ingroup Group_EndpointStreamRW + * + * \param[out] Buffer Pointer to the destination data buffer to write to. + * \param[in] Length Number of bytes to send via the currently selected endpoint. + * + * \return A value from the \ref Endpoint_ControlStream_RW_ErrorCodes_t enum. + */ + uint8_t Endpoint_Read_Control_EStream_LE(void* Buffer, + uint16_t Length) ATTR_NON_NULL_PTR_ARG(1); + + /** Reads the given number of bytes from the CONTROL endpoint from the given buffer in big endian, + * discarding fully read packets from the host as needed. The device IN acknowledgement is not + * automatically sent after success or failure states; the user is responsible for manually sending the + * setup IN to finalize the transfer via the \ref Endpoint_ClearIN() macro. + * + * \note This function automatically clears the control transfer's status stage. Do not manually attempt + * to clear the status stage when using this routine in a control transaction. + * \n\n + * + * \note This routine should only be used on CONTROL type endpoints. + * + * \warning Unlike the standard stream read/write commands, the control stream commands cannot be chained + * together; i.e. the entire stream data must be read or written at the one time. + * + * \ingroup Group_EndpointStreamRW + * + * \param[out] Buffer Pointer to the destination data buffer to write to. + * \param[in] Length Number of bytes to send via the currently selected endpoint. + * + * \return A value from the \ref Endpoint_ControlStream_RW_ErrorCodes_t enum. + */ + uint8_t Endpoint_Read_Control_Stream_BE(void* Buffer, + uint16_t Length) ATTR_NON_NULL_PTR_ARG(1); + + /** EEPROM buffer source version of \ref Endpoint_Read_Control_Stream_BE(). + * + * \note This function automatically clears the control transfer's status stage. Do not manually attempt + * to clear the status stage when using this routine in a control transaction. + * \n\n + * + * \note This routine should only be used on CONTROL type endpoints. + * + * \warning Unlike the standard stream read/write commands, the control stream commands cannot be chained + * together; i.e. the entire stream data must be read or written at the one time. + * + * \ingroup Group_EndpointStreamRW + * + * \param[out] Buffer Pointer to the destination data buffer to write to. + * \param[in] Length Number of bytes to send via the currently selected endpoint. + * + * \return A value from the \ref Endpoint_ControlStream_RW_ErrorCodes_t enum. + */ + uint8_t Endpoint_Read_Control_EStream_BE(void* Buffer, + uint16_t Length) ATTR_NON_NULL_PTR_ARG(1); + + /* Private Interface - For use in library only: */ + #if !defined(__DOXYGEN__) + /* Macros: */ + #define _ENDPOINT_GET_MAXSIZE(n) _ENDPOINT_GET_MAXSIZE2(ENDPOINT_DETAILS_EP ## n) + #define _ENDPOINT_GET_MAXSIZE2(details) _ENDPOINT_GET_MAXSIZE3(details) + #define _ENDPOINT_GET_MAXSIZE3(maxsize, db) maxsize + + #define _ENDPOINT_GET_DOUBLEBANK(n) _ENDPOINT_GET_DOUBLEBANK2(ENDPOINT_DETAILS_EP ## n) + #define _ENDPOINT_GET_DOUBLEBANK2(details) _ENDPOINT_GET_DOUBLEBANK3(details) + #define _ENDPOINT_GET_DOUBLEBANK3(maxsize, db) db + + #if defined(USB_SERIES_4_AVR) || defined(USB_SERIES_6_AVR) || defined(USB_SERIES_7_AVR) + #define ENDPOINT_DETAILS_EP0 64, true + #define ENDPOINT_DETAILS_EP1 256, true + #define ENDPOINT_DETAILS_EP2 64, true + #define ENDPOINT_DETAILS_EP3 64, true + #define ENDPOINT_DETAILS_EP4 64, true + #define ENDPOINT_DETAILS_EP5 64, true + #define ENDPOINT_DETAILS_EP6 64, true + #else + #define ENDPOINT_DETAILS_EP0 64, true + #define ENDPOINT_DETAILS_EP1 64, false + #define ENDPOINT_DETAILS_EP2 64, false + #define ENDPOINT_DETAILS_EP3 64, true + #define ENDPOINT_DETAILS_EP4 64, true + #endif + + #define Endpoint_ConfigureEndpoint(Number, Type, Direction, Size, Banks) \ + (__builtin_constant_p(Size) ? Endpoint_ConfigureEndpointStatic((Number), \ + (Type), \ + (Direction), \ + Size, Banks) : \ + Endpoint_ConfigureEndpointDynamic((Number), \ + (Type), \ + (Direction), \ + Size, Banks)) + + /* Function Prototypes: */ + void Endpoint_ClearEndpoints(void); + uint8_t Endpoint_BytesToEPSizeMaskDynamic(const uint16_t Size); + bool Endpoint_ConfigureEndpoint_Prv(const uint8_t Number, + const uint8_t UECFG0XData, + const uint8_t UECFG1XData); + + /* Inline Functions: */ + static inline uint8_t Endpoint_BytesToEPSizeMask(const uint16_t Bytes) ATTR_WARN_UNUSED_RESULT ATTR_CONST ATTR_ALWAYS_INLINE; + static inline uint8_t Endpoint_BytesToEPSizeMask(const uint16_t Bytes) + { + uint8_t MaskVal = 0; + uint16_t CheckBytes = 8; + + while (CheckBytes < Bytes) + { + MaskVal++; + CheckBytes <<= 1; + } + + return (MaskVal << EPSIZE0); + } + + static inline bool Endpoint_ConfigureEndpointStatic(const uint8_t Number, + const uint8_t Type, + const uint8_t Direction, + const uint16_t Size, + const uint8_t Banks) + { + return Endpoint_ConfigureEndpoint_Prv(Number, (((Type) << EPTYPE0) | (Direction)), + ((1 << ALLOC) | Banks | Endpoint_BytesToEPSizeMask(Size))); + } + + static inline bool Endpoint_ConfigureEndpointDynamic(const uint8_t Number, + const uint8_t Type, + const uint8_t Direction, + const uint16_t Size, + const uint8_t Banks) + { + return Endpoint_ConfigureEndpoint_Prv(Number, (((Type) << EPTYPE0) | (Direction)), + ((1 << ALLOC) | Banks | Endpoint_BytesToEPSizeMaskDynamic(Size))); + } + #endif + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/Host.c b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/Host.c new file mode 100644 index 0000000000..5b7a714bab --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/Host.c @@ -0,0 +1,345 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +#define __INCLUDE_FROM_USB_DRIVER +#include "../HighLevel/USBMode.h" + +#if defined(USB_CAN_BE_HOST) + +#define __INCLUDE_FROM_HOST_C +#include "Host.h" + +void USB_Host_ProcessNextHostState(void) +{ + uint8_t ErrorCode = HOST_ENUMERROR_NoError; + uint8_t SubErrorCode = HOST_ENUMERROR_NoError; + + static uint16_t WaitMSRemaining; + static uint8_t PostWaitState; + + switch (USB_HostState) + { + case HOST_STATE_WaitForDevice: + if (WaitMSRemaining) + { + if ((SubErrorCode = USB_Host_WaitMS(1)) != HOST_WAITERROR_Successful) + { + USB_HostState = PostWaitState; + ErrorCode = HOST_ENUMERROR_WaitStage; + break; + } + + if (!(--WaitMSRemaining)) + USB_HostState = PostWaitState; + } + + break; + case HOST_STATE_Powered: + WaitMSRemaining = HOST_DEVICE_SETTLE_DELAY_MS; + + USB_HostState = HOST_STATE_Powered_WaitForDeviceSettle; + break; + case HOST_STATE_Powered_WaitForDeviceSettle: + if (WaitMSRemaining--) + { + _delay_ms(1); + break; + } + else + { + USB_Host_VBUS_Manual_Off(); + + USB_OTGPAD_On(); + USB_Host_VBUS_Auto_Enable(); + USB_Host_VBUS_Auto_On(); + + USB_HostState = HOST_STATE_Powered_WaitForConnect; + } + + break; + case HOST_STATE_Powered_WaitForConnect: + if (USB_INT_HasOccurred(USB_INT_DCONNI)) + { + USB_INT_Clear(USB_INT_DCONNI); + USB_INT_Clear(USB_INT_DDISCI); + + USB_INT_Clear(USB_INT_VBERRI); + USB_INT_Enable(USB_INT_VBERRI); + + USB_Host_ResumeBus(); + Pipe_ClearPipes(); + + HOST_TASK_NONBLOCK_WAIT(100, HOST_STATE_Powered_DoReset); + } + + break; + case HOST_STATE_Powered_DoReset: + USB_Host_ResetDevice(); + + HOST_TASK_NONBLOCK_WAIT(200, HOST_STATE_Powered_ConfigPipe); + break; + case HOST_STATE_Powered_ConfigPipe: + Pipe_ConfigurePipe(PIPE_CONTROLPIPE, EP_TYPE_CONTROL, + PIPE_TOKEN_SETUP, ENDPOINT_CONTROLEP, + PIPE_CONTROLPIPE_DEFAULT_SIZE, PIPE_BANK_SINGLE); + + if (!(Pipe_IsConfigured())) + { + ErrorCode = HOST_ENUMERROR_PipeConfigError; + SubErrorCode = 0; + break; + } + + USB_HostState = HOST_STATE_Default; + break; + case HOST_STATE_Default: + USB_ControlRequest = (USB_Request_Header_t) + { + .bmRequestType = (REQDIR_DEVICETOHOST | REQTYPE_STANDARD | REQREC_DEVICE), + .bRequest = REQ_GetDescriptor, + .wValue = (DTYPE_Device << 8), + .wIndex = 0, + .wLength = 8, + }; + + uint8_t DataBuffer[8]; + + if ((SubErrorCode = USB_Host_SendControlRequest(DataBuffer)) != HOST_SENDCONTROL_Successful) + { + ErrorCode = HOST_ENUMERROR_ControlError; + break; + } + + USB_ControlPipeSize = DataBuffer[offsetof(USB_Descriptor_Device_t, Endpoint0Size)]; + + USB_Host_ResetDevice(); + + HOST_TASK_NONBLOCK_WAIT(200, HOST_STATE_Default_PostReset); + break; + case HOST_STATE_Default_PostReset: + Pipe_ConfigurePipe(PIPE_CONTROLPIPE, EP_TYPE_CONTROL, + PIPE_TOKEN_SETUP, ENDPOINT_CONTROLEP, + USB_ControlPipeSize, PIPE_BANK_SINGLE); + + if (!(Pipe_IsConfigured())) + { + ErrorCode = HOST_ENUMERROR_PipeConfigError; + SubErrorCode = 0; + break; + } + + USB_ControlRequest = (USB_Request_Header_t) + { + .bmRequestType = (REQDIR_HOSTTODEVICE | REQTYPE_STANDARD | REQREC_DEVICE), + .bRequest = REQ_SetAddress, + .wValue = USB_HOST_DEVICEADDRESS, + .wIndex = 0, + .wLength = 0, + }; + + if ((SubErrorCode = USB_Host_SendControlRequest(NULL)) != HOST_SENDCONTROL_Successful) + { + ErrorCode = HOST_ENUMERROR_ControlError; + break; + } + + HOST_TASK_NONBLOCK_WAIT(100, HOST_STATE_Default_PostAddressSet); + break; + case HOST_STATE_Default_PostAddressSet: + USB_Host_SetDeviceAddress(USB_HOST_DEVICEADDRESS); + + EVENT_USB_Host_DeviceEnumerationComplete(); + USB_HostState = HOST_STATE_Addressed; + break; + } + + if ((ErrorCode != HOST_ENUMERROR_NoError) && (USB_HostState != HOST_STATE_Unattached)) + { + EVENT_USB_Host_DeviceEnumerationFailed(ErrorCode, SubErrorCode); + + USB_Host_VBUS_Auto_Off(); + + EVENT_USB_Host_DeviceUnattached(); + + USB_ResetInterface(); + } +} + +uint8_t USB_Host_WaitMS(uint8_t MS) +{ + bool BusSuspended = USB_Host_IsBusSuspended(); + uint8_t ErrorCode = HOST_WAITERROR_Successful; + + USB_Host_ResumeBus(); + + while (MS) + { + if (USB_INT_HasOccurred(USB_INT_HSOFI)) + { + USB_INT_Clear(USB_INT_HSOFI); + MS--; + } + + if ((USB_HostState == HOST_STATE_Unattached) || (USB_CurrentMode == USB_MODE_DEVICE)) + { + ErrorCode = HOST_WAITERROR_DeviceDisconnect; + + break; + } + + if (Pipe_IsError() == true) + { + Pipe_ClearError(); + ErrorCode = HOST_WAITERROR_PipeError; + + break; + } + + if (Pipe_IsStalled() == true) + { + Pipe_ClearStall(); + ErrorCode = HOST_WAITERROR_SetupStalled; + + break; + } + } + + if (BusSuspended) + USB_Host_SuspendBus(); + + return ErrorCode; +} + +static void USB_Host_ResetDevice(void) +{ + bool BusSuspended = USB_Host_IsBusSuspended(); + + USB_INT_Disable(USB_INT_DDISCI); + + USB_Host_ResetBus(); + while (!(USB_Host_IsBusResetComplete())); + + USB_Host_ResumeBus(); + + USB_INT_Clear(USB_INT_HSOFI); + + for (uint8_t MSRem = 10; MSRem != 0; MSRem--) + { + /* Workaround for powerless-pull-up devices. After a USB bus reset, + all disconnection interrupts are suppressed while a USB frame is + looked for - if it is found within 10ms, the device is still + present. */ + + if (USB_INT_HasOccurred(USB_INT_HSOFI)) + { + USB_INT_Clear(USB_INT_HSOFI); + USB_INT_Clear(USB_INT_DDISCI); + break; + } + + _delay_ms(1); + } + + if (BusSuspended) + USB_Host_SuspendBus(); + + USB_INT_Enable(USB_INT_DDISCI); +} + +uint8_t USB_Host_SetDeviceConfiguration(const uint8_t ConfigNumber) +{ + USB_ControlRequest = (USB_Request_Header_t) + { + .bmRequestType = (REQDIR_HOSTTODEVICE | REQTYPE_STANDARD | REQREC_DEVICE), + .bRequest = REQ_SetConfiguration, + .wValue = ConfigNumber, + .wIndex = 0, + .wLength = 0, + }; + + Pipe_SelectPipe(PIPE_CONTROLPIPE); + + return USB_Host_SendControlRequest(NULL); +} + +uint8_t USB_Host_GetDeviceDescriptor(void* const DeviceDescriptorPtr) +{ + USB_ControlRequest = (USB_Request_Header_t) + { + .bmRequestType = (REQDIR_DEVICETOHOST | REQTYPE_STANDARD | REQREC_DEVICE), + .bRequest = REQ_GetDescriptor, + .wValue = (DTYPE_Device << 8), + .wIndex = 0, + .wLength = sizeof(USB_Descriptor_Device_t), + }; + + Pipe_SelectPipe(PIPE_CONTROLPIPE); + + return USB_Host_SendControlRequest(DeviceDescriptorPtr); +} + +uint8_t USB_Host_GetDeviceStringDescriptor(const uint8_t Index, + void* const Buffer, + const uint8_t BufferLength) +{ + USB_ControlRequest = (USB_Request_Header_t) + { + .bmRequestType = (REQDIR_DEVICETOHOST | REQTYPE_STANDARD | REQREC_DEVICE), + .bRequest = REQ_GetDescriptor, + .wValue = (DTYPE_String << 8) | Index, + .wIndex = 0, + .wLength = BufferLength, + }; + + Pipe_SelectPipe(PIPE_CONTROLPIPE); + + return USB_Host_SendControlRequest(Buffer); +} + +uint8_t USB_Host_ClearPipeStall(uint8_t EndpointNum) +{ + if (Pipe_GetPipeToken() == PIPE_TOKEN_IN) + EndpointNum |= ENDPOINT_DESCRIPTOR_DIR_IN; + + USB_ControlRequest = (USB_Request_Header_t) + { + .bmRequestType = (REQDIR_HOSTTODEVICE | REQTYPE_STANDARD | REQREC_ENDPOINT), + .bRequest = REQ_ClearFeature, + .wValue = FEATURE_ENDPOINT_HALT, + .wIndex = EndpointNum, + .wLength = 0, + }; + + Pipe_SelectPipe(PIPE_CONTROLPIPE); + + return USB_Host_SendControlRequest(NULL); +} + +#endif diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/Host.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/Host.h new file mode 100644 index 0000000000..3f639c1581 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/Host.h @@ -0,0 +1,492 @@ +/* + 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 USB host mode definitions. + * + * This file contains structures, function prototypes and macros related to USB host mode. + * + * \note This file should not be included directly. It is automatically included as needed by the USB driver + * dispatch header located in LUFA/Drivers/USB/USB.h. + */ + +/** \ingroup Group_USB + * @defgroup Group_Host Host Management + * + * USB Host mode related macros and enums. This module contains macros and enums which are used when + * the USB controller is initialized in host mode. + * + * @{ + */ + +#ifndef __USBHOST_H__ +#define __USBHOST_H__ + + /* Includes: */ + #include + #include + #include + + #include "../../../Common/Common.h" + #include "../HighLevel/StdDescriptors.h" + #include "Pipe.h" + #include "USBInterrupt.h" + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_USB_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/USB/USB.h instead. + #endif + + /* Public Interface - May be used in end-application: */ + /* Macros: */ + /** Indicates the fixed USB device address which any attached device is enumerated to when in + * host mode. As only one USB device may be attached to the AVR in host mode at any one time + * and that the address used is not important (other than the fact that it is non-zero), a + * fixed value is specified by the library. + */ + #define USB_HOST_DEVICEADDRESS 1 + + #if !defined(USB_HOST_TIMEOUT_MS) || defined(__DOXYGEN__) + /** Constant for the maximum software timeout period of sent USB control transactions to an attached + * device. If a device fails to respond to a sent control request within this period, the + * library will return a timeout error code. + * + * This value may be overridden in the user project makefile as the value of the + * \ref USB_HOST_TIMEOUT_MS token, and passed to the compiler using the -D switch. + */ + #define USB_HOST_TIMEOUT_MS 1000 + #endif + + #if !defined(HOST_DEVICE_SETTLE_DELAY_MS) || defined(__DOXYGEN__) + /** Constant for the delay in milliseconds after a device is connected before the library + * will start the enumeration process. Some devices require a delay of up to 5 seconds + * after connection before the enumeration process can start or incorrect operation will + * occur. + * + * This value may be overridden in the user project makefile as the value of the + * HOST_DEVICE_SETTLE_DELAY_MS token, and passed to the compiler using the -D switch. + */ + #define HOST_DEVICE_SETTLE_DELAY_MS 1500 + #endif + + /* Enums: */ + /** Enum for the various states of the USB Host state machine. Only some states are + * implemented in the LUFA library - other states are left to the user to implement. + * + * For information on each possible USB host state, refer to the USB 2.0 specification. + * Several of the USB host states are broken up further into multiple smaller sub-states, + * so that they can be internally implemented inside the library in an efficient manner. + * + * \see \ref USB_HostState, which stores the current host state machine state. + */ + enum USB_Host_States_t + { + HOST_STATE_WaitForDeviceRemoval = 0, /**< Internally implemented by the library. This state can be + * used by the library to wait until the attached device is + * removed by the user - useful for when an error occurs or + * further communication with the device is not needed. This + * allows for other code to run while the state machine is + * effectively disabled. + */ + HOST_STATE_WaitForDevice = 1, /**< Internally implemented by the library. This state indicates + * that the stack is waiting for an interval to elapse before + * continuing with the next step of the device enumeration + * process. + * + * \note Do not manually change to this state in the user code. + */ + HOST_STATE_Unattached = 2, /**< Internally implemented by the library. This state indicates + * that the host state machine is waiting for a device to be + * attached so that it can start the enumeration process. + * + * \note Do not manually change to this state in the user code. + */ + HOST_STATE_Powered = 3, /**< Internally implemented by the library. This state indicates + * that a device has been attached, and the library's internals + * are being configured to begin the enumeration process. + * + * \note Do not manually change to this state in the user code. + */ + HOST_STATE_Powered_WaitForDeviceSettle = 4, /**< Internally implemented by the library. This state indicates + * that the stack is waiting for the initial settling period to + * elapse before beginning the enumeration process. + * + * \note Do not manually change to this state in the user code. + */ + HOST_STATE_Powered_WaitForConnect = 5, /**< Internally implemented by the library. This state indicates + * that the stack is waiting for a connection event from the USB + * controller to indicate a valid USB device has been attached to + * the bus and is ready to be enumerated. + * + * \note Do not manually change to this state in the user code. + */ + HOST_STATE_Powered_DoReset = 6, /**< Internally implemented by the library. This state indicates + * that a valid USB device has been attached, and that it is + * will now be reset to ensure it is ready for enumeration. + * + * \note Do not manually change to this state in the user code. + */ + HOST_STATE_Powered_ConfigPipe = 7, /**< Internally implemented by the library. This state indicates + * that the attached device is currently powered and reset, and + * that the control pipe is now being configured by the stack. + * + * \note Do not manually change to this state in the user code. + */ + HOST_STATE_Default = 8, /**< Internally implemented by the library. This state indicates + * that the stack is currently retrieving the control endpoint's + * size from the device, so that the control pipe can be altered + * to match. + * + * \note Do not manually change to this state in the user code. + */ + HOST_STATE_Default_PostReset = 9, /**< Internally implemented by the library. This state indicates that + * the control pipe is being reconfigured to match the retrieved + * control endpoint size from the device, and the device's USB bus + * address is being set. + * + * \note Do not manually change to this state in the user code. + */ + HOST_STATE_Default_PostAddressSet = 10, /**< Internally implemented by the library. This state indicates that + * the device's address has now been set, and the stack is has now + * completed the device enumeration process. This state causes the + * stack to change the current USB device address to that set for + * the connected device, before progressing to the user-implemented + * HOST_STATE_Addressed state for further communications. + * + * \note Do not manually change to this state in the user code. + */ + HOST_STATE_Addressed = 11, /**< May be implemented by the user project. This state should + * set the device configuration before progressing to the + * HOST_STATE_Configured state. Other processing (such as the + * retrieval and processing of the device descriptor) should also + * be placed in this state. + */ + HOST_STATE_Configured = 12, /**< May be implemented by the user project. This state should implement the + * actual work performed on the attached device and changed to the + * HOST_STATE_Suspended or HOST_STATE_WaitForDeviceRemoval states as needed. + */ + HOST_STATE_Suspended = 15, /**< May be implemented by the user project. This state should be maintained + * while the bus is suspended, and changed to either the HOST_STATE_Configured + * (after resuming the bus with the USB_Host_ResumeBus() macro) or the + * HOST_STATE_WaitForDeviceRemoval states as needed. + */ + }; + + /** Enum for the error codes for the \ref EVENT_USB_Host_HostError() event. + * + * \see \ref Group_Events for more information on this event. + */ + enum USB_Host_ErrorCodes_t + { + HOST_ERROR_VBusVoltageDip = 0, /**< VBUS voltage dipped to an unacceptable level. This + * error may be the result of an attached device drawing + * too much current from the VBUS line, or due to the + * AVR's power source being unable to supply sufficient + * current. + */ + }; + + /** Enum for the error codes for the \ref EVENT_USB_Host_DeviceEnumerationFailed() event. + * + * \see \ref Group_Events for more information on this event. + */ + enum USB_Host_EnumerationErrorCodes_t + { + HOST_ENUMERROR_NoError = 0, /**< No error occurred. Used internally, this is not a valid + * ErrorCode parameter value for the \ref EVENT_USB_Host_DeviceEnumerationFailed() + * event. + */ + HOST_ENUMERROR_WaitStage = 1, /**< One of the delays between enumeration steps failed + * to complete successfully, due to a timeout or other + * error. + */ + HOST_ENUMERROR_NoDeviceDetected = 2, /**< No device was detected, despite the USB data lines + * indicating the attachment of a device. + */ + HOST_ENUMERROR_ControlError = 3, /**< One of the enumeration control requests failed to + * complete successfully. + */ + HOST_ENUMERROR_PipeConfigError = 4, /**< The default control pipe (address 0) failed to + * configure correctly. + */ + }; + + /* Inline Functions: */ + /** Resets the USB bus, including the endpoints in any attached device and pipes on the AVR host. + * USB bus resets leave the default control pipe configured (if already configured). + * + * If the USB bus has been suspended prior to issuing a bus reset, the attached device will be + * woken up automatically and the bus resumed after the reset has been correctly issued. + */ + static inline void USB_Host_ResetBus(void) ATTR_ALWAYS_INLINE; + static inline void USB_Host_ResetBus(void) + { + UHCON |= (1 << RESET); + } + + /** Determines if a previously issued bus reset (via the \ref USB_Host_ResetBus() macro) has + * completed. + * + * \return Boolean true if no bus reset is currently being sent, false otherwise. + */ + static inline bool USB_Host_IsBusResetComplete(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline bool USB_Host_IsBusResetComplete(void) + { + return ((UHCON & (1 << RESET)) ? false : true); + } + + /** Resumes USB communications with an attached and enumerated device, by resuming the transmission + * of the 1MS Start Of Frame messages to the device. When resumed, USB communications between the + * host and attached device may occur. + */ + static inline void USB_Host_ResumeBus(void) ATTR_ALWAYS_INLINE; + static inline void USB_Host_ResumeBus(void) + { + UHCON |= (1 << SOFEN); + } + + /** Suspends the USB bus, preventing any communications from occurring between the host and attached + * device until the bus has been resumed. This stops the transmission of the 1MS Start Of Frame + * messages to the device. + */ + static inline void USB_Host_SuspendBus(void) ATTR_ALWAYS_INLINE; + static inline void USB_Host_SuspendBus(void) + { + UHCON &= ~(1 << SOFEN); + } + + /** Determines if the USB bus has been suspended via the use of the \ref USB_Host_SuspendBus() macro, + * false otherwise. While suspended, no USB communications can occur until the bus is resumed, + * except for the Remote Wakeup event from the device if supported. + * + * \return Boolean true if the bus is currently suspended, false otherwise. + */ + static inline bool USB_Host_IsBusSuspended(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline bool USB_Host_IsBusSuspended(void) + { + return ((UHCON & (1 << SOFEN)) ? false : true); + } + + /** Determines if the attached device is currently enumerated in Full Speed mode (12Mb/s), or + * false if the attached device is enumerated in Low Speed mode (1.5Mb/s). + * + * \return Boolean true if the attached device is enumerated in Full Speed mode, false otherwise. + */ + static inline bool USB_Host_IsDeviceFullSpeed(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline bool USB_Host_IsDeviceFullSpeed(void) + { + return ((USBSTA & (1 << SPEED)) ? true : false); + } + + /** Determines if the attached device is currently issuing a Remote Wakeup request, requesting + * that the host resume the USB bus and wake up the device, false otherwise. + * + * \return Boolean true if the attached device has sent a Remote Wakeup request, false otherwise. + */ + static inline bool USB_Host_IsRemoteWakeupSent(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline bool USB_Host_IsRemoteWakeupSent(void) + { + return ((UHINT & (1 << RXRSMI)) ? true : false); + } + + /** Clears the flag indicating that a Remote Wakeup request has been issued by an attached device. */ + static inline void USB_Host_ClearRemoteWakeupSent(void) ATTR_ALWAYS_INLINE; + static inline void USB_Host_ClearRemoteWakeupSent(void) + { + UHINT &= ~(1 << RXRSMI); + } + + /** Accepts a Remote Wakeup request from an attached device. This must be issued in response to + * a device's Remote Wakeup request within 2ms for the request to be accepted and the bus to + * be resumed. + */ + static inline void USB_Host_ResumeFromWakeupRequest(void) ATTR_ALWAYS_INLINE; + static inline void USB_Host_ResumeFromWakeupRequest(void) + { + UHCON |= (1 << RESUME); + } + + /** Determines if a resume from Remote Wakeup request is currently being sent to an attached + * device. + * + * \return Boolean true if no resume request is currently being sent, false otherwise. + */ + static inline bool USB_Host_IsResumeFromWakeupRequestSent(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline bool USB_Host_IsResumeFromWakeupRequestSent(void) + { + return ((UHCON & (1 << RESUME)) ? false : true); + } + + /* Function Prototypes: */ + /** Convenience function. This routine sends a SetConfiguration standard request to the attached + * device, with the given configuration index. This can be used to easily set the device + * configuration without creating and sending the request manually. + * + * \note After this routine returns, the control pipe will be selected. + * + * \param[in] ConfigNumber Configuration index to send to the device. + * + * \return A value from the \ref USB_Host_SendControlErrorCodes_t enum to indicate the result. + */ + uint8_t USB_Host_SetDeviceConfiguration(const uint8_t ConfigNumber); + + /** Convenience function. This routine sends a GetDescriptor standard request to the attached + * device, requesting the device descriptor. This can be used to easily retrieve information + * about the device such as its VID, PID and power requirements. + * + * \note After this routine returns, the control pipe will be selected. + * + * \param[out] DeviceDescriptorPtr Pointer to the destination device descriptor structure where + * the read data is to be stored. + * + * \return A value from the \ref USB_Host_SendControlErrorCodes_t enum to indicate the result. + */ + uint8_t USB_Host_GetDeviceDescriptor(void* const DeviceDescriptorPtr); + + /** Convenience function. This routine sends a GetDescriptor standard request to the attached + * device, requesting the string descriptor of the specified index. This can be used to easily + * retrieve string descriptors from the device by index, after the index is obtained from the + * Device or Configuration descriptors. + * + * \note After this routine returns, the control pipe will be selected. + * + * \param[in] Index Index of the string index to retrieve. + * \param[out] Buffer Pointer to the destination buffer where the retrieved string descriptor is + * to be stored. + * \param[in] BufferLength Maximum size of the string descriptor which can be stored into the buffer. + * + * \return A value from the \ref USB_Host_SendControlErrorCodes_t enum to indicate the result. + */ + uint8_t USB_Host_GetDeviceStringDescriptor(const uint8_t Index, + void* const Buffer, + const uint8_t BufferLength); + + /** Clears a stall condition on the given pipe, via a ClearFeature request to the attached device. + * + * \note After this routine returns, the control pipe will be selected. + * + * \param[in] EndpointIndex Index of the endpoint to clear. + * + * \return A value from the \ref USB_Host_SendControlErrorCodes_t enum to indicate the result. + */ + uint8_t USB_Host_ClearPipeStall(uint8_t EndpointIndex); + + /* Private Interface - For use in library only: */ + #if !defined(__DOXYGEN__) + /* Macros: */ + static inline void USB_Host_HostMode_On(void) ATTR_ALWAYS_INLINE; + static inline void USB_Host_HostMode_On(void) + { + USBCON |= (1 << HOST); + } + + static inline void USB_Host_HostMode_Off(void) ATTR_ALWAYS_INLINE; + static inline void USB_Host_HostMode_Off(void) + { + USBCON &= ~(1 << HOST); + } + + static inline void USB_Host_VBUS_Auto_Enable(void) ATTR_ALWAYS_INLINE; + static inline void USB_Host_VBUS_Auto_Enable(void) + { + OTGCON &= ~(1 << VBUSHWC); + UHWCON |= (1 << UVCONE); + } + + static inline void USB_Host_VBUS_Manual_Enable(void) ATTR_ALWAYS_INLINE; + static inline void USB_Host_VBUS_Manual_Enable(void) + { + OTGCON |= (1 << VBUSHWC); + UHWCON &= ~(1 << UVCONE); + + DDRE |= (1 << 7); + } + + static inline void USB_Host_VBUS_Auto_On(void) ATTR_ALWAYS_INLINE; + static inline void USB_Host_VBUS_Auto_On(void) + { + OTGCON |= (1 << VBUSREQ); + } + + static inline void USB_Host_VBUS_Manual_On(void) ATTR_ALWAYS_INLINE; + static inline void USB_Host_VBUS_Manual_On(void) + { + PORTE |= (1 << 7); + } + + static inline void USB_Host_VBUS_Auto_Off(void) ATTR_ALWAYS_INLINE; + static inline void USB_Host_VBUS_Auto_Off(void) + { + OTGCON |= (1 << VBUSRQC); + } + + static inline void USB_Host_VBUS_Manual_Off(void) ATTR_ALWAYS_INLINE; + static inline void USB_Host_VBUS_Manual_Off(void) + { + PORTE &= ~(1 << 7); + } + + static inline void USB_Host_SetDeviceAddress(const uint8_t Address) ATTR_ALWAYS_INLINE; + static inline void USB_Host_SetDeviceAddress(const uint8_t Address) + { + UHADDR = (Address & 0x7F); + } + + /* Enums: */ + enum USB_Host_WaitMSErrorCodes_t + { + HOST_WAITERROR_Successful = 0, + HOST_WAITERROR_DeviceDisconnect = 1, + HOST_WAITERROR_PipeError = 2, + HOST_WAITERROR_SetupStalled = 3, + }; + + /* Function Prototypes: */ + void USB_Host_ProcessNextHostState(void); + uint8_t USB_Host_WaitMS(uint8_t MS); + + #if defined(__INCLUDE_FROM_HOST_C) + static void USB_Host_ResetDevice(void); + #endif + #endif + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/OTG.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/OTG.h new file mode 100644 index 0000000000..deb786642f --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/OTG.h @@ -0,0 +1,154 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief USB OTG mode definitions. + * + * This file contains structures, function prototypes and macros related to USB OTG mode, where two USB devices + * may be linked directly together and exchange host/device roles as needed. + * + * \note This file should not be included directly. It is automatically included as needed by the USB driver + * dispatch header located in LUFA/Drivers/USB/USB.h. + */ + +/** \ingroup Group_USB + * @defgroup Group_OTG USB On The Go (OTG) Management + * + * This module contains macros for embedded USB hosts with dual role On The Go capabilities, for managing role + * exchange. OTG is a way for two USB dual role devices to talk to one another directly without fixed device/host + * roles. + * + * @{ + */ + +#ifndef __USBOTG_H__ +#define __USBOTG_H__ + + /* Includes: */ + #include + #include + + #include "../../../Common/Common.h" + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_USB_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/USB/USB.h instead. + #endif + + /* Public Interface - May be used in end-application: */ + /* Macros: */ + /** Mask for the VBUS pulsing method of SRP, supported by some OTG devices. + * + * \see \ref USB_OTG_Device_InitiateSRP(). + */ + #define USB_OTG_SRP_VBUS (1 << SRPSEL) + + /** Mask for the Data + pulsing method of SRP, supported by some OTG devices. + * + * \see \ref USB_OTG_Device_InitiateSRP(). + */ + #define USB_OTG_STP_DATA 0 + + /* Inline Functions: */ + /** Initiate a Host Negotiation Protocol request. This indicates to the other connected device + * that the device wishes to change device/host roles. + */ + static inline void USB_OTG_Device_RequestHNP(void) ATTR_ALWAYS_INLINE; + static inline void USB_OTG_Device_RequestHNP(void) + { + OTGCON |= (1 << HNPREQ); + } + + /** Cancel a Host Negotiation Protocol request. This stops a pending HNP request to the other + * connected device. + */ + static inline void USB_OTG_Device_CancelHNPRequest(void) ATTR_ALWAYS_INLINE; + static inline void USB_OTG_Device_CancelHNPRequest(void) + { + OTGCON &= ~(1 << HNPREQ); + } + + /** Determines if the device is currently sending a HNP to an attached host. + * + * \return Boolean true if currently sending a HNP to the other connected device, false otherwise + */ + static inline bool USB_OTG_Device_IsSendingHNP(void) ATTR_ALWAYS_INLINE; + static inline bool USB_OTG_Device_IsSendingHNP(void) + { + return ((OTGCON & (1 << HNPREQ)) ? true : false); + } + + /** Initiates a Session Request Protocol request. Most OTG devices turn off VBUS when the USB + * interface is not in use, to conserve power. Sending a SRP to a USB OTG device running in + * host mode indicates that VBUS should be applied and a session started. + * + * There are two different methods of sending a SRP - either pulses on the VBUS line, or by + * pulsing the Data + line via the internal pull-up resistor. + * + * \param[in] SRPTypeMask Mask indicating the type of SRP to use, either \ref USB_OTG_SRP_VBUS or + * \ref USB_OTG_STP_DATA. + */ + static inline void USB_OTG_Device_InitiateSRP(const uint8_t SRPTypeMask) ATTR_ALWAYS_INLINE; + static inline void USB_OTG_Device_InitiateSRP(const uint8_t SRPTypeMask) + { + OTGCON = ((OTGCON & ~(1 << SRPSEL)) | (SRPTypeMask | (1 << SRPREQ))); + } + + /** Accepts a HNP from a connected device, indicating that both devices should exchange + * device/host roles. + */ + static inline void USB_OTG_Host_AcceptHNP(void) ATTR_ALWAYS_INLINE; + static inline void USB_OTG_Host_AcceptHNP(void) + { + OTGCON |= (1 << HNPREQ); + } + + /** Rejects a HNP from a connected device, indicating that both devices should remain in their + * current device/host roles. + */ + static inline void USB_OTG_Host_RejectHNP(void) ATTR_ALWAYS_INLINE; + static inline void USB_OTG_Host_RejectHNP(void) + { + OTGCON &= ~(1 << HNPREQ); + } + + /** Indicates if the connected device is not currently sending a HNP request. + * + * \return Boolean true if a HNP is currently being issued by the connected device, false otherwise. + */ + static inline bool USB_OTG_Host_IsHNPReceived(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline bool USB_OTG_Host_IsHNPReceived(void) + { + return ((OTGCON & (1 << HNPREQ)) ? true : false); + } + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/Pipe.c b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/Pipe.c new file mode 100644 index 0000000000..f70f0184f1 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/Pipe.c @@ -0,0 +1,296 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +#define __INCLUDE_FROM_USB_DRIVER +#include "../HighLevel/USBMode.h" + +#if defined(USB_CAN_BE_HOST) + +#define __INCLUDE_FROM_PIPE_C +#include "Pipe.h" + +uint8_t USB_ControlPipeSize = PIPE_CONTROLPIPE_DEFAULT_SIZE; + +bool Pipe_ConfigurePipe(const uint8_t Number, + const uint8_t Type, + const uint8_t Token, + const uint8_t EndpointNumber, + const uint16_t Size, + const uint8_t Banks) +{ + Pipe_SelectPipe(Number); + Pipe_EnablePipe(); + + UPCFG1X = 0; + + UPCFG0X = ((Type << EPTYPE0) | Token | ((EndpointNumber & PIPE_EPNUM_MASK) << PEPNUM0)); + UPCFG1X = ((1 << ALLOC) | Banks | Pipe_BytesToEPSizeMask(Size)); + + Pipe_SetInfiniteINRequests(); + + return Pipe_IsConfigured(); +} + +void Pipe_ClearPipes(void) +{ + UPINT = 0; + + for (uint8_t PNum = 0; PNum < PIPE_TOTAL_PIPES; PNum++) + { + Pipe_SelectPipe(PNum); + UPIENX = 0; + UPINTX = 0; + UPCFG1X = 0; + Pipe_DisablePipe(); + } +} + +bool Pipe_IsEndpointBound(const uint8_t EndpointAddress) +{ + uint8_t PrevPipeNumber = Pipe_GetCurrentPipe(); + + for (uint8_t PNum = 0; PNum < PIPE_TOTAL_PIPES; PNum++) + { + Pipe_SelectPipe(PNum); + + if (!(Pipe_IsConfigured())) + continue; + + uint8_t PipeToken = Pipe_GetPipeToken(); + bool PipeTokenCorrect = true; + + if (PipeToken != PIPE_TOKEN_SETUP) + PipeTokenCorrect = (PipeToken == ((EndpointAddress & PIPE_EPDIR_MASK) ? PIPE_TOKEN_IN : PIPE_TOKEN_OUT)); + + if (PipeTokenCorrect && (Pipe_BoundEndpointNumber() == (EndpointAddress & PIPE_EPNUM_MASK))) + return true; + } + + Pipe_SelectPipe(PrevPipeNumber); + return false; +} + +uint8_t Pipe_WaitUntilReady(void) +{ + #if (USB_STREAM_TIMEOUT_MS < 0xFF) + uint8_t TimeoutMSRem = USB_STREAM_TIMEOUT_MS; + #else + uint16_t TimeoutMSRem = USB_STREAM_TIMEOUT_MS; + #endif + + for (;;) + { + if (Pipe_GetPipeToken() == PIPE_TOKEN_IN) + { + if (Pipe_IsINReceived()) + return PIPE_READYWAIT_NoError; + } + else + { + if (Pipe_IsOUTReady()) + return PIPE_READYWAIT_NoError; + } + + if (Pipe_IsStalled()) + return PIPE_READYWAIT_PipeStalled; + else if (USB_HostState == HOST_STATE_Unattached) + return PIPE_READYWAIT_DeviceDisconnected; + + if (USB_INT_HasOccurred(USB_INT_HSOFI)) + { + USB_INT_Clear(USB_INT_HSOFI); + + if (!(TimeoutMSRem--)) + return PIPE_READYWAIT_Timeout; + } + } +} + +uint8_t Pipe_Discard_Stream(uint16_t Length +#if !defined(NO_STREAM_CALLBACKS) + , StreamCallbackPtr_t Callback +#endif + ) +{ + uint8_t ErrorCode; + + Pipe_SetPipeToken(PIPE_TOKEN_IN); + + if ((ErrorCode = Pipe_WaitUntilReady())) + return ErrorCode; + + #if defined(FAST_STREAM_TRANSFERS) + uint8_t BytesRemToAlignment = (Pipe_BytesInPipe() & 0x07); + + if (Length >= 8) + { + Length -= BytesRemToAlignment; + + switch (BytesRemToAlignment) + { + default: + do + { + if (!(Pipe_IsReadWriteAllowed())) + { + Pipe_ClearIN(); + + #if !defined(NO_STREAM_CALLBACKS) + if ((Callback != NULL) && (Callback() == STREAMCALLBACK_Abort)) + return PIPE_RWSTREAM_CallbackAborted; + #endif + + if ((ErrorCode = Pipe_WaitUntilReady())) + return ErrorCode; + } + + Length -= 8; + + Pipe_Discard_Byte(); + case 7: Pipe_Discard_Byte(); + case 6: Pipe_Discard_Byte(); + case 5: Pipe_Discard_Byte(); + case 4: Pipe_Discard_Byte(); + case 3: Pipe_Discard_Byte(); + case 2: Pipe_Discard_Byte(); + case 1: Pipe_Discard_Byte(); + } while (Length >= 8); + } + } + #endif + + while (Length) + { + if (!(Pipe_IsReadWriteAllowed())) + { + Pipe_ClearIN(); + + #if !defined(NO_STREAM_CALLBACKS) + if ((Callback != NULL) && (Callback() == STREAMCALLBACK_Abort)) + return PIPE_RWSTREAM_CallbackAborted; + #endif + + if ((ErrorCode = Pipe_WaitUntilReady())) + return ErrorCode; + } + else + { + Pipe_Discard_Byte(); + Length--; + } + } + + return PIPE_RWSTREAM_NoError; +} + +/* The following abuses the C preprocessor in order to copy-past common code with slight alterations, + * so that the code needs to be written once. It is a crude form of templating to reduce code maintenance. */ + +#define TEMPLATE_FUNC_NAME Pipe_Write_Stream_LE +#define TEMPLATE_BUFFER_TYPE const void* +#define TEMPLATE_TOKEN PIPE_TOKEN_OUT +#define TEMPLATE_CLEAR_PIPE() Pipe_ClearOUT() +#define TEMPLATE_BUFFER_OFFSET(Length) 0 +#define TEMPLATE_TRANSFER_BYTE(BufferPtr) Pipe_Write_Byte(*((uint8_t*)BufferPtr++)) +#include "Template/Template_Pipe_RW.c" + +#define TEMPLATE_FUNC_NAME Pipe_Write_PStream_LE +#define TEMPLATE_BUFFER_TYPE const void* +#define TEMPLATE_TOKEN PIPE_TOKEN_OUT +#define TEMPLATE_CLEAR_PIPE() Pipe_ClearOUT() +#define TEMPLATE_BUFFER_OFFSET(Length) 0 +#define TEMPLATE_TRANSFER_BYTE(BufferPtr) Pipe_Write_Byte(pgm_read_byte((uint8_t*)BufferPtr++)) +#include "Template/Template_Pipe_RW.c" + +#define TEMPLATE_FUNC_NAME Pipe_Write_EStream_LE +#define TEMPLATE_BUFFER_TYPE const void* +#define TEMPLATE_TOKEN PIPE_TOKEN_OUT +#define TEMPLATE_CLEAR_PIPE() Pipe_ClearOUT() +#define TEMPLATE_BUFFER_OFFSET(Length) 0 +#define TEMPLATE_TRANSFER_BYTE(BufferPtr) Pipe_Write_Byte(eeprom_read_byte((uint8_t*)BufferPtr++)) +#include "Template/Template_Pipe_RW.c" + +#define TEMPLATE_FUNC_NAME Pipe_Write_Stream_BE +#define TEMPLATE_BUFFER_TYPE const void* +#define TEMPLATE_TOKEN PIPE_TOKEN_OUT +#define TEMPLATE_CLEAR_PIPE() Pipe_ClearOUT() +#define TEMPLATE_BUFFER_OFFSET(Length) (Length - 1) +#define TEMPLATE_TRANSFER_BYTE(BufferPtr) Pipe_Write_Byte(*((uint8_t*)BufferPtr--)) +#include "Template/Template_Pipe_RW.c" + +#define TEMPLATE_FUNC_NAME Pipe_Write_PStream_BE +#define TEMPLATE_BUFFER_TYPE const void* +#define TEMPLATE_TOKEN PIPE_TOKEN_OUT +#define TEMPLATE_CLEAR_PIPE() Pipe_ClearOUT() +#define TEMPLATE_BUFFER_OFFSET(Length) (Length - 1) +#define TEMPLATE_TRANSFER_BYTE(BufferPtr) Pipe_Write_Byte(pgm_read_byte((uint8_t*)BufferPtr--)) +#include "Template/Template_Pipe_RW.c" + +#define TEMPLATE_FUNC_NAME Pipe_Write_EStream_BE +#define TEMPLATE_BUFFER_TYPE const void* +#define TEMPLATE_TOKEN PIPE_TOKEN_OUT +#define TEMPLATE_CLEAR_PIPE() Pipe_ClearOUT() +#define TEMPLATE_BUFFER_OFFSET(Length) (Length - 1) +#define TEMPLATE_TRANSFER_BYTE(BufferPtr) Pipe_Write_Byte(eeprom_read_byte((uint8_t*)BufferPtr--)) +#include "Template/Template_Pipe_RW.c" + +#define TEMPLATE_FUNC_NAME Pipe_Read_Stream_LE +#define TEMPLATE_BUFFER_TYPE void* +#define TEMPLATE_TOKEN PIPE_TOKEN_IN +#define TEMPLATE_CLEAR_PIPE() Pipe_ClearIN() +#define TEMPLATE_BUFFER_OFFSET(Length) 0 +#define TEMPLATE_TRANSFER_BYTE(BufferPtr) *((uint8_t*)BufferPtr++) = Pipe_Read_Byte() +#include "Template/Template_Pipe_RW.c" + +#define TEMPLATE_FUNC_NAME Pipe_Read_EStream_LE +#define TEMPLATE_BUFFER_TYPE void* +#define TEMPLATE_TOKEN PIPE_TOKEN_IN +#define TEMPLATE_CLEAR_PIPE() Pipe_ClearIN() +#define TEMPLATE_BUFFER_OFFSET(Length) 0 +#define TEMPLATE_TRANSFER_BYTE(BufferPtr) eeprom_update_byte((uint8_t*)BufferPtr++, Pipe_Read_Byte()) +#include "Template/Template_Pipe_RW.c" + +#define TEMPLATE_FUNC_NAME Pipe_Read_Stream_BE +#define TEMPLATE_BUFFER_TYPE void* +#define TEMPLATE_TOKEN PIPE_TOKEN_IN +#define TEMPLATE_CLEAR_PIPE() Pipe_ClearIN() +#define TEMPLATE_BUFFER_OFFSET(Length) (Length - 1) +#define TEMPLATE_TRANSFER_BYTE(BufferPtr) *((uint8_t*)BufferPtr--) = Pipe_Read_Byte() +#include "Template/Template_Pipe_RW.c" + +#define TEMPLATE_FUNC_NAME Pipe_Read_EStream_BE +#define TEMPLATE_BUFFER_TYPE void* +#define TEMPLATE_TOKEN PIPE_TOKEN_IN +#define TEMPLATE_CLEAR_PIPE() Pipe_ClearIN() +#define TEMPLATE_BUFFER_OFFSET(Length) (Length - 1) +#define TEMPLATE_TRANSFER_BYTE(BufferPtr) eeprom_update_byte((uint8_t*)BufferPtr--, Pipe_Read_Byte()) +#include "Template/Template_Pipe_RW.c" + +#endif diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/Pipe.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/Pipe.h new file mode 100644 index 0000000000..0b07cbb25a --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/Pipe.h @@ -0,0 +1,1153 @@ +/* + 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 USB host pipe management definitions. + * + * This file contains structures, function prototypes and macros related to the management of the device's + * data pipes when the library is initialized in USB host mode. + * + * \note This file should not be included directly. It is automatically included as needed by the USB driver + * dispatch header located in LUFA/Drivers/USB/USB.h. + */ + +/** \ingroup Group_USB + * @defgroup Group_PipeManagement Pipe Management + * + * This module contains functions, macros and enums related to pipe management when in USB Host mode. This + * module contains the pipe management macros, as well as pipe interrupt and data send/receive functions + * for various data types. + * + * @{ + */ + +/** @defgroup Group_PipeRW Pipe Data Reading and Writing + * + * Functions, macros, variables, enums and types related to data reading and writing from and to pipes. + */ + +/** \ingroup Group_PipeRW + * @defgroup Group_PipePrimitiveRW Read/Write of Primitive Data Types + * + * Functions, macros, variables, enums and types related to data reading and writing of primitive data types + * from and to pipes. + */ + +/** \ingroup Group_PipeRW + * @defgroup Group_PipeStreamRW Read/Write of Multi-Byte Streams + * + * Functions, macros, variables, enums and types related to data reading and writing of data streams from + * and to pipes. + */ + +/** @defgroup Group_PipePacketManagement Pipe Packet Management + * + * Functions, macros, variables, enums and types related to packet management of pipes. + */ + +/** @defgroup Group_PipeControlReq Pipe Control Request Management + * + * Module for host mode request processing. This module allows for the transmission of standard, class and + * vendor control requests to the default control endpoint of an attached device while in host mode. + * + * \see Chapter 9 of the USB 2.0 specification. + */ + +#ifndef __PIPE_H__ +#define __PIPE_H__ + + /* Includes: */ + #include + #include + #include + #include + + #include "../../../Common/Common.h" + #include "../HighLevel/USBTask.h" + + #if !defined(NO_STREAM_CALLBACKS) || defined(__DOXYGEN__) + #include "../HighLevel/StreamCallbacks.h" + #endif + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_USB_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/USB/USB.h instead. + #endif + + /* Private Interface - For use in library only: */ + #if !defined(__DOXYGEN__) + /* Macros: */ + #if !defined(ENDPOINT_CONTROLEP) && !defined(__DOXYGEN__) + #define ENDPOINT_CONTROLEP 0 + #endif + #endif + + /* Public Interface - May be used in end-application: */ + /* Macros: */ + /** Mask for \ref Pipe_GetErrorFlags(), indicating that an overflow error occurred in the pipe on the received data. */ + #define PIPE_ERRORFLAG_OVERFLOW (1 << 6) + + /** Mask for \ref Pipe_GetErrorFlags(), indicating that an underflow error occurred in the pipe on the received data. */ + #define PIPE_ERRORFLAG_UNDERFLOW (1 << 5) + + /** Mask for \ref Pipe_GetErrorFlags(), indicating that a CRC error occurred in the pipe on the received data. */ + #define PIPE_ERRORFLAG_CRC16 (1 << 4) + + /** Mask for \ref Pipe_GetErrorFlags(), indicating that a hardware timeout error occurred in the pipe. */ + #define PIPE_ERRORFLAG_TIMEOUT (1 << 3) + + /** Mask for \ref Pipe_GetErrorFlags(), indicating that a hardware PID error occurred in the pipe. */ + #define PIPE_ERRORFLAG_PID (1 << 2) + + /** Mask for \ref Pipe_GetErrorFlags(), indicating that a hardware data PID error occurred in the pipe. */ + #define PIPE_ERRORFLAG_DATAPID (1 << 1) + + /** Mask for \ref Pipe_GetErrorFlags(), indicating that a hardware data toggle error occurred in the pipe. */ + #define PIPE_ERRORFLAG_DATATGL (1 << 0) + + /** Token mask for \ref Pipe_ConfigurePipe(). This sets the pipe as a SETUP token (for CONTROL type pipes), + * which will trigger a control request on the attached device when data is written to the pipe. + */ + #define PIPE_TOKEN_SETUP (0 << PTOKEN0) + + /** Token mask for \ref Pipe_ConfigurePipe(). This sets the pipe as a IN token (for non-CONTROL type pipes), + * indicating that the pipe data will flow from device to host. + */ + #define PIPE_TOKEN_IN (1 << PTOKEN0) + + /** Token mask for \ref Pipe_ConfigurePipe(). This sets the pipe as a OUT token (for non-CONTROL type pipes), + * indicating that the pipe data will flow from host to device. + */ + #define PIPE_TOKEN_OUT (2 << PTOKEN0) + + /** Mask for the bank mode selection for the \ref Pipe_ConfigurePipe() macro. This indicates that the pipe + * should have one single bank, which requires less USB FIFO memory but results in slower transfers as + * only one USB device (the AVR or the attached device) can access the pipe's bank at the one time. + */ + #define PIPE_BANK_SINGLE (0 << EPBK0) + + /** Mask for the bank mode selection for the \ref Pipe_ConfigurePipe() macro. This indicates that the pipe + * should have two banks, which requires more USB FIFO memory but results in faster transfers as one + * USB device (the AVR or the attached device) can access one bank while the other accesses the second + * bank. + */ + #define PIPE_BANK_DOUBLE (1 << EPBK0) + + /** Pipe address for the default control pipe, which always resides in address 0. This is + * defined for convenience to give more readable code when used with the pipe macros. + */ + #define PIPE_CONTROLPIPE 0 + + /** Default size of the default control pipe's bank, until altered by the Endpoint0Size value + * in the device descriptor of the attached device. + */ + #define PIPE_CONTROLPIPE_DEFAULT_SIZE 64 + + /** Pipe number mask, for masking against pipe addresses to retrieve the pipe's numerical address + * in the device. + */ + #define PIPE_PIPENUM_MASK 0x07 + + /** Total number of pipes (including the default control pipe at address 0) which may be used in + * the device. Different USB AVR models support different amounts of pipes, this value reflects + * the maximum number of pipes for the currently selected AVR model. + */ + #define PIPE_TOTAL_PIPES 7 + + /** Size in bytes of the largest pipe bank size possible in the device. Not all banks on each AVR + * model supports the largest bank size possible on the device; different pipe numbers support + * different maximum bank sizes. This value reflects the largest possible bank of any pipe on the + * currently selected USB AVR model. + */ + #define PIPE_MAX_SIZE 256 + + /** Endpoint number mask, for masking against endpoint addresses to retrieve the endpoint's + * numerical address in the attached device. + */ + #define PIPE_EPNUM_MASK 0x0F + + /** Endpoint direction mask, for masking against endpoint addresses to retrieve the endpoint's + * direction for comparing with the ENDPOINT_DESCRIPTOR_DIR_* masks. + */ + #define PIPE_EPDIR_MASK 0x80 + + /* Enums: */ + /** Enum for the possible error return codes of the Pipe_WaitUntilReady function. + * + * \ingroup Group_PipeRW + */ + enum Pipe_WaitUntilReady_ErrorCodes_t + { + PIPE_READYWAIT_NoError = 0, /**< Pipe ready for next packet, no error. */ + PIPE_READYWAIT_PipeStalled = 1, /**< The device stalled the pipe while waiting. */ + PIPE_READYWAIT_DeviceDisconnected = 2, /**< Device was disconnected from the host while waiting. */ + PIPE_READYWAIT_Timeout = 3, /**< The device failed to accept or send the next packet + * within the software timeout period set by the + * \ref USB_STREAM_TIMEOUT_MS macro. + */ + }; + + /** Enum for the possible error return codes of the Pipe_*_Stream_* functions. + * + * \ingroup Group_PipeRW + */ + enum Pipe_Stream_RW_ErrorCodes_t + { + PIPE_RWSTREAM_NoError = 0, /**< Command completed successfully, no error. */ + PIPE_RWSTREAM_PipeStalled = 1, /**< The device stalled the pipe during the transfer. */ + PIPE_RWSTREAM_DeviceDisconnected = 2, /**< Device was disconnected from the host during + * the transfer. + */ + PIPE_RWSTREAM_Timeout = 3, /**< The device failed to accept or send the next packet + * within the software timeout period set by the + * \ref USB_STREAM_TIMEOUT_MS macro. + */ + PIPE_RWSTREAM_CallbackAborted = 4, /**< Indicates that the stream's callback function aborted + * the transfer early. + */ + }; + + /* Inline Functions: */ + /** Indicates the number of bytes currently stored in the current pipes's selected bank. + * + * \note The return width of this function may differ, depending on the maximum pipe bank size + * of the selected AVR model. + * + * \ingroup Group_PipeRW + * + * \return Total number of bytes in the currently selected Pipe's FIFO buffer. + */ + static inline uint16_t Pipe_BytesInPipe(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline uint16_t Pipe_BytesInPipe(void) + { + return UPBCX; + } + + /** Returns the pipe address of the currently selected pipe. This is typically used to save the + * currently selected pipe number so that it can be restored after another pipe has been manipulated. + * + * \return Index of the currently selected pipe. + */ + static inline uint8_t Pipe_GetCurrentPipe(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline uint8_t Pipe_GetCurrentPipe(void) + { + return (UPNUM & PIPE_PIPENUM_MASK); + } + + /** Selects the given pipe number. Any pipe operations which do not require the pipe number to be + * indicated will operate on the currently selected pipe. + * + * \param[in] PipeNumber Index of the pipe to select. + */ + static inline void Pipe_SelectPipe(const uint8_t PipeNumber) ATTR_ALWAYS_INLINE; + static inline void Pipe_SelectPipe(const uint8_t PipeNumber) + { + UPNUM = PipeNumber; + } + + /** Resets the desired pipe, including the pipe banks and flags. + * + * \param[in] PipeNumber Index of the pipe to reset. + */ + static inline void Pipe_ResetPipe(const uint8_t PipeNumber) ATTR_ALWAYS_INLINE; + static inline void Pipe_ResetPipe(const uint8_t PipeNumber) + { + UPRST = (1 << PipeNumber); + UPRST = 0; + } + + /** Enables the currently selected pipe so that data can be sent and received through it to and from + * an attached device. + * + * \pre The currently selected pipe must first be configured properly via \ref Pipe_ConfigurePipe(). + */ + static inline void Pipe_EnablePipe(void) ATTR_ALWAYS_INLINE; + static inline void Pipe_EnablePipe(void) + { + UPCONX |= (1 << PEN); + } + + /** Disables the currently selected pipe so that data cannot be sent and received through it to and + * from an attached device. + */ + static inline void Pipe_DisablePipe(void) ATTR_ALWAYS_INLINE; + static inline void Pipe_DisablePipe(void) + { + UPCONX &= ~(1 << PEN); + } + + /** Determines if the currently selected pipe is enabled, but not necessarily configured. + * + * \return Boolean True if the currently selected pipe is enabled, false otherwise. + */ + static inline bool Pipe_IsEnabled(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline bool Pipe_IsEnabled(void) + { + return ((UPCONX & (1 << PEN)) ? true : false); + } + + /** Gets the current pipe token, indicating the pipe's data direction and type. + * + * \return The current pipe token, as a PIPE_TOKEN_* mask. + */ + static inline uint8_t Pipe_GetPipeToken(void) ATTR_ALWAYS_INLINE; + static inline uint8_t Pipe_GetPipeToken(void) + { + return (UPCFG0X & (0x03 << PTOKEN0)); + } + + /** Sets the token for the currently selected pipe to one of the tokens specified by the PIPE_TOKEN_* + * masks. This can be used on CONTROL type pipes, to allow for bidirectional transfer of data during + * control requests, or on regular pipes to allow for half-duplex bidirectional data transfer to devices + * which have two endpoints of opposite direction sharing the same endpoint address within the device. + * + * \param[in] Token New pipe token to set the selected pipe to, as a PIPE_TOKEN_* mask. + */ + static inline void Pipe_SetPipeToken(const uint8_t Token) ATTR_ALWAYS_INLINE; + static inline void Pipe_SetPipeToken(const uint8_t Token) + { + UPCFG0X = ((UPCFG0X & ~(0x03 << PTOKEN0)) | Token); + } + + /** Configures the currently selected pipe to allow for an unlimited number of IN requests. */ + static inline void Pipe_SetInfiniteINRequests(void) ATTR_ALWAYS_INLINE; + static inline void Pipe_SetInfiniteINRequests(void) + { + UPCONX |= (1 << INMODE); + } + + /** Configures the currently selected pipe to only allow the specified number of IN requests to be + * accepted by the pipe before it is automatically frozen. + * + * \param[in] TotalINRequests Total number of IN requests that the pipe may receive before freezing. + */ + static inline void Pipe_SetFiniteINRequests(const uint8_t TotalINRequests) ATTR_ALWAYS_INLINE; + static inline void Pipe_SetFiniteINRequests(const uint8_t TotalINRequests) + { + UPCONX &= ~(1 << INMODE); + UPINRQX = TotalINRequests; + } + + /** Determines if the currently selected pipe is configured. + * + * \return Boolean true if the selected pipe is configured, false otherwise. + */ + static inline bool Pipe_IsConfigured(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline bool Pipe_IsConfigured(void) + { + return ((UPSTAX & (1 << CFGOK)) ? true : false); + } + + /** Retrieves the endpoint number of the endpoint within the attached device that the currently selected + * pipe is bound to. + * + * \return Endpoint number the currently selected pipe is bound to. + */ + static inline uint8_t Pipe_BoundEndpointNumber(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline uint8_t Pipe_BoundEndpointNumber(void) + { + return ((UPCFG0X >> PEPNUM0) & PIPE_EPNUM_MASK); + } + + /** Sets the period between interrupts for an INTERRUPT type pipe to a specified number of milliseconds. + * + * \param[in] Milliseconds Number of milliseconds between each pipe poll. + */ + static inline void Pipe_SetInterruptPeriod(const uint8_t Milliseconds) ATTR_ALWAYS_INLINE; + static inline void Pipe_SetInterruptPeriod(const uint8_t Milliseconds) + { + UPCFG2X = Milliseconds; + } + + /** Returns a mask indicating which pipe's interrupt periods have elapsed, indicating that the pipe should + * be serviced. + * + * \return Mask whose bits indicate which pipes have interrupted. + */ + static inline uint8_t Pipe_GetPipeInterrupts(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline uint8_t Pipe_GetPipeInterrupts(void) + { + return UPINT; + } + + /** Determines if the specified pipe number has interrupted (valid only for INTERRUPT type + * pipes). + * + * \param[in] PipeNumber Index of the pipe whose interrupt flag should be tested. + * + * \return Boolean true if the specified pipe has interrupted, false otherwise. + */ + static inline bool Pipe_HasPipeInterrupted(const uint8_t PipeNumber) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline bool Pipe_HasPipeInterrupted(const uint8_t PipeNumber) + { + return ((UPINT & (1 << PipeNumber)) ? true : false); + } + + /** Unfreezes the selected pipe, allowing it to communicate with an attached device. */ + static inline void Pipe_Unfreeze(void) ATTR_ALWAYS_INLINE; + static inline void Pipe_Unfreeze(void) + { + UPCONX &= ~(1 << PFREEZE); + } + + /** Freezes the selected pipe, preventing it from communicating with an attached device. */ + static inline void Pipe_Freeze(void) ATTR_ALWAYS_INLINE; + static inline void Pipe_Freeze(void) + { + UPCONX |= (1 << PFREEZE); + } + + /** Determines if the currently selected pipe is frozen, and not able to accept data. + * + * \return Boolean true if the currently selected pipe is frozen, false otherwise. + */ + static inline bool Pipe_IsFrozen(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline bool Pipe_IsFrozen(void) + { + return ((UPCONX & (1 << PFREEZE)) ? true : false); + } + + /** Clears the master pipe error flag. */ + static inline void Pipe_ClearError(void) ATTR_ALWAYS_INLINE; + static inline void Pipe_ClearError(void) + { + UPINTX &= ~(1 << PERRI); + } + + /** Determines if the master pipe error flag is set for the currently selected pipe, indicating that + * some sort of hardware error has occurred on the pipe. + * + * \see \ref Pipe_GetErrorFlags() macro for information on retrieving the exact error flag. + * + * \return Boolean true if an error has occurred on the selected pipe, false otherwise. + */ + static inline bool Pipe_IsError(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline bool Pipe_IsError(void) + { + return ((UPINTX & (1 << PERRI)) ? true : false); + } + + /** Clears all the currently selected pipe's hardware error flags, but does not clear the master error + * flag for the pipe. + */ + static inline void Pipe_ClearErrorFlags(void) ATTR_ALWAYS_INLINE; + static inline void Pipe_ClearErrorFlags(void) + { + UPERRX = 0; + } + + /** Gets a mask of the hardware error flags which have occurred on the currently selected pipe. This + * value can then be masked against the PIPE_ERRORFLAG_* masks to determine what error has occurred. + * + * \return Mask comprising of PIPE_ERRORFLAG_* bits indicating what error has occurred on the selected pipe. + */ + static inline uint8_t Pipe_GetErrorFlags(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline uint8_t Pipe_GetErrorFlags(void) + { + return ((UPERRX & (PIPE_ERRORFLAG_CRC16 | PIPE_ERRORFLAG_TIMEOUT | + PIPE_ERRORFLAG_PID | PIPE_ERRORFLAG_DATAPID | + PIPE_ERRORFLAG_DATATGL)) | + (UPSTAX & (PIPE_ERRORFLAG_OVERFLOW | PIPE_ERRORFLAG_UNDERFLOW))); + } + + /** Determines if the currently selected pipe may be read from (if data is waiting in the pipe + * bank and the pipe is an IN direction, or if the bank is not yet full if the pipe is an OUT + * direction). This function will return false if an error has occurred in the pipe, or if the pipe + * is an IN direction and no packet (or an empty packet) has been received, or if the pipe is an OUT + * direction and the pipe bank is full. + * + * \note This function is not valid on CONTROL type pipes. + * + * \ingroup Group_PipePacketManagement + * + * \return Boolean true if the currently selected pipe may be read from or written to, depending on its direction. + */ + static inline bool Pipe_IsReadWriteAllowed(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline bool Pipe_IsReadWriteAllowed(void) + { + return ((UPINTX & (1 << RWAL)) ? true : false); + } + + /** Determines if an IN request has been received on the currently selected pipe. + * + * \ingroup Group_PipePacketManagement + * + * \return Boolean true if the current pipe has received an IN packet, false otherwise. + */ + static inline bool Pipe_IsINReceived(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline bool Pipe_IsINReceived(void) + { + return ((UPINTX & (1 << RXINI)) ? true : false); + } + + /** Determines if the currently selected pipe is ready to send an OUT request. + * + * \ingroup Group_PipePacketManagement + * + * \return Boolean true if the current pipe is ready for an OUT packet, false otherwise. + */ + static inline bool Pipe_IsOUTReady(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline bool Pipe_IsOUTReady(void) + { + return ((UPINTX & (1 << TXOUTI)) ? true : false); + } + + /** Determines if no SETUP request is currently being sent to the attached device on the selected + * CONTROL type pipe. + * + * \ingroup Group_PipePacketManagement + * + * \return Boolean true if the current pipe is ready for a SETUP packet, false otherwise. + */ + static inline bool Pipe_IsSETUPSent(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline bool Pipe_IsSETUPSent(void) + { + return ((UPINTX & (1 << TXSTPI)) ? true : false); + } + + /** Sends the currently selected CONTROL type pipe's contents to the device as a SETUP packet. + * + * \ingroup Group_PipePacketManagement + */ + static inline void Pipe_ClearSETUP(void) ATTR_ALWAYS_INLINE; + static inline void Pipe_ClearSETUP(void) + { + UPINTX &= ~((1 << TXSTPI) | (1 << FIFOCON)); + } + + /** Acknowledges the reception of a setup IN request from the attached device on the currently selected + * pipe, freeing the bank ready for the next packet. + * + * \ingroup Group_PipePacketManagement + */ + static inline void Pipe_ClearIN(void) ATTR_ALWAYS_INLINE; + static inline void Pipe_ClearIN(void) + { + UPINTX &= ~((1 << RXINI) | (1 << FIFOCON)); + } + + /** Sends the currently selected pipe's contents to the device as an OUT packet on the selected pipe, freeing + * the bank ready for the next packet. + * + * \ingroup Group_PipePacketManagement + */ + static inline void Pipe_ClearOUT(void) ATTR_ALWAYS_INLINE; + static inline void Pipe_ClearOUT(void) + { + UPINTX &= ~((1 << TXOUTI) | (1 << FIFOCON)); + } + + /** Determines if the device sent a NAK (Negative Acknowledge) in response to the last sent packet on + * the currently selected pipe. This occurs when the host sends a packet to the device, but the device + * is not currently ready to handle the packet (i.e. its endpoint banks are full). Once a NAK has been + * received, it must be cleared using \ref Pipe_ClearNAKReceived() before the previous (or any other) packet + * can be re-sent. + * + * \ingroup Group_PipePacketManagement + * + * \return Boolean true if an NAK has been received on the current pipe, false otherwise. + */ + static inline bool Pipe_IsNAKReceived(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline bool Pipe_IsNAKReceived(void) + { + return ((UPINTX & (1 << NAKEDI)) ? true : false); + } + + /** Clears the NAK condition on the currently selected pipe. + * + * \ingroup Group_PipePacketManagement + * + * \see \ref Pipe_IsNAKReceived() for more details. + */ + static inline void Pipe_ClearNAKReceived(void) ATTR_ALWAYS_INLINE; + static inline void Pipe_ClearNAKReceived(void) + { + UPINTX &= ~(1 << NAKEDI); + } + + /** Determines if the currently selected pipe has had the STALL condition set by the attached device. + * + * \ingroup Group_PipePacketManagement + * + * \return Boolean true if the current pipe has been stalled by the attached device, false otherwise. + */ + static inline bool Pipe_IsStalled(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline bool Pipe_IsStalled(void) + { + return ((UPINTX & (1 << RXSTALLI)) ? true : false); + } + + /** Clears the STALL condition detection flag on the currently selected pipe, but does not clear the + * STALL condition itself (this must be done via a ClearFeature control request to the device). + * + * \ingroup Group_PipePacketManagement + */ + static inline void Pipe_ClearStall(void) ATTR_ALWAYS_INLINE; + static inline void Pipe_ClearStall(void) + { + UPINTX &= ~(1 << RXSTALLI); + } + + /** Reads one byte from the currently selected pipe's bank, for OUT direction pipes. + * + * \ingroup Group_PipePrimitiveRW + * + * \return Next byte in the currently selected pipe's FIFO buffer. + */ + static inline uint8_t Pipe_Read_Byte(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline uint8_t Pipe_Read_Byte(void) + { + return UPDATX; + } + + /** Writes one byte from the currently selected pipe's bank, for IN direction pipes. + * + * \ingroup Group_PipePrimitiveRW + * + * \param[in] Byte Next byte to write into the the currently selected pipe's FIFO buffer. + */ + static inline void Pipe_Write_Byte(const uint8_t Byte) ATTR_ALWAYS_INLINE; + static inline void Pipe_Write_Byte(const uint8_t Byte) + { + UPDATX = Byte; + } + + /** Discards one byte from the currently selected pipe's bank, for OUT direction pipes. + * + * \ingroup Group_PipePrimitiveRW + */ + static inline void Pipe_Discard_Byte(void) ATTR_ALWAYS_INLINE; + static inline void Pipe_Discard_Byte(void) + { + uint8_t Dummy; + + Dummy = UPDATX; + } + + /** Reads two bytes from the currently selected pipe's bank in little endian format, for OUT + * direction pipes. + * + * \ingroup Group_PipePrimitiveRW + * + * \return Next word in the currently selected pipe's FIFO buffer. + */ + static inline uint16_t Pipe_Read_Word_LE(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline uint16_t Pipe_Read_Word_LE(void) + { + union + { + uint16_t Word; + uint8_t Bytes[2]; + } Data; + + Data.Bytes[0] = UPDATX; + Data.Bytes[1] = UPDATX; + + return Data.Word; + } + + /** Reads two bytes from the currently selected pipe's bank in big endian format, for OUT + * direction pipes. + * + * \ingroup Group_PipePrimitiveRW + * + * \return Next word in the currently selected pipe's FIFO buffer. + */ + static inline uint16_t Pipe_Read_Word_BE(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline uint16_t Pipe_Read_Word_BE(void) + { + union + { + uint16_t Word; + uint8_t Bytes[2]; + } Data; + + Data.Bytes[1] = UPDATX; + Data.Bytes[0] = UPDATX; + + return Data.Word; + } + + /** Writes two bytes to the currently selected pipe's bank in little endian format, for IN + * direction pipes. + * + * \ingroup Group_PipePrimitiveRW + * + * \param[in] Word Next word to write to the currently selected pipe's FIFO buffer. + */ + static inline void Pipe_Write_Word_LE(const uint16_t Word) ATTR_ALWAYS_INLINE; + static inline void Pipe_Write_Word_LE(const uint16_t Word) + { + UPDATX = (Word & 0xFF); + UPDATX = (Word >> 8); + } + + /** Writes two bytes to the currently selected pipe's bank in big endian format, for IN + * direction pipes. + * + * \ingroup Group_PipePrimitiveRW + * + * \param[in] Word Next word to write to the currently selected pipe's FIFO buffer. + */ + static inline void Pipe_Write_Word_BE(const uint16_t Word) ATTR_ALWAYS_INLINE; + static inline void Pipe_Write_Word_BE(const uint16_t Word) + { + UPDATX = (Word >> 8); + UPDATX = (Word & 0xFF); + } + + /** Discards two bytes from the currently selected pipe's bank, for OUT direction pipes. + * + * \ingroup Group_PipePrimitiveRW + */ + static inline void Pipe_Discard_Word(void) ATTR_ALWAYS_INLINE; + static inline void Pipe_Discard_Word(void) + { + uint8_t Dummy; + + Dummy = UPDATX; + Dummy = UPDATX; + } + + /** Reads four bytes from the currently selected pipe's bank in little endian format, for OUT + * direction pipes. + * + * \ingroup Group_PipePrimitiveRW + * + * \return Next double word in the currently selected pipe's FIFO buffer. + */ + static inline uint32_t Pipe_Read_DWord_LE(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline uint32_t Pipe_Read_DWord_LE(void) + { + union + { + uint32_t DWord; + uint8_t Bytes[4]; + } Data; + + Data.Bytes[0] = UPDATX; + Data.Bytes[1] = UPDATX; + Data.Bytes[2] = UPDATX; + Data.Bytes[3] = UPDATX; + + return Data.DWord; + } + + /** Reads four bytes from the currently selected pipe's bank in big endian format, for OUT + * direction pipes. + * + * \ingroup Group_PipePrimitiveRW + * + * \return Next double word in the currently selected pipe's FIFO buffer. + */ + static inline uint32_t Pipe_Read_DWord_BE(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline uint32_t Pipe_Read_DWord_BE(void) + { + union + { + uint32_t DWord; + uint8_t Bytes[4]; + } Data; + + Data.Bytes[3] = UPDATX; + Data.Bytes[2] = UPDATX; + Data.Bytes[1] = UPDATX; + Data.Bytes[0] = UPDATX; + + return Data.DWord; + } + + /** Writes four bytes to the currently selected pipe's bank in little endian format, for IN + * direction pipes. + * + * \ingroup Group_PipePrimitiveRW + * + * \param[in] DWord Next double word to write to the currently selected pipe's FIFO buffer. + */ + static inline void Pipe_Write_DWord_LE(const uint32_t DWord) ATTR_ALWAYS_INLINE; + static inline void Pipe_Write_DWord_LE(const uint32_t DWord) + { + UPDATX = (DWord & 0xFF); + UPDATX = (DWord >> 8); + UPDATX = (DWord >> 16); + UPDATX = (DWord >> 24); + } + + /** Writes four bytes to the currently selected pipe's bank in big endian format, for IN + * direction pipes. + * + * \ingroup Group_PipePrimitiveRW + * + * \param[in] DWord Next double word to write to the currently selected pipe's FIFO buffer. + */ + static inline void Pipe_Write_DWord_BE(const uint32_t DWord) ATTR_ALWAYS_INLINE; + static inline void Pipe_Write_DWord_BE(const uint32_t DWord) + { + UPDATX = (DWord >> 24); + UPDATX = (DWord >> 16); + UPDATX = (DWord >> 8); + UPDATX = (DWord & 0xFF); + } + + /** Discards four bytes from the currently selected pipe's bank, for OUT direction pipes. + * + * \ingroup Group_PipePrimitiveRW + */ + static inline void Pipe_Discard_DWord(void) ATTR_ALWAYS_INLINE; + static inline void Pipe_Discard_DWord(void) + { + uint8_t Dummy; + + Dummy = UPDATX; + Dummy = UPDATX; + Dummy = UPDATX; + Dummy = UPDATX; + } + + /* External Variables: */ + /** Global indicating the maximum packet size of the default control pipe located at address + * 0 in the device. This value is set to the value indicated in the attached device's device + * descriptor once the USB interface is initialized into host mode and a device is attached + * to the USB bus. + * + * \note This variable should be treated as read-only in the user application, and never manually + * changed in value. + */ + extern uint8_t USB_ControlPipeSize; + + /* Function Prototypes: */ + #if !defined(NO_STREAM_CALLBACKS) || defined(__DOXYGEN__) + #define __CALLBACK_PARAM , StreamCallbackPtr_t Callback + #else + #define __CALLBACK_PARAM + #endif + + /** Configures the specified pipe number with the given pipe type, token, target endpoint number in the + * attached device, bank size and banking mode. Pipes should be allocated in ascending order by their + * address in the device (i.e. pipe 1 should be configured before pipe 2 and so on) to prevent fragmentation + * of the USB FIFO memory. + * + * The pipe type may be one of the EP_TYPE_* macros listed in LowLevel.h, the token may be one of the + * PIPE_TOKEN_* masks. + * + * The bank size must indicate the maximum packet size that the pipe can handle. Different pipe + * numbers can handle different maximum packet sizes - refer to the chosen USB AVR's datasheet to + * determine the maximum bank size for each pipe. + * + * The banking mode may be either \ref PIPE_BANK_SINGLE or \ref PIPE_BANK_DOUBLE. + * + * A newly configured pipe is frozen by default, and must be unfrozen before use via the \ref Pipe_Unfreeze() + * before being used. Pipes should be kept frozen unless waiting for data from a device while in IN mode, or + * sending data to the device in OUT mode. IN type pipes are also automatically configured to accept infinite + * numbers of IN requests without automatic freezing - this can be overridden by a call to + * \ref Pipe_SetFiniteINRequests(). + * + * \note The default control pipe should not be manually configured by the user application, as it + * is automatically configured by the library internally. + * \n\n + * + * \note This routine will select the specified pipe, and the pipe will remain selected once the + * routine completes regardless of if the pipe configuration succeeds. + * + * \return Boolean true if the configuration is successful, false otherwise. + */ + bool Pipe_ConfigurePipe(const uint8_t Number, + const uint8_t Type, + const uint8_t Token, + const uint8_t EndpointNumber, + const uint16_t Size, + const uint8_t Banks); + + /** Spin-loops until the currently selected non-control pipe is ready for the next packed of data to be read + * or written to it, aborting in the case of an error condition (such as a timeout or device disconnect). + * + * \ingroup Group_PipeRW + * + * \return A value from the Pipe_WaitUntilReady_ErrorCodes_t enum. + */ + uint8_t Pipe_WaitUntilReady(void); + + /** Determines if a pipe has been bound to the given device endpoint address. If a pipe which is bound to the given + * endpoint is found, it is automatically selected. + * + * \param[in] EndpointAddress Address and direction mask of the endpoint within the attached device to check. + * + * \return Boolean true if a pipe bound to the given endpoint address of the specified direction is found, false + * otherwise. + */ + bool Pipe_IsEndpointBound(const uint8_t EndpointAddress); + + /** Reads and discards the given number of bytes from the pipe, discarding fully read packets from the host + * as needed. The last packet is not automatically discarded once the remaining bytes has been read; the + * user is responsible for manually discarding the last packet from the device via the \ref Pipe_ClearIN() macro. + * Between each USB packet, the given stream callback function is executed repeatedly until the next packet is ready, + * allowing for early aborts of stream transfers. + * + * The callback routine should be created according to the information in \ref Group_StreamCallbacks. + * If the token NO_STREAM_CALLBACKS is passed via the -D option to the compiler, stream callbacks are + * disabled and this function has the Callback parameter omitted. + * + * The pipe token is set automatically, thus this can be used on bi-directional pipes directly without + * having to explicitly change the data direction with a call to \ref Pipe_SetPipeToken(). + * + * \ingroup Group_PipeStreamRW + * + * \param[in] Length Number of bytes to send via the currently selected pipe. + * \param[in] Callback Name of a callback routine to call between successive USB packet transfers, NULL if no callback. + * + * \return A value from the \ref Pipe_Stream_RW_ErrorCodes_t enum. + */ + uint8_t Pipe_Discard_Stream(uint16_t Length + __CALLBACK_PARAM); + + /** Writes the given number of bytes to the pipe from the given buffer in little endian, + * sending full packets to the device as needed. The last packet filled is not automatically sent; + * the user is responsible for manually sending the last written packet to the host via the + * \ref Pipe_ClearOUT() macro. Between each USB packet, the given stream callback function is + * executed repeatedly until the next packet is ready, allowing for early aborts of stream transfers. + * + * The callback routine should be created according to the information in \ref Group_StreamCallbacks. + * If the token NO_STREAM_CALLBACKS is passed via the -D option to the compiler, stream callbacks are + * disabled and this function has the Callback parameter omitted. + * + * The pipe token is set automatically, thus this can be used on bi-directional pipes directly without + * having to explicitly change the data direction with a call to \ref Pipe_SetPipeToken(). + * + * \ingroup Group_PipeStreamRW + * + * \param[in] Buffer Pointer to the source data buffer to read from. + * \param[in] Length Number of bytes to read for the currently selected pipe into the buffer. + * \param[in] Callback Name of a callback routine to call between successive USB packet transfers, NULL if no callback. + * + * \return A value from the \ref Pipe_Stream_RW_ErrorCodes_t enum. + */ + uint8_t Pipe_Write_Stream_LE(const void* Buffer, + uint16_t Length + __CALLBACK_PARAM) ATTR_NON_NULL_PTR_ARG(1); + + /** EEPROM buffer source version of \ref Pipe_Write_Stream_LE(). + * + * \ingroup Group_PipeStreamRW + * + * \param[in] Buffer Pointer to the source data buffer to read from. + * \param[in] Length Number of bytes to read for the currently selected pipe into the buffer. + * \param[in] Callback Name of a callback routine to call between successive USB packet transfers, NULL if no callback. + * + * \return A value from the \ref Pipe_Stream_RW_ErrorCodes_t enum. + */ + uint8_t Pipe_Write_EStream_LE(const void* Buffer, + uint16_t Length + __CALLBACK_PARAM) ATTR_NON_NULL_PTR_ARG(1); + + /** FLASH buffer source version of \ref Pipe_Write_Stream_LE(). + * + * \pre The FLASH data must be located in the first 64KB of FLASH for this function to work correctly. + * + * \ingroup Group_PipeStreamRW + * + * \param[in] Buffer Pointer to the source data buffer to read from. + * \param[in] Length Number of bytes to read for the currently selected pipe into the buffer. + * \param[in] Callback Name of a callback routine to call between successive USB packet transfers, NULL if no callback. + * + * \return A value from the \ref Pipe_Stream_RW_ErrorCodes_t enum. + */ + uint8_t Pipe_Write_PStream_LE(const void* Buffer, + uint16_t Length + __CALLBACK_PARAM) ATTR_NON_NULL_PTR_ARG(1); + + /** Writes the given number of bytes to the pipe from the given buffer in big endian, + * sending full packets to the device as needed. The last packet filled is not automatically sent; + * the user is responsible for manually sending the last written packet to the host via the + * \ref Pipe_ClearOUT() macro. Between each USB packet, the given stream callback function is + * executed repeatedly until the next packet is ready, allowing for early aborts of stream transfers. + * + * The callback routine should be created according to the information in \ref Group_StreamCallbacks. + * If the token NO_STREAM_CALLBACKS is passed via the -D option to the compiler, stream callbacks are + * disabled and this function has the Callback parameter omitted. + * + * The pipe token is set automatically, thus this can be used on bi-directional pipes directly without + * having to explicitly change the data direction with a call to \ref Pipe_SetPipeToken(). + * + * \ingroup Group_PipeStreamRW + * + * \param[in] Buffer Pointer to the source data buffer to read from. + * \param[in] Length Number of bytes to read for the currently selected pipe into the buffer. + * \param[in] Callback Name of a callback routine to call between successive USB packet transfers, NULL if no callback. + * + * \return A value from the \ref Pipe_Stream_RW_ErrorCodes_t enum. + */ + uint8_t Pipe_Write_Stream_BE(const void* Buffer, + uint16_t Length + __CALLBACK_PARAM) ATTR_NON_NULL_PTR_ARG(1); + + /** EEPROM buffer source version of \ref Pipe_Write_Stream_BE(). + * + * \ingroup Group_PipeStreamRW + * + * \param[in] Buffer Pointer to the source data buffer to read from. + * \param[in] Length Number of bytes to read for the currently selected pipe into the buffer. + * \param[in] Callback Name of a callback routine to call between successive USB packet transfers, NULL if no callback. + * + * \return A value from the \ref Pipe_Stream_RW_ErrorCodes_t enum. + */ + uint8_t Pipe_Write_EStream_BE(const void* Buffer, + uint16_t Length + __CALLBACK_PARAM) ATTR_NON_NULL_PTR_ARG(1); + + /** FLASH buffer source version of \ref Pipe_Write_Stream_BE(). + * + * \pre The FLASH data must be located in the first 64KB of FLASH for this function to work correctly. + * + * \ingroup Group_PipeStreamRW + * + * \param[in] Buffer Pointer to the source data buffer to read from. + * \param[in] Length Number of bytes to read for the currently selected pipe into the buffer. + * \param[in] Callback Name of a callback routine to call between successive USB packet transfers, NULL if no callback. + * + * \return A value from the \ref Pipe_Stream_RW_ErrorCodes_t enum. + */ + uint8_t Pipe_Write_PStream_BE(const void* Buffer, + uint16_t Length + __CALLBACK_PARAM) ATTR_NON_NULL_PTR_ARG(1); + + /** Reads the given number of bytes from the pipe into the given buffer in little endian, + * sending full packets to the device as needed. The last packet filled is not automatically sent; + * the user is responsible for manually sending the last written packet to the host via the + * \ref Pipe_ClearIN() macro. Between each USB packet, the given stream callback function is + * executed repeatedly until the next packet is ready, allowing for early aborts of stream transfers. + * + * The callback routine should be created according to the information in \ref Group_StreamCallbacks. + * If the token NO_STREAM_CALLBACKS is passed via the -D option to the compiler, stream callbacks are + * disabled and this function has the Callback parameter omitted. + * + * The pipe token is set automatically, thus this can be used on bi-directional pipes directly without + * having to explicitly change the data direction with a call to \ref Pipe_SetPipeToken(). + * + * \ingroup Group_PipeStreamRW + * + * \param[out] Buffer Pointer to the source data buffer to write to. + * \param[in] Length Number of bytes to read for the currently selected pipe to read from. + * \param[in] Callback Name of a callback routine to call between successive USB packet transfers, NULL if no callback. + * + * \return A value from the \ref Pipe_Stream_RW_ErrorCodes_t enum. + */ + uint8_t Pipe_Read_Stream_LE(void* Buffer, + uint16_t Length + __CALLBACK_PARAM) ATTR_NON_NULL_PTR_ARG(1); + + /** EEPROM buffer source version of \ref Pipe_Read_Stream_LE(). + * + * \ingroup Group_PipeStreamRW + * + * \param[out] Buffer Pointer to the source data buffer to write to. + * \param[in] Length Number of bytes to read for the currently selected pipe to read from. + * \param[in] Callback Name of a callback routine to call between successive USB packet transfers, NULL if no callback. + * + * \return A value from the \ref Pipe_Stream_RW_ErrorCodes_t enum. + */ + uint8_t Pipe_Read_EStream_LE(void* Buffer, + uint16_t Length + __CALLBACK_PARAM) ATTR_NON_NULL_PTR_ARG(1); + + /** Reads the given number of bytes from the pipe into the given buffer in big endian, + * sending full packets to the device as needed. The last packet filled is not automatically sent; + * the user is responsible for manually sending the last written packet to the host via the + * \ref Pipe_ClearIN() macro. Between each USB packet, the given stream callback function is + * executed repeatedly until the next packet is ready, allowing for early aborts of stream transfers. + * + * The callback routine should be created according to the information in \ref Group_StreamCallbacks. + * If the token NO_STREAM_CALLBACKS is passed via the -D option to the compiler, stream callbacks are + * disabled and this function has the Callback parameter omitted. + * + * The pipe token is set automatically, thus this can be used on bi-directional pipes directly without + * having to explicitly change the data direction with a call to \ref Pipe_SetPipeToken(). + * + * \ingroup Group_PipeStreamRW + * + * \param[out] Buffer Pointer to the source data buffer to write to. + * \param[in] Length Number of bytes to read for the currently selected pipe to read from. + * \param[in] Callback Name of a callback routine to call between successive USB packet transfers, NULL if no callback. + * + * \return A value from the \ref Pipe_Stream_RW_ErrorCodes_t enum. + */ + uint8_t Pipe_Read_Stream_BE(void* Buffer, + uint16_t Length + __CALLBACK_PARAM) ATTR_NON_NULL_PTR_ARG(1); + + /** EEPROM buffer source version of \ref Pipe_Read_Stream_BE(). + * + * \ingroup Group_PipeStreamRW + * + * \param[out] Buffer Pointer to the source data buffer to write to. + * \param[in] Length Number of bytes to read for the currently selected pipe to read from. + * \param[in] Callback Name of a callback routine to call between successive USB packet transfers, NULL if no callback. + * + * \return A value from the \ref Pipe_Stream_RW_ErrorCodes_t enum. + */ + uint8_t Pipe_Read_EStream_BE(void* Buffer, + uint16_t Length + __CALLBACK_PARAM) ATTR_NON_NULL_PTR_ARG(1); + + /* Private Interface - For use in library only: */ + #if !defined(__DOXYGEN__) + /* Function Prototypes: */ + void Pipe_ClearPipes(void); + + /* Inline Functions: */ + static inline uint8_t Pipe_BytesToEPSizeMask(const uint16_t Bytes) ATTR_WARN_UNUSED_RESULT ATTR_CONST ATTR_ALWAYS_INLINE; + static inline uint8_t Pipe_BytesToEPSizeMask(const uint16_t Bytes) + { + uint8_t MaskVal = 0; + uint16_t CheckBytes = 8; + + while ((CheckBytes < Bytes) && (CheckBytes < PIPE_MAX_SIZE)) + { + MaskVal++; + CheckBytes <<= 1; + } + + return (MaskVal << EPSIZE0); + } + + #endif + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/Template/Template_Endpoint_Control_R.c b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/Template/Template_Endpoint_Control_R.c new file mode 100644 index 0000000000..43abe6e1e5 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/Template/Template_Endpoint_Control_R.c @@ -0,0 +1,45 @@ +uint8_t TEMPLATE_FUNC_NAME (void* Buffer, + uint16_t Length) +{ + uint8_t* DataStream = ((uint8_t*)Buffer + TEMPLATE_BUFFER_OFFSET(Length)); + + if (!(Length)) + Endpoint_ClearOUT(); + + while (Length) + { + if (Endpoint_IsSETUPReceived()) + return ENDPOINT_RWCSTREAM_HostAborted; + + if (USB_DeviceState == DEVICE_STATE_Unattached) + return ENDPOINT_RWCSTREAM_DeviceDisconnected; + else if (USB_DeviceState == DEVICE_STATE_Suspended) + return ENDPOINT_RWCSTREAM_BusSuspended; + + if (Endpoint_IsOUTReceived()) + { + while (Length && Endpoint_BytesInEndpoint()) + { + TEMPLATE_TRANSFER_BYTE(DataStream); + Length--; + } + + Endpoint_ClearOUT(); + } + } + + while (!(Endpoint_IsINReady())) + { + if (USB_DeviceState == DEVICE_STATE_Unattached) + return ENDPOINT_RWCSTREAM_DeviceDisconnected; + else if (USB_DeviceState == DEVICE_STATE_Suspended) + return ENDPOINT_RWCSTREAM_BusSuspended; + } + + return ENDPOINT_RWCSTREAM_NoError; +} + + +#undef TEMPLATE_BUFFER_OFFSET +#undef TEMPLATE_FUNC_NAME +#undef TEMPLATE_TRANSFER_BYTE \ No newline at end of file diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/Template/Template_Endpoint_Control_W.c b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/Template/Template_Endpoint_Control_W.c new file mode 100644 index 0000000000..dc2c37dfc5 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/Template/Template_Endpoint_Control_W.c @@ -0,0 +1,54 @@ +uint8_t TEMPLATE_FUNC_NAME (const void* Buffer, + uint16_t Length) +{ + uint8_t* DataStream = ((uint8_t*)Buffer + TEMPLATE_BUFFER_OFFSET(Length)); + bool LastPacketFull = false; + + if (Length > USB_ControlRequest.wLength) + Length = USB_ControlRequest.wLength; + else if (!(Length)) + Endpoint_ClearIN(); + + while (Length || LastPacketFull) + { + if (Endpoint_IsSETUPReceived()) + return ENDPOINT_RWCSTREAM_HostAborted; + + if (Endpoint_IsOUTReceived()) + break; + + if (USB_DeviceState == DEVICE_STATE_Unattached) + return ENDPOINT_RWCSTREAM_DeviceDisconnected; + else if (USB_DeviceState == DEVICE_STATE_Suspended) + return ENDPOINT_RWCSTREAM_BusSuspended; + + if (Endpoint_IsINReady()) + { + uint8_t BytesInEndpoint = Endpoint_BytesInEndpoint(); + + while (Length && (BytesInEndpoint < USB_ControlEndpointSize)) + { + TEMPLATE_TRANSFER_BYTE(DataStream); + Length--; + BytesInEndpoint++; + } + + LastPacketFull = (BytesInEndpoint == USB_ControlEndpointSize); + Endpoint_ClearIN(); + } + } + + while (!(Endpoint_IsOUTReceived())) + { + if (USB_DeviceState == DEVICE_STATE_Unattached) + return ENDPOINT_RWCSTREAM_DeviceDisconnected; + else if (USB_DeviceState == DEVICE_STATE_Suspended) + return ENDPOINT_RWCSTREAM_BusSuspended; + } + + return ENDPOINT_RWCSTREAM_NoError; +} + +#undef TEMPLATE_BUFFER_OFFSET +#undef TEMPLATE_FUNC_NAME +#undef TEMPLATE_TRANSFER_BYTE \ No newline at end of file diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/Template/Template_Endpoint_RW.c b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/Template/Template_Endpoint_RW.c new file mode 100644 index 0000000000..fc9df951da --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/Template/Template_Endpoint_RW.c @@ -0,0 +1,79 @@ +uint8_t TEMPLATE_FUNC_NAME (TEMPLATE_BUFFER_TYPE Buffer, + uint16_t Length + __CALLBACK_PARAM) +{ + uint8_t* DataStream = ((uint8_t*)Buffer + TEMPLATE_BUFFER_OFFSET(Length)); + uint8_t ErrorCode; + + if ((ErrorCode = Endpoint_WaitUntilReady())) + return ErrorCode; + + #if defined(FAST_STREAM_TRANSFERS) + uint8_t BytesRemToAlignment = (Endpoint_BytesInEndpoint() & 0x07); + + if (Length >= 8) + { + Length -= BytesRemToAlignment; + + switch (BytesRemToAlignment) + { + default: + do + { + if (!(Endpoint_IsReadWriteAllowed())) + { + TEMPLATE_CLEAR_ENDPOINT(); + + #if !defined(NO_STREAM_CALLBACKS) + if ((Callback != NULL) && (Callback() == STREAMCALLBACK_Abort)) + return ENDPOINT_RWSTREAM_CallbackAborted; + #endif + + if ((ErrorCode = Endpoint_WaitUntilReady())) + return ErrorCode; + } + + Length -= 8; + + TEMPLATE_TRANSFER_BYTE(DataStream); + case 7: TEMPLATE_TRANSFER_BYTE(DataStream); + case 6: TEMPLATE_TRANSFER_BYTE(DataStream); + case 5: TEMPLATE_TRANSFER_BYTE(DataStream); + case 4: TEMPLATE_TRANSFER_BYTE(DataStream); + case 3: TEMPLATE_TRANSFER_BYTE(DataStream); + case 2: TEMPLATE_TRANSFER_BYTE(DataStream); + case 1: TEMPLATE_TRANSFER_BYTE(DataStream); + } while (Length >= 8); + } + } + #endif + + while (Length) + { + if (!(Endpoint_IsReadWriteAllowed())) + { + TEMPLATE_CLEAR_ENDPOINT(); + + #if !defined(NO_STREAM_CALLBACKS) + if ((Callback != NULL) && (Callback() == STREAMCALLBACK_Abort)) + return ENDPOINT_RWSTREAM_CallbackAborted; + #endif + + if ((ErrorCode = Endpoint_WaitUntilReady())) + return ErrorCode; + } + else + { + TEMPLATE_TRANSFER_BYTE(DataStream); + Length--; + } + } + + return ENDPOINT_RWSTREAM_NoError; +} + +#undef TEMPLATE_FUNC_NAME +#undef TEMPLATE_BUFFER_TYPE +#undef TEMPLATE_TRANSFER_BYTE +#undef TEMPLATE_CLEAR_ENDPOINT +#undef TEMPLATE_BUFFER_OFFSET \ No newline at end of file diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/Template/Template_Pipe_RW.c b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/Template/Template_Pipe_RW.c new file mode 100644 index 0000000000..fb64dd837b --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/Template/Template_Pipe_RW.c @@ -0,0 +1,82 @@ +uint8_t TEMPLATE_FUNC_NAME (TEMPLATE_BUFFER_TYPE Buffer, + uint16_t Length + __CALLBACK_PARAM) +{ + uint8_t* DataStream = ((uint8_t*)Buffer + TEMPLATE_BUFFER_OFFSET(Length)); + uint8_t ErrorCode; + + Pipe_SetPipeToken(TEMPLATE_TOKEN); + + if ((ErrorCode = Pipe_WaitUntilReady())) + return ErrorCode; + + #if defined(FAST_STREAM_TRANSFERS) + uint8_t BytesRemToAlignment = (Pipe_BytesInPipe() & 0x07); + + if (Length >= 8) + { + Length -= BytesRemToAlignment; + + switch (BytesRemToAlignment) + { + default: + do + { + if (!(Pipe_IsReadWriteAllowed())) + { + TEMPLATE_CLEAR_PIPE(); + + #if !defined(NO_STREAM_CALLBACKS) + if ((Callback != NULL) && (Callback() == STREAMCALLBACK_Abort)) + return PIPE_RWSTREAM_CallbackAborted; + #endif + + if ((ErrorCode = Pipe_WaitUntilReady())) + return ErrorCode; + } + + Length -= 8; + + TEMPLATE_TRANSFER_BYTE(DataStream); + case 7: TEMPLATE_TRANSFER_BYTE(DataStream); + case 6: TEMPLATE_TRANSFER_BYTE(DataStream); + case 5: TEMPLATE_TRANSFER_BYTE(DataStream); + case 4: TEMPLATE_TRANSFER_BYTE(DataStream); + case 3: TEMPLATE_TRANSFER_BYTE(DataStream); + case 2: TEMPLATE_TRANSFER_BYTE(DataStream); + case 1: TEMPLATE_TRANSFER_BYTE(DataStream); + } while (Length >= 8); + } + } + #endif + + while (Length) + { + if (!(Pipe_IsReadWriteAllowed())) + { + TEMPLATE_CLEAR_PIPE(); + + #if !defined(NO_STREAM_CALLBACKS) + if ((Callback != NULL) && (Callback() == STREAMCALLBACK_Abort)) + return PIPE_RWSTREAM_CallbackAborted; + #endif + + if ((ErrorCode = Pipe_WaitUntilReady())) + return ErrorCode; + } + else + { + TEMPLATE_TRANSFER_BYTE(DataStream); + Length--; + } + } + + return PIPE_RWSTREAM_NoError; +} + +#undef TEMPLATE_FUNC_NAME +#undef TEMPLATE_BUFFER_TYPE +#undef TEMPLATE_TOKEN +#undef TEMPLATE_TRANSFER_BYTE +#undef TEMPLATE_CLEAR_PIPE +#undef TEMPLATE_BUFFER_OFFSET diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/USBController.c b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/USBController.c new file mode 100644 index 0000000000..907e2bab0a --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/USBController.c @@ -0,0 +1,271 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +#define __INCLUDE_FROM_USB_DRIVER +#include "USBController.h" + +#if (!defined(USB_HOST_ONLY) && !defined(USB_DEVICE_ONLY)) +volatile uint8_t USB_CurrentMode = USB_MODE_NONE; +#endif + +#if !defined(USE_STATIC_OPTIONS) +volatile uint8_t USB_Options; +#endif + +void USB_Init( + #if defined(USB_CAN_BE_BOTH) + const uint8_t Mode + #endif + + #if (defined(USB_CAN_BE_BOTH) && !defined(USE_STATIC_OPTIONS)) + , + #elif (!defined(USB_CAN_BE_BOTH) && defined(USE_STATIC_OPTIONS)) + void + #endif + + #if !defined(USE_STATIC_OPTIONS) + const uint8_t Options + #endif + ) +{ + #if defined(USB_CAN_BE_BOTH) + USB_CurrentMode = Mode; + #endif + + #if !defined(USE_STATIC_OPTIONS) + USB_Options = Options; + #endif + + #if defined(USB_CAN_BE_HOST) + USB_ControlPipeSize = PIPE_CONTROLPIPE_DEFAULT_SIZE; + #endif + + #if defined(USB_DEVICE_ONLY) && (defined(USB_SERIES_6_AVR) || defined(USB_SERIES_7_AVR)) + UHWCON |= (1 << UIMOD); + #elif defined(USB_HOST_ONLY) + UHWCON &= ~(1 << UIMOD); + #elif defined(USB_CAN_BE_BOTH) + if (Mode == USB_MODE_UID) + { + UHWCON |= (1 << UIDE); + + USB_INT_Clear(USB_INT_IDTI); + USB_INT_Enable(USB_INT_IDTI); + + USB_CurrentMode = USB_GetUSBModeFromUID(); + } + else if (Mode == USB_MODE_DEVICE) + { + UHWCON |= (1 << UIMOD); + } + else if (Mode == USB_MODE_HOST) + { + UHWCON &= ~(1 << UIMOD); + } + else + { + EVENT_USB_InitFailure(USB_INITERROR_NoUSBModeSpecified); + return; + } + #endif + + USB_ResetInterface(); + + #if defined(USB_SERIES_4_AVR) || defined(USB_SERIES_6_AVR) || defined(USB_SERIES_7_AVR) + USB_OTGPAD_On(); + #endif + + USB_IsInitialized = true; +} + +void USB_ShutDown(void) +{ + USB_ResetInterface(); + USB_Detach(); + USB_Controller_Disable(); + + USB_INT_DisableAllInterrupts(); + USB_INT_ClearAllInterrupts(); + + #if defined(USB_SERIES_6_AVR) || defined(USB_SERIES_7_AVR) + UHWCON &= ~(1 << UIMOD); + #endif + + if (!(USB_Options & USB_OPT_MANUAL_PLL)) + USB_PLL_Off(); + + USB_REG_Off(); + + #if defined(USB_SERIES_4_AVR) || defined(USB_SERIES_6_AVR) || defined(USB_SERIES_7_AVR) + USB_OTGPAD_Off(); + #endif + + #if defined(USB_CAN_BE_BOTH) + UHWCON &= ~(1 << UIDE); + #endif + + USB_IsInitialized = false; + + #if defined(USB_CAN_BE_BOTH) + USB_CurrentMode = USB_MODE_NONE; + #endif +} + +void USB_ResetInterface(void) +{ + USB_INT_DisableAllInterrupts(); + USB_INT_ClearAllInterrupts(); + + #if defined(USB_CAN_BE_HOST) + USB_HostState = HOST_STATE_Unattached; + #endif + + #if defined(USB_CAN_BE_DEVICE) + USB_DeviceState = DEVICE_STATE_Unattached; + USB_ConfigurationNumber = 0; + + #if !defined(NO_DEVICE_REMOTE_WAKEUP) + USB_RemoteWakeupEnabled = false; + #endif + + #if !defined(NO_DEVICE_SELF_POWER) + USB_CurrentlySelfPowered = false; + #endif + #endif + + if (!(USB_Options & USB_OPT_MANUAL_PLL)) + { + #if defined(USB_SERIES_4_AVR) + PLLFRQ = ((1 << PLLUSB) | (1 << PDIV3) | (1 << PDIV1)); + #endif + + USB_PLL_On(); + while (!(USB_PLL_IsReady())); + } + + USB_Controller_Reset(); + + #if defined(USB_CAN_BE_BOTH) + if (UHWCON & (1 << UIDE)) + { + USB_INT_Clear(USB_INT_IDTI); + USB_INT_Enable(USB_INT_IDTI); + USB_CurrentMode = USB_GetUSBModeFromUID(); + } + #endif + + if (!(USB_Options & USB_OPT_REG_DISABLED)) + USB_REG_On(); + else + USB_REG_Off(); + + USB_CLK_Unfreeze(); + + #if (defined(USB_CAN_BE_DEVICE) && (defined(USB_SERIES_4_AVR) || defined(USB_SERIES_6_AVR) || defined(USB_SERIES_7_AVR))) + if (USB_CurrentMode == USB_MODE_DEVICE) + { + if (USB_Options & USB_DEVICE_OPT_LOWSPEED) + USB_Device_SetLowSpeed(); + else + USB_Device_SetFullSpeed(); + } + #endif + + #if (defined(USB_CAN_BE_DEVICE) && !defined(FIXED_CONTROL_ENDPOINT_SIZE)) + if (USB_CurrentMode == USB_MODE_DEVICE) + { + USB_Descriptor_Device_t* DeviceDescriptorPtr; + + if (CALLBACK_USB_GetDescriptor((DTYPE_Device << 8), 0, (void*)&DeviceDescriptorPtr) != NO_DESCRIPTOR) + { + #if defined(USE_RAM_DESCRIPTORS) + USB_ControlEndpointSize = DeviceDescriptorPtr->Endpoint0Size; + #elif defined(USE_EEPROM_DESCRIPTORS) + USB_ControlEndpointSize = eeprom_read_byte(&DeviceDescriptorPtr->Endpoint0Size); + #else + USB_ControlEndpointSize = pgm_read_byte(&DeviceDescriptorPtr->Endpoint0Size); + #endif + } + } + #endif + + USB_Attach(); + + #if defined(USB_DEVICE_ONLY) + USB_INT_Clear(USB_INT_SUSPEND); + USB_INT_Enable(USB_INT_SUSPEND); + USB_INT_Clear(USB_INT_EORSTI); + USB_INT_Enable(USB_INT_EORSTI); + + #if defined(USB_SERIES_4_AVR) || defined(USB_SERIES_6_AVR) || defined(USB_SERIES_7_AVR) + USB_INT_Enable(USB_INT_VBUS); + #endif + #elif defined(USB_HOST_ONLY) + USB_Host_HostMode_On(); + + USB_Host_VBUS_Auto_Off(); + USB_OTGPAD_Off(); + + USB_Host_VBUS_Manual_Enable(); + USB_Host_VBUS_Manual_On(); + + USB_INT_Enable(USB_INT_SRPI); + USB_INT_Enable(USB_INT_BCERRI); + #else + if (USB_CurrentMode == USB_MODE_DEVICE) + { + USB_INT_Clear(USB_INT_SUSPEND); + USB_INT_Enable(USB_INT_SUSPEND); + USB_INT_Clear(USB_INT_EORSTI); + USB_INT_Enable(USB_INT_EORSTI); + + #if defined(USB_SERIES_4_AVR) || defined(USB_SERIES_6_AVR) || defined(USB_SERIES_7_AVR) + USB_INT_Enable(USB_INT_VBUS); + #endif + + #if defined(CONTROL_ONLY_DEVICE) + UENUM = ENDPOINT_CONTROLEP; + #endif + } + else if (USB_CurrentMode == USB_MODE_HOST) + { + USB_Host_HostMode_On(); + + USB_Host_VBUS_Auto_Off(); + USB_OTGPAD_Off(); + + USB_Host_VBUS_Manual_Enable(); + USB_Host_VBUS_Manual_On(); + + USB_INT_Enable(USB_INT_SRPI); + USB_INT_Enable(USB_INT_BCERRI); + } + #endif +} diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/USBController.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/USBController.h new file mode 100644 index 0000000000..f0db7faf4c --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/USBController.h @@ -0,0 +1,465 @@ +/* + 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 USB low level USB controller definitions. + * + * This file contains structures, function prototypes and macros related to the low level configuration of the + * USB controller, to start, stop and reset the USB library core. + * + * \note This file should not be included directly. It is automatically included as needed by the USB driver + * dispatch header located in LUFA/Drivers/USB/USB.h. + */ + +/** \ingroup Group_USB + * @defgroup Group_USBManagement USB Interface Management + * + * Functions, macros, variables, enums and types related to the setup and management of the USB interface. + * + * @{ + */ + +#ifndef __USBCONTROLLER_H__ +#define __USBCONTROLLER_H__ + + /* Includes: */ + #include + #include + #include + + #include "../HighLevel/USBMode.h" + + #include "../../../Common/Common.h" + #include "../HighLevel/USBMode.h" + #include "../HighLevel/Events.h" + #include "../HighLevel/USBTask.h" + #include "USBInterrupt.h" + + #if defined(USB_CAN_BE_HOST) || defined(__DOXYGEN__) + #include "Host.h" + #include "Pipe.h" + #include "OTG.h" + #include "../HighLevel/HostStandardReq.h" + #endif + + #if defined(USB_CAN_BE_DEVICE) || defined(__DOXYGEN__) + #include "Device.h" + #include "Endpoint.h" + #include "../HighLevel/DeviceStandardReq.h" + #endif + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Preprocessor Checks and Defines: */ + #if !defined(__INCLUDE_FROM_USB_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/USB/USB.h instead. + #endif + + #if !defined(F_CLOCK) + #error F_CLOCK is not defined. You must define F_CLOCK to the frequency of the unprescaled input clock in your project makefile. + #endif + + #if (F_CLOCK == 8000000) + #if (defined(__AVR_AT90USB82__) || defined(__AVR_AT90USB162__) || \ + defined(__AVR_ATmega8U2__) || defined(__AVR_ATmega16U2__) || \ + defined(__AVR_ATmega32U2__)) + #define USB_PLL_PSC 0 + #elif (defined(__AVR_ATmega16U4__) || defined(__AVR_ATmega32U4__)) + #define USB_PLL_PSC 0 + #elif (defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB1286__) || defined(__AVR_ATmega32U6__)) + #define USB_PLL_PSC ((1 << PLLP1) | (1 << PLLP0)) + #elif (defined(__AVR_AT90USB647__) || defined(__AVR_AT90USB1287__)) + #define USB_PLL_PSC ((1 << PLLP1) | (1 << PLLP0)) + #endif + #elif (F_CLOCK == 16000000) + #if (defined(__AVR_AT90USB82__) || defined(__AVR_AT90USB162__) || \ + defined(__AVR_ATmega8U2__) || defined(__AVR_ATmega16U2__) || \ + defined(__AVR_ATmega32U2__)) + #define USB_PLL_PSC (1 << PLLP0) + #elif (defined(__AVR_ATmega16U4__) || defined(__AVR_ATmega32U4__)) + #define USB_PLL_PSC (1 << PINDIV) + #elif (defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB647__) || defined(__AVR_ATmega32U6__)) + #define USB_PLL_PSC ((1 << PLLP2) | (1 << PLLP1)) + #elif (defined(__AVR_AT90USB1286__) || defined(__AVR_AT90USB1287__)) + #define USB_PLL_PSC ((1 << PLLP2) | (1 << PLLP0)) + #endif + #endif + + #if !defined(USB_PLL_PSC) + #error No PLL prescale value available for chosen F_CPU value and AVR model. + #endif + + /* Public Interface - May be used in end-application: */ + /* Macros: */ + /** Mode mask for the \ref USB_CurrentMode global. This indicates that the USB interface is currently not + * initialized into any mode. + */ + #define USB_MODE_NONE 0 + + /** Mode mask for the \ref USB_CurrentMode global and the \ref USB_Init() function. This indicates that the + * USB interface is or should be initialized in the USB device mode. + */ + #define USB_MODE_DEVICE 1 + + /** Mode mask for the \ref USB_CurrentMode global and the \ref USB_Init() function. This indicates that the + * USB interface is or should be initialized in the USB host mode. + */ + #define USB_MODE_HOST 2 + + #if defined(USB_CAN_BE_BOTH) || defined(__DOXYGEN__) + /** Mode mask for the the \ref USB_Init() function. This indicates that the USB interface should be + * initialized into whatever mode the UID pin of the USB AVR indicates, and that the device + * should swap over its mode when the level of the UID pin changes during operation. + * + * \note This token is not available on AVR models which do not support both host and device modes. + */ + #define USB_MODE_UID 3 + #endif + + /** Regulator disable option mask for \ref USB_Init(). This indicates that the internal 3.3V USB data pad + * regulator should be enabled to regulate the data pin voltages to within the USB standard. + * + * \note See USB AVR data sheet for more information on the internal pad regulator. + */ + #define USB_OPT_REG_DISABLED (1 << 1) + + /** Regulator enable option mask for \ref USB_Init(). This indicates that the internal 3.3V USB data pad + * regulator should be disabled and the AVR's VCC level used for the data pads. + * + * \note See USB AVR data sheet for more information on the internal pad regulator. + */ + #define USB_OPT_REG_ENABLED (0 << 1) + + /** Manual PLL control option mask for \ref USB_Init(). This indicates to the library that the user application + * will take full responsibility for controlling the AVR's PLL (used to generate the high frequency clock + * that the USB controller requires) and ensuring that it is locked at the correct frequency for USB operations. + */ + #define USB_OPT_MANUAL_PLL (1 << 2) + + /** Automatic PLL control option mask for \ref USB_Init(). This indicates to the library that the library should + * take full responsibility for controlling the AVR's PLL (used to generate the high frequency clock + * that the USB controller requires) and ensuring that it is locked at the correct frequency for USB operations. + */ + #define USB_OPT_AUTO_PLL (0 << 2) + + /** Mask for a CONTROL type endpoint or pipe. + * + * \note See \ref Group_EndpointManagement and \ref Group_PipeManagement for endpoint/pipe functions. + */ + #define EP_TYPE_CONTROL 0x00 + + /** Mask for an ISOCHRONOUS type endpoint or pipe. + * + * \note See \ref Group_EndpointManagement and \ref Group_PipeManagement for endpoint/pipe functions. + */ + #define EP_TYPE_ISOCHRONOUS 0x01 + + /** Mask for a BULK type endpoint or pipe. + * + * \note See \ref Group_EndpointManagement and \ref Group_PipeManagement for endpoint/pipe functions. + */ + #define EP_TYPE_BULK 0x02 + + /** Mask for an INTERRUPT type endpoint or pipe. + * + * \note See \ref Group_EndpointManagement and \ref Group_PipeManagement for endpoint/pipe functions. + */ + #define EP_TYPE_INTERRUPT 0x03 + + #if !defined(USB_STREAM_TIMEOUT_MS) || defined(__DOXYGEN__) + /** Constant for the maximum software timeout period of the USB data stream transfer functions + * (both control and standard) when in either device or host mode. If the next packet of a stream + * is not received or acknowledged within this time period, the stream function will fail. + * + * This value may be overridden in the user project makefile as the value of the + * \ref USB_STREAM_TIMEOUT_MS token, and passed to the compiler using the -D switch. + */ + #define USB_STREAM_TIMEOUT_MS 100 + #endif + + /* Inline Functions: */ + #if defined(USB_SERIES_4_AVR) || defined(USB_SERIES_6_AVR) || defined(USB_SERIES_7_AVR) || defined(__DOXYGEN__) + /** Returns boolean true if the VBUS line is currently high (i.e. the USB host is supplying power), + * otherwise returns false. + * + * \note This function is not available on some AVR models which do not support hardware VBUS monitoring. + */ + static inline bool USB_VBUS_GetStatus(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline bool USB_VBUS_GetStatus(void) + { + return ((USBSTA & (1 << VBUS)) ? true : false); + } + #endif + + /** Detaches the device from the USB bus. This has the effect of removing the device from any + * attached host, ceasing USB communications. If no host is present, this prevents any host from + * enumerating the device once attached until \ref USB_Attach() is called. + */ + static inline void USB_Detach(void) ATTR_ALWAYS_INLINE; + static inline void USB_Detach(void) + { + UDCON |= (1 << DETACH); + } + + /** Attaches the device to the USB bus. This announces the device's presence to any attached + * USB host, starting the enumeration process. If no host is present, attaching the device + * will allow for enumeration once a host is connected to the device. + * + * This is inexplicably also required for proper operation while in host mode, to enable the + * attachment of a device to the host. This is despite the bit being located in the device-mode + * register and despite the datasheet making no mention of its requirement in host mode. + */ + static inline void USB_Attach(void) ATTR_ALWAYS_INLINE; + static inline void USB_Attach(void) + { + UDCON &= ~(1 << DETACH); + } + + /* Function Prototypes: */ + /** Main function to initialize and start the USB interface. Once active, the USB interface will + * allow for device connection to a host when in device mode, or for device enumeration while in + * host mode. + * + * As the USB library relies on interrupts for the device and host mode enumeration processes, + * the user must enable global interrupts before or shortly after this function is called. In + * device mode, interrupts must be enabled within 500ms of this function being called to ensure + * that the host does not time out whilst enumerating the device. In host mode, interrupts may be + * enabled at the application's leisure however enumeration will not begin of an attached device + * until after this has occurred. + * + * Calling this function when the USB interface is already initialized will cause a complete USB + * interface reset and re-enumeration. + * + * \param[in] Mode This is a mask indicating what mode the USB interface is to be initialized to. + * Valid mode masks are \ref USB_MODE_DEVICE, \ref USB_MODE_HOST or \ref USB_MODE_UID. + * + * \param[in] Options Mask indicating the options which should be used when initializing the USB + * interface to control the USB interface's behaviour. This should be comprised of + * a USB_OPT_REG_* mask to control the regulator, a USB_OPT_*_PLL mask to control the + * PLL, and a USB_DEVICE_OPT_* mask (when the device mode is enabled) to set the device + * mode speed. + * + * \note To reduce the FLASH requirements of the library if only device or host mode is required, + * the mode can be statically set in the project makefile by defining the token USB_DEVICE_ONLY + * (for device mode) or USB_HOST_ONLY (for host mode), passing the token to the compiler + * via the -D switch. If the mode is statically set, this parameter does not exist in the + * function prototype. + * \n\n + * + * \note To reduce the FLASH requirements of the library if only fixed settings are are required, + * the options may be set statically in the same manner as the mode (see the Mode parameter of + * this function). To statically set the USB options, pass in the USE_STATIC_OPTIONS token, + * defined to the appropriate options masks. When the options are statically set, this + * parameter does not exist in the function prototype. + * \n\n + * + * \note The mode parameter does not exist on devices where only one mode is possible, such as USB + * AVR models which only implement the USB device mode in hardware. + * + * \see Device.h for the USB_DEVICE_OPT_* masks. + */ + void USB_Init( + #if defined(USB_CAN_BE_BOTH) || defined(__DOXYGEN__) + const uint8_t Mode + #endif + + #if (defined(USB_CAN_BE_BOTH) && !defined(USE_STATIC_OPTIONS)) || defined(__DOXYGEN__) + , + #elif (!defined(USB_CAN_BE_BOTH) && defined(USE_STATIC_OPTIONS)) + void + #endif + + #if !defined(USE_STATIC_OPTIONS) || defined(__DOXYGEN__) + const uint8_t Options + #endif + ); + + /** Shuts down the USB interface. This turns off the USB interface after deallocating all USB FIFO + * memory, endpoints and pipes. When turned off, no USB functionality can be used until the interface + * is restarted with the \ref USB_Init() function. + */ + void USB_ShutDown(void); + + /** Resets the interface, when already initialized. This will re-enumerate the device if already connected + * to a host, or re-enumerate an already attached device when in host mode. + */ + void USB_ResetInterface(void); + + /* Enums: */ + /** Enum for error codes relating to the powering on of the USB interface. These error codes are + * used in the ErrorCode parameter value of the \ref EVENT_USB_InitFailure() event. + */ + enum USB_InitErrorCodes_t + { + USB_INITERROR_NoUSBModeSpecified = 0, /**< Indicates that \ref USB_Init() was called with an + * invalid or missing Mode parameter. + */ + }; + + /* Global Variables: */ + #if (!defined(USB_HOST_ONLY) && !defined(USB_DEVICE_ONLY)) || defined(__DOXYGEN__) + /** Indicates the mode that the USB interface is currently initialized to. This value will be + * one of the USB_MODE_* masks defined elsewhere in this module. + * + * \note This variable should be treated as read-only in the user application, and never manually + * changed in value. + */ + extern volatile uint8_t USB_CurrentMode; + #elif defined(USB_HOST_ONLY) + #define USB_CurrentMode USB_MODE_HOST + #elif defined(USB_DEVICE_ONLY) + #define USB_CurrentMode USB_MODE_DEVICE + #endif + + #if !defined(USE_STATIC_OPTIONS) || defined(__DOXYGEN__) + /** Indicates the current USB options that the USB interface was initialized with when \ref USB_Init() + * was called. This value will be one of the USB_MODE_* masks defined elsewhere in this module. + * + * \note This variable should be treated as read-only in the user application, and never manually + * changed in value. + */ + extern volatile uint8_t USB_Options; + #elif defined(USE_STATIC_OPTIONS) + #define USB_Options USE_STATIC_OPTIONS + #endif + + /* Private Interface - For use in library only: */ + #if !defined(__DOXYGEN__) + /* Inline Functions: */ + static inline void USB_PLL_On(void) ATTR_ALWAYS_INLINE; + static inline void USB_PLL_On(void) + { + PLLCSR = USB_PLL_PSC; + PLLCSR |= (1 << PLLE); + } + + static inline void USB_PLL_Off(void) ATTR_ALWAYS_INLINE; + static inline void USB_PLL_Off(void) + { + PLLCSR = 0; + } + + static inline bool USB_PLL_IsReady(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline bool USB_PLL_IsReady(void) + { + return ((PLLCSR & (1 << PLOCK)) ? true : false); + } + + static inline void USB_REG_On(void) ATTR_ALWAYS_INLINE; + static inline void USB_REG_On(void) + { + #if defined(USB_SERIES_4_AVR) || defined(USB_SERIES_6_AVR) || defined(USB_SERIES_7_AVR) + UHWCON |= (1 << UVREGE); + #else + REGCR &= ~(1 << REGDIS); + #endif + } + + static inline void USB_REG_Off(void) ATTR_ALWAYS_INLINE; + static inline void USB_REG_Off(void) + { + #if defined(USB_SERIES_4_AVR) || defined(USB_SERIES_6_AVR) || defined(USB_SERIES_7_AVR) + UHWCON &= ~(1 << UVREGE); + #else + REGCR |= (1 << REGDIS); + #endif + } + + #if defined(USB_SERIES_4_AVR) || defined(USB_SERIES_6_AVR) || defined(USB_SERIES_7_AVR) + static inline void USB_OTGPAD_On(void) ATTR_ALWAYS_INLINE; + static inline void USB_OTGPAD_On(void) + { + USBCON |= (1 << OTGPADE); + } + + static inline void USB_OTGPAD_Off(void) ATTR_ALWAYS_INLINE; + static inline void USB_OTGPAD_Off(void) + { + USBCON &= ~(1 << OTGPADE); + } + #endif + + static inline void USB_CLK_Freeze(void) ATTR_ALWAYS_INLINE; + static inline void USB_CLK_Freeze(void) + { + USBCON |= (1 << FRZCLK); + } + + static inline void USB_CLK_Unfreeze(void) ATTR_ALWAYS_INLINE; + static inline void USB_CLK_Unfreeze(void) + { + USBCON &= ~(1 << FRZCLK); + } + + static inline void USB_Controller_Enable(void) ATTR_ALWAYS_INLINE; + static inline void USB_Controller_Enable(void) + { + USBCON |= (1 << USBE); + } + + static inline void USB_Controller_Disable(void) ATTR_ALWAYS_INLINE; + static inline void USB_Controller_Disable(void) + { + USBCON &= ~(1 << USBE); + } + + static inline void USB_Controller_Reset(void) ATTR_ALWAYS_INLINE; + static inline void USB_Controller_Reset(void) + { + const uint8_t Temp = USBCON; + + USBCON = (Temp & ~(1 << USBE)); + USBCON = (Temp | (1 << USBE)); + } + + #if defined(USB_CAN_BE_BOTH) + static inline uint8_t USB_GetUSBModeFromUID(void) ATTR_WARN_UNUSED_RESULT ATTR_ALWAYS_INLINE; + static inline uint8_t USB_GetUSBModeFromUID(void) + { + if (USBSTA & (1 << ID)) + return USB_MODE_DEVICE; + else + return USB_MODE_HOST; + } + #endif + + #endif + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/USBInterrupt.c b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/USBInterrupt.c new file mode 100644 index 0000000000..1c6d6caa79 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/USBInterrupt.c @@ -0,0 +1,250 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +#define __INCLUDE_FROM_USB_DRIVER +#include "USBInterrupt.h" + +void USB_INT_DisableAllInterrupts(void) +{ + #if defined(USB_SERIES_6_AVR) || defined(USB_SERIES_7_AVR) + USBCON &= ~((1 << VBUSTE) | (1 << IDTE)); + #elif defined(USB_SERIES_4_AVR) + USBCON &= ~(1 << VBUSTE); + #endif + + #if defined(USB_CAN_BE_HOST) + UHIEN = 0; + OTGIEN = 0; + #endif + + #if defined(USB_CAN_BE_DEVICE) + UDIEN = 0; + #endif +} + +void USB_INT_ClearAllInterrupts(void) +{ + #if defined(USB_SERIES_4_AVR) || defined(USB_SERIES_6_AVR) || defined(USB_SERIES_7_AVR) + USBINT = 0; + #endif + + #if defined(USB_CAN_BE_HOST) + UHINT = 0; + OTGINT = 0; + #endif + + #if defined(USB_CAN_BE_DEVICE) + UDINT = 0; + #endif +} + +ISR(USB_GEN_vect, ISR_BLOCK) +{ + #if defined(USB_CAN_BE_DEVICE) + #if defined(USB_SERIES_4_AVR) || defined(USB_SERIES_6_AVR) || defined(USB_SERIES_7_AVR) + if (USB_INT_HasOccurred(USB_INT_VBUS) && USB_INT_IsEnabled(USB_INT_VBUS)) + { + USB_INT_Clear(USB_INT_VBUS); + + if (USB_VBUS_GetStatus()) + { + USB_DeviceState = DEVICE_STATE_Powered; + EVENT_USB_Device_Connect(); + } + else + { + USB_DeviceState = DEVICE_STATE_Unattached; + EVENT_USB_Device_Disconnect(); + } + } + #endif + + if (USB_INT_HasOccurred(USB_INT_SUSPEND) && USB_INT_IsEnabled(USB_INT_SUSPEND)) + { + USB_INT_Clear(USB_INT_SUSPEND); + + USB_INT_Disable(USB_INT_SUSPEND); + USB_INT_Enable(USB_INT_WAKEUP); + + USB_CLK_Freeze(); + + if (!(USB_Options & USB_OPT_MANUAL_PLL)) + USB_PLL_Off(); + + #if defined(USB_SERIES_2_AVR) && !defined(NO_LIMITED_CONTROLLER_CONNECT) + USB_DeviceState = DEVICE_STATE_Unattached; + EVENT_USB_Device_Disconnect(); + #else + USB_DeviceState = DEVICE_STATE_Suspended; + EVENT_USB_Device_Suspend(); + #endif + } + + if (USB_INT_HasOccurred(USB_INT_WAKEUP) && USB_INT_IsEnabled(USB_INT_WAKEUP)) + { + if (!(USB_Options & USB_OPT_MANUAL_PLL)) + { + USB_PLL_On(); + while (!(USB_PLL_IsReady())); + } + + USB_CLK_Unfreeze(); + + USB_INT_Clear(USB_INT_WAKEUP); + + USB_INT_Disable(USB_INT_WAKEUP); + USB_INT_Enable(USB_INT_SUSPEND); + + #if defined(USB_SERIES_2_AVR) && !defined(NO_LIMITED_CONTROLLER_CONNECT) + USB_DeviceState = (USB_ConfigurationNumber) ? DEVICE_STATE_Configured : DEVICE_STATE_Powered; + EVENT_USB_Device_Connect(); + #else + USB_DeviceState = (USB_ConfigurationNumber) ? DEVICE_STATE_Configured : DEVICE_STATE_Addressed; + EVENT_USB_Device_WakeUp(); + #endif + } + + if (USB_INT_HasOccurred(USB_INT_EORSTI) && USB_INT_IsEnabled(USB_INT_EORSTI)) + { + USB_INT_Clear(USB_INT_EORSTI); + + USB_DeviceState = DEVICE_STATE_Default; + USB_ConfigurationNumber = 0; + + USB_INT_Clear(USB_INT_SUSPEND); + USB_INT_Disable(USB_INT_SUSPEND); + USB_INT_Enable(USB_INT_WAKEUP); + + Endpoint_ClearEndpoints(); + + Endpoint_ConfigureEndpoint(ENDPOINT_CONTROLEP, EP_TYPE_CONTROL, + ENDPOINT_DIR_OUT, USB_ControlEndpointSize, + ENDPOINT_BANK_SINGLE); + + #if defined(INTERRUPT_CONTROL_ENDPOINT) + USB_INT_Enable(USB_INT_RXSTPI); + #endif + + EVENT_USB_Device_Reset(); + } + + if (USB_INT_HasOccurred(USB_INT_SOFI) && USB_INT_IsEnabled(USB_INT_SOFI)) + { + USB_INT_Clear(USB_INT_SOFI); + + EVENT_USB_Device_StartOfFrame(); + } + #endif + + #if defined(USB_CAN_BE_HOST) + if (USB_INT_HasOccurred(USB_INT_DDISCI) && USB_INT_IsEnabled(USB_INT_DDISCI)) + { + USB_INT_Clear(USB_INT_DDISCI); + USB_INT_Clear(USB_INT_DCONNI); + USB_INT_Disable(USB_INT_DDISCI); + + EVENT_USB_Host_DeviceUnattached(); + + USB_ResetInterface(); + } + + if (USB_INT_HasOccurred(USB_INT_VBERRI) && USB_INT_IsEnabled(USB_INT_VBERRI)) + { + USB_INT_Clear(USB_INT_VBERRI); + + USB_Host_VBUS_Manual_Off(); + USB_Host_VBUS_Auto_Off(); + + EVENT_USB_Host_HostError(HOST_ERROR_VBusVoltageDip); + EVENT_USB_Host_DeviceUnattached(); + + USB_HostState = HOST_STATE_Unattached; + } + + if (USB_INT_HasOccurred(USB_INT_SRPI) && USB_INT_IsEnabled(USB_INT_SRPI)) + { + USB_INT_Clear(USB_INT_SRPI); + USB_INT_Disable(USB_INT_SRPI); + + EVENT_USB_Host_DeviceAttached(); + + USB_INT_Enable(USB_INT_DDISCI); + + USB_HostState = HOST_STATE_Powered; + } + + if (USB_INT_HasOccurred(USB_INT_BCERRI) && USB_INT_IsEnabled(USB_INT_BCERRI)) + { + USB_INT_Clear(USB_INT_BCERRI); + + EVENT_USB_Host_DeviceEnumerationFailed(HOST_ENUMERROR_NoDeviceDetected, 0); + EVENT_USB_Host_DeviceUnattached(); + + USB_ResetInterface(); + } + #endif + + #if defined(USB_CAN_BE_BOTH) + if (USB_INT_HasOccurred(USB_INT_IDTI) && USB_INT_IsEnabled(USB_INT_IDTI)) + { + USB_INT_Clear(USB_INT_IDTI); + + if (USB_DeviceState != DEVICE_STATE_Unattached) + EVENT_USB_Device_Disconnect(); + + if (USB_HostState != HOST_STATE_Unattached) + EVENT_USB_Host_DeviceUnattached(); + + USB_CurrentMode = USB_GetUSBModeFromUID(); + EVENT_USB_UIDChange(); + + USB_ResetInterface(); + } + #endif +} + +#if defined(INTERRUPT_CONTROL_ENDPOINT) && defined(USB_CAN_BE_DEVICE) +ISR(USB_COM_vect, ISR_BLOCK) +{ + uint8_t PrevSelectedEndpoint = Endpoint_GetCurrentEndpoint(); + + Endpoint_SelectEndpoint(ENDPOINT_CONTROLEP); + USB_INT_Disable(USB_INT_RXSTPI); + + NONATOMIC_BLOCK(NONATOMIC_FORCEOFF) + { + USB_Device_ProcessControlRequest(); + } + + Endpoint_SelectEndpoint(ENDPOINT_CONTROLEP); + USB_INT_Enable(USB_INT_RXSTPI); + Endpoint_SelectEndpoint(PrevSelectedEndpoint); +} +#endif diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/USBInterrupt.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/USBInterrupt.h new file mode 100644 index 0000000000..6e62beccfd --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/LowLevel/USBInterrupt.h @@ -0,0 +1,105 @@ +/* + 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 USB controller interrupt service routine management. + * + * This file contains definitions required for the correct handling of low level USB service routine interrupts + * from the USB controller. + * + * \note This file should not be included directly. It is automatically included as needed by the USB driver + * dispatch header located in LUFA/Drivers/USB/USB.h. + */ + +#ifndef __USBINTERRUPT_H__ +#define __USBINTERRUPT_H__ + + /* Includes: */ + #include + #include + #include + #include + + /* Enable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + extern "C" { + #endif + + /* Preprocessor Checks: */ + #if !defined(__INCLUDE_FROM_USB_DRIVER) + #error Do not include this file directly. Include LUFA/Drivers/USB/USB.h instead. + #endif + + /* Private Interface - For use in library only: */ + #if !defined(__DOXYGEN__) + /* Macros: */ + #define USB_INT_Enable(int) MACROS{ USB_INT_GET_EN_REG(int) |= USB_INT_GET_EN_MASK(int); }MACROE + #define USB_INT_Disable(int) MACROS{ USB_INT_GET_EN_REG(int) &= ~(USB_INT_GET_EN_MASK(int)); }MACROE + #define USB_INT_Clear(int) MACROS{ USB_INT_GET_INT_REG(int) &= ~(USB_INT_GET_INT_MASK(int)); }MACROE + #define USB_INT_IsEnabled(int) ((USB_INT_GET_EN_REG(int) & USB_INT_GET_EN_MASK(int)) ? true : false) + #define USB_INT_HasOccurred(int) ((USB_INT_GET_INT_REG(int) & USB_INT_GET_INT_MASK(int)) ? true : false) + + #define USB_INT_GET_EN_REG(a, b, c, d) a + #define USB_INT_GET_EN_MASK(a, b, c, d) b + #define USB_INT_GET_INT_REG(a, b, c, d) c + #define USB_INT_GET_INT_MASK(a, b, c, d) d + + #define USB_INT_VBUS USBCON, (1 << VBUSTE) , USBINT, (1 << VBUSTI) + #define USB_INT_IDTI USBCON, (1 << IDTE) , USBINT, (1 << IDTI) + #define USB_INT_WAKEUP UDIEN , (1 << WAKEUPE), UDINT , (1 << WAKEUPI) + #define USB_INT_SUSPEND UDIEN , (1 << SUSPE) , UDINT , (1 << SUSPI) + #define USB_INT_EORSTI UDIEN , (1 << EORSTE) , UDINT , (1 << EORSTI) + #define USB_INT_DCONNI UHIEN , (1 << DCONNE) , UHINT , (1 << DCONNI) + #define USB_INT_DDISCI UHIEN , (1 << DDISCE) , UHINT , (1 << DDISCI) + #define USB_INT_BCERRI OTGIEN, (1 << BCERRE) , OTGINT, (1 << BCERRI) + #define USB_INT_VBERRI OTGIEN, (1 << VBERRE) , OTGINT, (1 << VBERRI) + #define USB_INT_SOFI UDIEN, (1 << SOFE) , UDINT , (1 << SOFI) + #define USB_INT_HSOFI UHIEN, (1 << HSOFE) , UHINT , (1 << HSOFI) + #define USB_INT_RSTI UHIEN , (1 << RSTE) , UHINT , (1 << RSTI) + #define USB_INT_SRPI OTGIEN, (1 << SRPE) , OTGINT, (1 << SRPI) + #define USB_INT_RXSTPI UEIENX, (1 << RXSTPE) , UEINTX, (1 << RXSTPI) + + /* Includes: */ + #include "../../../Common/Common.h" + #include "../HighLevel/USBMode.h" + #include "../HighLevel/Events.h" + #include "USBController.h" + + /* Function Prototypes: */ + void USB_INT_ClearAllInterrupts(void); + void USB_INT_DisableAllInterrupts(void); + #endif + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/USB.h b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/USB.h new file mode 100644 index 0000000000..b2eb47dd79 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Drivers/USB/USB.h @@ -0,0 +1,395 @@ +/* + LUFA Library + Copyright (C) Dean Camera, 2010. + + dean [at] fourwalledcubicle [dot] com + www.fourwalledcubicle.com +*/ + +/* + Copyright 2010 Dean Camera (dean [at] fourwalledcubicle [dot] com) + + Permission to use, copy, modify, distribute, and sell this + software and its documentation for any purpose is hereby granted + without fee, provided that the above copyright notice appear in + all copies and that both that the copyright notice and this + permission notice and warranty disclaimer appear in supporting + documentation, and that the name of the author not be used in + advertising or publicity pertaining to distribution of the + software without specific, written prior permission. + + The author disclaim all warranties with regard to this + software, including all implied warranties of merchantability + and fitness. In no event shall the author be liable for any + special, indirect or consequential damages or any damages + whatsoever resulting from loss of use, data or profits, whether + in an action of contract, negligence or other tortious action, + arising out of or in connection with the use or performance of + this software. +*/ + +/** \file + * \brief Master include file for the library USB functionality. + * + * Master include file for the library USB functionality. + * + * This file should be included in all user projects making use of the USB portions of the library, instead of + * including any headers in the USB/LowLevel/ or USB/HighLevel/ subdirectories. + */ + +/** @defgroup Group_USB USB Core - LUFA/Drivers/USB/USB.h + * + * \section Sec_Dependencies Module Source Dependencies + * The following files must be built with any user project that uses this module: + * - LUFA/Drivers/USB/LowLevel/Device.c (Makefile source module name: LUFA_SRC_USB) + * - LUFA/Drivers/USB/LowLevel/Endpoint.c (Makefile source module name: LUFA_SRC_USB) + * - LUFA/Drivers/USB/LowLevel/Host.c (Makefile source module name: LUFA_SRC_USB) + * - LUFA/Drivers/USB/LowLevel/Pipe.c (Makefile source module name: LUFA_SRC_USB) + * - LUFA/Drivers/USB/LowLevel/USBController.c (Makefile source module name: LUFA_SRC_USB) + * - LUFA/Drivers/USB/LowLevel/USBInterrupt.c (Makefile source module name: LUFA_SRC_USB) + * - LUFA/Drivers/USB/HighLevel/ConfigDescriptor.c (Makefile source module name: LUFA_SRC_USB) + * - LUFA/Drivers/USB/HighLevel/DeviceStandardReq.c (Makefile source module name: LUFA_SRC_USB) + * - LUFA/Drivers/USB/HighLevel/Events.c (Makefile source module name: LUFA_SRC_USB) + * - LUFA/Drivers/USB/HighLevel/HostStandardReq.c (Makefile source module name: LUFA_SRC_USB) + * - LUFA/Drivers/USB/HighLevel/USBTask.c (Makefile source module name: LUFA_SRC_USB) + * + * \section Module Description + * Driver and framework for the USB controller hardware on the USB series of AVR microcontrollers. This module + * consists of many submodules, and is designed to provide an easy way to configure and control USB host, device + * or OTG mode USB applications. + * + * The USB stack requires the sole control over the USB controller in the microcontroller only; i.e. it does not + * require any additional AVR timers, etc. to operate. This ensures that the USB stack requires as few resources + * as possible. + * + * The USB stack can be used in Device Mode for connections to USB Hosts (see \ref Group_Device), in Host mode for + * hosting of other USB devices (see \ref Group_Host), or as a dual role device which can either act as a USB host + * or device depending on what peripheral is connected (see \ref Group_OTG). Both modes also require a common set + * of USB management functions found \ref Group_USBManagement. + */ + +/** @defgroup Group_USBClassDrivers USB Class Drivers + * + * Drivers for both host and device mode of the standard USB classes, for rapid application development. + * Class drivers give a framework which sits on top of the low level library API, allowing for standard + * USB classes to be implemented in a project with minimal user code. These drivers can be used in + * conjunction with the library low level APIs to implement interfaces both via the class drivers and via + * the standard library APIs. + * + * Multiple device mode class drivers can be used within a project, including multiple instances of the + * same class driver. In this way, USB Hosts and Devices can be made quickly using the internal class drivers + * so that more time and effort can be put into the end application instead of the USB protocol. + * + * The available class drivers and their modes are listed below. + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * +* + * + * + * + * + * + * + * + * + * + * + * + *
USB ClassDevice ModeHost Mode
AudioYesNo
CDCYesYes
HIDYesYes
MIDIYesYes
Mass StorageYesYes
PrinterNoYes
RNDISYesYes
Still ImageNoYes
+ * + * + * \section Sec_UsingClassDrivers Using the Class Drivers + * To make the Class drivers easy to integrate into a user application, they all implement a standardized + * design with similarly named/used function, enums, defines and types. The two different modes are implemented + * slightly differently, and thus will be explained separately. For information on a specific class driver, read + * the class driver's module documentation. + * + * \subsection SSec_ClassDriverDevice Device Mode Class Drivers + * Implementing a Device Mode Class Driver in a user application requires a number of steps to be followed. Firstly, + * the module configuration and state structure must be added to the project source. These structures are named in a + * similar manner between classes, that of USB_ClassInfo_{Class Name}_Device_t, and are used to hold the + * complete state and configuration for each class instance. Multiple class instances is where the power of the class + * drivers lie; multiple interfaces of the same class simply require more instances of the Class Driver's ClassInfo + * structure. + * + * Inside the ClassInfo structure lies two sections, a Config section, and a State section. The Config + * section contains the instance's configuration parameters, and must have all fields set by the user application + * before the class driver is used. Each Device mode Class driver typically contains a set of configuration parameters + * for the endpoint size/number of the associated logical USB interface, plus any class-specific configuration parameters. + * + * The State section of the ClassInfo structures are designed to be controlled by the Class Drivers only for + * maintaining the Class Driver instance's state, and should not normally be set by the user application. + * + * The following is an example of a properly initialized instance of the Audio Class Driver structure: + * + * \code + * USB_ClassInfo_Audio_Device_t My_Audio_Interface = + * { + * .Config = + * { + * .StreamingInterfaceNumber = 1, + * + * .DataINEndpointNumber = 1, + * .DataINEndpointSize = 256, + * }, + * }; + * \endcode + * + * \note The class driver's configuration parameters should match those used in the device's descriptors that are + * sent to the host. + * + * To initialize the Class driver instance, the driver's {Class Name}_Device_ConfigureEndpoints() function + * should be called in response to the \ref EVENT_USB_Device_ConfigurationChanged() event. This function will return a + * boolean value if the driver successfully initialized the instance. Like all the class driver functions, this function + * takes in the address of the specific instance you wish to initialize - in this manner, multiple separate instances of + * the same class type can be initialized like thus: + * + * \code + * void EVENT_USB_Device_ConfigurationChanged(void) + * { + * LEDs_SetAllLEDs(LEDMASK_USB_READY); + * + * if (!(Audio_Device_ConfigureEndpoints(&My_Audio_Interface))) + * LEDs_SetAllLEDs(LEDMASK_USB_ERROR); + * } + * \endcode + * + * Once initialized, it is important to maintain the class driver's state by repeatedly calling the Class Driver's + * {Class Name}_Device_USBTask() function in the main program loop. The exact implementation of this + * function varies between class drivers, and can be used for any internal class driver purpose to maintain each + * instance. Again, this function uses the address of the instance to operate on, and thus needs to be called for each + * separate instance, just like the main USB maintenance routine \ref USB_USBTask(): + * + * \code + * int main(void) + * { + * SetupHardware(); + * + * LEDs_SetAllLEDs(LEDMASK_USB_NOTREADY); + * + * for (;;) + * { + * Create_And_Process_Samples(); + * + * Audio_Device_USBTask(&My_Audio_Interface); + * USB_USBTask(); + * } + * } + * \endcode + * + * The final standardized Device Class Driver function is the Control Request handler function + * {Class Name}_Device_ProcessControlRequest(), which should be called when the + * \ref EVENT_USB_Device_UnhandledControlRequest() event fires. This function should also be + * called for each class driver instance, using the address of the instance to operate on as + * the function's parameter. The request handler will abort if it is determined that the current + * request is not targeted at the given class driver instance, thus these methods can safely be + * called one-after-another in the event handler with no form of error checking: + * + * \code + * void EVENT_USB_Device_UnhandledControlRequest(void) + * { + * Audio_Device_ProcessControlRequest(&My_Audio_Interface); + * } + * \endcode + * + * Each class driver may also define a set of callback functions (which are prefixed by "CALLBACK_" + * in the function's name) which must also be added to the user application - refer to each + * individual class driver's documentation for mandatory callbacks. In addition, each class driver may + * also define a set of events (identifiable by their prefix of "EVENT_" in the function's name), which + * the user application may choose to implement, or ignore if not needed. + * + * The individual Device Mode Class Driver documentation contains more information on the non-standardized, + * class-specific functions which the user application can then use on the driver instances, such as data + * read and write routines. See each driver's individual documentation for more information on the + * class-specific functions. + * + * \subsection SSec_ClassDriverHost Host Mode Class Drivers + * Implementing a Host Mode Class Driver in a user application requires a number of steps to be followed. Firstly, + * the module configuration and state structure must be added to the project source. These structures are named in a + * similar manner between classes, that of USB_ClassInfo_{Class Name}_Host_t, and are used to hold the + * complete state and configuration for each class instance. Multiple class instances is where the power of the class + * drivers lie; multiple interfaces of the same class simply require more instances of the Class Driver's ClassInfo + * structure. + * + * Inside the ClassInfo structure lies two sections, a Config section, and a State section. The Config + * section contains the instance's configuration parameters, and must have all fields set by the user application + * before the class driver is used. Each Device mode Class driver typically contains a set of configuration parameters + * for the endpoint size/number of the associated logical USB interface, plus any class-specific configuration parameters. + * + * The State section of the ClassInfo structures are designed to be controlled by the Class Drivers only for + * maintaining the Class Driver instance's state, and should not normally be set by the user application. + * + * The following is an example of a properly initialized instance of the MIDI Class Driver structure: + * + * \code + * USB_ClassInfo_MIDI_Host_t My_MIDI_Interface = + * { + * .Config = + * { + * .DataINPipeNumber = 1, + * .DataINPipeDoubleBank = false, + * + * .DataOUTPipeNumber = 2, + * .DataOUTPipeDoubleBank = false, + * }, + * }; + * \endcode + * + * To initialize the Class driver instance, the driver's {Class Name}_Host_ConfigurePipes() function + * should be called in response to the host state machine entering the \ref HOST_STATE_Addressed state. This function + * will return an error code from the class driver's {Class Name}_EnumerationFailure_ErrorCodes_t enum + * to indicate if the driver successfully initialized the instance and bound it to an interface in the attached device. + * Like all the class driver functions, this function takes in the address of the specific instance you wish to initialize - + * in this manner, multiple separate instances of the same class type can be initialized. A fragment of a Class Driver + * based Host mode application may look like the following: + * + * \code + * switch (USB_HostState) + * { + * case HOST_STATE_Addressed: + * LEDs_SetAllLEDs(LEDMASK_USB_ENUMERATING); + * + * uint16_t ConfigDescriptorSize; + * uint8_t ConfigDescriptorData[512]; + * + * if (USB_Host_GetDeviceConfigDescriptor(1, &ConfigDescriptorSize, ConfigDescriptorData, + * sizeof(ConfigDescriptorData)) != HOST_GETCONFIG_Successful) + * { + * LEDs_SetAllLEDs(LEDMASK_USB_ERROR); + * USB_HostState = HOST_STATE_WaitForDeviceRemoval; + * break; + * } + * + * if (MIDI_Host_ConfigurePipes(&My_MIDI_Interface, + * ConfigDescriptorSize, ConfigDescriptorData) != MIDI_ENUMERROR_NoError) + * { + * LEDs_SetAllLEDs(LEDMASK_USB_ERROR); + * USB_HostState = HOST_STATE_WaitForDeviceRemoval; + * break; + * } + * + * // Other state handler code here + * \endcode + * + * Note that the function also required the device's configuration descriptor so that it can determine which interface + * in the device to bind to - this can be retrieved as shown in the above fragment using the + * \ref USB_Host_GetDeviceConfigDescriptor() function. If the device does not implement the interface the class driver + * is looking for, if all the matching interfaces are already bound to class driver instances or if an error occurs while + * binding to a device interface (for example, a device endpoint bank larger that the maximum supported bank size is used) + * the configuration will fail. + * + * Once initialized, it is important to maintain the class driver's state by repeatedly calling the Class Driver's + * {Class Name}_Host_USBTask() function in the main program loop. The exact implementation of this + * function varies between class drivers, and can be used for any internal class driver purpose to maintain each + * instance. Again, this function uses the address of the instance to operate on, and thus needs to be called for each + * separate instance, just like the main USB maintenance routine \ref USB_USBTask(): + * + * \code + * int main(void) + * { + * SetupHardware(); + * + * LEDs_SetAllLEDs(LEDMASK_USB_NOTREADY); + * + * for (;;) + * { + * switch (USB_HostState) + * { + * // Host state machine handling here + * } + * + * MIDI_Host_USBTask(&My_Audio_Interface); + * USB_USBTask(); + * } + * } + * \endcode + * + * Each class driver may also define a set of callback functions (which are prefixed by "CALLBACK_" + * in the function's name) which must also be added to the user application - refer to each + * individual class driver's documentation for mandatory callbacks. In addition, each class driver may + * also define a set of events (identifiable by their prefix of "EVENT_" in the function's name), which + * the user application may choose to implement, or ignore if not needed. + * + * The individual Host Mode Class Driver documentation contains more information on the non-standardized, + * class-specific functions which the user application can then use on the driver instances, such as data + * read and write routines. See each driver's individual documentation for more information on the + * class-specific functions. + */ + +#ifndef __USB_H__ +#define __USB_H__ + + /* Macros: */ + #if !defined(__DOXYGEN__) + #define __INCLUDE_FROM_USB_DRIVER + #endif + + /* Includes: */ + #include "HighLevel/USBMode.h" + + /* Preprocessor Checks: */ + #if (!defined(USB_SERIES_2_AVR) && !defined(USB_SERIES_4_AVR) && \ + !defined(USB_SERIES_6_AVR) && !defined(USB_SERIES_7_AVR)) + #error The currently selected AVR model is not supported under the USB component of the LUFA library. + #endif + + /* Includes: */ + #include "HighLevel/USBTask.h" + #include "HighLevel/Events.h" + #include "HighLevel/StdDescriptors.h" + #include "HighLevel/ConfigDescriptor.h" + + #include "LowLevel/USBController.h" + #include "LowLevel/USBInterrupt.h" + + #if defined(USB_CAN_BE_HOST) || defined(__DOXYGEN__) + #include "LowLevel/Host.h" + #include "LowLevel/Pipe.h" + #include "HighLevel/HostStandardReq.h" + #endif + + #if defined(USB_CAN_BE_DEVICE) || defined(__DOXYGEN__) + #include "LowLevel/Device.h" + #include "LowLevel/Endpoint.h" + #include "HighLevel/DeviceStandardReq.h" + #endif + + #if defined(USB_CAN_BE_BOTH) || defined(__DOXYGEN__) + #include "LowLevel/OTG.h" + #endif + +#endif + diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/License.txt b/Tools/ArduPPM/ATMega32U2/LUFA/License.txt new file mode 100644 index 0000000000..82e3f74ec9 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/License.txt @@ -0,0 +1,17 @@ +Permission to use, copy, modify, and distribute 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. diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/AboutLUFA.txt b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/AboutLUFA.txt new file mode 100644 index 0000000000..7728347c60 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/AboutLUFA.txt @@ -0,0 +1,20 @@ +/** \file + * + * This file contains special DoxyGen information for the generation of the main page and other special + * documentation pages. It is not a project source file. + */ + +/** + * \page Page_AboutLUFA About LUFA + * + * This section of the manual contains information about the library as a whole, including its supported targets, + * past and planned changes, and links to other projects incorporating LUFA. + * + * Subsections: + * \li \subpage Page_DeviceSupport - Current Device and Hardware Support + * \li \subpage Page_Resources - LUFA and USB Related Resources + * \li \subpage Page_ChangeLog - Project Changelog + * \li \subpage Page_FutureChanges - Planned Changes to the Library + * \li \subpage Page_LUFAPoweredProjects - Other Projects Using LUFA + */ + \ No newline at end of file diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/AlternativeStacks.txt b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/AlternativeStacks.txt new file mode 100644 index 0000000000..60342f8e8f --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/AlternativeStacks.txt @@ -0,0 +1,62 @@ +/** \file + * + * This file contains special DoxyGen information for the generation of the main page and other special + * documentation pages. It is not a project source file. + */ + +/** + * \page Page_AlternativeStacks Alternative USB AVR Stacks + * + * LUFA is not the only stack available for the USB AVRs, although it is perhaps the best (see \ref Page_WhyUseLUFA). + * In the interests of completeness and user choice, other known USB AVR stacks are listed here. + * + * \section Sec_HardwareStacks Hardware USB AVR Stacks + * These are the known alternative USB stacks which are designed for and run exclusively on the USB AVR series microcontrollers, + * which contain on-chip USB controller hardware for maximum features and speed. + * + * - Name: Atmel USB AVR Stack (Atmel Inc.) \n + * Cost: Free \n + * License: Atmel Limited License (see Atmel download for details) \n + * Website: http://atmel.com/dyn/products/app_notes.asp?family_id=607#USB \n + * Description: This is the official Atmel USB AVR stack, for their 8-bit USB AVR lineup. Each series of + * USB AVR is separated into a separate download stack, which is both AVR-GCC and IAR compatible. + * + * - Name: Dr. Stefan Salewski's AT90USB1287 Stack (Dr. Stefan Salewski) \n + * Cost: Free \n + * License: GPL \n + * Website: http://www.ssalewski.de/AT90USB_firmware.html.en \n + * Description: This is a GPL'd library specifically designed for the AT90USB1287, by Dr. Stefan Salewski, a + * German Physicist. It compiles for AVR-GCC and can potentially be modified to work on other USB + * AVR models. + * + * - Name: PJRC Teensy Stack (Paul Stoffregen) \n + * Cost: Free \n + * License: BSD \n + * Website: http://www.pjrc.com/teensy/usb_debug_only.html \n + * Description: Not so much a complete stack as a collection of USB enabled demos, this library is specifically + * designed for the PJRC Teensy line of USB AVRs, and thus may need to be modified for other USB AVR + * chips. These minimal code samples shows the inner workings of the USB controller, without all the + * abstraction present in most other USB AVR stacks. + * + * \section Sec_SoftwareStacks Software AVR Stacks + * These are the known alternative USB stacks which can run on regular AVR models, lacking dedicated hardware USB controllers + * via a bit-banged (emulated) version of the USB protocol. They are limited in their capabilities due to the cycles required + * to be dedicated to managing the USB bus, but offer a cheap way to implement USB functionality into a design. + * + * - Name: AVR309: Software USB (Atmel) \n + * Cost: Free \n + * License: None Stated \n + * Website: http://www.atmel.com/dyn/Products/app_notes.asp?family_id=607 \n + * Description: Atmel's official software USB implementation, an Application Note containing work by Igor Cesko. This + * is a minimal assembly-only implementation of software USB, providing HID functionality. Less compile + * options than V-USB (see below). + * + * - Name: V-USB (Objective Development) \n + * Cost: Free for some uses, see website for licensing \n + * License: Dual GPL2/Custom \n + * Website: http://www.obdev.at/products/vusb/index.html \n + * Description: Well regarded and complete USB 1.1 software stack for several AVR models, implementing Low Speed HID. + * Used in many commercial and non-commercial designs, with user-submitted projects available for viewing + * on the company's website. Uses C language code mixed with assembly for time-critical sections. + */ + diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/BuildingLinkableLibraries.txt b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/BuildingLinkableLibraries.txt new file mode 100644 index 0000000000..70919c0a23 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/BuildingLinkableLibraries.txt @@ -0,0 +1,22 @@ +/** \file + * + * This file contains special DoxyGen information for the generation of the main page and other special + * documentation pages. It is not a project source file. + */ + +/** \page Page_BuildLibrary Building as a Linkable Library + * + * The LUFA library can be built as a proper linkable library (with the extention .a) under AVR-GCC, so that + * the library does not need to be recompiled with each revision of a user project. Instructions for creating + * a library from a given source tree can be found in the AVR-GCC user manual included in the WinAVR install + * /Docs/ directory. + * + * However, building the library is not recommended, as the static (compile-time) options will be + * unable to be changed without a recompilation of the LUFA code. Therefore, if the library is to be built + * from the LUFA source, it should be made to be application-specific and compiled with the static options + * that are required for each project (which should be recorded along with the library). + * + * Normal library use has the library components compiled in at the same point as the application code, as + * demonstrated in the library demos and applications. This is the preferred method, as the library is recompiled + * each time to ensure that all static options for a particular application are applied. + */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/ChangeLog.txt b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/ChangeLog.txt new file mode 100644 index 0000000000..6ea4dfb760 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/ChangeLog.txt @@ -0,0 +1,993 @@ +/** \file + * + * This file contains special DoxyGen information for the generation of the main page and other special + * documentation pages. It is not a project source file. + */ + + /** \page Page_ChangeLog Project Changelog + * + * \section Sec_ChangeLog100807 Version 100807 + * New: + * - Added new ADC_DisableChannel() function (thanks to Mich Davis) + * - Added new VTARGET_REF_VOLTS and VTARGET_SCALE_FACTOR compile time defines to the AVRISP-MKII programmer project to set + * the VTARGET reference voltage and scale factor + * - Added new pgm_read_ptr() macro to Common.h for reading of pointers out of flash memory space + * - Added new SWAPENDIAN_16() and SWAPENDIAN_32() macros to Common.h for statically initialized variables at compile time + * - Added new Drivers/USB/LowLevel/Device.c file to house Device mode specific functions that are more complicated than simple macros + * - Added new AVRStudio 4 project files for all library demos, projects and bootloaders + * - Added ability to set the serial baud rate via the user's terminal in the XPLAINBridge project + * - Added new LUFA module variables for the different source modules in the core library makefile to simplify project makefiles + * - Added start of a new Test and Measurement class demo (thanks to Peter Lawrence) + * - Added new SPI_ORDER_* data order masks to the SPI peripheral driver + * - Added support to the AVRISP-MKII project for ISP speeds slower than 125KHz via a new software SPI driver + * - Added support for the new button/LED on the latest model USBTINY-MKII + * + * Changed: + * - The RingBuff library code has been replaced in the XPLAINBridge, Benito and USBtoSerial projects with an ultra lightweight + * ring buffer to help improve the reliability of the projects + * - The EEPROM stream read/write functions now use eeprom_update_byte() instead of eeprom_write_byte(), so that only + * changed bytes are written to EEPROM to preserve its lifespan + * - Changed over the AVRISP-MKII and TemperatureDataLogger projects to use eeprom_update_byte() when writing non-volatile + * parameters to EEPROM to preserve its lifespan + * - Removed unused line encoding data and control requests from the CDC Bootloader code, to save space + * - Renamed SERIAL_STREAM_ASSERT() macro to STDOUT_ASSERT() + * - The USB_Device_IsRemoteWakeupSent() and USB_Device_IsUSBSuspended() macros have been deleted, as they are now obsolete + * - Rewrote the implementation of the SwapEndian_16() and SwapEndian_32() functions so that they compile down in most instances to + * minimal loads and stores rather than complicated shifts + * - The software UART in the XPLAINBridge has been largely altered to try to improve upon its performance and reliability + * - The USBtoSerial and Benito projects now flushes received data via a flush timer, so that several bytes can be transmitted at once + * - Removed the automated checking of event names in the demo, project and bootloader makefiles due to inconsistencies between the + * behaviour of the command line tools used to perform the check on each platform + * - Internal USB driver source files renamed and moved to ease future possible architecture ports + * - All internal pseudo-function macros have been converted to true inline functions for type-safety and readability + * - Changed LED indicator masks for the AVRISP-MKII project, so that there are defined roles for each LED + * - Altered the CDC Device and Host Class drivers' receive byte routines, so that no data is indicated by the function returning a + * negative value (thanks to Andreas Paulin) + * - Added auto flushing of OUT data to the CDC Host Class driver's USBTask function to automatically flush the send pipe buffer + * + * Fixed: + * - Fixed AVRISP project sending a LOAD EXTENDED ADDRESS command to 128KB AVRs after programming or reading from + * the last page of FLASH (thanks to Gerard Sexton) + * - Fixed AVRISP project not sending a full erase-and-write EEPROM command to XMEGA targets when writing to the EEPROM + * instead of the split write-only command (thanks to Tim Margush) + * - Fixed RNDISEthernet demos crashing when calculating checksums for Ethernet/TCP packets of more than ~500 bytes due to + * an overflow in the checksum calculation loop (thanks to Kevin Malec) + * - Fixed XPLAINBridge project not correctly reading the XMEGA's supply voltage when reporting back to the host + * - Fixed incorrect signature for the ATMEGA32U2 in the DFU bootloader (thanks to Axel Rohde) + * - Fixed internal device serial not being accessible on the ATMEGAXXU2 AVRs (thanks to Axel Rohde) + * - Fixed void pointer arithmetic in ConfigDescriptor.h breaking C++ compatibility (thanks to Michael Hennebry) + * - Fixed broken PDI EEPROM Section Erase functionality in the AVRISP-MKII project + * - Fixed USB_Device_SendRemoteWakeup() not working when the USB clock was frozen during USB bus suspend (thanks to Brian Dickman) + * - Fixed occasional lockup of the AVRISP project due to the timeout extension code incorrectly extending the timeout in + * PDI and TPI programming modes infinitely + * - Fixed HID device class driver still using PrevReportINBuffer for GetReport control requests even when it has been + * set to NULL by the user application (thanks to Axel Rohde) + * - Fixed MIDI_Device_SendEventPacket() not correctly waiting for the endpoint to become ready (thanks to Robin Green) + * - Fixed Benito and USBtoSerial projects not turning off the USART before reconfiguring it, which could cause incorrect + * operation to occur (thanks to Bob Paddock) + * - Fixed Serial peripheral driver not turning off the USART before reconfiguring it, which would cause incorrect operation + * to occur (thanks to Bob Paddock) + * - Fixed software application start command broken in the DFU class bootloader when dfu-programmer is used due to application + * start address corruption + * + * \section Sec_ChangeLog100513 Version 100513 + * New: + * - Added incomplete MIDIToneGenerator project + * - Added new Relay Controller Board project (thanks to OBinou) + * - Added board hardware driver support for the Teensy, USBTINY MKII, Benito and JM-DB-U2 lines of third party USB AVR boards + * - Added new ATTR_NO_INIT variable attribute for global variables that should not be automatically cleared on startup + * - Added new ENDPOINT_*_BusSuspended error code to the Endpoint function, so that the stream functions early-abort if the bus + * is suspended before or during a transfer + * - Added new EVENT_CDC_Device_BreakSent() event and CDC_Host_SendBreak() function to the Device and Host CDC Class drivers + * - Added ReportType parameter to the HID device class driver CALLBACK_HID_Device_ProcessHIDReport() function so that FEATURE + * reports from the host to the device can be correctly processed + * - Added ReportType parameter to the HID host class driver HID_Host_SendReportByID() function so that FEATURE reports can be + * issued to the attached device + * + * Changed: + * - AVRISP programmer project now has a more robust timeout system + * - Added a timeout value to the TWI_StartTransmission() function, within which the addressed device must respond + * - Webserver project now uses the board LEDs to indicate the current IP configuration state + * - Added ENABLE_TELNET_SERVER compile time option to the Webserver project to disable the TELNET server if desired + * - Increased throughput of the USBtoSerial demo on systems that send multiple bytes per packet (thanks to Opendous Inc.) + * - Double bank CDC endpoints in the XPLAIN Bridge project, re-enable JTAG once the mode selection pin has been sampled. + * - Standardized the naming scheme given to configuration descriptor sub-elements in the Device mode demos, bootloaders + * and projects + * - All Class Driver Host mode demos now correctly set the board LEDs to READY once the enumeration process has completed + * - Added LIBUSB_FILTERDRV_COMPAT compile time option to the AVRISP programmer project to make the code compatible with Windows + * builds of avrdude at the expense of AVRStudio compatibility + * - Removed two-step endpoint/pipe bank clear and switch sequence for smaller, faster endpoint/pipe code + * - The USB_Init() function no longer calls sei() - the user is now responsible for enabling interrupts when they are ready + * for them to be enabled (thanks to Andrei Krainev) + * - The Audio_Device_IsSampleReceived() and Audio_Device_IsReadyForNextSample() functions are now inline, to reduce overhead + * - Removed the cast to uint16_t on the set baud rate in the USBtoSerial project, so that the higher >1M baud rates can be + * selected (thanks to Steffan Woltjer) + * - Removed software PDI and TPI emulation from the AVRISP-MKII clone project as it was very buggy and slow - PDI and TPI must + * now be implemented via separate programming headers + * - The CDC class bootloader now uses a watchdog reset rather than a soft-reset when exited to ensure that all hardware is + * properly reset to their defaults + * - Device mode class driver callbacks are now fired before the control request status stage is sent to prevent the host from + * timing out if another request is immediately fired and the device has a lengthy callback routine + * - The TeensyHID bootloader has been removed, per request from Paul at PJRC + * - The LIBUSB_FILTERDRV_COMPAT compile time option in the XPLAINBridge and AVRISP-MKII projects has been renamed + * LIBUSB_DRIVER_COMPAT, as it applies to all software on all platforms using the libUSB driver + * + * Fixed: + * - Fixed possible device lockup when INTERRUPT_CONTROL_ENDPOINT is enabled and the control endpoint is not properly + * selected when the ISR completes + * - Fixed AVRISP-MKII clone project not correctly issuing LOAD EXTENDED ADDRESS commands when the extended address + * boundary is crossed during programming or read back (thanks to Gerard Sexton) + * - Fixed warnings when building the AVRISP-MKII clone project with the ENABLE_XPROG_PROTOCOL compile time option disabled + * - Fixed software PDI/TPI programming mode in the AVRISP project not correctly toggling just the clock pin + * - Fixed TWI_StartTransmission() corrupting the contents of the GPIOR0 register + * - Fixed TWI driver not aborting when faced with no response after attempting to address a device on the bus + * - Fixed ADC routines not correctly returning the last result when multiple channels were read + * - Fixed ADC routines failing to read the extended channels (Channels 8 to 13, Internal Temperature Sensor) on the + * U4 series USB AVR parts + * - Fixed LowLevel MassStorage demo broken on the U2 series USB AVRs due to unsupported double-banked endpoint modes used + * - Fixed compilation error in the AudioInput demos when MICROPHONE_BIASED_TO_HALF_RAIL is defined (thanks to C. Scott Ananian) + * - Fixed incorrect definition of HID_ALIGN_DATA() causing incorrect HID report item data alignment + * - Fixed Still Image Host class driver not resetting the transaction ID when a new session is opened, fixed driver not sending + * a valid session ID to the device + * - Removed invalid dfu and flip related targets from the bootloaders - bootloaders can only be replaced with an external programmer + * - Fixed Set/Clear Feature requests directed to a non-configured endpoint not returning a stall to the host + * - Fixed HID Device Class Driver not allocating a temporary buffer when the host requests a report via the control endpoint and the + * user has set the PrevReportINBuffer driver configuration element to NULL (thanks to Lars Noschinski) + * - Fixed device state not being reset to DEVICE_STATE_Default if the host sets a 0x00 device address + * - Fixed device not stalling configuration requests before the device's address has been set + * - Fixed possibility of internal signature retrieval being corrupted if an interrupt occurs during a signature byte + * read (thanks to Andrei Krainev) + * - Fixed device state not being reset back to the default state if the host sets the address to 0 + * - Fixed Set Configuration requests not being stalled until the host has set the device's address + * - Fixed Host mode HID class driver not sending the correct report type when HID_Host_SendReportByID() was called and the + * HID_HOST_BOOT_PROTOCOL_ONLY compile time option is set + * - Fixed INTERRUPT_CONTROL_ENDPOINT compile time option preventing other interrupts from occurring while the control endpoint + * request is being processed, causing possible lockups if a USB interrupt occurs during a transfer + * - Remove incorrect Abstract Call Management class specific descriptor from the CDC demos, bootloaders and projects + * + * \section Sec_ChangeLog100219 Version 100219 + * + * New: + * - Added TPI programming support for 6-pin ATTINY devices to the AVRISP programmer project (thanks to Tom Light) + * - Added command timeout counter to the AVRISP project so that the device no longer freezes when incorrectly connected + * to a target + * - Added new TemperatureDataLogger application, a USB data logger which writes to the device's dataflash and appears to + * the host as a standard Mass Storage device when inserted + * - Added MIDI event packing support to the MIDI Device and Host mode Class drivers, allowing for multiple MIDI events to + * sent or received in packed form in a single USB packet + * - Added new MIDI send buffer flush routines to the MIDI Device and Host mode Class drivers, to flush packed events + * - Added master mode hardware TWI driver for easy TWI peripheral control + * - Added ADC MUX masks for the standard ADC input channels on all AVR models with an ADC, altered demos to use these masks + * as on some models, the channel number is not identical to its single-ended ADC MUX mask + * - New Webserver project, a RNDIS host USB webserver using the open source uIP TCP/IP network stack and FatFS library + * - New BOARD value option BOARD_NONE (equivalent to not specifying BOARD) which will remove all board hardware drivers which + * do not adversely affect the code operation (currently only the LEDs driver) + * - Added keyboard modifier masks (HID_KEYBOARD_MODIFER_*) and LED report masks (KEYBOARD_LED_*) to the HID class driver and + * Keyboard demos + * - Added .5MHz recovery clock to the AVRISP programmer project when in ISP programming mode to correct mis-set fuses + * + * Changed: + * - Slowed down software USART carried PDI programming in the AVRISP project to prevent transmission errors + * - Renamed the AVRISP project folder to AVRISP-MKII to reduce confusion + * - Renamed the RESET_LINE_* makefile tokens in the AVRISP MKII Project to AUX_LINE_*, as they are not always used for target + * reset + * - Changed over the MassStorageKeyboard Class driver device demo to use Start of Frame events rather than a timer to keep track + * of elapsed milliseconds + * - Inlined currently unused (but standardized) maintenance functions in the Device and Host Class drivers to save space + * - The XPLAINBridge project now selects between a USB to Serial bridge and a PDI programmer on startup, reading the JTAG port's + * TDI pin to determine which mode to use + * - Removed the stream example code from the Low Level VirtualSerial demos, as they were buggy and only served to add clutter + * + * Fixed: + * - Fixed AVRISP project not able to enter programming mode when ISP protocol is used + * - Fixed AVRISP PDI race condition where the guard time between direction changes could be interpreted as a start bit + * - Fixed ADC_IsReadingComplete() returning an inverted result + * - Fixed blocking CDC streams not aborting when the host is disconnected + * - Fixed XPLAIN board Dataflash driver broken due to incorrect preprocessor commands + * - Fixed inverted XPLAIN LED driver output (LED turned on when it was supposed to be turned off, and vice-versa) + * - Fixed Class Driver struct interface numbers in the KeyboardMouse and VirtualSerialMouse demos (thanks to Renaud Cerrato) + * - Fixed invalid USB controller PLL prescaler values for the ATMEGAxxU2 controllers + * - Fixed lack of support for the ATMEGA32U2 in the DFU and CDC class bootloaders + * - Fixed Benito project not resetting the target AVR automatically when programming has completed + * - Fixed DFU bootloader programming not discarding the correct number of filler bytes from the host when non-aligned programming + * ranges are specified (thanks to Thomas Bleeker) + * - Fixed CDC and RNDIS host demos and class drivers - bidirectional endpoints should use two separate pipes, not one half-duplex pipe + * - Fixed Pipe_IsEndpointBound() not taking the endpoint's direction into account + * - Fixed EEPROM and FLASH ISP programming in the AVRISP project + * - Fixed incorrect values of USB_CONFIG_ATTR_SELFPOWERED and USB_CONFIG_ATTR_REMOTEWAKEUP tokens (thanks to Claus Christensen) + * - Fixed SerialStream driver blocking while waiting for characters to be received instead of returning EOF + * - Fixed SerialStream driver not setting stdin to the created serial stream (thanks to Mike Alexander) + * - Fixed USB_GetHIDReportSize() returning the number of bits in the specified report instead of bytes + * - Fixed AVRISP project not extending the command delay after each successful page/word/byte program + * - Fixed accuracy of the SERIAL_UBBRVAL() and SERIAL_2X_UBBRVAL() macros for higher baud rates (thanks to Renaud Cerrato) + * + * \section Sec_ChangeLog091223 Version 091223 + * + * New: + * - Added activity LED indicators to the AVRISP project to indicate when the device is busy processing a command + * - The USB target family and allowable USB mode tokens are now public and documented (USB_CAN_BE_*, USB_SERIES_*_AVR) + * - Added new XPLAIN USB to Serial Bridge project (thanks to John Steggall for initial proof-of-concept, David Prentice + * and Peter Danneger for revised software USART code) + * - Added new RNDIS Ethernet Host LowLevel demo + * - Added new RNDIS Ethernet Host Class Driver + * - Added new RNDIS Ethernet Host ClassDriver demo + * - Added CDC_Host_Flush() function to the CDC Host Class driver to flush sent data to the attached device + * - Added PDI programming support for XMEGA devices to the AVRISP programmer project (thanks to Justin Mattair) + * - Added support for the XPLAIN board Dataflash, with new XPLAIN_REV1 board target for the different dataflash used + * on the first revision boards compared to the one mounted on later revisions + * - Added new HID_ALIGN_DATA() macro to return the pre-retrieved value of a HID report item, left-aligned to a given datatype + * - Added new PreviousValue to the HID Report Parser report item structure, for easy monitoring of previous report item values + * - Added new EVK527 board target + * - Added new USB_Host_GetDeviceStringDescriptor() convenience function + * - Added new LEDNotification project to the library, to give a visual LED notification on new events from the host + * - Added new NO_DEVICE_REMOTE_WAKEUP and NO_DEVICE_SELF_POWER compile time options + * + * Changed: + * - Removed code in the Keyboard demos to send zeroed reports between two reports with differing numbers of key codes + * as this relied on non-standard OS driver behaviour to repeat key groups + * - The SCSI_Request_Sense_Response_t and SCSI_Inquiry_Response_t type defines are now part of the Mass Storage Class + * driver common defines, rather than being defined in the Host mode Class driver section only + * - The USB_MODE_HOST token is now defined even when host mode is not available + * - The CALLBACK_HID_Device_CreateHIDReport() HID Device Class driver callback now has a new ReportType parameter to + * indicate the report type to generate + * - All Class Drivers now return false or the "DeviceDisconnected" error code of their respective error enums when a function + * is called when no host/device is connected where possible + * - The HOST_SENDCONTROL_DeviceDisconnect enum value has been renamed to HOST_SENDCONTROL_DeviceDisconnected to be in line + * with the rest of the library error codes + * - Make MIDI device demos also turn off the on board LEDs if MIDI Note On messages are sent with a velocity of zero, + * which some devices use instead of Note Off messages (thanks to Robin Green) + * - The CDC demos are now named "VirtualSerial" instead to indicate the demos' function rather than its implemented USB class, + * to reduce confusion and to be in line with the rest of the LUFA demos + * - The SImage_Host_SendBlockHeader() and SImage_Host_ReceiveBlockHeader() Still Image Host Class driver functions are now public + * + * Fixed: + * - Added missing CDC_Host_CreateBlockingStream() function code to the CDC Host Class driver + * - Fixed incorrect values for REPORT_ITEM_TYPE_* enum values causing corrupt data in the HID Host Parser + * - Fixed misnamed SI_Host_USBTask() and SI_Host_ConfigurePipes() functions + * - Fixed broken USB_GetNextDescriptor() function causing the descriptor to jump ahead double the expected amount + * - Fixed Pipe_IsEndpointBound() not masking the given Endpoint Address against PIPE_EPNUM_MASK + * - Fixed host state machine not enabling Auto VBUS mode when HOST_DEVICE_SETTLE_DELAY_MS is set to zero + * - Fixed misnamed Pipe_SetPipeToken() macro for setting a pipe's direction + * - Fixed CDCHost failing on devices with bidirectional endpoints + * - Fixed USB driver failing to define the PLL prescaler mask for the ATMEGA8U2 and ATMEGA16U2 + * - Fixed HID Parser not distributing the Usage Min and Usage Max values across an array of report items + * - Fixed Mass Storage Host Class driver and Low Level demo not clearing the error condition if an attached device returns a + * STALL to a GET MAX LUN request (thanks to Martin Luxen) + * - Fixed TeensyHID bootloader not properly shutting down the USB interface to trigger a disconnection on the host before resetting + * - Fixed MassStorageHost Class driver demo not having USB_STREAM_TIMEOUT_MS compile time option set properly to prevent slow + * devices from timing out the data pipes + * - Fixed the definition of the Endpoint_BytesInEndpoint() macro for the U4 series AVR parts + * - Fixed MIDI host Class driver MIDI_Host_SendEventPacket() routine not properly checking for Pipe ready before writing + * - Fixed use of deprecated struct initializers, removed library unused parameter warnings when compiled with -Wextra enabled + * - Fixed Still Image Host Class driver truncating the PIMA response code (thanks to Daniel Seibert) + * - Fixed USB_CurrentMode not being reset to USB_MODE_NONE when the USB interface is shut down and both Host and Device modes can be + * used (thanks to Daniel Levy) + * - Fixed TeensyHID bootloader not enumerating to the host correctly (thanks to Clint Fisher) + * - Fixed AVRISP project timeouts not checking for the correct timeout period (thanks to Carl Ott) + * - Fixed STK525 Dataflash driver using incorrect bit-shifting for Dataflash addresses (thanks to Tim Mitchell) + * + * \section Sec_ChangeLog091122 Version 091122 + * + * New: + * - Added new Dual Role Keyboard/Mouse demo + * - Added new HID_HOST_BOOT_PROTOCOL_ONLY compile time token to reduce the size of the HID Host Class driver when + * Report protocol is not needed + * - Added new MIDI LowLevel and ClassDriver Host demo, add new MIDI Host Class driver + * - Added new CDC/Mouse ClassDriver device demo + * - Added new Joystick Host ClassDriver and LowLevel demos + * - Added new Printer Host mode Class driver + * - Added new Printer Host mode ClassDriver demo + * - Added optional support for double banked endpoints and pipes in the Device and Host mode Class drivers + * - Added new stream creation function to the CDC Class drivers, to easily make standard I/O streams from CDC Class driver instances + * + * Changed: + * - Removed mostly useless "TestApp" demo, as it was mainly useful only for checking for syntax errors in the library + * - MIDI device demos now receive MIDI events from the host and display note ON messages via the board LEDs + * - Cleanups to the Device mode Mass Storage demo application SCSI routines + * - Changed Audio Class driver sample read/write functions to be inline, to reduce the number of cycles needed to transfer + * samples to and from the device (allowing more time for sample processing and output) + * - Audio class Device mode demos now work at both 16MHz and 8MHz, rather than just at 8MHz + * - The previous USBtoSerial demo has been moved into the projects directory, as it was just a modified CDC demo + * - The Endpoint/Pipe functions now use the const qualifier on the input buffer + * - Changed the CALLBACK_HIDParser_FilterHIDReportItem() callback to pass a HID_ReportItem_t rather than just the current + * item's attributes, to expose more information on the item (including it's type, collection path, etc.) + * - Changed MouseHostWithParser demos to check that the report items have a Mouse usage collection as a parent at some point, + * to prevent Joysticks from enumerating with the demo + * - Corrected the name of the misnamed USB_GetDeviceConfigDescriptor() function to USB_Host_GetDeviceConfigDescriptor(). + * - Keyboard LowLevel/ClassDriver demos now support multiple simultaneous key presses (up to 6) per report + * + * Fixed: + * - Fixed PrinterHost demo returning invalid Device ID data when the attached device does not have a + * device ID (thanks to Andrei Krainev) + * - Changed LUFA_VERSION_INTEGER define to use BCD values, to make comparisons easier + * - Fixed issue in the HID Host class driver's HID_Host_SendReportByID() routine using the incorrect mode (control/pipe) + * to send report to the attached device + * - Fixed ClassDriver AudioOutput device demo not selecting an audio output mode + * - Fixed incorrect SampleFrequencyType value in the AudioInput and AudioOutput ClassDriver demos' descriptors + * - Fixed incorrect event name rule in demo/project/bootloader makefiles + * - Fixed HID device class driver not reselecting the correct endpoint once the user callback routines have been called + * - Corrected HID descriptor in the Joystick Device demos - buttons should be placed outside the pointer collection + * - Fixed HID report parser collection paths invalid due to misplaced semicolon in the free path item search loop + * - Fixed HID host Class driver report send/receive report broken when issued through the control pipe + * - Fixed HOST_STATE_AS_GPIOR compile time option being ignored when in host mode (thanks to David Lyons) + * - Fixed LowLevel Keyboard demo not saving the issues report only after it has been sent to the host + * - Fixed Endpoint_Write_Control_Stream_* functions not sending a terminating IN when given data Length is zero + * + * \section Sec_ChangeLog090924 Version 090924 + * + * New: + * - Added new host mode class drivers and matching demos to the library for rapid application development + * - Added flag to the HID report parser to indicate if a device has multiple reports + * - Added new EVENT_USB_Device_StartOfFrame() event, controlled by the new USB_Device_EnableSOFEvents() and + * USB_Device_DisableSOFEvents() macros to give bus-synchronized millisecond interrupts when in USB device mode + * - Added new Endpoint_SetEndpointDirection() macro for bidirectional endpoints + * - Added new AVRISP project, a LUFA powered clone of the Atmel AVRISP-MKII programmer + * - Added ShutDown() functions for all hardware peripheral drivers, so that peripherals can be turned off after use + * - Added new CDC_Device_Flush() command to the device mode CDC Class driver to flush Device->Host data + * - Added extra masks to the SPI driver, changed SPI_Init() so that the clock polarity and sample modes can be set + * - Added new callback to the HID report parser, so that the user application can filter only the items it is interested + * in to be stored into the HIDReportInfo structure to save RAM + * - Added support for the officially recommended external peripheral layout for the BUMBLEB board (thanks to Dave Fletcher) + * - Added new Pipe_IsFrozen() macro to determine if the currently selected pipe is frozen + * - Added new USB_GetHIDReportSize() function to the HID report parser to retrieve the size of a given report by its ID + * - Added new combined Mass Storage and Keyboard demo (thanks to Matthias Hullin) + * + * Changed: + * - SetIdle requests to the HID device driver with a 0 idle period (send changes only) now only affect the requested + * HID interface within the device, not all HID interfaces + * - Added explicit attribute masks to the device mode demos' descriptors + * - Added return values to the CDC and MIDI class driver transmit functions + * - Optimized Endpoint_Read_Word_* and Pipe_Read_Word_* macros to reduce compiled size + * - Added non-null function parameter pointer restrictions to USB Class drivers to improve user code reliability + * - Added new "Common" section to the class drivers, to hold all mode-independent definitions for clarity + * - Moved SCSI command/sense constants into the Mass Storage Class driver, instead of the user-code + * - Altered the SCSI commands in the LowLevel Mass Storage Host to save on FLASH space by reducing function calls + * - Changed the parameters and behaviour of the USB_GetDeviceConfigDescriptor() function so that it now performs size checks + * and data validations internally, to simplify user code + * - Changed HIDParser to only zero out important values in the Parsed HID Report Item Information structure to save cycles + * - The HID report parser now always processed FEATURE items - HID_ENABLE_FEATURE_PROCESSING token now has no effect + * - The HID report parser now always ignores constant-data items, HID_INCLUDE_CONSTANT_DATA_ITEMS token now has no effect + * - The Benito Programmer project now has its own unique VID/PID pair allocated from the Atmel donated LUFA VID/PID pool + * - Add in new invalid event hook check targets to project makefiles to produce compilation errors when invalid event names + * are used in a project + * - The HID Report Parser now gives information on the total length of each report within a HID interface + * - The USE_NONSTANDARD_DESCRIPTOR_NAMES compile time token has been removed - there are now separate USB_Descriptor_* and + * USB_StdDescriptor_* structures for both the LUFA and standardized element naming conventions so both may be used + * + * Fixed: + * - Fixed possible lockup in the CDC device class driver, when the host sends data that is a multiple of the + * endpoint's bank + * - Fixed swapped parameters in the HID state memory copy call while processing a HID PUSH item in the HID report parser + * - Fixed memory corruption HID report parser when too many COLLECTION or PUSH items were processed + * - Fixed HID report parser not resetting the FEATURE item count when a REPORT ID item is encountered + * - Fixed USBtoSerial demos not reading in UDR1 when the USART receives data but the USB interface is not enumerated, + * causing continuous USART receive interrupts + * - Fixed misspelled event name in the Class driver USBtoSerial demo, preventing correct operation + * - Fixed invalid data being returned when a GetStatus request is issued in Device mode with an unhandled data recipient + * - Added hardware USART receive interrupt and software buffering to the Benito project to ensure received data is not + * missed or corrupted + * - Fixed Device mode HID Class driver always sending IN packets, even when nothing to report + * - Fixed Device mode HID Class driver not explicitly initializing the ReportSize parameter to zero before calling callback + * routine, so that ignored callbacks don't cause incorrect data to be sent + * - Fixed StillImageHost not correctly freezing and unfreezing data pipes while waiting for a response block header + * - Fixed error in the PrinterHost demo preventing the full page data from being sent to the attached device (thanks to John Andrews) + * - Fixed CDC based demos and projects' INF driver files under 64 bit versions of Windows (thanks to Ronny Hanson, Thomas Bleeker) + * - Re-add in missing flip, flip-ee, dfu and dfu-ee targets to project makefiles (thanks to Opendous Inc.) + * - Fix allowable F_CPU values comment in project makefiles to more accurately reflect the allowable values on the USB AVRs + * - Fixed DFU and CDC class bootloaders on the series 2 USB AVRs, corrected invalid signatures, added support for the new + * ATMEGAxx2 series 2 variant AVRs to the DFU bootloader + * - Fixed Low Level USBtoSerial demo not storing received characters (thanks to Michael Cooper) + * - Fixed MIDI Device Class driver not sending/receiving MIDI packets of the correct size (thanks to Thomas Bleeker) + * + * + * \section Sec_ChangeLog090810 Version 090810 + * + * New: + * - Added new device class drivers and matching demos to the library for rapid application development + * - Added new PrinterHost demo (thanks to John Andrews) + * - Added USB Missile Launcher project, submitted by Dave Fletcher + * - Added new Benito Arduino Programmer project + * - Added incomplete device and host mode demos for later enhancement + * - Updated MassStorage device block write routines to use ping-pong Dataflash buffering to increase throughput by around 30% + * - Error status LEDs shown when device endpoint configuration fails to complete in all demos and projects + * - Added new USB_Host_SetDeviceConfiguration() convenience function for easy configuration selection of devices while in USB + * host mode + * - Added new USB_Host_ClearPipeStall() convenience function to clear a stall condition on an attached device's endpoint + * - Added new USB_Host_GetDeviceDescriptor() convenience function to retrieve the attached device's Device descriptor + * - Added new Endpoint_ClearStatusStage() convenience function to assist with the status stages of control transfers + * - Added new USE_INTERNAL_SERIAL define for using the unique serial numbers in some AVR models as the USB device's serial number, + * added NO_INTERNAL_SERIAL compile time option to turn off new serial number reading code + * - Added new DATAFLASH_CHIP_MASK() macro to the Dataflash driver, which returns the Dataflash select mask for the given chip index + * - Added new HOST_STATE_WaitForDeviceRemoval host state machine state for non-blocking disabling of device communications until the + * device has been removed (for use when an error occurs or communications with the device have completed) + * - Added new FAST_STREAM_TRANSFERS compile time option for faster stream transfers via multiple bytes copied per stream loop + * - Added stdio stream demo code to the CDC device demos, to show how to create standard streams out of the virtual serial ports + * - Added new EEPROM and FLASH buffer versions of the Endpoint and Pipe stream functions + * - Added new USE_FLASH_DESCRIPTORS and FIXED_NUM_CONFIGURATIONS compile time options + * - Added support for the new ATMEGA32U2, ATMEGA16U2 and ATMEGA8U2 AVR models + * - Added new USB_DeviceState variable to keep track of the current Device mode USB state + * - Added new LEDs_ToggleLEDs() function to the LEDs driver + * - Added new Pipe_BoundEndpointNumber() and Pipe_IsEndpointBound() functions + * - Added new DEVICE_STATE_AS_GPIOR and HOST_STATE_AS_GPIOR compile time options + * - Added 404 Not Found errors to the webserver in the RNDIS demos to indicate invalid URLs + * + * Changed: + * - Deprecated pseudo-scheduler and removed dynamic memory allocator from the library (first no longer needed and second unused) + * - The device-mode CALLBACK_USB_GetDescriptor() function now has an extra parameter so that the memory space in which the requested + * descriptor is located can be specified. This means that descriptors can now be located in multiple memory spaces within a device. + * - Removed vague USB_IsConnected global - test USB_DeviceState or USB_HostState explicitly to gain previous functionality + * - Removed USB_IsSuspended global - test USB_DeviceState against DEVICE_STATE_Suspended instead + * - Extended USB_GetDeviceConfigDescriptor() routine to require the configuration number within the device to fetch + * - Dataflash_WaitWhileBusy() now always ensures that the dataflash is ready for the next command immediately after returning, + * no need to call Dataflash_ToggleSelectedChipCS() afterwards + * - Low level API MIDI device demo no longer blocks if a note change event is sent while the endpoint is not ready + * - Pipe_GetErrorFlags() now returns additional error flags for overflow and underflow errors + * - Pipe stream functions now automatically set the correct pipe token, so that bidirectional pipes can be used + * - Pipe_ConfigurePipe() now automatically defaults IN pipes to accepting infinite IN requests, this can still be changed by calling + * the existing Pipe_SetFiniteINRequests() function + * - Changed F_CLOCK entries in project makefiles to alias to F_CPU by default, as this is the most common case + * - Host mode demos now use sane terminal escape codes, so that text is always readable and events/program output is visually distinguished + * from one another using foreground colours + * - Internal per-device preprocessing conditions changed to per-device series rather than per-controller group for finer-grain + * internal control + * - Interrupts are no longer disabled during the processing of Control Requests on the default endpoint while in device mode + * - AudioOutput demos now always output to board LEDs, regardless of output mode (removed AUDIO_OUT_LEDS project option) + * - Removed SINGLE_DEVICE_CONFIGURATION compile time option in favor of the new FIXED_NUM_CONFIGURATIONS option so that the exact number + * of device configurations can be defined statically + * - Removed VBUS events, as they are already exposed to the user application via the regular device connection and disconnection events + * - Renamed and altered existing events to properly separate out Host and Device mode events + * - All demos switched over from GNU99 standards mode to C99 standards mode, to reduce the dependancies on GCC-only language extensions + * + * Fixed: + * - Changed bootloaders to use FLASHEND rather than the existence of RAMPZ to determine if far FLASH pointers are needed to fix + * bootloaders on some of the USB AVR devices where avr-libc erroneously defines RAMPZ + * - Fixes to MassStorageHost for better device compatibility (increase command timeout, change MassStore_WaitForDataReceived() + * to only unfreeze and check one data pipe at a time) to prevent incorrect device enumerations and freezes while transferring data + * - Make Pipe_ConfigurePipe() mask the given endpoint number against PIPE_EPNUM_MASK to ensure the endpoint IN direction bit is + * cleared to prevent endpoint type corruption + * - Fixed issue opening CDC-ACM ports on hosts when the CDC device tries to send data before the host has set the line encoding + * - Fixed USB_OPT_MANUAL_PLL option being ignored during device disconnects on some models (thanks to Brian Dickman) + * - Fixed documentation mentioning Pipe_GetCurrentToken() function when correct function name is Pipe_GetPipeToken() + * - Fixed ADC driver for the ATMEGA32U4 and ATMEGA16U4 (thanks to Opendous Inc.) + * - Fixed CDCHost demo unfreezing the pipes at the point of configuration, rather than use + * - Fixed MassStorage demo not clearing the reset flag when a Mass Storage Reset is issued while not processing a command + * - Fixed USB_Host_SendControlRequest() not re-suspending the USB bus when initial device ready-wait fails + * - Fixed USB Pad regulator not being disabled on some AVR models when the USB_OPT_REG_DISABLED option is used + * - Fixed Host mode to Device mode UID change not causing a USB Disconnect event when a device was connected + * - Fixed Mouse/Keyboard demos not performing the correct arithmetic on the Idle period at the right times (thanks to Brian Dickman) + * - Fixed GenericHID failing HID class tests due to incorrect Logical Minimum and Logical Maximum values (thanks to Sren Greiner) + * - Fixed incorrect PIPE_EPNUM_MASK mask causing pipe failures on devices with endpoint addresses of 8 and above (thanks to John Andrews) + * - Fixed report data alignment issues in the MouseHostWithParser demo when X and Y movement data size is not a multiple of 8 bits + * - Fixed HID Report Descriptor Parser not correctly resetting internal states when a REPORT ID element is encountered + * - Fixed incorrect BUTTONS_BUTTON1 for the STK526 target + * - Fixed RNDIS demos freezing when more than one connection was attempted simultaneously, causing memory corruption + * - Fixed USBtoSerial demo receiving noise from the USART due to pull-up not being enabled + * + * + * \section Sec_ChangeLog090605 Version 090605 + * + * - Fixed bug in RNDISEthernet and DualCDC demos not using the correct USB_ControlRequest structure for control request data + * - Fixed documentation showing incorrect USB mode support on the supported AVRs list + * - Fixed RNDISEthernet not working under Linux due to Linux requiring an "optional" RNDIS request which was unhandled + * - Fixed Mouse and Keyboard device demos not acting in accordance with the HID specification for idle periods (thanks to Brian Dickman) + * - Removed support for endpoint/pipe non-control interrupts; these did not act in the way users expected, and had many subtle issues + * - Fixed Device Mode not handling Set Feature and Clear Feature Chapter 9 requests that are addressed to the device (thanks to Brian Dickman) + * - Moved control endpoint interrupt handling into the library itself, enable via the new INTERRUPT_CONTROL_ENDPOINT token + * - Fixed CDCHost not clearing configured pipes and resetting configured pipes mask when a partially enumerated invalid CDC + * interface is skipped + * - Clarified the size of library tokens which accept integer values in the Compile Time Tokens page, values now use the smallest datatype + * inside the library that is able to hold their defined value to save space + * - Removed DESCRIPTOR_ADDRESS() macro as it was largely superfluous and only served to obfuscate code + * - Rewritten event system to remove all macros, to make user code clearer + * - Fixed incorrect ENDPOINT_EPNUM_MASK mask preventing endpoints above EP3 from being selected (thanks to Jonathan Oakley) + * - Removed STREAM_CALLBACK() macro - callbacks now use regular function definitions to clarify user code + * - Removed DESCRIPTOR_COMPARATOR() macro - comparators should now use regular function definitions to clarify user code + * - USB_IsConnected is now cleared before the USB_Disconnect() event is fired in response to VBUS being removed + * - Fixed incorrect PID value being used in the USBtoSerial project (thanks to Phill) + * - Deleted StdDescriptors.c, renamed USB_GetDescriptor() to CALLBACK_USB_GetDescriptor, moved ConfigDescriptor.c/.h from the + * LUFA/Drivers/USB/Class/ directory to LUFA/Drivers/USB/HighLevel/ in preparation for the new USB class APIs + * - Moved out each demos' functionality library files (e.g. Ring Buffer library) to /Lib directories for a better directory structure + * - Removed Tx interrupt from the USBtoSerial demo; now sends characters via polling to ensure more time for the Rx interrupt + * - Fixed possible enumeration errors from spin-loops which may fail to exit if the USB connection is severed before the exit condition + * becomes true + * + * + * \section Sec_ChangeLog090510 Version 090510 + * + * - Added new GenericHIDHost demo + * - Corrections to the KeyboardHost and MouseHost demos' pipe handling to freeze and unfreeze the data pipes at the point of use + * - KeyboardHost, MouseHost and GenericHIDHost demos now save and restore the currently selected pipe inside the pipe ISR + * - Changed GenericHID device demo to use the LUFA scheduler, added INTERRUPT_DATA_ENDPOINT and INTERRUPT_CONTROL_ENDPOINT compile + * time options + * - All comments in the library, bootloaders, demos and projects have now been spell-checked and spelling mistakes/typos corrected + * - Added new PIMA_DATA_SIZE() define to the Still Image Host demo + * - Add call to MassStore_WaitForDataReceived() in MassStore_GetReturnedStatus() to ensure that the CSW has been received in the + * extended MSC timeout period before continuing, to prevent long processing delays from causing the MassStore_GetReturnedStatus() + * to early-abort (thanks to Dmitry Maksimov) + * - Move StdRequestType.h, StreamCallbacks.h, USBMode.h from the LowLevel USB driver directory to the HighLevel USB driver directory, + * where they are more suited + * - Removed all binary constants and replaced with decimal or hexadecimal constants so that unpatched GCC compilers can still build the + * code without having to be itself patched and recompiled first + * - Added preprocessor checks and documentation to the bootloaders giving information about missing SIGNATURE_x defines due to + * outdated avr-libc versions. + * - Added support to the CDCHost demo for devices with multiple CDC interfaces which are not the correct ACM type preceding the desired + * ACM CDC interface + * - Fixed GenericHID demo not starting USB and HID management tasks when not using interrupt driven modes (thanks to Carl Kjeldsen) + * - Fixed RNDISEthenet demo checking the incorrect message field for packet size constraints (thanks to Jonathan Oakley) + * - Fixed WriteNextReport code in the GenericHIDHost demo using incorrect parameter types and not selecting the correct endpoint + * - Adjusted sample CTC timer calculations in the AudioOutput and AudioInput demos to match the CTC calculations in the AVR datasheet, + * and to fix instances where rounding caused the endpoint to underflow (thanks to Robin Theunis) + * - The USB_Host_SendControlRequest() function no longer automatically selects the Control pipe (pipe 0), so that other control type + * pipes can be used with the function + * - The USB Host management task now saves and restores the currently selected pipe before and after the task completes + * - Fixed GenericHIDHost demo report write routine incorrect for control type requests (thanks to Andrei Krainev) + * - Removed Endpoint_ClearCurrentBank() and Pipe_ClearCurrentBank() in favor of new Endpoint_ClearIN(), Endpoint_ClearOUT(), + * Pipe_ClearIN() and Pipe_ClearOUT() macros (done to allow for the detection of packets of zero length) + * - Renamed *_ReadWriteAllowed() macros to *_IsReadWriteAllowed() to remain consistent with the rest of the LUFA API + * - Endpoint_IsSetupReceived() macro has been renamed to Endpoint_IsSETUPReceived(), Endpoint_ClearSetupReceived() macro has been + * renamed to Endpoint_ClearSETUP(), the Pipe_IsSetupSent() macro has been renamed to Pipe_IsSETUPSent() and the + * Pipe_ClearSetupSent() macro is no longer applicable and should be removed - changes made to compliment the new endpoint and pipe + * bank management API + * - Updated all demos, bootloaders and projects to use the new endpoint and pipe management APIs (thanks to Roman Thiel from Curetis AG) + * - Updated library doxygen documentation, added groups, changed documentation macro functions to real functions for clarity + * - Removed old endpoint and pipe aliased read/write/discard routines which did not have an explicit endian specifier for clarity + * - Removed the ButtLoadTag.h header file, as no one used for its intended purpose anyway + * - Renamed the main Drivers/AT90USBXXX directory to Drivers/Peripheral, renamed the Serial_Stream driver to SerialStream + * - Fixed CDC and USBtoSerial demos freezing where buffers were full while still transmitting or receiving (thanks to Peter Hand) + * - Removed "Host_" section of the function names in ConfigDescriptor.h, as most of the routines can now be used in device mode on the + * device descriptor + * - Renamed functions in the HID parser to have a "USB_" prefix and the acronym "HID" in the name + * - Fixed incorrect HID interface class and subclass values in the Mouse and KeyboardMouse demos (thanks to Brian Dickman) + * - Capitalized the "Descriptor_Search" and "Descriptor_Search_Comp" prefixes of the values in the DSearch_Return_ErrorCodes_t and + * DSearch_Comp_Return_ErrorCodes_t enums + * - Removed "ERROR" from the enum names in the endpoint and pipe stream error code enums + * - Renamed the USB_PowerOnErrorCodes_t enum to USB_InitErrorCodes_t, renamed the POWERON_ERROR_NoUSBModeSpecified enum value to + * USB_INITERROR_NoUSBModeSpecified + * - Renamed USB_PowerOnFail event to USB_InitFailure + * - Renamed OTG.h header functions to be more consistent with the rest of the library API + * - Changed over all deprecated GCC structure tag initializers to the standardized C99 format (thanks to Mike Alexander) + * - USB_HostRequest renamed to USB_ControlRequest, entire control request header is now read into USB_ControlRequest in Device mode + * rather than having the library pass only partially read header data to the application + * - The USB_UnhandledControlPacket event has had its parameters removed, in favor of accessing the new USB_ControlRequest structure + * - The Endpoint control stream functions now correctly send a ZLP to the host when less data than requested is sent + * - Fixed USB_RemoteWakeupEnabled flag never being set (the REMOTE WAKEUP Set Feature request was not being handled) + * - Renamed the FEATURELESS_CONTROL_ONLY_DEVICE compile-time token to CONTROL_ONLY_DEVICE + * - Endpoint configuration is now refined to give better output when all configurations have static inputs - removed the now useless + * STATIC_ENDPOINT_CONFIGURATION compile time token + * - Fixed SPI driver init function not clearing SPI2X bit when not needed + * - Fixed PREVENT ALLOW MEDIUM REMOVAL command issuing in the MassStorageHost demo using incorrect parameters (thanks to Mike Alex) + * - Fixed MassStorageHost demo broken due to an incorrect if statement test in MassStore_GetReturnedStatus() + * - Fixed reversed signature byte ordering in the CDC bootloader (thanks to Johannes Raschke) + * - Changed PIPE_CONTROLPIPE_DEFAULT_SIZE from 8 to 64 to try to prevent problems with faulty devices which do not respect the given + * wLength value when reading in the device descriptor + * - Fixed missing semicolon in the ATAVRUSBRF01 LED board driver code (thanks to Morten Lund) + * - Changed LED board driver code to define dummy LED masks for the first four board LEDs, so that user code can be compiled for boards + * with less than four LEDs without code modifications (thanks to Morten Lund) + * - Changed HWB board driver to Buttons driver, to allow for the support of future boards with more than one mounted GPIO button + * - Serial driver now correctly calculates the baud register value when in double speed mode + * - Init function of the Serial driver is now static inline to product smaller code for the common-case of static init values + * + * + * \section Sec_ChangeLog090401 Version 090401 + * + * - Fixed MagStripe project configuration descriptor containing an unused (blank) endpoint descriptor + * - Incorporated makefile changes by Denver Gingerich to retain compatibility with stock (non-WinAVR) AVR-GCC installations + * - Fixed makefile EEPROM programming targets programming FLASH data in addition to EEPROM data + * - LUFA devices now enumerate correctly with LUFA hosts + * - Fixed Configuration Descriptor search routine freezing when a comparator returned a failure + * - Removed HID report item serial dump in the MouseHostWithParser and KeyboardHostWithParser - useful only for debugging, and + * slowed down the enumeration of HID devices too much + * - Increased the number of bits per track which can be read in the MagStripe project to 8192 when compiled for the AT90USBXXX6/7 + * - Fixed KeyboardMouse demo discarding the wIndex value in the REQ_GetReport request + * - USBtoSerial demo now discards all Rx data when not connected to a USB host, rather than buffering characters for transmission + * next time the device is attached to a host. + * - Added new F_CLOCK compile time constant to the library and makefiles, to give the raw input clock (used to feed the PLL before any + * clock prescaling is performed) frequency, so that the PLL prescale mask can be determined + * - Changed stream wait timeout counter to be 16-bit, so that very long timeout periods can be set for correct communications with + * badly designed hosts or devices which greatly exceed the USB specification limits + * - Mass Storage Host demo now uses a USB_STREAM_TIMEOUT_MS of two seconds to maintain compatibility with poorly designed devices + * - Function attribute ATTR_ALWAYSINLINE renamed to ATTR_ALWAYS_INLINE to match other function attribute macro naming conventions + * - Added ATTR_ALWAYS_INLINE attribute to several key inlined library components, to ensure they are inlined in all circumstances + * - Removed SetSystemClockPrescaler() macro, the clock_prescale_set() avr-libc macro has been corrected in recent avr-libc versions + * - Fixed incorrect/missing control status stage transfers on demos, bootloaders and applications (thanks to Nate Lawson) + * - The NO_CLEARSET_FEATURE_REQUEST compile time token has been renamed to FEATURELESS_CONTROL_ONLY_DEVICE, and its function expanded + * to also remove parts of the Get Status chapter 9 request to further reduce code usage + * - Makefile updated to include output giving the currently selected BOARD parameter value + * - Board Dataflash driver now allows for dataflash ICs which use different shifts for setting the current page/byte address (thanks + * to Kenneth Clubb) + * - Added DataflashManager_WriteBlocks_RAM() and DataflashManager_ReadBlocks_RAM() functions to the MassStorage demo, to allow for easy + * interfacing with a FAT library for dataflash file level access + * - Corrected CDC class bootloader to fix a few bugs, changed address counter to store x2 addresses for convenience + * - Fixed typos in the SPI driver SPI_SPEED_FCPU_DIV_64 and SPI_SPEED_FCPU_DIV_128 masks (thanks to Markus Zocholl) + * - Keyboard and Mouse device demos (normal, data interrupt and fully interrupt driven) combined into unified keyboard and mouse demos + * - Keyboard and Mouse host demos (normal and data interrupt driven) combined into unified keyboard and mouse demos + * - Removed AVRISP_Programmer project due to code quality concerns + * - Fixed CDC demo not sending an empty packet after each transfer to prevent the host from buffering incoming data + * - Fixed documentation typos and preprocessor checks relating to misspellings of the USE_RAM_DESCRIPTORS token (thanks to Ian Gregg) + * - Fixed USBTask.h not conditionally including HostChapter9.h only when USB_CAN_BE_HOST is defined (thanks to Ian Gregg) + * - Fixed incorrect ADC driver init register manipulation (thanks to Tobias) + * - Added new GenericHID device demo application + * - Fixed Still Image Host SImage_SendData() function not clearing the pipe bank after sending data + * + * + * \section Sec_ChangeLog090209 Version 090209 + * + * - PWM timer mode in AudioOut demo changed to Fast PWM for speed + * - Updated Magstripe project to work with the latest hardware revision + * - Fixed library not responding to the BCERRI flag correctly in host mode, leading to device lockups + * - Fixed library handling Get Descriptor requests when not addressed as standard requests to the device or interface (thanks to + * Nate Lawson) + * - Fixed serious data corruption issue in MassStorage demo dataflash write routine + * - Added new NO_CLEARSET_FEATURE_REQUEST compile time token + * - USB task now restores previous global interrupt state after execution, rather than forcing global interrupts to be enabled + * - Fixed USB_DeviceEnumerationComplete event firing after each configuration change, rather than once after the initial configuration + * - Added ENDPOINT_DOUBLEBANK_SUPPORTED() macros to Endpoint.h, altered ENDPOINT_MAX_SIZE() to allow user to specify endpoint + * - ENDPOINT_MAX_ENDPOINTS changed to ENDPOINT_TOTAL_ENDPOINTS, PIPE_MAX_PIPES changed to PIPE_TOTAL_PIPES + * - Endpoint and Pipe non-control stream functions now ensure endpoint or pipe is ready before reading or writing + * - Changed Teensy bootloader to use a watchdog reset when exiting rather than a software jump + * - Fixed integer promotion error in MassStorage and MassStorageHost demos, corrupting read/write transfers + * - SPI_SendByte is now SPI_TransferByte, added new SPI_SendByte and SPI_ReceiveByte functions for fast one-way transfer + * - MassStorage demo changed to use new fast one-way SPI transfers to increase throughput + * - MassStorage handling of Mass Storage Reset class request improved + * - Altered MassStorage demo dataflash block read code for speed + * - Added USB_IsSuspended global flag + * - Simplified internal Dual Mode (OTG) USB library code to reduce code size + * - Extended stream timeout period to 100ms from 50ms + * - Mass Storage Host demo commands now all return an error code from the Pipe_Stream_RW_ErrorCodes_t enum + * - Added SubErrorCode parameter to the USB_DeviceEnumerationFailed event + * - VBUS drop interrupt now disabled during the manual-to-auto VBUS delivery handoff + * - Simplified low level backend so that device/host mode initialization uses the same code paths + * - Added workaround for faulty Mass Storage devices which do not implement the required GET_MAX_LUN request + * - Removed buggy Telnet application from the RNDIS demo + * - Moved Mass Storage class requests in the Mass Storage Host demo to wrapper functions in MassStoreCommands.c + * - Fixed incorrect SCSI command size value in the Request Sense command in MassStoreCommands.c + * - Added SetProtocol request to HID class non-parser Mouse and Keyboard demos to force devices to use the correct Boot Protocol + * - Added new "dfu" and "flip" programming targets to project makefiles + * - HID_PARSE_Sucessful enum member typo corrected to HID_PARSE_Successful + * - Changed COLLECTION item structures in the HID descriptor parser to include the collection's Usage Page value + * - Serial driver now sets Tx line as output, enables pull-up on Rx line + * - Fixed smaller USB AVRs raising multiple connection and disconnection events when NO_LIMITED_CONTROLLER_CONNECT is disabled + * - Added HOST_DEVICE_SETTLE_DELAY_MS to give the host delay after a device is connected before it is enumerated + * - Fixed KeyboardHostWithParser demo linking against the wrong global variables + * - Completed doxygen documentation of remaining library bootloaders, demos and projects + * - Fixed incorrect bootloader start address in the TeensyHID bootloader + * - Added HWB button whole-disk ASCII dump functionality to MassStoreHost demo + * - Replaced printf_P(PSTR("%c"), {Variable}) calls with putchar() for speed and size savings + * - Serial driver now accepts baud rates over 16-bits in size, added double speed flag option + * - Fixed incorrect callback abort return value in Pipe.c + * - Added new flip-ee and dfu-ee makefile targets (courtesy of Opendous Inc.) + * - Removed reboot-on-disconnect code from the TeensyHID bootloader, caused problems on some systems + * - Fixed AudioOutput and AudioInput demos looping on the endpoint data, rather than processing a sample at a time and returning + * each time the task runs to allow for other tasks to execute + * - Added support for the Atmel ATAVRUSBRF01 board + * - Added AVRISP Programmer Project, courtesy of Opendous Inc. + * - Fixed CDC Host demo not searching through both CDC interfaces for endpoints + * - Fixed incorrect Product String descriptor length in the DFU class bootloader + * + * + * \section Sec_ChangeLog081224 Version 081224 + * + * - MyUSB name changed to LUFA, the Lightweight USB Framework for AVRs + * - Fixed Mass Storage Host demo's MassStore_SendCommand() delay in the incorrect place + * - Fixed USBtoSerial demo not calling ReconfigureUSART() after a change in the line encoding + * - Fixed infinite loop in host mode Host-to-Device control transfers with data stages + * - HID report parser now supports devices with multiple reports in one interface via Report IDs + * - Fixed RZUSBSTICK board LED driver header incorrect macro definition order causing compile errors + * - Calling USB_Init() when the USB interface is already configured now forces a complete interface reset + * and re-enumeration - fixes MyUSB DFU bootloader not switching to app code correctly when soft reset used + * - Fixed "No newline at end of file" warning when stream callbacks are enabled + * - DFU bootloader now uses fixed signature bytes per device, rather than reading them out dynamically for size + * - Added new FIXED_CONTROL_ENDPOINT_SIZE and USE_SINGLE_DEVICE_CONFIGURATION switches to statically define certain values to + * reduce compiled binary size + * - Added new NO_LIMITED_CONTROLLER_CONNECT switch to prevent the library from trying to determine bus connection + * state from the suspension and wake up events on the smaller USB AVRs + * - Added summary of all library compile time tokens to the documentation + * - Added overview of the LUFA scheduler to the documentation + * - Removed MANUAL_PLL_CONTROL compile time token, replaced with a mask for the USB_Init() Options parameter + * - CDC bootloader now uses the correct non-far or far versions of the pgm_* functions depending on if RAMPZ is defined + * - Doxygen documentation now contains documentation on all the projects, bootloaders and most demos included with the library + * - CDC bootloader now runs user application when USB disconnected rather than waiting for a hard reset + * - MouseHostWithParser and KeyboardHostWithParser now support multiple-report devices + * - RNDIS demo can now close connections correctly using the new TCP_APP_CLOSECONNECTION() macro - used in Webserver + * - Fixed the DFU bootloader, no longer freezes up when certain files are programmed into an AVR, made reading/writing faster + * - Fixed mouse/joystick up/down movements reversed - HID mouse X/Y coordinates use a left-handed coordinate system, not a normal + * right-handed system + * - Added stub code to the CDC and USBtoSerial demos showing how to read and set the RS-232 handshake lines - not currently used in + * the demos, but the example code and supporting defines are now in place + * - Interrupts are now disabled when processing a control request in device mode, to avoid exceeding the strict control request + * timing requirements. + * - All demos now use a central StatusUpdate() function rather than direct calls to the board LED functions, so that the demos can + * easily be altered to show different LED combinations (or do something else entirely) as the demo's status changes + * - Removed LED commands from the CDC bootloader, unused by most AVR910 programming software + * - Fixed RNDIS demo ICMP ping requests echoing back incorrect data + * - Added DHCP server code to RNDIS demo, allowing for hands-free auto configuration on any PC + * - Fixed DFU bootloader PID value for the ATMEGA16U4 AVR + * - Endpoint and Pipe configuration functions now return an error code indicating success or failure + * - USB Reset in device mode now resets and disables all device endpoints + * - Added intermediate states to the host mode state machine, reducing the USB task blocking time to no more than 1ms explicitly per + * invocation when in host mode + * - Added support for the ATMEGA32U6 microcontroller + * - Added STATIC_ENDPOINT_CONFIGURATION compile time option, enabled in the bootloaders to minimize space usage + * - Removed redundant code from the USB device GetStatus() chapter 9 processing routine + * - Added new TeensyHID bootloader, compatible with the Teensy HID protocol (http://www.pjrc.com/teensy/) + * - Versions are now numbered by release dates, rather than arbitrary major/minor revision numbers + * - USB_RemoteWakeupEnabled is now correctly set and cleared by SetFeature and ClearFeature requests from the host + * - Changed prototype of GetDescriptor, so that it now returns the descriptor size (or zero if the descriptor doesn't exist) + * rather than passing the size back to the caller through a parameter and returning a boolean + * + * + * \section Sec_ChangeLog153 Version 1.5.3 - Released 2nd October, 2008 + * + * - Fixed CDC bootloader using pgmspace macros for some descriptors inappropriately + * - Updated all Mouse and Keyboard device demos to include boot protocol support (now works in BIOS) + * - Renamed bootloader directories to remove spaces, which were causing build problems on several OSes + * - Removed serial number strings from all but the MassStore demo where it is required - users were not + * modifying the code to either omit the descriptor or use a unique serial per device causing problems + * when multiple units of the same device were plugged in at the same time + * - AudioOutput and AudioInput demos now correctly silence endpoints when not enabled by the host + * - Added KeyboardMouse demo (Keyboard and Mouse functionality combined into a single demo) + * - Added DriverStubs directory to house board level driver templates, to make MyUSB compatible custom board + * driver creation easier + * - Extended MassStorage demo to support multiple LUNs, 2 by default + * - Fixed incorrect device address mask, preventing the device from enumerating with addresses larger than 63 + * - Fixed incorrect data direction mask in the GetStatus standard request, preventing it from being handled + * - Fixed incorrect GetStatus standard request for endpoints, now returns the endpoint STALL status correctly + * - Added in new USB_RemoteWakeupEnabled and USB_CurrentlySelfPowered flags rather than using fixed values + * - Added DualCDC demo to demonstrate the use of Interface Association Descriptors + * - Added pipe NAK detection and clearing API + * - Added pipe status change (NAK, STALL, etc.) interrupt API + * - Fixed MassStorageHost demo so that it no longer freezes randomly when issuing several commands in a row + * - Host demos configuration descriptor routines now return a unique error code when the returned data does + * not have a valid configuration descriptor header + * - Added Endpoint_WaitUntilReady() and Pipe_WaitUntilReady() functions + * - Stream functions now have software timeouts, timeout period can be set by the USB_STREAM_TIMEOUT_MS token + * - All demos now pass the USB.org automated Chapter 9 device compliance tests + * - All HID demos now pass the USB.org automated HID compliance tests + * - Polling interval of the interrupt endpoint in the CDC based demos changed to 0xFF to fix problems on Linux systems + * - Changed stream functions to accept a new callback function, with NO_STREAM_CALLBACKS used to disable all callbacks + * - Mass Storage demo dataflash management routines changed to use the endpoint stream functions + * - Added AVRStudio project files for each demo in addition to the existing Programmer's Notepad master project file + * - Re-added call to ReconfigureUSART() in USBtoSerial SetLineCoding request, so that baud rate changes + * are reflected in the hardware (change was previously lost) + * + * + * \section Sec_ChangeLog152 Version 1.5.2 - Released 31st July, 2008 + * + * - Fixed SwapEndian_32() function in Common.h so that it now works correctly (wrong parameter types) + * - Updated RNDIS demo - notification endpoint is no longer blocking so that it works with faulty Linux RNDIS + * implementations (where the notification endpoint is ignored in favor of polling the control endpoint) + * - Fixed incorrect Vendor Description string return size in RNDIS demo for the OID_GEN_VENDOR_DESCRIPTION OID token + * - Added very basic TCP/IP stack and HTTP/TELNET servers to RNDIS demo + * - Fixed DFU bootloader exit causing programming software to complain about failed writes + * - Fixed DFU bootloader EEPROM programming mode wiping first flash page + * - Fixed Clear/Set Feature device standard request processing code (fixing MassStorage demo in the process) + * - Added support for the ATMEGA16U4 AVR microcontroller + * - Library license changed from LGPLv3 to MIT license + * + * + * \section Sec_ChangeLog151 Version 1.5.1 - Released 31st July, 2008 + * + * - Changed host demos to enable the host function task on the firing of the USB_DeviceEnumerationComplete event + * rather than the USB_DeviceAttached event + * - HID Usage Stack now forcefully cleared after an IN/OUT/FEATURE item has been completely processed to remove + * any referenced but not created usages + * - Changed USB_INT_DisableAllInterrupts() and USB_INT_ClearAllInterrupts(), USB_Host_GetNextDescriptorOfType(), + * USB_Host_GetNextDescriptorOfTypeBefore(), USB_Host_GetNextDescriptorOfTypeAfter() to normal functions (from inline) + * - Fixed USBtoSerial demo not sending data, only receiving + * - Fixed main makefile to make all by default, fixed MagStripe directory case to prevent case-sensitive path problems + * - ConfigDescriptor functions made normal, instead of static inline + * - Pipe/Endpoint *_Ignore_* functions changed to *_Discard_*, old names still present as aliases + * - Fixed ENDPOINT_MAX_SIZE define to be correct on limited USB controller AVRs + * - Changed endpoint and pipe size translation routines to use previous IF/ELSE IF cascade code, new algorithmic + * approach was buggy and caused problems + * - Bootloaders now compile with -fno-inline-small-functions option to reduce code size + * - Audio demos now use correct endpoint sizes for full and limited controller USB AVRs, double banking in all cases + * to be in line with the specification (isochronous endpoints MUST be double banked) + * - Added Interface Association descriptor to StdDescriptors.h, based on the relevant USB2.0 ECN + * - Fixed MIDI demo, corrected Audio Streaming descriptor to follow the MIDI-specific AS structure + * - Fixed HID class demo descriptors so that the HID interface's protocol is 0x00 (required for non-boot protocol HID + * devices) to prevent problems on hosts expecting the boot protocol functions to be supported + * - Added read/write control stream functions to Endpoint.h + * - Fixed AudioOut demo not setting port pins to inputs on USB disconnect properly + * - Added RNDISEthernet demo application + * + * + * \section Sec_ChangeLog150 Version 1.5.0 - Released 10 June, 2008 + * + * - Fixed MIDI demo, now correctly waits for the endpoint to be ready between multiple note messages + * - Added CDC Host demo application + * - Added KeyboardFullInt demo application + * - Endpoint and Pipe creation routines now mask endpoint/pipe size with the size mask, to remove transaction + * size bits not required for the routines (improves compatibility with devices) + * - Fixed AudioInput demo - now correctly sends sampled audio to the host PC + * - Fixed AudioOutput demo once more -- apparently Windows requires endpoint packets to be >=192 bytes + * - Shrunk round-robbin scheduler code slightly via the use of struct pointers rather than array indexes + * - Fixed off-by-one error when determining if the Usage Stack is full inside the HID Report parser + * - Renamed Magstripe.h to MagstripeHW.h and moved driver out of the library and into the MagStripe demo folder + * - Added preprocessor checks to enable C linkage on the library components when used with a C++ compiler + * - Added Still Image Host demo application + * - The USB device task now restores the previously selected endpoint, allowing control requests to be transparently + * handled via interrupts while other endpoints are serviced through polling + * - Fixed device signature being sent in reverse order in the CDC bootloader + * - Host demos now have a separate ConfigDescriptor.c/.h file for configuration descriptor processing + * - HostWithParser demos now have a separate HIDReport.c/.h file for HID report processing and dumping + * - Removed non-mandatory commands from MassStorage demo to save space, fixed SENSE ResponseCode value + * - CDC demos now send empty packets after sending a full one to prevent buffering issues on the host + * - Updated demo descriptors to use VID/PID values donated by Atmel + * - Added DoxyGen documentation to the source files + * - Fixed Serial_IsCharReceived() definition, was previously reversed + * - Removed separate USB_Descriptor_Language_t descriptor, USB_Descriptor_String_t is used instead + * - Removed unused Device Qualifier descriptor structure + * - Renamed the USB_CreateEndpoints event to the more appropriate USB_ConfigurationChanged + * - Fixed MassStorageHost demo reading in the block data in reverse + * - Removed outdated typedefs in StdRequestType.h, superseded by the macro masks + * - Corrected OTG.h is now included when the AVR supports both Host and Device modes, for creating OTG products + * - USB_DeviceEnumerationComplete event is now also fired when in device mode and the host has finished its enumeration + * - Interrupt driven demos now properly restore previously selected endpoint when ISR is complete + * - The value of USB_HOST_TIMEOUT_MS can now be overridden in the user project makefile to a custom fixed timeout value + * - Renamed USB_Host_SOFGeneration_* macros to more friendly USB_Host_SuspendBus(), USB_Host_ResumeBus() + * and USB_Host_IsBusSuspended() + * - Renamed *_*_Is* macros to *_Is* to make all flag checking macros consistent, Pipe_SetInterruptFreq() is now + * Pipe_SetInterruptPeriod() to use the correct terminology + * - UnicodeString member of USB_Descriptor_String_t struct changed to an ordinary int array type, so that the GCC + * Unicode strings (prefixed with an L before the opening quotation mark) can be used instead of explicit arrays + * of ASCII characters + * - Fixed Endpoint/Pipes being configured incorrectly if the maximum endpoint/pipe size for the selected USB AVR + * model was given as the bank size + * - HID device demos now use a true raw array for the HID report descriptor rather than a struct wrapped array + * - Added VERSION_BCD() macro, fixed reported HID and USB version numbers in demo descriptors + * - Cleaned up GetDescriptor device chapter 9 handler function + * - Added GET_REPORT class specific request to HID demos to make them complaint to the HID class + * - Cleaned up setting of USB_IsInitialized and USB_IsConnected values to only when needed + * - Removed Atomic.c and ISRMacro.h; the library was already only compatible with recent avr-lib-c for other reasons + * - All demos and library functions now use USB standardized names for the USB data (bRequest, wLength, etc.) + * - Added USE_NONSTANDARD_DESCRIPTOR_NAMES token to switch back to the non-standard descriptor element names + * + * + * \section Sec_ChangeLog141 Version 1.4.1 - Released 5 May, 2008 + * + * - Enhanced KeyboardWithParser demo, now prints out pressed alphanumeric characters like the standard demo + * - Fixed MassStorage demo, read/writes using non mode-10 commands now work correctly + * - Corrected version number in Version.h + * + * + * \section Sec_ChangeLog140 Version 1.4.0 - Released 5 May, 2008 + * + * - Added HID Report Parser API to the library + * - Added Mouse and Keyboard host demo applications, using the new HID report parser engine + * - Added MouseFullInt demo, which demonstrates a fully interrupt (including control requests) mouse device + * - Fixed incorrect length value in the audio control descriptor of the AudioOutput and AudioInput demos + * - Added MIDI device demo application to the library + * - Fixed problem preventing USB devices from being resumed from a suspended state + * - Added new CDC class bootloader to the library, based on the AVR109 bootloader protocol + * - Added header to each demo application indicating the mode, class, subclass, standards used and supported speed + * - Functions expecting endpoint/pipe numbers are no longer automatically masked against ENDPOINT_EPNUM_MASK or + * PIPE_PIPENUM_MASK - this should be manually added to code which requires it + * - Fixed DFU class bootloader - corrected frequency of flash page writes, greatly reducing programming time + * - Renamed AVR_HOST_GetDeviceConfigDescriptor() to USB_Host_GetDeviceConfigDescriptor() and AVR_HOST_GetNextDescriptor() + * to USB_Host_GetNextDescriptor() + * - Added new USB_Host_GetNextDescriptorOfTypeBefore() and USB_Host_GetNextDescriptorOfTypeAfter() routines + * - Moved configuration descriptor routines to MyUSB/Drivers/USB/Class/, new accompanying ConfigDescriptors.c file + * - Added new configuration descriptor comparator API for more powerful descriptor parsing, updated host demos to use the + * new comparator API + * - Fixed MassStorageHost demo capacity printout, and changed data read/write mode from little-endian to the correct + * big-endian for SCSI devices + * - Fixed macro/function naming consistency; USB_HOST is now USB_Host, USB_DEV is now USB_Device + * - Added better error reporting to host demos + * - Added 10 microsecond delay after addressing devices in host mode, to prevent control stalls + * + * + * \section Sec_ChangeLog132 Version 1.3.2 - Released April 1st, 2008 + * + * - Added call to ReconfigureUSART() in USBtoSerial SetLineCoding request, so that baud rate changes + * are reflected in the hardware + * - Fixed CDC and USBtoSerial demos - Stream commands do not work for control endpoints, and the + * GetLineCoding request had an incorrect RequestType mask preventing it from being processed + * - Improved reliability of the USBtoSerial demo, adding a busy wait while the buffer is full + * - Device control endpoint size is now determined from the device's descriptors rather than being fixed + * - Separated out SPI code into new SPI driver in AT90USBXXX driver directory + * - Bootloader now returns correct PID for the selected USB AVR model, not just the AT90USB128X PID + * - Added support for the RZUSBSTICK board + * - Bicolour driver removed in favor of generic LEDs driver + * - Added support for the ATMEGA32U4 AVR + * - Added MANUAL_PLL_CONTROL compile time option to prevent the USB library from manipulating the PLL + * + * + * \section Sec_ChangeLog131 Version 1.3.1 - Released March 19th 2008 + * + * - Fixed USB to Serial demo - class value in the descriptors was incorrect + * - Control endpoint size changed from 64 bytes to 8 bytes to save on USB FIFO RAM and to allow low + * speed mode devices to enumerate properly + * - USB to Serial demo data endpoints changed to dual-banked 16 byte to allow the demo to work + * on USB AVRs with limited USB FIFO RAM + * - Changed demo endpoint numbers to use endpoints 3 and 4 for double banking, to allow limited + * USB device controller AVRs (AT90USB162, AT90USB82) to function correctly + * - Updated Audio Out demo to use timer 1 for AVRs lacking a timer 3 for the PWM output + * - Fixed incorrect USB_DEV_OPT_HIGHSPEED entry in the Mass Storage device demo makefile + * - Optimized Mass Storage demo for a little extra transfer speed + * - Added LED indicators to the Keyboard demo for Caps Lock, Num Lock and Scroll Lock + * - Added Endpoint_Read_Stream, Endpoint_Write_Stream, Pipe_Read_Stream and Pipe_Write_Stream functions + * (including Big and Little Endian variants) + * - Made Dataflash functions inline for speed, removed now empty Dataflash.c driver file + * - Added new SetSystemClockPrescaler() macro (thanks to Joerg Wunsch) + * - Fixed Endpoint_ClearStall() to function correctly on full USB controller AVRs (AT90USBXXX6/7) + * - Endpoint_Setup_In_Clear() and Endpoint_Setup_Out_Clear() no longer set FIFOCON, in line with the + * directives in the datasheet + * - Fixed PLL prescaler defines for all AVR models and frequencies + * - Fixed ENDPOINT_INT_IN and ENDPOINT_INT_OUT definitions + * - Added interrupt driven keyboard and mouse device demos + * - Combined USB_Device_ClearFeature and USB_Device_SetFeature requests into a single routine for code + * size savings + * - Added missing Pipe_GetCurrentPipe() macro to Pipe.h + * + * + * \section Sec_ChangeLog130 Version 1.3.0 - Released March 7th 2008 + * + * - Unnecessary control endpoint config removed from device mode + * - Fixed device standard request interpreter accidentally processing some class-specific requests + * - Added USE_RAM_DESCRIPTORS and USE_EEPROM_DESCRIPTORS compile time options to instruct the library + * to use descriptors stored in RAM or EEPROM rather than flash memory + * - All demos now disable watchdog on startup, in case it has been enabled by fuses or the bootloader + * - USB_DEV_OPT_LOWSPEED option now works correctly + * - Added ability to set the USB options statically for a binary size reduction via the USE_STATIC_OPTIONS + * compile time define + * - USB_Init no longer takes a Mode parameter if compiled for a USB device with no host mode option, or + * if forced to a particular mode via the USB_HOST_ONLY or USB_DEVICE_ONLY compile time options + * - USB_Init no longer takes an Options parameter if options statically configured by USE_STATIC_OPTIONS + * - Endpoint_Ignore_* and Pipe_Ignore_* made smaller by making the dummy variable non-volatile so that the + * compiler can throw away the result more efficiently + * - Added in an optional GroupID value to each scheduler entry, so that groups of tasks can once again be + * controlled by the new Scheduler_SetGroupTaskMode() routine + * - Added support for AT90USB162 and AT90USB82 AVR models + * - Added support for the STK525 and STK526 boards + * - Added support for custom board drivers to be supplied by selecting the board type as BOARD_USER, and + * placing board drivers in {Application Directory}/Board/ + * - PLL is now stopped and USB clock is frozen when detached from host in device mode, to save power + * - Joystick defines are now in synch with the schematics - orientation will be rotated for the USBKEY + * - Fixed USB_DEV_IsUSBSuspended() - now checks the correct register + * - Fixed data transfers to devices when in host mode + * - Renamed USB_DEV_OPT_HIGHSPEED to USB_DEV_OPT_FULLSPEED and USB_HOST_IsDeviceHighSpeed() to + * USB_HOST_IsDeviceFullSpeed() to be in line with the official USB speed names (to avoid confusion with + * the real high speed mode, which is unavailable on the USB AVRs) + * + * + * \section Sec_ChangeLog120 Version 1.2.0 - Released February 4th, 2008 + * + * - Added USB_DeviceEnumerationComplete event for host mode + * - Added new Scheduler_Init routine to prepare the scheduler, so that tasks can be started and + * stopped before the scheduler has been started (via Scheduler_Start) + * - Connection events in both Device and Host mode are now interrupt-driven, allowing the USB management + * task to be stopped when the USB is not connected to a host or device + * - All demos updated to stop the USB task when not in use via the appropriate USB events + * - Mass Storage Host demo application updated to function correctly with all USB flash disks + * - Mass Storage Host demo application now prints out the capacity and number of LUNs in the attached + * device, and prints the first block as hexadecimal numbers rather than ASCII characters + * - Endpoint and Pipe clearing routines now clear the Endpoint/Pipe interrupt and status flags + * - Shifted error handling code in the host enum state machine to a single block, to reduce code complexity + * - Added in DESCRIPTOR_TYPE, DESCRIPTOR_SIZE and DESCRIPTOR_CAST macros to make config descriptor processing + * clearer in USB hosts and DESCRIPTOR_ADDRESS for convenience in USB devices + * - Added in alloca macro to common.h, in case the user is using an old version of avr-lib-c missing the macro + * + * + * \section Sec_ChangeLog130 Version 1.1.0 - Released January 25th 2008 + * + * - Fixed DCONNI interrupt being enabled accidentally after a USB reset + * - Fixed DDISCI interrupt not being disabled when a device is not connected + * - Added workaround for powerless pull-up devices causing false disconnect interrupts + * - Added USB_DeviceEnumerationFailed event for Host mode + * - AVR_HOST_GetDeviceConfigDescriptor routine no longer modifies ConfigSizePtr if a valid buffer + * pointer is passed + * - Added ALLOCABLE_BYTES to DynAlloc, and added code to make the size of key storage variables + * dependant on size of memory parameters passed in via the user project's makefile + * - Fixed incorrect device reset routine being called in USBTask + * - Devices which do not connect within the standard 300mS are now supported + * - Removed incorrect ATTR_PURE from Scheduler_SetTaskMode(), which was preventing tasks from being + * started/stopped, as well as USB_InitTaskPointer(), which was breaking dual device/host USB projects + * - Changed scheduler to use the task name rather than IDs for setting the task mode, eliminating the + * need to have a task ID list + * - ID transition interrupt now raises the appropriate device/host disconnect event if device attached + * - Fixed double VBUS change (and VBUS -) event when detaching in device mode + * - Added ability to disable ANSI terminal codes by the defining of DISABLE_TERMINAL_CODES in makefile + * - Removed return from ConfigurePipe and ConfigureEndpoint functions - use Pipe_IsConfigured() and + * Endpoint_IsConfigured() after calling the config functions to determine success + */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/CompileTimeTokens.txt b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/CompileTimeTokens.txt new file mode 100644 index 0000000000..fbfbc3d984 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/CompileTimeTokens.txt @@ -0,0 +1,200 @@ +/** \file + * + * This file contains special DoxyGen information for the generation of the main page and other special + * documentation pages. It is not a project source file. + */ + +/** \page Page_TokenSummary Summary of Compile Tokens + * + * The following lists all the possible tokens which can be defined in a project makefile, and passed to the + * compiler via the -D switch, to alter the LUFA library code. These tokens may alter the library behaviour, + * or remove features unused by a given application in order to save flash space. + * + * + * \section Sec_SummaryNonUSBTokens Non USB Related Tokens + * This section describes compile tokens which affect non-USB sections of the LUFA library. + * + * DISABLE_TERMINAL_CODES - ( \ref Group_Terminal ) \n + * If an application contains ANSI terminal control codes listed in TerminalCodes.h, it might be desired to remove them + * at compile time for use with a terminal which is non-ANSI control code aware, without modifying the source code. If + * this token is defined, all ANSI control codes in the application code from the TerminalCodes.h header are removed from + * the source code at compile time. + * + * + * \section Sec_SummaryUSBClassTokens USB Class Driver Related Tokens + * This section describes compile tokens which affect USB class-specific drivers in the LUFA library. + * + * HID_HOST_BOOT_PROTOCOL_ONLY - ( \ref Group_USBClassHIDHost ) \n + * By default, the USB HID Host class driver is designed to work with HID devices using either the Boot or Report HID + * communication protocols. On devices where the Report protocol is not used (i.e. in applications where only basic + * Mouse or Keyboard operation is desired, using boot compatible devices), the code responsible for the Report protocol + * mode can be removed to save space in the compiled application by defining this token. When defined, it is still necessary + * to explicitly put the attached device into Boot protocol mode via a call to \ref HID_Host_SetBootProtocol(). + * + * HID_STATETABLE_STACK_DEPTH=x - ( \ref Group_HIDParser ) \n + * HID reports may contain PUSH and POP elements, to store and retrieve the current HID state table onto a stack. This + * allows for reports to save the state table before modifying it slightly for a data item, and then restore the previous + * state table in a compact manner. This token may be defined to a non-zero 8-bit value to give the maximum depth of the state + * table stack. If not defined, this defaults to the value indicated in the HID.h file documentation. + * + * HID_USAGE_STACK_DEPTH=x - ( \ref Group_HIDParser ) \n + * HID reports generally contain many USAGE elements, which are assigned to INPUT, OUTPUT and FEATURE items in succession + * when multiple items are defined at once (via REPORT COUNT elements). This allows for several items to be defined with + * different usages in a compact manner. This token may be defined to a non-zero 8-bit value to set the maximum depth of the + * usage stack, indicating the maximum number of USAGE items which can be stored temporarily until the next INPUT, OUTPUT + * and FEATURE item. If not defined, this defaults to the value indicated in the HID.h file documentation. + * + * HID_MAX_COLLECTIONS=x - ( \ref Group_HIDParser ) \n + * HID reports generally contain several COLLECTION elements, used to group related data items together. Collection information + * is stored separately in the processed usage structure (and referred to by the data elements in the structure) to save space. + * This token may be defined to a non-zero 8-bit value to set the maximum number of COLLECTION items which can be processed by the + * parser into the resultant processed report structure. If not defined, this defaults to the value indicated in the HID.h file + * documentation. + * + * HID_MAX_REPORTITEMS=x - ( \ref Group_HIDParser ) \n + * All HID reports contain one or more INPUT, OUTPUT and/or FEATURE items describing the data which can be sent to and from the HID + * device. Each item has associated usages, bit offsets in the item reports and other associated data indicating the manner in which + * the report data should be interpreted by the host. This token may be defined to a non-zero 8-bit value to set the maximum number of + * data elements which can be stored in the processed HID report structure, including INPUT, OUTPUT and (if enabled) FEATURE items. + * If a item has a multiple count (i.e. a REPORT COUNT of more than 1), each item in the report count is placed separately in the + * processed HID report table. If not defined, this defaults to the value indicated in the HID.h file documentation. + * + * HID_MAX_REPORT_IDS=x - ( \ref Group_HIDParser ) \n + * HID reports may contain several report IDs, to logically distinguish grouped device data from one another - for example, a combination + * keyboard and mouse might use report IDs to separate the keyboard reports from the mouse reports. In order to determine the size of each + * report, and thus know how many bytes must be read or written, the size of each report (IN, OUT and FEATURE) must be calculated and + * stored. This token may be defined to a non-zero 8-bit value to set the maximum number of report IDs in a device which can be processed + * and their sizes calculated/stored into the resultant processed report structure. If not defined, this defaults to the value indicated in + * the HID.h file documentation. + * + * + * \section Sec_SummaryUSBTokens General USB Driver Related Tokens + * This section describes compile tokens which affect USB driver stack as a whole in the LUFA library. + * + * NO_STREAM_CALLBACKS - ( \ref Group_EndpointPacketManagement , \ref Group_PipePacketManagement )\n + * Both the endpoint and the pipe driver code contains stream functions, allowing for arrays of data to be sent to or from the + * host easily via a single function call (rather than complex routines worrying about sending full packets, waiting for the endpoint/ + * pipe to become ready, etc.). By default, these stream functions require a callback function which is executed after each byte processed, + * allowing for early-aborts of stream transfers by the application. If callbacks are not required in an application, they can be removed + * by defining this token, reducing the compiled binary size. When removed, the stream functions no longer accept a callback function as + * a parameter. + * + * FAST_STREAM_TRANSFERS - ( \ref Group_EndpointPacketManagement , \ref Group_PipePacketManagement )\n + * By default, streams are transferred internally via a loop, sending or receiving one byte per iteration before checking for a bank full + * or empty condition. This allows for multiple stream functions to be chained together easily, as there are no alignment issues. However, + * this can lead to heavy performance penalties in applications where large streams are used frequently. When this compile time option is + * used, bytes are sent or received in groups of 8 bytes at a time increasing performance at the expense of a larger flash memory consumption + * due to the extra code required to deal with byte alignment. + * + * USE_STATIC_OPTIONS=x - ( \ref Group_USBManagement ) \n + * By default, the USB_Init() function accepts dynamic options at runtime to alter the library behaviour, including whether the USB pad + * voltage regulator is enabled, and the device speed when in device mode. By defining this token to a mask comprised of the USB options + * mask defines usually passed as the Options parameter to USB_Init(), the resulting compiled binary can be decreased in size by removing + * the dynamic options code, and replacing it with the statically set options. When defined, the USB_Init() function no longer accepts an + * Options parameter. + * + * USB_DEVICE_ONLY - ( \ref Group_USBManagement ) \n + * For the USB AVR models supporting both device and host USB modes, the USB_Init() function contains a Mode parameter which specifies the + * mode the library should be initialized to. If only device mode is required, the code for USB host mode can be removed from the binary to + * save space. When defined, the USB_Init() function no longer accepts a Mode parameter. This define is irrelevant on smaller USB AVRs which + * do not support host mode. + * + * USB_HOST_ONLY - ( \ref Group_USBManagement ) \n + * Same as USB_DEVICE_ONLY, except the library is fixed to USB host mode rather than USB device mode. Not available on some USB AVR models. + * + * USB_STREAM_TIMEOUT_MS=x - ( \ref Group_USBManagement ) \n + * When endpoint and/or pipe stream functions are used, by default there is a timeout between each transfer which the connected device or host + * must satisfy, or the stream function aborts the remaining data transfer. This token may be defined to a non-zero 16-bit value to set the timeout + * period for stream transfers, specified in milliseconds. If not defined, the default value specified in LowLevel.h is used instead. + * + * NO_LIMITED_CONTROLLER_CONNECT - ( \ref Group_Events ) \n + * On the smaller USB AVRs, the USB controller lacks VBUS events to determine the physical connection state of the USB bus to a host. In lieu of + * VBUS events, the library attempts to determine the connection state via the bus suspension and wake up events instead. This however may be + * slightly inaccurate due to the possibility of the host suspending the bus while the device is still connected. If accurate connection status is + * required, the VBUS line of the USB connector should be routed to an AVR pin to detect its level, so that the USB_DeviceState global + * can be accurately set and the \ref EVENT_USB_Device_Connect() and \ref EVENT_USB_Device_Disconnect() events manually raised by the RAISE_EVENT macro. + * When defined, this token disables the library's auto-detection of the connection state by the aforementioned suspension and wake up events. + * + * + * \section Sec_SummaryUSBDeviceTokens USB Device Mode Driver Related Tokens + * This section describes compile tokens which affect USB driver stack of the LUFA library when used in Device mode. + * + * USE_RAM_DESCRIPTORS - ( \ref Group_Descriptors ) \n + * Define this token to indicate to the USB driver that all device descriptors are stored in RAM, rather than being located in any one + * of the AVR's memory spaces. RAM descriptors may be desirable in applications where the descriptors need to be modified at runtime. + * + * USE_FLASH_DESCRIPTORS - ( \ref Group_Descriptors ) \n + * Similar to USE_RAM_DESCRIPTORS, but all descriptors are stored in the AVR's FLASH memory rather than RAM. + * + * USE_EEPROM_DESCRIPTORS - ( \ref Group_Descriptors ) \n + * Similar to USE_RAM_DESCRIPTORS, but all descriptors are stored in the AVR's EEPROM memory rather than RAM. + * + * NO_INTERNAL_SERIAL - ( \ref Group_Descriptors ) \n + * Some AVR models contain a unique 20-digit serial number which can be used as the device serial number, while in device mode. This + * allows the host to uniquely identify the device regardless of if it is moved between USB ports on the same computer, allowing + * allocated resources (such as drivers, COM Port number allocations) to be preserved. This is not needed in many apps, and so the + * code that performs this task can be disabled by defining this option and passing it to the compiler via the -D switch. + * + * FIXED_CONTROL_ENDPOINT_SIZE=x - ( \ref Group_EndpointManagement ) \n + * By default, the library determines the size of the control endpoint (when in device mode) by reading the device descriptor. + * Normally this reduces the amount of configuration required for the library, allows the value to change dynamically (if + * descriptors are stored in EEPROM or RAM rather than flash memory) and reduces code maintenance. However, this token can be + * defined to a non-zero value instead to give the size in bytes of the control endpoint, to reduce the size of the compiled + * binary. + * + * DEVICE_STATE_AS_GPIOR - ( \ref Group_Device ) \n + * One of the most frequently used global variables in the stack is the USB_DeviceState global, which indicates the current state of + * the Device State Machine. To reduce the amount of code and time required to access and modify this global in an application, this token + * may be defined to a value between 0 and 2 to fix the state variable into one of the three general purpose IO registers inside the AVR + * reserved for application use. When defined, the corresponding GPIOR register should not be used within the user application except + * implicitly via the library APIs. + * + * FIXED_NUM_CONFIGURATIONS=x - ( \ref Group_Device ) \n + * By default, the library determines the number of configurations a USB device supports by reading the device descriptor. This reduces + * the amount of configuration required to set up the library, and allows the value to change dynamically (if descriptors are stored in + * EEPROM or RAM rather than flash memory) and reduces code maintenance. However, this value may be fixed via this token in the project + * makefile to reduce the compiled size of the binary at the expense of flexibility. + * + * CONTROL_ONLY_DEVICE \n + * In some limited USB device applications, there are no device endpoints other than the control endpoint; i.e. all device communication + * is through control endpoint requests. Defining this token will remove several features related to the selection and control of device + * endpoints internally, saving space. Generally, this is usually only useful in (some) bootloaders and is best avoided. + * + * INTERRUPT_CONTROL_ENDPOINT - ( \ref Group_USBManagement ) \n + * Some applications prefer to not call the USB_USBTask() management task regularly while in device mode, as it can complicate code significantly. + * Instead, when device mode is used this token can be passed to the library via the -D switch to allow the library to manage the USB control + * endpoint entirely via USB controller interrupts asynchronously to the user application. When defined, USB_USBTask() does not need to be called + * when in USB device mode. + * + * NO_DEVICE_REMOTE_WAKEUP - (\ref Group_Device ) \n + * Many devices do not require the use of the Remote Wakeup features of USB, used to wake up the USB host when suspended. On these devices, + * the code required to manage device Remote Wakeup can be disabled by defining this token and passing it to the library via the -D switch. + * + * NO_DEVICE_SELF_POWER - (\ref Group_Device ) \n + * USB devices may be bus powered, self powered, or a combination of both. When a device can be both bus powered and self powered, the host may + * query the device to determine the current power source, via \ref USB_CurrentlySelfPowered. For solely bus powered devices, this global and the + * code required to manage it may be disabled by passing this token to the library via the -D switch. + * + * + * \section Sec_SummaryUSBHostTokens USB Host Mode Driver Related Tokens + * + * This section describes compile tokens which affect USB driver stack of the LUFA library when used in Host mode. + * + * HOST_STATE_AS_GPIOR - ( \ref Group_Host ) \n + * One of the most frequently used global variables in the stack is the USB_HostState global, which indicates the current state of + * the Host State Machine. To reduce the amount of code and time required to access and modify this global in an application, this token + * may be defined to a value between 0 and 2 to fix the state variable into one of the three general purpose IO registers inside the AVR + * reserved for application use. When defined, the corresponding GPIOR register should not be used within the user application except + * implicitly via the library APIs. + * + * USB_HOST_TIMEOUT_MS=x - ( \ref Group_Host ) \n + * When a control transfer is initiated in host mode to an attached device, a timeout is used to abort the transfer if the attached + * device fails to respond within the timeout period. This token may be defined to a non-zero 16-bit value to set the timeout period for + * control transfers, specified in milliseconds. If not defined, the default value specified in Host.h is used instead. + * + * HOST_DEVICE_SETTLE_DELAY_MS=x - ( \ref Group_Host ) \n + * Some devices require a delay of up to 5 seconds after they are connected to VBUS before the enumeration process can be started, or + * they will fail to enumerate correctly. By placing a delay before the enumeration process, it can be ensured that the bus has settled + * back to a known idle state before communications occur with the device. This token may be defined to a 16-bit value to set the device + * settle period, specified in milliseconds. If not defined, the default value specified in Host.h is used instead. + */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/CompilingApps.txt b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/CompilingApps.txt new file mode 100644 index 0000000000..60c5a8ae28 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/CompilingApps.txt @@ -0,0 +1,30 @@ +/** \file + * + * This file contains special DoxyGen information for the generation of the main page and other special + * documentation pages. It is not a project source file. + */ + +/** \page Page_CompilingApps Compiling the Demos, Bootloaders and Projects + * + * The following details how to compile the included LUFA demos, applications and bootloaders using AVR-GCC. + * + * \section Sec_Prerequisites Prerequisites + * Before you can compile any of the LUFA library code or demos, you will need a recent distribution of avr-libc (1.6.2+) + * and the AVR-GCC (4.2+) compiler. For Windows users, the best way to obtain these is the WinAVR project + * (http://winavr.sourceforge.net) as this provides a single-file setup for everything required to compile your + * own AVR projects. + * + * \section Sec_Compiling Compiling a LUFA Application + * Compiling the LUFA demos, applications and/or bootloaders is very simple. LUFA comes with makefile scripts for + * each individual demo, bootloader and project folder, as well as scripts in the /Demos/, /Bootloaders/, /Projects/ + * and the LUFA root directory. This means that compilation can be started from any of the above directories, with + * a build started from an upper directory in the directory structure executing build of all child directories under it. + * This means that while a build inside a particular demo directory will build only that particular demo, a build stated + * from the /Demos/ directory will build all LUFA demo projects sequentially. + * + * To build a project from the source via the command line, the command "make all" should be executed from the command line in the directory + * of interest. To remove compiled files (including the binary output, all intermediately files and all diagnostic output + * files), execute "make clean". Once a "make all" has been run and no errors were encountered, the resulting binary will + * be located in the generated ".HEX" file. If your project makes use of pre-initialized EEPROM variables, the generated ".EEP" + * file will contain the project's EEPROM data. + */ \ No newline at end of file diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/ConfiguringApps.txt b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/ConfiguringApps.txt new file mode 100644 index 0000000000..058d79b1ff --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/ConfiguringApps.txt @@ -0,0 +1,87 @@ +/** \file + * + * This file contains special DoxyGen information for the generation of the main page and other special + * documentation pages. It is not a project source file. + */ + +/** \page Page_ConfiguringApps Configuring the Demos, Bootloaders and Projects + * + * If the target AVR model, clock speed, board or other settings are different to the current settings, they must be changed + * and the project recompiled from the source code before being programmed into the AVR microcontroller. Most project + * configuration options are located in the "makefile" build script inside each LUFA application's folder, however some + * demo or application-specific configuration settings (such as the output format in the AudioOut demo) are located in the + * main .c source file of the project. See each project's individual documentation for application-specific configuration + * values. + * + * Each project "makefile" contains all the script and configuration data required to compile each project. When opened with + * any regular basic text editor such as Notepad or WordPad (ensure that the save format is a pure ASCII text format) the + * build configuration settings may be altered. + * + * Inside each makefile, a number of configuration variables are located, with the format " = ". For + * each application, the important variables which should be altered are: + * + * - MCU, the target AVR processor. + * - BOARD, the target board hardware + * - F_CLOCK, the target raw master clock frequency, before any prescaling is performed + * - F_CPU, the target AVR CPU master clock frequency, after any prescaling + * - CDEFS, the C preprocessor defines which configure options the source code + * - LUFA_PATH, the path to the LUFA library source code + * - LUFA_OPTS, the compile time LUFA options which configure the library features + * + * These values should be changed to reflect the build hardware. + * + * \section Sec_MCU The MCU Parameter + * This parameter indicates the target AVR model for the compiled application. This should be set to the model of the target AVR + * (such as the AT90USB1287, or the ATMEGA32U4), in all lower-case (e.g. "at90usb1287"). Note that not all demos support all the + * USB AVR models, as they may make use of peripherals or modes only present in some devices. + * + * For supported library AVR models, see main documentation page. + * + * \section Sec_BOARD The BOARD Parameter + * This parameter indicates the target AVR board hardware for the compiled application. Some LUFA library drivers are board-specific, + * such as the LED driver, and the library needs to know the layout of the target board. If you are using one of the board models listed + * on the main library page, change this parameter to the board name in all UPPER-case. + * + * If you are not using any board-specific drivers in the LUFA library, or you are using a custom board layout, change this to read + * "USER" (no quotes) instead of a standard board name. If the USER board type is selected and the application makes use of one or more + * board-specific hardware drivers inside the LUFA library, then the appropriate stub drives files should be copied from the /BoardStubs/ + * directory into a /Board/ folder inside the application directory, and the stub driver completed with the appropriate code to drive the + * custom board's hardware. + * + * \section Sec_F_CLOCK The F_CLOCK Parameter + * This parameter indicates the target AVR's input clock frequency, in Hz. This is the actual clock input, before any prescaling is performed. In the + * USB AVR architecture, the input clock before any prescaling is fed directly to the PLL subsystem, and thus the PLL is derived directly from the + * clock input. The PLL then feeds the USB and other sections of the AVR with the correct upscaled frequencies required for those sections to function. + * + * Note that this value does not actually *alter* the AVR's input clock frequency, it is just a way to indicate to the library the clock frequency + * of the AVR as set by the AVR's fuses. If this value does not reflect the actual running frequency of the AVR, incorrect operation of one of more + * library components will occur. + * + * \section Sec_F_CPU The F_CPU Parameter + * This parameter indicates the target AVR's master CPU clock frequency, in Hz. + * + * Note that this value does not actually *alter* the AVR's CPU clock frequency, it is just a way to indicate to the library the clock frequency + * of the AVR core as set by the AVR's fuses. If this value does not reflect the actual running frequency of the AVR, incorrect operation of one of more + * library components will occur. + * + * \section Sec_CDEFS The CDEFS Parameter + * Many applications have features which can be controlled by the defining of specially named preprocessor tokens at the point of compilation - for example, + * an application might use a compile time token to turn on or off optional or mutually exclusive portions of code. Preprocessor tokens can be + * defined here by listing each one with the -D command line switch, and each token can optionally be defined to a specific value. When defined in the + * project makefile, these behave as if they were defined in every source file via a normal preprocessor define statement. + * + * Most applications will actually have multiple CDEF lines, which are concatenated together with the "+=" operator. This ensures that large + * numbers of configuration options remain readable by splitting up groups of options into separate lines. + * + * \section Sec_LUFA_PATH The LUFA_PATH Parameter + * As each LUFA program requires the LUFA library source code to compile correctly, the application must know where the LUFA library is located. This + * value specifies the path to the LUFA library base relative to the path of the project makefile. + * + * \section Sec_LUFA_OPTS The LUFA_OPTS Parameter + * This value is similar to the CDEFS parameter listed elsewhere -- indeed, it is simply a convenient place to group LUFA related tokens away from the + * application's compile time tokens. Normally, these options do not need to be altered to allow an application to compile and run correctly on a + * different board or AVR to the current configuration - if the options are incorrect, then the demo is most likely incompatible with the chosen USB AVR + * model and cannot be made to function through the altering of the makefile settings alone (or at all). Settings such as the USB mode (device, host or both), + * the USB interface speed (Low or Full speed) and other LUFA configuration options can be set here - see \ref Page_TokenSummary documentation for details + * on the available LUFA compile time configuration options. + */ \ No newline at end of file diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/DevelopingWithLUFA.txt b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/DevelopingWithLUFA.txt new file mode 100644 index 0000000000..8223c9257e --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/DevelopingWithLUFA.txt @@ -0,0 +1,22 @@ +/** \file + * + * This file contains special DoxyGen information for the generation of the main page and other special + * documentation pages. It is not a project source file. + */ + +/** + * \page Page_DevelopingWithLUFA Developing With LUFA + * + * This section of the manual contains information on LUFA development, such as Getting Started information, + * information on compile-time tuning of the library and other developer-related sections. + * + * Subsections: + * \li \subpage Page_TokenSummary - Summary of Compile Time Tokens + * \li \subpage Page_Migration - Migrating from an Older LUFA Version + * \li \subpage Page_VIDPID - Allocated USB VID and PID Values + * \li \subpage Page_BuildLibrary - Building as a Linkable Library + * \li \subpage Page_WritingBoardDrivers - How to Write Custom Board Drivers + * \li \subpage Page_SoftwareBootloaderStart - How to jump to the bootloader in software + * \li \subpage Page_SchedulerOverview - Overview of the Simple LUFA Scheduler (DEPRECATED) + */ + \ No newline at end of file diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/DeviceSupport.txt b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/DeviceSupport.txt new file mode 100644 index 0000000000..47cfc4ad71 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/DeviceSupport.txt @@ -0,0 +1,41 @@ +/** \file + * + * This file contains special DoxyGen information for the generation of the main page and other special + * documentation pages. It is not a project source file. + */ + +/** + * \page Page_DeviceSupport Device and Hardware Support + * + * Currently supported AVR models: + * - AT90USB82 (USB Device Only) + * - ATMEGA8U2 (USB Device Only) + * - AT90USB162 (USB Device Only) + * - ATMEGA16U2 (USB Device Only) + * - ATMEGA16U4 (USB Device Only) + * - ATMEGA32U2 (USB Device Only) + * - ATMEGA32U4 (USB Device Only) + * - ATMEGA32U6 (USB Device Only) + * - AT90USB646 (USB Device Only) + * - AT90USB647 (USB Host and Device) + * - AT90USB1286 (USB Device Only) + * - AT90USB1287 (USB Host and Device) + * + * Currently supported Atmel boards (see \ref Group_BoardTypes): + * - AT90USBKEY + * - ATAVRUSBRF01 + * - EVK527 + * - RZUSBSTICK + * - STK525 + * - STK526 + * - XPLAIN (Both original first revision board, and newer boards with a different Dataflash model) + * + * Currently supported third-party boards (see \ref Group_BoardTypes): + * - Bumble-B (using officially recommended peripheral layout) + * - Benito + * - JM-DB-U2 + * - Teensy (all revisions and versions) + * - USBTINY MKII (all revisions and versions) + * - Any Other Custom User Boards (with Board Drivers if desired, see \ref Page_WritingBoardDrivers) + */ + \ No newline at end of file diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/DirectorySummaries.txt b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/DirectorySummaries.txt new file mode 100644 index 0000000000..25f2db0648 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/DirectorySummaries.txt @@ -0,0 +1,171 @@ +/** \file + * + * This file contains special DoxyGen information for the generation of the main page and other special + * documentation pages. It is not a project source file. + */ + +/** \dir LUFA/Common + * \brief Common library header files. + * + * This folder contains header files which are common to all parts of the LUFA library. They may be used freely in + * user applications. + * + * \dir LUFA/Drivers + * \brief Library hardware and software drivers. + * + * This folder contains all the library hardware and software drivers for each supported board and USB AVR + * microcontroller model. + * + * \dir LUFA/Drivers/Misc + * \brief Miscellaneous driver files. + * + * This folder contains drivers for aspects other than the USB interface, board hardware or AVR peripherals. + * + * \dir LUFA/Drivers/Peripheral + * \brief USB AVR peripheral driver files. + * + * This folder contains drivers for several of the AVR internal peripherals such as the USART, compatible with + * all USB AVR models. + * + * \dir LUFA/Drivers/Peripheral/AVRU4U6U7 + * \brief AT90USBXXX6, AT90USBXXX7 and ATMEGAXXU4 AVR model peripheral driver files. + * + * This folder contains drivers for several of the AVR internal peripherals such as the USART, compatible only with + * the AT90USBXXX6, AT90USBXXX7 and ATMEGAXXU4 USB AVR models, such as the AT90USB1287. Its contents should not be + * included by the user application - the dispatch header file located in the parent directory should be used + * instead. + * + * \dir LUFA/Drivers/USB + * \brief USB controller peripheral driver files. + * + * This folder contains the main header files required to implement the USB interface in the USB supporting AVR models. + * The header files contained directly in this folder should be included in the user application in order to gain USB + * functionality, and the appropriate C source files in the LowLevel and HighLevel driver folders added to the compile + * and link stages. + * + * \dir LUFA/Drivers/USB/LowLevel + * \brief Low level USB driver files. + * + * This folder contains low level USB driver source files required to implement USB functionality on the USB AVR microcontrollers. + * + * \dir LUFA/Drivers/USB/HighLevel + * \brief High level USB driver files. + * + * This folder contains high level USB driver source files required to implement USB functionality on the USB AVR microcontrollers. + * + * \dir LUFA/Drivers/USB/Class + * \brief USB Class helper driver files. + * + * This folder contains drivers for implementing functionality of standardized USB classes. These are not used directly by the library, + * but provide a standard and library-maintained way of implementing functionality from some of the defined USB classes without extensive + * development effort. Is is recommended that these drivers be used where possible to reduce maintenance of user applications. + * + * \dir LUFA/Drivers/USB/Class/Device + * \brief USB Device Class helper driver files. + * + * Device mode drivers for the standard USB classes. + * + * \dir LUFA/Drivers/USB/Class/Host + * \brief USB Host Class helper driver files. + * + * Host mode drivers for the standard USB classes. + * + * \dir LUFA/Drivers/Board + * \brief Board hardware driver files. + * + * This folder contains drivers for interfacing with the physical hardware on supported commercial boards, primarily from + * the Atmel corporation. Header files in this folder should be included in user applications requiring the functionality of + * hardware placed on supported boards. + * + * \dir LUFA/Drivers/Board/USBKEY + * \brief USBKEY board hardware driver files. + * + * This folder contains drivers for hardware on the Atmel USBKEY demonstration board. The header files in this folder should + * not be included directly in user applications; the similarly named dispatch header files located in the parent Board directory + * should be included instead. + * + * \dir LUFA/Drivers/Board/STK526 + * \brief STK526 board hardware driver files. + * + * This folder contains drivers for hardware on the Atmel STK526 development board. The header files in this folder should + * not be included directly in user applications; the similarly named dispatch header files located in the parent Board directory + * should be included instead. + * + * \dir LUFA/Drivers/Board/STK525 + * \brief STK525 board hardware driver files. + * + * This folder contains drivers for hardware on the Atmel STK525 development board. The header files in this folder should + * not be included directly in user applications; the similarly named dispatch header files located in the parent Board directory + * should be included instead. + * + * \dir LUFA/Drivers/Board/RZUSBSTICK + * \brief RZUSBSTICK board hardware driver files. + * + * This folder contains drivers for hardware on the Atmel RZUSBSTICK board, as used in the Atmel "Raven" wireless kits. The header + * files in this folder should not be included directly in user applications; the similarly named dispatch header files located in + * the parent Board directory should be included instead. + * + * \dir LUFA/Drivers/Board/ATAVRUSBRF01 + * \brief ATAVRUSBRF01 board hardware driver files. + * + * This folder contains drivers for hardware on the Atmel ATAVRUSBRF01 board, as used in several Atmel wireless demo kits. The header + * files in this folder should not be included directly in user applications; the similarly named dispatch header files located in + * the parent Board directory should be included instead. + * + * \dir LUFA/Drivers/Board/BUMBLEB + * \brief BUMBLEB board hardware driver files. + * + * This folder contains drivers for hardware on the Fletchtronics Bumble-B board (http://fletchtronics.net/bumble-b). The header + * files in this folder should not be included directly in user applications; the similarly named dispatch header files located in + * the parent Board directory should be included instead. + * + * \dir LUFA/Drivers/Board/XPLAIN + * \brief XPLAIN board hardware driver files. + * + * This folder contains drivers for hardware on the Atmel XPLAIN board (all hardware revisions). The header files in this folder + * should not be included directly in user applications; the similarly named dispatch header files located in the parent Board + * directory should be included instead. + * + * \dir LUFA/Drivers/Board/EVK527 + * \brief XPLAIN board hardware driver files. + * + * This folder contains drivers for hardware on the Atmel EVK527 development board. The header files in this folder should + * not be included directly in user applications; the similarly named dispatch header files located in the parent Board directory + * should be included instead. + * + * \dir LUFA/Drivers/Board/TEENSY + * \brief TEENSY board hardware driver files. + * + * This folder contains drivers for hardware on all revisions of the PJRC Teensy boards (http://www.pjrc.com/teensy/). The header + * files in this folder should not be included directly in user applications; the similarly named dispatch header files located + * in the parent Board directory should be included instead. + * + * \dir LUFA/Drivers/Board/USBTINYMKII + * \brief USBTINY-MKII board hardware driver files. + * + * This folder contains drivers for hardware on all revisions of the USBTINY-MKII boards (http://tom-itx.dyndns.org:81/~webpage/). + * The header files in this folder should not be included directly in user applications; the similarly named dispatch header files + * located in the parent Board directory should be included instead. + * + * \dir LUFA/Drivers/Board/BENITO + * \brief BENITO board hardware driver files. + * + * This folder contains drivers for hardware on the Benito boards (http://dorkbotpdx.org/wiki/benito). The header files in this + * folder should not be included directly in user applications; the similarly named dispatch header files located in the parent + * Board directory should be included instead. + * + * \dir LUFA/Drivers/Board/JMDBU2 + * \brief JM-DB-U2 board hardware driver files. + * + * This folder contains drivers for hardware on the JM-DB-U2 boards (http://u2.mattair.net/). The header files in this folder + * should not be included directly in user applications; the similarly named dispatch header files located in the parent Board + * directory should be included instead. + * + * \dir LUFA/DriverStubs + * \brief Driver stub header files for custom boards, to allow the LUFA board drivers to operate. + * + * This contains stub files for the LUFA board drivers. If the LUFA board drivers are used with board hardware other than those + * directly supported by the library, the BOARD parameter of the application's makefile can be set to "USER", and these stub files + * copied to the "/Board/" directory of the application's folder. When fleshed out with working driver code for the custom board, + * the corresponding LUFA board APIs will work correctly with the non-standard board hardware. + */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/Donating.txt b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/Donating.txt new file mode 100644 index 0000000000..fff54adcb3 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/Donating.txt @@ -0,0 +1,24 @@ +/** \file + * + * This file contains special DoxyGen information for the generation of the main page and other special + * documentation pages. It is not a project source file. + */ + +/** + * \page Page_Donating Donating to Support This Project + * + * \image html Author.jpg "Dean Camera, LUFA Developer" + * + * I am a 20 year old University student studying for a double degree in Computer Science and Electronics Engineering. + * The development and support of this library requires much effort from myself, as I am the sole developer, maintainer + * and supporter. Please consider donating a small amount to support this and my future Open Source projects - All + * donations are greatly appreciated. + * + * Note that commercial entities can remove the attribution portion of the LUFA license by a one-time fee - see + * \ref Page_LicenseInfo for more details (Note: Please do NOT pay this in advance through the donation link below - + * contact author for payment details.). + * + * \image html "http://www.pledgie.com/campaigns/6927.png?skin_name=chrome" + * Donate to this project via PayPal - Thanks in Advance! + */ + diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/FutureChanges.txt b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/FutureChanges.txt new file mode 100644 index 0000000000..020779b973 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/FutureChanges.txt @@ -0,0 +1,38 @@ +/** \file + * + * This file contains special DoxyGen information for the generation of the main page and other special + * documentation pages. It is not a project source file. + */ + + /** \page Page_FutureChanges Future Changes + * + * Below is a list of future changes which are proposed for the LUFA library, but not yet started/complete. + * This gives an unordered list of future changes which will be available in future releases of the library. + * If you have an item to add to this list, please contact the library author via email, the LUFA mailing list, + * or post your suggestion as an enhancement request to the project bug tracker. + * + * Targeted for Future Releases: + * - Code Features + * -# Add hub support when in Host mode for multiple devices + * -# Add ability to get number of bytes not written with pipe/endpoint write routines after an error + * -# Add standardized descriptor names to class driver structures + * -# Change makefiles to allow for absolute LUFA location to be used + * - Documentation/Support + * -# Add detailed overviews of how each demo works + * -# Add board overviews + * -# Write LUFA tutorials + * - Demos/Projects + * -# Multiple-Report HID device + * -# Device/Host USB bridge + * -# Alternative (USB-IF endorsed) USB-CDC Ethernet Class + * -# Finish Test and Measurement Class demo + * -# Finish BluetoothHost demo + * -# Finish SideShow demo + * -# Finish StandaloneProgrammer project + * -# Finish MIDIToneGenerator project + * -# Correct mishandling of error cases in Mass Storage demos + * - Ports + * -# AVR32 UC3B series microcontrollers + * -# Atmel ARM7 series microcontrollers + * -# Other (commercial) C compilers + */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/GettingStarted.txt b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/GettingStarted.txt new file mode 100644 index 0000000000..c161bfe1fd --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/GettingStarted.txt @@ -0,0 +1,26 @@ +/** \file + * + * This file contains special DoxyGen information for the generation of the main page and other special + * documentation pages. It is not a project source file. + */ + +/** \page Page_GettingStarted Getting Started + * + * Out of the box, LUFA contains a large number of pre-made class demos for you to test, experiment with and + * ultimately build upon for your own projects. All the demos (where possible) come pre-configured to build and + * run correctly on the AT90USB1287 AVR microcontroller, mounted on the Atmel USBKEY board and running at an 8MHz + * master clock. This is due to two reasons; one, it is the hardware the author possesses, and two, it is the most + * popular Atmel USB demonstration board to date. To learn how to reconfigure, recompile and program the included + * LUFA applications using different settings, see the subsections below. + * + * Most of the included demos in the /Demos/ folder come in both ClassDriver and LowLevel varieties. If you are new + * to LUFA, it is highly recommended that you look at the ClassDriver versions first, which use the pre-made USB + * Class Drivers (\ref Group_USBClassDrivers) to simplify the use of the standard USB classes in user applications. + * + * For an overview of the included library applications, bootloaders and demos, see \ref Page_LibraryApps. + * + * Subsections: + * \li \subpage Page_ConfiguringApps - How to Configure the Included Demos, Projects and Bootloaders + * \li \subpage Page_CompilingApps - How to Compile the Included Demos, Projects and Bootloaders + * \li \subpage Page_ProgrammingApps - How to Program an AVR with the Included Demos, Projects and Bootloaders + */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/Groups.txt b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/Groups.txt new file mode 100644 index 0000000000..a204412e19 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/Groups.txt @@ -0,0 +1,20 @@ +/** \file + * + * This file contains special DoxyGen information for the generation of the main page and other special + * documentation pages. It is not a project source file. + */ + +/** @defgroup Group_BoardDrivers Board Drivers + * + * Functions, macros, variables, enums and types related to the control of physical board hardware. + */ + +/** @defgroup Group_PeripheralDrivers On-chip Peripheral Drivers + * + * Functions, macros, variables, enums and types related to the control of AVR subsystems. + */ + +/** @defgroup Group_MiscDrivers Miscellaneous Drivers + * + * Miscellaneous driver Functions, macros, variables, enums and types. + */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/LUFAPoweredProjects.txt b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/LUFAPoweredProjects.txt new file mode 100644 index 0000000000..abb0e02ddd --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/LUFAPoweredProjects.txt @@ -0,0 +1,87 @@ +/** \file + * + * This file contains special DoxyGen information for the generation of the main page and other special + * documentation pages. It is not a project source file. + */ + +/** \page Page_LUFAPoweredProjects User Projects Powered by LUFA + * + * LUFA is currently in use all around the world, in many applications both commercial and non-commercial. Below is a + * list of known public LUFA powered projects, which all use the LUFA library in some way. Feel free to visit each project's + * home page for more information on each project. + * + * If you have a project that you would like to add to this list, please contact me via the details on the main page of this + * documentation. + * + * \section Sec_BoardsUsingLUFA AVR-USB Development Boards Using LUFA + * + * The following is a list of known AVR USB development boards, which recommend using LUFA for the USB stack. Some of these + * are open design, and all are available for purchase as completed development boards suitable for project development. + * + * - AT90USB162 Breadboard PCB (Russian): http://microsin.ru/content/view/685/44/ + * - Benito #7, a no-frills USB board: http://www.dorkbotpdx.org/wiki/benito + * - JM-DB-U2, an ATMEGA32U2 development board: http://www.mattairtech.com/index.php/development-boards/atmega32u2-development-board.html + * - Micropendous, an open design/source set of AVR USB development boards: http://micropendous.org/ + * - Nanduino, a do-it-yourself AT90USB162 board: http://www.makestuff.eu/wordpress/?page_id=569 + * - Teensy and Teensy++, two other AVR USB development boards: http://www.pjrc.com/teensy/index.html + * - U2DIL/U4DIL, a set of DIP layout USB AVR boards: http://www.reworld.eu/re/en/products/u2dil/ + * - USB10 AKA "The Ferret", a AT90USB162 development board: http://www.soc-machines.com + * - USBFOO 2, AT90USB162 based development board: http://shop.kernelconcepts.de/product_info.php?products_id=102 + * + * \section Sec_LUFAProjects Projects Using LUFA (Hobbyist) + * + * The following are known hobbyist projects using LUFA. Most are open source, and show off interesting ways that the LUFA library + * can be incorporated into many different applications. + * + * - Accelerometer Game Joystick: http://www.crictor.co.il/he/episodes/joystick/ + * - Arcade Controller: http://fletchtronics.net/arcade-controller-made-petunia + * - AVR USB Modem, a 3G Wireless Modem host: http://code.google.com/p/avrusbmodem/ + * - Bicycle POV: http://www.code.google.com/p/bicycleledpov/ + * - BusNinja, an AVR clone of the popular BusPirate project: http://blog.hodgepig.org/busninja/ + * - CAMTRIG, a remote Camera Trigger device: http://code.astraw.com/projects/motmot/camtrig + * - CD Driver Emulator Dongle for ISO Files: http://cdemu.blogspot.com/ + * - ClockTamer, a configurable clock generator: http://code.google.com/p/clock-tamer/ + * - EMUCOMBOX, a USB-RS422 adapter for E-Mu Emax samplers: http://users.skynet.be/emxp/EMUCOMBOX.htm + * - Estick JTAG, an ARM JTAG debugger: http://code.google.com/p/estick-jtag/ + * - "Fingerlicking Wingdinger" (WARNING: Bad Language if no Javascript), a MIDI controller: http://noisybox.net/electronics/wingdinger/ + * - Garmin GPS USB to NMEA standard serial sentence translator: http://github.com/nall/garmin-transmogrifier/tree/master + * - Generic HID Device Creator: http://generichid.sourceforge.net/ + * - Ghetto Drum, a MIDI drum controller: http://noisybox.net/art/gdrum/ + * - IR Remote to Keyboard decoder: http://netzhansa.blogspot.com/2010/04/our-living-room-hi-fi-setup-needs-mp3.html + * - LED Panel controller: http://projects.peterpolidoro.net/caltech/panelscontroller/panelscontroller.htm + * - Linux Secure Storage Dongle: http://github.com/TomMD/teensy + * - MakeTV Episode Dispenser: http://www.youtube.com/watch?v=BkWUi18hl3g + * - MidiMonster, a USB-to-MIDI gateway board: http://www.dorkbotpdx.org/wiki/midimonster + * - NES Controller USB modification: http://projects.peterpolidoro.net/video/NESUSB.htm + * - Opendous-JTAG, an open source ARM JTAG debugger: http://code.google.com/p/opendous-jtag/ + * - Openkubus, an open source hardware-based authentication dongle: http://code.google.com/p/openkubus/ + * - Orbee, a USB connected RGB Orb for notifications: http://www.franksworkshop.com.au/Electronics/Orbee/Orbee.htm + * - Programmable XBOX controller: http://richard-burke.dyndns.org/wordpress/pan-galactic-gargantuan-gargle-brain-aka-xbox-360-usb-controller/ + * - Reprap with LUFA, a LUFA powered 3D printer: http://code.google.com/p/at90usb1287-code-for-arduino-and-eclipse/ + * - SD Card reader: http://elasticsheep.com/2010/04/teensy2-usb-mass-storage-with-an-sd-card/ + * - SEGA Megadrive/Genesis Development Cartridge: http://www.makestuff.eu/wordpress/?page_id=398 + * - Stripe Snoop, a Magnetic Card reader: http://www.ossguy.com/ss_usb/ + * - Touchscreen Input Device: http://capnstech.blogspot.com/2010/07/touchscreen-update.html + * - USB Interface for Playstation Portable Devices: http://forums.ps2dev.org/viewtopic.php?t=11001 + * - Userial, a USB to Serial converter with SPI, I2C and other protocols: http://www.tty1.net/userial/ + * - XUM1541, a Commodore 64 floppy drive to USB adapter: http://www.root.org/~nate/c64/xum1541/ + * + * \section Sec_LUFACommercialProjects Projects Using LUFA (Commercial) + * + * The following is a list of known commercial products using LUFA. Some of these are open source, although many are "black-box" + * solutions with no source code given. + * + * - ARPS Locator: http://la3t.hamradio.no/lab//?id=tracker_en + * - Digital Survey Instruments Magnetometer and Pointer: http://www.digitalsurveyinstruments.com/ + * - Penguino, an Arduino Board With On-Board LUFA Powered Debugger/Programmer: http://wiki.icy.com.au/PenguinoAVR + * - Many of Busware's Products: http://www.busware.de/ + * - MIDIFighter, a USB-MIDI controller: http://www.midifighter.com/ + * - Mobo 4.3, a USB controlled all band (160-10m) HF SDR transceiver: http://sites.google.com/site/lofturj/mobo4_3 + * - Retrode, a USB Games Console Cartridge Reader: http://www.retrode.org + * - XMEGA Development Board, using LUFA as an On-Board Programmer: http://xmega.mattair.net/ + * + * \section Sec_LUFAPublications Publications Mentioning LUFA + * - Elektor Magazine, "My First AVR-USB" by Antoine Authier (feature), January 2010 Issue + * - Elektor Magazine, "USB is Cool/Sucks" by Jerry Jacobs and Chris Vossen (minor mention), January 2010 Issue + * - Elektor Magazine, "20 x Open Source" by Jens Nickel, March 2010 Issue + */ \ No newline at end of file diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/LUFAvsAtmelStack.txt b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/LUFAvsAtmelStack.txt new file mode 100644 index 0000000000..1eb6d008c7 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/LUFAvsAtmelStack.txt @@ -0,0 +1,46 @@ +/** \file + * + * This file contains special DoxyGen information for the generation of the main page and other special + * documentation pages. It is not a project source file. + */ + +/** + * \page Page_LUFAvsAtmelStack LUFA vs the Atmel Stack + * + * Atmel offers an official USB AVR stack, which may be incorporated into user projects and products. As LUFA and the Atmel + * stack aims to give roughly the same functionality to a design, it is often asked what advantages LUFA carries over the + * official Atmel USB stack. Below are just some of the advantages to choosing LUFA over the official stack. + * + * - Licensing: + * LUFA is released under a very permissive MIT license (see \ref Page_LicenseInfo), while the Atmel stack carries several + * restrictions as to how and where it can be used. LUFA's licensing should be suitable for both Commercial and Non-Commercial + * entities alike. + * + * - Demos and Projects: + * Unlike the Atmel stack, LUFA comes with many different Device and Host mode Demos and Projects ready to run out of the box. + * Atmel favors separate downloads for each of their (small set) of USB AVR demos, which requires more time and offers less + * to the end-user. LUFA also contains several open source Bootloaders, which can be modified as the user wishes to suit his or + * her application, instead of being forced to use Atmel's single prebuilt (closed-source) DFU bootloader. + * + * - Central Library Code: + * LUFA is designed to allow the central library core code to be shared amongst several projects, so long as the compiled object + * files are cleaned between different projects. This is in direct contrast to the Atmel library, which is strongly coupled to the + * project it is integrated with. Using LUFA allows for only one copy of the library core to be needed for all applications, and + * makes updating the library used in all projects a trivial copy-and-paste process. + * + * - Clean API: + * One of the main design goals of LUFA is to make the API easy to use. While LUFA is a fluid project which has undergone many + * API improvements, the API is arguably much nicer to use and easier to understand than the equivalent Atmel stack code. LUFA's + * API is also more complete than the Atmel stack, and contains many features to speed up application development. + * + * - Full Hardware Support: + * LUFA supports the full range of Atmel's USB AVR microcontrollers (see \ref Page_DeviceSupport), with porting between chips being + * as simple as a single compile switch in many cases. Atmel's stack requires different libraries to be used based on the USB AVR + * microcontroller series, complicating the process of moving between USB AVR models. In addition, LUFA contains drivers for all the + * hardware contained on Atmel's USB AVR based boards, so you can get started quickly and easily. + * + * - Better Library Support: + * As many people are now using LUFA, there is a community being built around it. You can get answers to your LUFA related questions + * quickly by either emailing the library author (subject to author's schedule) or by posting to the official LUFA support mailing list. + */ + diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/LibraryApps.txt b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/LibraryApps.txt new file mode 100644 index 0000000000..7d4f3f7cf1 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/LibraryApps.txt @@ -0,0 +1,114 @@ +/** \file + * + * This file contains special DoxyGen information for the generation of the main page and other special + * documentation pages. It is not a project source file. + */ + +/** \page Page_LibraryApps Included Library Applications + * + * The LUFA library ships with several different host and device demos, located in the /Demos/ subdirectory. Within this + * directory the demos are separated by USB mode (Device, Host, OTG) and further separated by the use or non-use of the + * library USB Class drivers (which abstract out the actual implementation of the USB classes to simplify development even + * further at the expense of a loss of flexibility). + * + * With one or two exceptions (e.g. proprietary classes such as RNDIS) all the included demos will work across all OSes without + * the need for special drivers. On Windows, some demos require the supplied .INF file to be used as the device driver, which + * directs the OS to use its inbuilt class drivers for the device. + * + * Also included with the library are two fully functional bootloaders, located in the /Bootloaders/ subdirectory. + * The DFU class bootloader is compatible with Atmel's FLIP software or the open source dfu-programmer project, while + * the CDC class (AVR109 protocol) is compatible with such open source software as AVRDUDE and AVR-OSP. + * + * User-submitted projects are located in the /Projects/ subdirectory. If you wish to have your LUFA project included, + * please email it to the Library author. + * + * \section Sec_AppOverview Overview of Included Library Applications + * The following shows the folder structure of the included library applications, including demos, bootloaders and user-submitted + * open source projects. + * + * + * + * - Demos + * - Device + * - ClassDriver + * - AudioInput - Audio In (microphone) demo, using the library USB Audio Class driver framework + * - AudioOutput - Audio Out (speaker) demo, using the library USB Audio Class driver framework + * - DualVirtualSerial - Dual Virtual Serial Port demo, using the library USB CDC Class driver framework + * - GenericHID - Generic Human Interface Class demo, using the library USB HID Class driver framework + * - Joystick - USB Joystick demo, using the library USB HID Class driver framework + * - Keyboard - USB Keyboard demo, using the library USB HID Class driver framework + * - KeyboardMouse - Dual Keyboard/Mouse demo, using the library USB HID Class driver framework + * - MassStorage - Dual Drive Mass Storage demo, using the library USB Mass Storage Class driver framework + * - MassStorageKeyboard - Mass Storage and Keyboard demo, using the library USB Mass Storage/HID Class driver frameworks + * - MIDI - MIDI In demo, using the library USB MIDI-Audio Class driver framework + * - Mouse - USB Mouse demo, using the library USB HID driver framework + * - RNDISEthernet - RNDIS Ethernet Webserver demo, using the library USB RNDIS driver framework + * - VirtualSerial - Virtual Serial Port demo, using the library USB CDC Class driver framework + * - VirtualSerialMouse - Virtual Serial Port and Mouse demo, using the library USB CDC and HID Class driver frameworks + * - LowLevel + * - AudioInput - Audio In (microphone) demo, using the low level LUFA APIs to implement the USB Audio class + * - AudioOutput - Audio Out (speaker) demo, using the low level LUFA APIs to implement the USB Audio class + * - DualVirtualSerial - Dual Virtual Serial Port demo, using the low level LUFA APIs to implement the USB CDC class + * - GenericHID - Generic Human Interface Class demo, using the low level LUFA APIs to implement the USB HID class + * - Joystick - USB Joystick demo, using the low level LUFA APIs to implement the USB HID class + * - Keyboard - USB Keyboard demo, using the low level LUFA APIs to implement the USB HID class + * - KeyboardMouse - Dual Keyboard/Mouse demo, using the low level LUFA APIs to implement the USB HID class + * - MassStorage - Dual Drive Mass Storage demo, using the low level LUFA APIs to implement the USB Mass Storage class + * - MIDI - MIDI In demo, using the low level LUFA APIs to implement the USB MIDI-Audio class + * - Mouse - USB Mouse demo, using the low level LUFA APIs to implement the USB HID class + * - RNDISEthernet - RNDIS Ethernet Webserver demo, using the low level LUFA APIs to implement the USB RNDIS class + * - VirtualSerial - Virtual Serial Port demo, using the low level LUFA APIs to implement the USB CDC class + * - Incomplete + * - SideShow - Incomplete Windows SideShow demo, using the low level LUFA APIs to implement the USB SideShow class + * - Host + * - ClassDriver + * - JoystickHostWithParser - Joystick host demo with HID Descriptor parser, using the library USB HID Class driver framework + * - KeyboardHost - USB Keyboard host demo, using the library USB HID Class driver framework + * - KeyboardHostWithParser - USB Keyboard host demo with HID Descriptor parser, using the library USB HID Class + * driver framework + * - MassStorageHost - Mass Storage host demo, using the library USB Mass Storage Class driver framework + * - MouseHost - Mouse host demo, using the library USB HID Class driver framework + * - MouseHostWithParser - Mouse host demo with HID Descriptor parser, using the library USB HID Class driver framework + * - RNDISHost - RNDIS Ethernet host demo, using the library USB RNDIS Class driver framework + * - StillImageHost - Still Image Camera host demo, using the library USB Still Image Class driver framework + * - VirtualSerialHost - Virtual Serial Port host demo, using the library USB CDC Class driver framework + * - LowLevel + * - JoystickHostWithParser - Joystick host demo with HID Descriptor parser, using the low level LUFA APIs to implement + * the USB HID class + * - GenericHIDHost - Generic HID host demo, using the low level LUFA APIs to implement the USB HID class + * - KeyboardHost - USB Keyboard host demo, using the low level LUFA APIs to implement the USB HID class + * - KeyboardHostWithParser - USB Keyboard host demo with HID Descriptor parser, using the low level LUFA APIs to + * implement the USB HID class + * - MassStorageHost - Mass Storage host demo, using the low level LUFA APIs to implement the USB Mass Storage class + * - MouseHost - Mouse host demo, using the low level LUFA APIs to implement the USB HID class + * - MouseHostWithParser - Mouse host demo with HID Descriptor parser, using the low level LUFA APIs to implement the + * USB HID class + * - PrinterHost - Printer host demo, using the low level LUFA APIs to implement the USB Printer class + * - RNDISHost - RNDIS Ethernet host demo, using the low level LUFA APIs to implement the RNDIS class + * - StillImageHost - Still Image Camera host demo, using the low level LUFA APIs to implement the USB Still Image class + * - VirtualSerialHost - Virtual Serial Port host demo, using the low level LUFA APIs to implement the USB CDC class + * - Incomplete + * - BluetoothHost - Incomplete Bluetooth host demo, using the low level LUFA APIs to implement the USB Bluetooth class + * - DualRole + * - ClassDriver + * - MouseHostDevice - Dual role Mouse Host and Mouse Device demo, using the library USB CDC Class driver framework + * - Bootloaders + * - DFU - DFU Class USB bootloader, compatible with Atmel's FLIP and the open source dfu-programmer software + * - CDC - CDC Class USB bootloader, compatible with any AVR910 protocol programming software such as AVRDude + * - Projects + * - AVRISP-MKII - AVRISP-MKII Programmer Clone project + * - Benito - Benito Board Arduino Programmer project + * - LEDNotifier - USB LED Notification project + * - Magstripe - Magnetic Stripe Card Reader project + * - MissileLaucher - Toy Missile Launcher Host project + * - RelayBoard - Relay board controller, controllable via the "sismpctl" Linux application + * - TempDataLogger - Temperature Datalogging project, using the FatFS library + * - USBtoSerial - USB to USART Serial Converter project + * - Webserver - RNDIS Host Webserver with DHCP client, powered by uIP TCP/IP stack project and FatFS library + * - XPLAINBridge - XPLAIN alternative PDI Programmer/USB to Serial Bridge firmware project + * - Incomplete + * - MIDIToneGenerator - Incomplete MIDI Tone Generator application, to convert MIDI note messages into audio tones + * - StandaloneProgrammer - Incomplete Standalone AVR Programmer application, to program AVRs directly from a Mass Storage disk + * + * + */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/LibraryResources.txt b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/LibraryResources.txt new file mode 100644 index 0000000000..10f98d90df --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/LibraryResources.txt @@ -0,0 +1,35 @@ +/** \file + * + * This file contains special DoxyGen information for the generation of the main page and other special + * documentation pages. It is not a project source file. + */ + +/** + * \page Page_Resources Library Resources + * + * \section Sec_ProjectPages LUFA Related Webpages + * Project Homepage: http://www.fourwalledcubicle.com/LUFA.php \n + * Author's Website: http://www.fourwalledcubicle.com \n + * Development Blog: http://www.fourwalledcubicle.com/blog \n + * Commercial Licenses: http://fourwalledcubicle.com/PurchaseLUFA.php \n + * + * \section Sec_ProjectHelp Assistance With LUFA + * Discussion Group: http://groups.google.com/group/myusb-support-list \n + * Author's Email: dean [at] fourwalledcubicle [dot] com + * Author's Skype: abcminiuser + * + * \section Sec_InDevelopment Latest In-Development Source Code + * Official Releases, SVN Access, Issue Tracker: http://code.google.com/p/lufa-lib/ \n + * Git Access: http://github.com/abcminiuser/lufa-lib \n + * Mercurial Access: http://bitbucket.org/abcminiuser/lufa-lib \n + * Latest Repository Source Archive: http://github.com/abcminiuser/lufa-lib/archives/master \n + * Commit RSS Feed: http://github.com/feeds/abcminiuser/commits/lufa-lib/master \n + * + * \section Sec_Toolchain AVR Toolchain + * WinAVR Website: http://winavr.sourceforge.net \n + * avr-libc Website: http://www.nongnu.org/avr-libc/ \n + * + * \section Sec_USBResources USB Resources + * USB-IF Website: http://www.usb.org \n + */ + diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/LicenseInfo.txt b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/LicenseInfo.txt new file mode 100644 index 0000000000..03b30a90b8 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/LicenseInfo.txt @@ -0,0 +1,21 @@ +/** \file + * + * This file contains special DoxyGen information for the generation of the main page and other special + * documentation pages. It is not a project source file. + */ + +/** + * \page Page_LicenseInfo Source Code License + * + * The LUFA library is currently released under the MIT license, included below. + * + * Commercial entities can opt out of the public disclosure clause in this license + * for a one-time US$1500 payment. This provides a non-exclusive modified MIT licensed which + * allows for the free use of the LUFA library, bootloaders and (where the sole copyright + * is attributed to Dean Camera) demos without public disclosure within an organization, in + * addition to three free hours of consultation with the library author, and priority support. + * Please visit the Commercial License link on \ref Page_Resources for more information on + * ordering a commercial license for your company. + * + * \verbinclude License.txt + */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/MainPage.txt b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/MainPage.txt new file mode 100644 index 0000000000..f8cd2e576d --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/MainPage.txt @@ -0,0 +1,45 @@ +/** \file + * + * This file contains special DoxyGen information for the generation of the main page and other special + * documentation pages. It is not a project source file. + */ + +/** + * \mainpage + * + * \image html LUFA.png + *
Logo design by Ryo - http://ryophotography.wordpress.com
+ * \n + * + * LUFA is donationware. For author and donation information, see \ref Page_Donating. + * + * LUFA is an open-source USB library for the USB-enabled AVR microcontrollers, released under the MIT license (see \ref Page_LicenseInfo). + * It supports a large number of USB AVR models and boards (see \ref Page_DeviceSupport). It is designed to provide an easy to use, + * feature rich framework for the development of USB peripherals and hosts. + * + * LUFA focuses on the microcontroller side of USB development only; it includes no PC host USB driver development facilities - other projects + * such as the Windows Driver Development Kit, Windows USB Device Mode Framework and libusb may be of interest for developing custom OS drivers. + * While custom USB devices can be made with LUFA using such tools, the included demos all use the inbuilt OS drivers for each USB class for + * simplicity. + * + * The library is currently in a stable release, suitable for download and incorporation into user projects for + * both host and device modes. For information about the project progression, see the blog link at \ref Page_Resources. + * + * LUFA is written specifically for the free AVR-GCC compiler, and uses several GCC-only extensions to make the + * library API more streamlined and robust. You can download AVR-GCC for free in a convenient windows package, + * from the the WinAVR website (see \ref Page_Resources). + * + * The only required AVR peripherals for LUFA is the USB controller itself and interrupts - LUFA does not require the use of the + * microcontroller's timers or other hardware, leaving more hardware to the application developer. + * + * Accompanying LUFA in the download package is a set of example demo applications, plus several Bootloaders of different classes + * and open source LUFA powered projects. + * + * Subsections: + * \li \subpage Page_WhyUseLUFA - What are the advantages of using LUFA? + * \li \subpage Page_LUFAvsAtmelStack - How does LUFA compare to the Atmel USB AVR stack? + * \li \subpage Page_AlternativeStacks - Alternative USB AVR Stacks + * \li \subpage Page_LicenseInfo - Project source license and commercial use information + * \li \subpage Page_Donating - Donating to support this project + * \li \subpage Page_LibraryApps - Overview of included Demos, Bootloaders and Projects + */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/MigrationInformation.txt b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/MigrationInformation.txt new file mode 100644 index 0000000000..f620020d71 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/MigrationInformation.txt @@ -0,0 +1,529 @@ +/** \file + * + * This file contains special DoxyGen information for the generation of the main page and other special + * documentation pages. It is not a project source file. + */ + +/** \page Page_Migration Migrating from Older Versions + * + * Below is migration information for updating existing projects based on previous versions of the LUFA library + * to the next version released. It does not indicate all new additions to the library in each version change, only + * areas relevant to making older projects compatible with the API changes of each new release. + * + * \section Sec_Migration100807 Migrating from 100513 to 100807 + * + * Non-USB Library Components + * - The Dataflash board driver stub file has changed, as dataflash functions previously located in the internal + * Dataflash driver of the library have now been moved to the individual board files. Existing drivers can + * copy-paste the new functions from the board Dataflash stub driver. + * + * USB Core + * - A new USB driver source file, Drivers/USB/LowLevel/Device.c now exists. This source file should be added to all project + * makefiles using the USB driver of LUFA, or the makefile should be updated to use the new module source variables. + * - The Drivers/USB/LowLevel/DevChapter9.c source file has moved to Drivers/USB/HighLevel/DeviceStandardReq.c - this should + * be updated in all project makefiles, or the makefile should be updated to use the new module source variables. + * - The Drivers/USB/LowLevel/HostChapter9.h source file has moved to Drivers/USB/HighLevel/HostStandardReq.c - this should + * be updated in all project makefiles, or the makefile should be updated to use the new module source variables. + * - The Drivers/USB/LowLevel/LowLevel.c source file has moved to Drivers/LowLevel/USBController.c - this should be updated + * in all project makefiles, or the makefile should be updated to use the new module source variables. + * + * Device Mode + * - The USB_Device_IsRemoteWakeupSent() macro has been removed, as the remote wakeup request is now fully handled by the + * enhanced \ref USB_Device_SendRemoteWakeup() function. Existing code may now discard any checks to USB_Device_IsRemoteWakeupSent(). + * - The USB_Device_IsUSBSuspended() macro has been removed, as it is obsolete. Existing code should compare \ref USB_DeviceState + * to see if it the device is in the \ref DEVICE_STATE_Suspended state instead. + * - The \ref CDC_Device_ReceiveByte() function has changed, and now returns a signed 16-bit integer, with -1 indicating no data was + * received. This allows for more efficient coding, as a call to \ref CDC_Device_BytesReceived() is no longer needed if the exact + * number of queued bytes received is not needed. + * + * Host Mode + * - The \ref CDC_Host_ReceiveByte() function has changed, and now returns a signed 16-bit integer, with -1 indicating no data was + * received. This allows for more efficient coding, as a call to \ref CDC_Device_BytesReceived() is no longer needed if the exact + * number of queued bytes received is not needed. + * - The \ref CDC_Host_USBTask() now calls \ref CDC_Host_Flush() automatically, flushing any queued data to the attached device. Manual + * flushing of the interface is no longer needed if the flushes should be in sync with calls to \ref CDC_Host_USBTask(). + * + * \section Sec_Migration100513 Migrating from 100219 to 100513 + * + * Non-USB Library Components + * - The \ref TWI_StartTransmission() function now takes in a timeout period, expressed in milliseconds, within which the addressed + * device must respond or the function will abort. + * + * Device Mode + * - The \ref USB_Init() function no longer calls sei() to enable global interrupts, as the user application may need + * to perform other initialization before it is ready to handle global interrupts. The user application is now responsible + * for enabling global interrupts before or shortly after calling \ref USB_Init() to ensure that the enumeration process + * functions correctly. + * - The USBInterrupt.c USB driver source file has been relocated from LUFA/Drivers/USB/HighLevel/ to LUFA/Drivers/USB/LowLevel. + * Projects must update their makefile SRC values accordingly. + * - The HID Device Class driver's function signature for the CALLBACK_HID_Device_ProcessHIDReport() function has been changed, to + * allow for a new ReportType parameter. This new parameter must be added in all user applications using the Device mode HID Class + * Driver, but may be ignored unless Host-to-Device FEATURE HID reports are used. + * + * Host Mode + * - The \ref USB_Init() function no longer calls sei() to enable global interrupts, as the user application may need + * to perform other initialization before it is ready to handle global interrupts. The user application is now responsible + * for enabling global interrupts before or shortly after calling \ref USB_Init() to ensure that the enumeration process + * functions correctly. + * - The USBInterrupt.c USB driver source file has been relocated from LUFA/Drivers/USB/HighLevel/ to LUFA/Drivers/USB/LowLevel. + * Projects must update their makefile SRC values accordingly. + * - The HID Host Class driver's function signature for the HID_Host_SendReportByID() function has been changed, to allow for a new + * ReportType parameter. Existing calls to this function should substitute REPORT_ITEM_TYPE_Out as this parameter's value. + * + * \section Sec_Migration100219 Migrating from 091223 to 100219 + * + * Non-USB Library Components + * - Due to some ADC channels not being identical to their ADC MUX selection masks for single-ended conversions on some AVR models, + * the ADC driver now has explicit masks for each of the standard ADC channels (see \ref Group_ADC). These masks should be used + * when calling the ADC functions to ensure proper operation across all AVR models. Note that the \ref ADC_SetupChannel() function + * is an exception, and should always be called with a channel number rather than a channel mask. + * + * Host Mode + * - The MIDI Host Class driver send and receive routines now operate on packed events, where multiple MIDI events may be + * packed into a single USB packet. This means that the sending of MIDI events will now be delayed until the MIDI send + * pipe bank is full. To override this new behaviour and revert to the previous behaviour, the user application may manually + * flush the queued event(s) to the device by calling \ref MIDI_Host_Flush(). + * - The Pipe_IsEndpointBound() function now takes the endpoint's direction into account, by checking if the MSB of the endpoint's address + * is set to denote IN endpoints. If the previous functionality where the direction is to be discounted is required, mask the endpoint + * address against the \ref PIPE_EPNUM_MASK token before calling Pipe_IsEndpointBound(). + * + * Device Mode + * - The MIDI Device Class driver send and receive routines now operate on packed events, where multiple MIDI events may be + * packed into a single USB packet. This means that the sending of MIDI events will now be delayed until the MIDI send + * endpoint bank is full. To override this new behaviour and revert to the previous behaviour, the user application may manually + * flush the queued event(s) to the host by calling \ref MIDI_Device_Flush(). + * + * \section Sec_Migration091223 Migrating from 091122 to 091223 + * + * Host Mode + * - The Still Image Host Class driver SI_Host_USBTask() and SI_Host_ConfigurePipes() functions were misnamed, and are + * now named \ref SImage_Host_USBTask() and \ref SImage_Host_ConfigurePipes() respectively. + * - The HOST_SENDCONTROL_DeviceDisconnect enum value has been renamed to \ref HOST_SENDCONTROL_DeviceDisconnected to be in + * line with the rest of the library error codes. + * - The HID Parser item usages no longer contain separate minimum and maximum values, as this was a violation of the HID + * specification. Instead, the values are distributed evenly across each item as its usage value, to ensure that all items + * can be distinguished from one-another. + * + * Device Mode + * - The CALLBACK_HID_Device_CreateHIDReport() HID Device Class driver callback now has a new ReportType parameter to + * indicate the report type to generate. Existing applications may simply add and ignore this additional parameter. + * + * \section Sec_Migration091122 Migrating from 090924 to 091122 + * + * Host Mode + * - The HID_PARSE_UsageStackOverflow HID parser error constant is now named \ref HID_PARSE_UsageListOverflow + * - The \ref CALLBACK_HIDParser_FilterHIDReportItem() HID Parser callback now passes a complete HID_ReportItem_t to the + * user application, instead of just its attributes. + * - The USB_GetDeviceConfigDescriptor() function was incorrectly named and is now called \ref USB_Host_GetDeviceConfigDescriptor(). + * + * \section Sec_Migration090924 Migrating from 090810 to 090924 + * + * Non-USB Library Components + * - The ADC_Off() function has been renamed to \ref ADC_ShutDown() to be consistent with the rest of the library. + * - The \ref SPI_Init() routine's parameters have changed, so that the clock polarity and data sampling modes can be set. See + * the \ref SPI_Init() function documentation for more details + * - The \ref Dataflash_Init() routine no longer initializes the SPI bus - the SPI bus should be initialized manually via a + * call to SPI_Init() before using the Dataflash driver + * + * Host Mode + * - The USB_GetDeviceConfigDescriptor() function's parameters and behaviour has changed; the user is required to + * preallocate the largest allowable buffer, and pass the size of the buffer to the function. This allows for a single + * call to the function to retrieve, size check and validate the Configuration Descriptor rather than having the user + * application perform these intermediary steps. + * - The HID report parser now requires a mandatory callback in the user code, to filter only the items the application + * is interested in into the processed HID report item structure to save RAM. See \ref CALLBACK_HIDParser_FilterHIDReportItem(). + * - The HID report parser now always parses FEATURE and always ignores constant-data items - the HID_ENABLE_FEATURE_PROCESSING + * and HID_INCLUDE_CONSTANT_DATA_ITEMS compile time tokens now have no effect. + * - The USE_NONSTANDARD_DESCRIPTOR_NAMES compile time token has been removed - there are now separate USB_Descriptor_* + * and USB_StdDescriptor_* structures for both the LUFA and standardized element naming conventions so that both may be used in + * the one project. For existing projects using the standardized names, change all code to use the USB_StdDescriptor_* variants. + * + * Device Mode + * - The USE_NONSTANDARD_DESCRIPTOR_NAMES compile time token has been removed - there are now separate USB_Descriptor_* + * and USB_StdDescriptor_* structures for both the LUFA and standardized element naming conventions so that both may be used in + * the one project. For existing projects using the standardized names, change all code to use the USB_StdDescriptor_* variants. + * + * \section Sec_Migration090810 Migrating from 090605 to 090810 + * + * All + * - The "Simple Scheduler" has been deprecated, as it was little more than an abstracted loop and caused much confusion. + * User applications using the scheduler should switch to regular loops instead. The scheduler code will be removed in a future + * release. + * - The "Dynamic Memory Block Allocator" has been removed, as it was unused in (and unrelated to) the LUFA library and never + * used in user applications. The library is available from the author's website for those wishing to still use it in their + * applications. + * + * Non-USB Library Components + * - The ATTR_NOINLINE function attribute macro has been renamed to ATTR_NO_INLINE to be in line with the rest of the function attribute + * macro names. + * + * Library Demos + * - Most demos now have a corresponding Class Driver implementation, which uses the new internal library class drivers for the standard + * USB classes. This allows for more rapid device and host development, and so should be used in preference to the low level APIs where + * possible so that fixes to the class drivers propagate to all applications which use them automatically with each new LUFA release. + * + * Host Mode + * - The HIDParser.c module has moved from LUFA/Drivers/USB/Class/ to LUFA/Drivers/USB/Class/Host/. + * - The USB_GetDeviceConfigDescriptor() function now requires the desired configuration index within the device as its first + * parameter, to add support for multi-configuration devices. Existing code should use a configuration index of 1 to indicate the + * first configuration descriptor within the device. + * - The non-standard "Ready" host state has been removed. Existing \ref HOST_STATE_Configured code should be moved to the end of + * the existing \ref HOST_STATE_Addressed state, and the existing HOST_STATE_Ready state code should be moved to the \ref HOST_STATE_Configured + * state. + * - The USB_IsConnected global has been removed, as it is too vague for general use. Test \ref USB_HostState explicitly to ensure the host is + * in the desired state instead. + * - The USB event names have been changed and their firing conditions changed to properly separate out Host mode events from Device mode + * events. See the \ref Group_Events page for details on the new event names and firing conditions. + * + * Device Mode + * - The \ref CALLBACK_USB_GetDescriptor() function now takes an extra parameter to specify the descriptor's memory space so that + * descriptors in mixed memory spaces can be used. The previous functionality can be returned by defining the USE_FLASH_DESCRIPTORS + * token in the project makefile to fix all descriptors into FLASH space and remove the extra function parameter. + * - The USB_IsSuspended global has been removed - test \ref USB_DeviceState against \ref DEVICE_STATE_Suspended instead. + * - The USB_IsConnected global has been removed, as it is too vague for general use. Test \ref USB_DeviceState explicitly to ensure the device + * is in the desired state instead. + * - The VBUS events have been removed, as they are already exposed to the user via the USB_Connect and USB_Disconnect events. + * - The USB event names have been changed and their firing conditions changed to properly separate out Host mode events from Device mode + * events. See the \ref Group_Events page for details on the new event names and firing conditions. * + * + * \section Sec_Migration090605 Migrating from 090510 to 090605 + * + * Device Mode + * - Support for non-control data endpoint interrupts has been dropped due to many issues in the implementation. All existing + * projects using interrupts on non-control endpoints should switch to polling. For control interrupts, the library can + * manage the control endpoint via interrupts automatically by compiling with the INTERRUPT_CONTROL_ENDPOINT token defined. + * - The DESCRIPTOR_ADDRESS() macro has been removed. User applications should use normal casts to obtain a descriptor's memory + * address. + * - The library events system has been rewritten, so that all macros have been removed to allow for clearer user code. See + * \ref Group_Events for new API details. + * - The STREAM_CALLBACK() macro has been removed. User applications should replace all instances of the macro with regular + * function signatures of a function accepting no arguments and returning a uint8_t value. + * - The Event_DeviceError() event no longer exists, as its sole caller (unlinked USB_GetDescriptor() function) now produces a + * compilation error rather than a runtime error. The StdDescriptors.c file no longer exists as a result, and should be removed + * from project makefiles. + * - The USB_GetDescriptor() function has been renamed to CALLBACK_USB_GetDescriptor() to be in line with the new CALLBACK_ function + * prefixes for functions which *must* be implemented in the user application. + * + * Host Mode + * - Support for non-control data pipe interrupts has been dropped due to many issues in the implementation. All existing + * projects using interrupts on non-control pipes should switch to polling. + * - The library events system has been rewritten, so that all macros have been removed to allow for clearer user code. See + * \ref Group_Events for new API details. + * - The STREAM_CALLBACK() macro has been removed. User applications should replace all instances of the macro with regular + * function signatures of a function accepting no arguments and returning a uint8_t value. + * - The DESCRIPTOR_COMPARATOR() macro has been removed. User applications should replace all instances of the macro with + * regular function signatures of a function accepting a void pointer to the descriptor to test, and returning a uint8_t value. + * + * + * \section Sec_Migration090510 Migrating from 090401 to 090510 + * + * All + * - The ButtLoadTag.h header has been removed, as it was never used for its intended purpose. Projects should either remove all + * BUTTLOADTAG elements, or download and extract ButtLoadTag.h header from the ButtLoad project. + * - The Drivers/AT90USBXXX directory has been renamed to Drivers/Peripheral. + * - The Serial_Stream driver has been renamed to SerialStream to remain consistent with the rest of the library naming scheme. + * - The HWB driver has changed to the Buttons driver. See the board Buttons driver documentation for the new API. + * + * Dual Role Mode + * - The USB_PowerOnFail even has been renamed to USB_InitFailure. + * - The functions in OTG.h have been renamed to remain more consistent with the library API. See the functions in OTG.h for more + * details. + * + * Library Demos + * - Most demos, bootloaders and applications have had significant changes from previous versions. Applications built off of any + * library demos should update to the latest versions. + * + * Device Mode + * - The Endpoint_ClearCurrentBank() macro has been removed, and is now replaced with the Endpoint_ClearIN(), Endpoint_ClearOUT() + * macros. See Endpoint.h documentation for more details on the new endpoint management macros. + * - The Endpoint_ReadWriteAllowed() macro has been renamed to Endpoint_IsReadWriteAllowed() to be more consistent with the rest of + * the API naming scheme. + * - The Endpoint_IsSetupINReady() and Endpoint_IsSetupOutReceived() macros have been renamed to Endpoint_IsINReady() and + * Endpoint_IsOUTReceived() respectively. + * - The Endpoint_IsSetupReceived() macro has been renamed to Endpoint_IsSETUPReceived(). + * - The Endpoint_ClearSetupReceived() macro has been renamed to Endpoint_ClearSETUP(). + * - All endpoint read/write/discard aliases which did not have an explicitly endianness specifier (such as Endpoint_Read_Word()) have + * been removed for clarity. Existing projects should use the "_LE" suffix on such calls to use the explicit Little Endian versions. + * - The USB_UnhandledControlPacket event no longer has any parameters. User code should no longer attempt to read in the remainder of + * the Control Request header as all Control Request header data is now preloaded by the library and made available in the + * USB_ControlRequest structure. + * - The FEATURELESS_CONTROL_ONLY_DEVICE token has been renamed to CONTROL_ONLY_DEVICE. + * - The STATIC_ENDPOINT_CONFIGURATION is no longer applicable as the library will apply this optimization when appropriate automatically. + * - The values of the Endpoint_Stream_RW_ErrorCodes_t and Endpoint_ControlStream_RW_ErrorCodes_t enums have had the "ERROR_" portion + * of their names removed. + * + * Host Mode + * - The USB_Host_SendControlRequest() function no longer automatically selects the Control pipe (pipe 0) to allow it to be used on + * other control type pipes. Care should be taken to ensure that the Control pipe is always selected before the function is called + * in existing projects where the Control pipe is to be operated on. + * - The USB Host management task now saves and restores the currently selected pipe before and after the task runs. Projects no longer + * need to manage this manually when calling the USB management task. + * - The Pipe_ClearCurrentBank() macro has been removed, and is now replaced with the Pipe_ClearIN(), Pipe_ClearOUT() macros. See + * Pipe.h documentation for more details on the new pipe management macros. + * - The Pipe_ReadWriteAllowed() macro has been renamed to Pipe_IsReadWriteAllowed() to be more consistent with the rest of the API + * naming scheme. + * - The Pipe_IsSetupINReceived() and Pipe_IsOutReady() macros have been renamed to Pipe_IsINReceived() and Pipe_IsOUTReady() + * respectively. + * - The new Pipe_ClearSETUP() macro should be used to send SETUP transactions, rather than the previous Pipe_ClearSetupOUT() macro. + * - The Pipe_IsSetupSent() macro has been renamed to Pipe_IsSETUPSent(). + * - The Pipe_ClearSetupSent() macro is no longer applicable and should be removed. + * - All pipe read/write/discard aliases which did not have an explicitly endianness specifier (such as Pipe_Read_Word()) have + * been removed for clarity. Existing projects should use the "_LE" suffix on such calls to use the explicit Little Endian versions. + * - The Host_IsResetBusDone() macro has been renamed to Host_IsBusResetComplete(). + * - The Pipe_Ignore_Word() and Pipe_Ignore_DWord() functions have been renamed to Pipe_Discard_Word() and Pipe_Discard_DWord() to remain + * consistent with the rest of the pipe API. + * - It is no longer needed to manually include the headers from LUFA/Drivers/USB/Class, as they are now included along with the rest + * of the USB headers when LUFA/Drivers/USB/USB.h is included. + * - Functions in the ConfigDescriptor.h header file no longer have "Host_" as part of their names. + * - The ProcessHIDReport() has been renamed to USB_ProcessHIDReport(), GetReportItemInfo() has been renamed to USB_GetHIDReportItemInfo() + * and SetReportItemInfo() has been renamed to USB_GetHIDReportItemInfo(). + * - The values of the DSearch_Return_ErrorCodes_t and DSearch_Comp_Return_ErrorCodes_t enums have had their respective "Descriptor_Search" + * and "Descriptor_Search_Comp" prefixes changed to all caps. + * - The USB_HostRequest global has been renamed to USB_ControlRequest, and is used in Device mode also. The USB_Host_Request_Header_t + * structure type has been renamed to USB_Request_Header_t. + * - The values of the Pipe_Stream_RW_ErrorCodes_t enum have had the "ERROR_" portion of their names removed. + * + * + * \section Sec_Migration090401 Migrating from 090209 to 090401 + * + * All + * - LUFA projects must now give the raw input clock frequency (before any prescaling) as a compile time constant "F_CLOCK", + * defined in the project makefile and passed to the compiler via the -D switch. + * - The makefile EEPROM programming targets for FLIP and dfu-programmer no longer program in the FLASH data in addition to the + * EEPROM data into the device. If both are to be programmed, both the EEPROM and FLASH programming targets must be called. + * - As the avr-libc macro has been corrected in recent avr-libc distributions, the SetSystemClockPrescaler() macro has been removed. + * Include and call clock_prescale_set(clock_div_1); instead on recent avr-libc distributions. + * + * Library Demos + * - The USBtoSerial demo now discards all data when not connected to a host, rather than buffering it for later transmission. + * - Most demos, bootloaders and applications have had their control request handling code corrected, to properly send the status + * stage in all handled requests. If you are using code based off one of the library demos, bootloaders or applications, you should + * update to the latest revisions. + * + * Non-USB Library Components + * - The ATTR_ALWAYSINLINE function attribute macro has been renamed to ATTR_ALWAYS_INLINE. + * - Custom board Dataflash drivers now require the implementation of Dataflash_SelectChipFromPage() and Dataflash_SendAddressBytes(). + * + * Device Mode + * - The NO_CLEARSET_FEATURE_REQUEST compile time token has been renamed to FEATURELESS_CONTROL_ONLY_DEVICE, and its function expanded + * to also remove parts of the Get Status chapter 9 request to further reduce code usage. On all applications currently using the + * NO_CLEARSET_FEATURE_REQUEST compile time token, it can be replaced with the FEATURELESS_CONTROL_ONLY_DEVICE token with no further + * modifications required. + * + * + * \section Sec_Migration090209 Migrating from 081217 to 090209 + * + * Device Mode + * - The ENDPOINT_MAX_ENDPOINTS constant has been renamed to the more appropriate name of ENDPOINT_TOTAL_ENDPOINTS. + * - The USB_STREAM_TIMEOUT_MS stream timeout default period has been extended to 100ms. This can be overridden in the user + * makefile if desired to restore the previous 50ms timeout. + * + * Host Mode + * - The PIPE_MAX_ENDPOINTS constant has been renamed to the more appropriate name of PIPE_TOTAL_ENDPOINTS. + * - The USB_STREAM_TIMEOUT_MS stream timeout default period has been extended to 100ms. This can be overridden in the user + * makefile if desired to restore the previous 50ms timeout. + * - The USB_DeviceEnumerationFailed event now contains a second "SubErrorCode" parameter, giving the error code of the function + * which failed. + * - The HID_PARSE_Sucessful enum member constant has been corrected to HID_PARSE_Successful. + * + * Non-USB Library Components + * - The previous SPI_SendByte() functionality is now located in SPI_TransferByte(). SPI_SendByte() now discards the return byte + * for speed, to compliment the new SPI_ReceiveByte() function. If two-way SPI transfers are required, calls to SPI_SendByte() + * should be changed to SPI_TransferByte(). + * - The serial driver now sets the Tx line as an output explicitly, and enables the pull-up of the Rx line. + * - The Serial_Init() and SerialStream_Init() functions now take a second DoubleSpeed parameter, which indicates if the USART + * should be initialized in double speed mode - useful in some circumstances for attaining baud rates not usually possible at + * the given AVR clock speed. + * + * Library Demos + * - Most library demos have been enhanced and/or had errors corrected. All users of all demos should upgrade their codebase to + * the latest demo versions. + * + * + * \section Sec_Migration171208 Migrating from V1.5.3 to 081217 + * + * All + * - The MyUSB project name has been changed to LUFA (Lightweight Framework for USB AVRs). All references to MyUSB, including macro names, + * have been changed to LUFA. + * + * Library Demos + * - The ReconfigureUSART() routine in the USBtoSerial demo was not being called after new line encoding + * parameters were set by the host. Projects built on the USBtoSerial code should update to the latest version. + * - The HID Parser now supports multiple report (on a single endpoint) HID devices. The MouseHostWithParser and + * KeyboardHostWithPaser demos use the updated API functions to function correctly on such devices. Projects + * built on either "WithParser" demo should update to the latest code. + * - The RNDIS demo TCP stack has been modified so that connections can be properly closed. It is still not + * recommended that the MyUSB RNDIS demo TCP/IP stack be used for anything other than demonstration purposes, + * as it is neither a full nor a standards compliant implementation. + * + * Non-USB Library Components + * - The Serial_IsCharReceived() macro has been changed to the correct spelling of Serial_IsCharReceived() in Serial.h. + * + * Device Mode + * - The MANUAL_PLL_CONTROL compile time token has been removed, and replaced with a USB_OPT_MANUAL_PLL mask + * to be used in the Options parameter of the USB_Init() function. + * - Calling USB_Init() now forces a complete USB interface reset and enumeration, even if the USB interface is + * currently initialized. + * - Interrupts are now disabled when processing control requests, to avoid problems with interrupts causing the library + * or user request processing code to exceed the strict USB timing requirements on control transfers. + * - The USB Reset event now resets and disables all device endpoints. If user code depends on endpoints remaining configured + * after a Reset event, it should be altered to explicitly re-initialize all user endpoints. + * - The prototype for the GetDescriptor function has been changed, as the return value was redundant. The function now + * returns the size of the descriptor, rather than passing it back via a parameter, or returns NO_DESCRIPTOR if the specified + * descriptor does not exist. + * - The NO_DESCRIPTOR_STRING macro has been renamed NO_DESCRIPTOR, and is now also used as a possible return value for the + * GetDescriptor function. + * + * Host Mode + * - The MANUAL_PLL_CONTROL compile time token has been removed, and replaced with a USB_OPT_MANUAL_PLL mask + * to be used in the Options parameter of the USB_Init() function. + * - The HID report parser now supports multiple Report IDs. The HID report parser GetReportItemInfo() and + * SetReportItemInfo() routines now return a boolean, set if the requested report item was located in the + * current report. If sending a report to a multi-report device, the first byte of the report is automatically + * set to the report ID of the given report item. + * - Calling USB_Init() now forces a complete USB interface reset and enumeration, even if the USB interface is + * currently initialized. + * + * + * \section Sec_Migration152 Migrating from V1.5.2 to V1.5.3 + * + * Library Demos + * - Previously, all demos contained a serial number string descriptor, filled with all zeros. A serial number + * string is required in Mass Storage devices, or devices which are to retain settings when moved between + * ports on a machine. As people were not changing the serial number value, this was causing conflicts and so + * the serial number descriptor has been removed from all but the Mass Storage demo, which requires it. + * - The AudioOut and AudioIn demos did not previously silence their endpoints when the host has deactivated + * them. Projects built upon either demo should upgrade to the latest code. + * - The FEATURE_ENDPOINT macro has been renamed FEATURE_ENDPOINT_HALT, and is now correctly documented. + * - The MassStoreHost demo contained errors which caused it to lock up randomly on certain devices. Projects built + * on the MassStoreDemo code should update to the latest version. + * - The Interrupt type endpoint in the CDC based demos previously had a polling interval of 0x02, which caused + * problems on some Linux systems. This has been changed to 0xFF, projects built on the CDC demos should upgrade + * to the latest code. + * - The HID keyboard and mouse demos were not previously boot mode compatible. To enable boot mode support, projects + * built on the keyboard or mouse demos (or derivatives) should upgrade to the latest code. + * - The Mass Storage demo was not previously standards compliant. Projects built on the Mass Storage demo should + * upgrade to the latest code. + * - The USART was not being reconfigured after the host sent new encoding settings in the USBtoSerial demo. This was + * previously discovered and fixed, but the change was lost. Projects built on the USBtoSerial demo should update + * to the latest code. + * + * Device Mode + * - The endpoint non-control stream functions now have a default timeout of 50ms between packets in the stream. + * If this timeout is exceeded, the function returns the new ENDPOINT_RWSTREAM_ERROR_Timeout error value. The + * timeout value can be overridden by defining the USB_STREAM_TIMEOUT_MS in the project makefile to the desired + * timeout duration in ms. + * - Rather than returning fixed values, the flags indicating if the device has Remote Wakeup currently enabled + * and/or is self-powered are now accessed and set through the new USB_RemoteWakeupEnabled and + * USB_CurrentlySelfPowered macros. See the DevChapter9.h documentation for more details. + * - All endpoint stream functions now require an extra Callback function parameter. Existing code may be updated + * to either supply NO_STREAM_CALLBACK as the extra parameter, or disable stream callbacks altogether by passing + * the token NO_STREAM_CALLBACKS to the compiler using the -D switch. + * + * Host Mode + * - The pipe non-control stream functions now have a default timeout of 50ms between packets in the stream. + * If this timeout is exceeded, the function returns the new PIPE_RWSTREAM_ERROR_Timeout error value. The + * timeout value can be overridden by defining the USB_STREAM_TIMEOUT_MS in the project makefile to the desired + * timeout duration in ms. + * - CollectionPath_t has been renamed to HID_CollectionPath_t to be more in line with the other HID parser structures. + * - All pipe stream functions now require an extra Callback function parameter. Existing code may be updated + * to either supply NO_STREAM_CALLBACK as the extra parameter, or disable stream callbacks altogether by passing + * the token NO_STREAM_CALLBACKS to the compiler using the -D switch. + * + * + * \section Sec_Migration151 Migrating from V1.5.1 to V1.5.2 + * + * Library Demos + * - The RNDIS demo application has been updated so that it is functional on Linux under earlier implementations + * of the RNDIS specification, which had non-standard behaviour. Projects built upon the demo should upgrade + * to the latest code. + * - The DFU class bootloader has had several bugs corrected in this release. It is recommended that where + * possible any existing devices upgrade to the latest bootloader code. + * + * + * \section Sec_Migration150 Migrating from V1.5.0 to V1.5.1 + * + * Library Demos + * - The USBtoSerial demo was broken in the 1.5.0 release, due to incorrect register polling in place of the + * global "Transmitting" flag. The change has been reverted in this release. Projects built upon the demo + * should upgrade to the latest code. + * - The HID class demos did not implement the mandatory GetReport HID class request. Projects built upon the HID + * demos should upgrade to the latest code. + * - The HID class demos incorrectly reported themselves as boot-protocol enabled HID devices in their descriptors. + * Projects built upon the HID demos should upgrade to the latest code. + * - The MIDI device demo had incorrect AudioStreaming interface descriptors. Projects built upon the MIDI demo + * should upgrade to the latest code. + * - The AudioOut demo did not correctly tristate the speaker pins when USB was disconnected, wasting power. + * Projects built upon the AudioOut demo should upgrade to the latest code. + * + * + * \section Sec_Migration141 Migrating from V1.4.1 to V1.5.0 + * + * Library Demos + * - Previous versions of the library demos had incorrectly encoded BCD version numbers in the descriptors. To + * avoid such mistakes in the future, the VERSION_BCD macro has been added to StdDescriptors.h. Existing + * projects should at least manually correct the BCD version numbers, or preferably update the descriptors to + * encode the version number in BCD format using the new macro. + * - The mandatory GetReport class-specific request was accidentally omitted from previous versions of the demos + * based on the Human Interface Device (HID) class. This has been corrected, and any user projects based on the + * HID demos should also be updated accordingly. + * - The CDC demos now correctly send an empty packet directly after a full packet, to end the transmission. + * Failure to do this on projects which always or frequently send full packets will cause buffering issues on + * the host OS. All CDC user projects are advised to update their transmission routines in the same manner as + * the library CDC demos. + * - The previous interrupt-driven Endpoint/Pipe demos did not properly save and restore the currently selected + * Endpoint/Pipe when the ISR fired. This has been corrected - user projects based on the interrupt driven + * demos should also update to properly save and restore the selected Endpoint/Pipe. + * + * Non-USB Library Components + * - The Atomic.h and ISRMacro.h header files in MyUSB/Common have been removed, as the library is now only + * compatible with avr-libc library versions newer than the time before the functionality of the deleted + * headers was available. + * + * Device Mode + * - The GetDescriptor function (see StdDescriptors.h) now has a new prototype, with altered parameter names and + * functions. Existing projects will need to update the GetDescriptor implementation to reflect the new API. + * The previously split Type and Index parameters are now passed as the original wValue parameter to the + * function, to make way for the USB specification wIndex parameter which is not the same as the + * previous Index parameter. + * - The USB_UnhandledControlPacket event (see Events.h) now has new parameter names, to be in line with the + * official USB specification. Existing code will need to be altered to use the new parameter names. + * - The USB_CreateEndpoints event (see Events.h) has been renamed to USB_ConfigurationChanged, which is more + * appropriate. It fires in an identical manner to the previously named event, thus the only change to be made + * is the event name itself in the user project. + * - The USB_Descriptor_Language_t structure no longer exists in StdDescriptors.h, as this was a + * pseudo-descriptor modeled on the string descriptor. It is replaced by the true USB_Descriptor_String_t type + * descriptor as indicated in the USB specification, thus all device code must be updated accordingly. + * - The names of several Endpoint macros have been changed to be more consistent with the rest of the library, + * with no implementation changes. This means that existing code can be altered to use the new macro names + * with no other considerations required. See Endpoint.h for the new macro names. + * - The previous version of the MassStorage demo had an incorrect value in the SCSI_Request_Sense_Response_t + * structure named SenseData in SCSI.c which caused some problems with some hosts. User projects based on this + * demo should correct the structure value to maintain compatibility across multiple OS platforms. + * - By default, the descriptor structures use the official USB specification names for the elements. Previous + * versions of the library used non-standard (but more verbose) names, which are still usable in the current + * and future releases when the correct compile time option is enabled. See the StdDescriptors.h file + * documentation for more details. + * + * Host Mode + * - The USB_Host_Request_Header_t structure in HostChapter9.h (used for issuing control requests) has had its + * members renamed to the official USB specification names for requests. Existing code will need to be updated + * to use the new names. + * - The names of several Pipe macros have been changed to be more consistent with the rest of the library, + * with no implementation changes. This means that existing code can be altered to use the new macro names + * with no other considerations required. See Pipe.h for the new macro names. + * - By default, the descriptor structures use the official USB specification names for the elements. Previous + * versions of the library used non-standard (but more verbose) names, which are still usable in the current + * and future releases when the correct compile time option is enabled. See the StdDescriptors.h file + * documentation for more details. + * - The names of the macros in Host.h for controlling the SOF generation have been renamed, see the Host.h + * module documentation for the new macro names. + * + * Dual Role Mode + * - The OTG.h header file has been corrected so that the macros now perform their stated functions. Any existing + * projects using custom headers to fix the broken OTG header should now be altered to once again use the OTG + * header inside the library. + * - The USB_DeviceEnumerationComplete event (see Events.h) now also fires in Device mode, when the host has + * finished enumerating the device. Projects relying on the event only firing in Host mode should be updated + * so that the event action only occurs when the USB_Mode global is set to USB_MODE_HOST. + */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/ProgrammingApps.txt b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/ProgrammingApps.txt new file mode 100644 index 0000000000..4f3107502a --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/ProgrammingApps.txt @@ -0,0 +1,27 @@ +/** \file + * + * This file contains special DoxyGen information for the generation of the main page and other special + * documentation pages. It is not a project source file. + */ + +/** \page Page_ProgrammingApps Programming an Application into a USB AVR + * + * Once you have built an application, you will need a way to program in the resulting ".HEX" file (and, if your + * application uses EEPROM variables with initial values, also a ".EEP" file) into your USB AVR. Normally, the + * reprogramming of an AVR device must be performed using a special piece of programming hardware, through one of the + * supported AVR programming protocols - ISP, HVSP, HVPP, JTAG or dW. This can be done through a custom programmer, + * a third party programmer, or an official Atmel AVR tool - for more information, see the Atmel.com website. + * + * Alternatively, you can use the bootloader. From the Atmel factory, each USB AVR comes preloaded with the Atmel + * DFU (Device Firmware Update) class bootloader, a small piece of AVR firmware which allows the remainder of the + * AVR to be programmed through a non-standard interface such as the serial USART port, SPI, or (in this case) USB. + * Bootloaders have the advantage of not requiring any special hardware for programming, and cannot usually be erased + * or broken without an external programming device. They have disadvantages however; they cannot change the fuses of + * the AVR (special configuration settings that control the operation of the chip itself) and a small portion of the + * AVR's FLASH program memory must be reserved to contain the bootloader firmware, and thus cannot be used by the + * loaded application. Atmel's DFU bootloader is either 4KB (for the smaller USB AVRs) or 8KB (for the larger USB AVRs). + * + * If you wish to use the DFU bootloader to program in your application, refer to your DFU programmer's documentation. + * Atmel provides a free utility called FLIP which is USB AVR compatible, and an open source (Linux compatible) + * alternative exists called "dfu-programmer". + */ \ No newline at end of file diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/SchedulerOverview.txt b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/SchedulerOverview.txt new file mode 100644 index 0000000000..b59821fe0b --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/SchedulerOverview.txt @@ -0,0 +1,35 @@ +/** \file + * + * This file contains special DoxyGen information for the generation of the main page and other special + * documentation pages. It is not a project source file. + */ + +/** \page Page_SchedulerOverview LUFA Scheduler Overview + * + * THE LUFA SCHEDULER IS NOW DEPRECATED AND WILL BE REMOVED IN A FUTURE RELEASE. EXISTING CODE SHOULD CONVERT + * TO STANDARD LOOPS AS SHOWN IN THE CURRENT LIBRARY DEMOS. + * + * + * The LUFA library comes with a small, basic round-robbin scheduler which allows for small "tasks" to be executed + * continuously in sequence, and enabled/disabled at runtime. Unlike a conventional, complex RTOS scheduler, the + * LUFA scheduler is very simple in design and operation and is essentially a loop conditionally executing a series + * of functions. + * + * Each LUFA scheduler task should be written similar to an ISR; it should execute quickly (so that no one task + * hogs the processor, preventing another from running before some sort of timeout is exceeded). Unlike normal RTOS + * tasks, each LUFA scheduler task is a regular function, and thus must be designed to be called, and designed to + * return to the calling scheduler function repeatedly. Data which must be preserved between task calls should be + * declared as global or (preferably) as a static local variable inside the task. + * + * The scheduler consists of a task list, listing all the tasks which can be executed by the scheduler. Once started, + * each task is then called one after another, unless the task is stopped by another running task or interrupt. + * + * + * If desired, the LUFA scheduler does not need to be used in a LUFA powered application. A more conventional + * approach to application design can be used, or a proper scheduling RTOS inserted in the place of the LUFA scheduler. + * In the case of the former the USB task must be run manually repeatedly to maintain USB communications, and in the + * case of the latter a proper RTOS task must be set up to do the same. + * + * + * For more information on the LUFA scheduler, see the Scheduler.h file documentation. + */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/SoftwareBootloaderJump.txt b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/SoftwareBootloaderJump.txt new file mode 100644 index 0000000000..6e7ea584ee --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/SoftwareBootloaderJump.txt @@ -0,0 +1,68 @@ +/** \file + * + * This file contains special DoxyGen information for the generation of the main page and other special + * documentation pages. It is not a project source file. + */ + +/** + * \page Page_SoftwareBootloaderStart Entering the Bootloader via Software + * + * A common requirement of many applications is the ability to jump to the programmed bootloader of a chip + * on demand, via the code's firmware (i.e. not as a result of any physical user interaction with the + * hardware). This might be required because the device does not have any physical user input, or simply + * just to streamline the device upgrade process on the host PC. + * + * The following C code snippet may be used to enter the bootloader upon request by the user application. + * By using the watchdog to physically reset the controller, it is ensured that all system hardware is + * completely reset to their defaults before the bootloader is run. This is important; since bootloaders + * are written to occupy a very limited space, they usually make assumptions about the register states based + * on the default values after a hard-reset of the chip. + * + * \code + * #include + * #include + * #include + * + * #include + * #include + * + * uint32_t Boot_Key ATTR_NO_INIT; + * + * #define MAGIC_BOOT_KEY 0xDC42ACCA + * #define BOOTLOADER_START_ADDRESS (FLASH_SIZE_BYTES - BOOTLOADER_SEC_SIZE_BYTES) + * + * void Bootloader_Jump_Check(void) ATTR_INIT_SECTION(3); + * void Bootloader_Jump_Check(void) + * { + * // If the reset source was the bootloader and the key is correct, clear it and jump to the bootloader + * if ((MCUSR & (1<FLASH_SIZE_BYTES and + * BOOTLOADER_SEC_SIZE_BYTES tokens should be replaced with the total flash size of the AVR + * in bytes, and the allocated size of the bootloader section for the target AVR. + * + */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/VIDAndPIDValues.txt b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/VIDAndPIDValues.txt new file mode 100644 index 0000000000..41ad560858 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/VIDAndPIDValues.txt @@ -0,0 +1,423 @@ +/** \file + * + * This file contains special DoxyGen information for the generation of the main page and other special + * documentation pages. It is not a project source file. + */ + +/** \page Page_VIDPID VID and PID values + * + * \section Sec_VIDPID_Allocations + * The LUFA library uses VID/PID combinations generously donated by Atmel. The following VID/PID combinations + * are used within the LUFA demos, and thus may be re-used by derivations of each demo. Free PID values may be + * used by future LUFA demo projects. + * + * These VID/PID values should not be used in commercial designs under any circumstances. Private projects + * may use the following values freely, but must accept any collisions due to other LUFA derived private projects + * sharing identical values. It is suggested that private projects using interfaces compatible with existing + * demos share the save VID/PID value. + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + * + *
+ * VID + * + * PID + * + * Usage + *
+ * 0x03EB + * + * 0x2040 + * + * Test VID/PID (See below) + *
+ * 0x03EB + * + * 0x2041 + * + * Mouse Demo Application + *
+ * 0x03EB + * + * 0x2042 + * + * Keyboard Demo Application + *
+ * 0x03EB + * + * 0x2043 + * + * Joystick Demo Application + *
+ * 0x03EB + * + * 0x2044 + * + * CDC Demo Application + *
+ * 0x03EB + * + * 0x2045 + * + * Mass Storage Demo Application + *
+ * 0x03EB + * + * 0x2046 + * + * Audio Output Demo Application + *
+ * 0x03EB + * + * 0x2047 + * + * Audio Input Demo Application + *
+ * 0x03EB + * + * 0x2048 + * + * MIDI Demo Application + *
+ * 0x03EB + * + * 0x2049 + * + * MagStripe Project + *
+ * 0x03EB + * + * 0x204A + * + * CDC Bootloader + *
+ * 0x03EB + * + * 0x204B + * + * USB to Serial Demo Application + *
+ * 0x03EB + * + * 0x204C + * + * RNDIS Demo Application + *
+ * 0x03EB + * + * 0x204D + * + * Combined Keyboard and Mouse Demo Application + *
+ * 0x03EB + * + * 0x204E + * + * Dual CDC Demo Application + *
+ * 0x03EB + * + * 0x204F + * + * Generic HID Demo Application + *
+ * 0x03EB + * + * 0x2060 + * + * Benito Programmer Project + *
+ * 0x03EB + * + * 0x2061 + * + * Combined Mass Storage and Keyboard Demo + *
+ * 0x03EB + * + * 0x2062 + * + * Combined CDC and Mouse Demo + *
+ * 0x03EB + * + * 0x2063 + * + * Mass Storage/HID Interface Datalogger Project + *
+ * 0x03EB + * + * 0x2064 + * + * Interfaceless Control-Only LUFA Devices + *
+ * 0x03EB + * + * 0x2065 + * + * Test and Measurement Demo + *
+ * 0x03EB + * + * 0x2066 + * + * Currently Unallocated + *
+ * 0x03EB + * + * 0x2067 + * + * Currently Unallocated + *
+ * 0x03EB + * + * 0x2068 + * + * Currently Unallocated + *
+ * 0x03EB + * + * 0x2069 + * + * Currently Unallocated + *
+ * 0x03EB + * + * 0x206A + * + * Currently Unallocated + *
+ * 0x03EB + * + * 0x206B + * + * Currently Unallocated + *
+ * 0x03EB + * + * 0x206C + * + * Currently Unallocated + *
+ * 0x03EB + * + * 0x206D + * + * Currently Unallocated + *
+ * 0x03EB + * + * 0x206E + * + * Currently Unallocated + *
+ * 0x03EB + * + * 0x206F + * + * Currently Unallocated + *
+ * + * \section Sec_Test_VIDPID The Test VID/PID Combination: + * For use in testing of LUFA powered devices during development only, by non-commercial entities. + * All devices must accept collisions on this VID/PID range (from other in-development LUFA devices) + * to be resolved by using a unique release number in the Device Descriptor. No devices using this + * VID/PID combination may be released to the general public. + */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/WhyUseLUFA.txt b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/WhyUseLUFA.txt new file mode 100644 index 0000000000..093a025e87 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/WhyUseLUFA.txt @@ -0,0 +1,46 @@ +/** \file + * + * This file contains special DoxyGen information for the generation of the main page and other special + * documentation pages. It is not a project source file. + */ + +/** + * \page Page_WhyUseLUFA Why Use LUFA? + * + * The LUFA Library has many advantages over implementing the code required to drive the USB AVRs directly. + * It is much more preferable to incorporate LUFA into your existing projects - or even make a new project + * using LUFA - than it is to start from scratch and use the USB AVR registers directly. Some of these reasons + * are: + * + * - Portability: + * The LUFA stack is designed to run (at some capacity) on the entire Atmel range of USB AVRs, regardless of the + * exact USB controller revision used. If you decide to implement your own USB stack, you will either need to + * code around the differences between each USB AVR controller's implementation between different chip models, or + * require your code to run on only one specific USB AVR model series. + * + * - Speed of Development: + * LUFA ships with a wide range of pre-made demos, bootloaders and projects for you to try, learn and extend. Each + * of these demos are tested (where possible) across as many USB AVRs and Operating Systems as possible, to ensure + * that they work under as many conditions as possible. In addition, there are inbuilt class drivers for several of + * the USB classes which you can make use of in your projects with minimal effort. + * + * - Maintainability: + * As LUFA takes care of much of the USB implementation, you can be left to focusing on your actual project's + * functionality, rather than being held back developing and debugging the USB stack code. Since LUFA uses clear APIs + * for USB development, your code will be more readable than if it had the low level USB stack code integrated into + * it directly. Updating the LUFA library is a simple folder-replacement and gives new features and bug fixes in + * seconds each time a new release is made. + * + * - Size: + * Not just requiring less code to make complex USB devices, LUFA (under most cases with the correct compile options) + * requires less FLASH space than Atmel's stack, meaning more space for the user application*. + * + * - Support: + * Since many people are now using LUFA in their own projects, you can take advantage of other's knowledge when you run + * into difficulties or need some advice. In addition, you can also email the library author to receive personalized + * support when you need it (subject to author's schedule). + * + * * Atmel Stack Mouse Device Demo 4292 bytes, LUFA Mouse Low Level Device Demo 3372 bytes, under identical build + * environments + */ + diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/WritingBoardDrivers.txt b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/WritingBoardDrivers.txt new file mode 100644 index 0000000000..c3371a93a5 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/WritingBoardDrivers.txt @@ -0,0 +1,26 @@ +/** \file + * + * This file contains special DoxyGen information for the generation of the main page and other special + * documentation pages. It is not a project source file. + */ + +/** \page Page_WritingBoardDrivers Writing LUFA Board Drivers + * + * LUFA ships with several basic pre-made board drivers, to control hardware present on the supported board + * hardware - such as Dataflash ICs, LEDs, Joysticks, or other hardware peripherals. When compiling an application + * which makes use of one or more board drivers located in LUFA/Drivers/Board, you must also indicate what board + * hardware you are using in your project makefile. This is done by defining the BOARD macro using the -D switch + * passed to the compiler, with a constant of BOARD_{Name}. For example -DBOARD=BOARD_USBKEY instructs the + * compiler to use the USBKEY board hardware drivers. + * + * If your application does not use *any* board level drivers, you can omit the definition of the BOARD macro. + * However, some users may wish to write their own custom board hardware drivers which are to remain compatible + * with the LUFA hardware API. To do this, the BOARD macro should be defined to the value BOARD_USER. This indicates + * that the board level drivers should be located in a folder named "Board" located inside the application's folder. + * + * When used, the driver stub files located in the DriverStubs folder should be copied to the user Board directory, + * and fleshed out to include the values and code needed to control the custom board hardware. Once done, the existing + * LUFA board level APIs (accessed in the regular LUFA/Drivers/Board/ folder) will redirect to the user board drivers, + * maintaining code compatibility and allowing for a different board to be selected through the project makefile with + * no code changes. + */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Scheduler/Scheduler.c b/Tools/ArduPPM/ATMega32U2/LUFA/Scheduler/Scheduler.c new file mode 100644 index 0000000000..7113ee322b --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Scheduler/Scheduler.c @@ -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. +*/ + +#include "Scheduler.h" + +volatile SchedulerDelayCounter_t Scheduler_TickCounter; +volatile uint8_t Scheduler_TotalTasks; + +bool Scheduler_HasDelayElapsed(const uint16_t Delay, + SchedulerDelayCounter_t* const DelayCounter) +{ + SchedulerDelayCounter_t CurrentTickValue_LCL; + SchedulerDelayCounter_t DelayCounter_LCL; + + ATOMIC_BLOCK(ATOMIC_RESTORESTATE) + { + CurrentTickValue_LCL = Scheduler_TickCounter; + } + + DelayCounter_LCL = *DelayCounter; + + if (CurrentTickValue_LCL >= DelayCounter_LCL) + { + if ((CurrentTickValue_LCL - DelayCounter_LCL) >= Delay) + { + *DelayCounter = CurrentTickValue_LCL; + return true; + } + } + else + { + if (((MAX_DELAYCTR_COUNT - DelayCounter_LCL) + CurrentTickValue_LCL) >= Delay) + { + *DelayCounter = CurrentTickValue_LCL; + return true; + } + } + + return false; +} + +void Scheduler_SetTaskMode(const TaskPtr_t Task, + const bool TaskStatus) +{ + TaskEntry_t* CurrTask = &Scheduler_TaskList[0]; + + while (CurrTask != &Scheduler_TaskList[Scheduler_TotalTasks]) + { + if (CurrTask->Task == Task) + { + CurrTask->TaskStatus = TaskStatus; + break; + } + + CurrTask++; + } +} + +void Scheduler_SetGroupTaskMode(const uint8_t GroupID, + const bool TaskStatus) +{ + TaskEntry_t* CurrTask = &Scheduler_TaskList[0]; + + while (CurrTask != &Scheduler_TaskList[Scheduler_TotalTasks]) + { + if (CurrTask->GroupID == GroupID) + CurrTask->TaskStatus = TaskStatus; + + CurrTask++; + } +} diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Scheduler/Scheduler.h b/Tools/ArduPPM/ATMega32U2/LUFA/Scheduler/Scheduler.h new file mode 100644 index 0000000000..673a933f8e --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Scheduler/Scheduler.h @@ -0,0 +1,294 @@ +/* + 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 Simple round-robbin pseudo-task scheduler. + * + * Simple round-robbin cooperative scheduler for use in basic projects where non real-time tasks need + * to be executed. Each task is executed in sequence, and can be enabled or disabled individually or as a group. + * + * \deprecated This module is deprecated and will be removed in a future library release. + */ + +/** @defgroup Group_Scheduler Simple Task Scheduler - LUFA/Scheduler/Scheduler.h + * + * \deprecated This module is deprecated and will be removed in a future library release. + * + * \section Sec_Dependencies Module Source Dependencies + * The following files must be built with any user project that uses this module: + * - LUFA/Scheduler/Scheduler.c (Makefile source module name: LUFA_SRC_SCHEDULER) + * + * \section Module Description + * Simple round-robbin cooperative scheduler for use in basic projects where non real-time tasks need + * to be executed. Each task is executed in sequence, and can be enabled or disabled individually or as a group. + * + * For a task to yield it must return, thus each task should have persistent data marked with the static attribute. + * + * Usage Example: + * \code + * #include + * + * TASK(MyTask1); + * TASK(MyTask2); + * + * TASK_LIST + * { + * { .Task = MyTask1, .TaskStatus = TASK_RUN, .GroupID = 1 }, + * { .Task = MyTask2, .TaskStatus = TASK_RUN, .GroupID = 1 }, + * } + * + * int main(void) + * { + * Scheduler_Start(); + * } + * + * TASK(MyTask1) + * { + * // Implementation Here + * } + * + * TASK(MyTask2) + * { + * // Implementation Here + * } + * \endcode + * + * @{ + */ + +#ifndef __SCHEDULER_H__ +#define __SCHEDULER_H__ + + /* Includes: */ + #include + #include + + #include + + #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: */ + /** Creates a new scheduler task body or prototype. Should be used in the form: + * \code + * TASK(TaskName); // Prototype + * + * TASK(TaskName) + * { + * // Task body + * } + * \endcode + */ + #define TASK(name) void name (void) + + /** Defines a task list array, containing one or more task entries of the type TaskEntry_t. Each task list + * should be encased in curly braces and ended with a comma. + * + * Usage Example: + * \code + * TASK_LIST + * { + * { .Task = MyTask1, .TaskStatus = TASK_RUN, .GroupID = 1 }, + * // More task entries here + * } + * \endcode + */ + #define TASK_LIST TaskEntry_t Scheduler_TaskList[] = + + /** Constant, giving the maximum delay in scheduler ticks which can be stored in a variable of type + * \ref SchedulerDelayCounter_t. + */ + #define TASK_MAX_DELAY (MAX_DELAYCTR_COUNT - 1) + + /** Task status mode constant, for passing to \ref Scheduler_SetTaskMode() or \ref Scheduler_SetGroupTaskMode(). */ + #define TASK_RUN true + + /** Task status mode constant, for passing to \ref Scheduler_SetTaskMode() or \ref Scheduler_SetGroupTaskMode(). */ + #define TASK_STOP false + + /* Pseudo-Function Macros: */ + #if defined(__DOXYGEN__) + /** Starts the scheduler in its infinite loop, executing running tasks. This should be placed at the end + * of the user application's main() function, as it can never return to the calling function. + */ + void Scheduler_Start(void); + + /** Initialises the scheduler so that the scheduler functions can be called before the scheduler itself + * is started. This must be executed before any scheduler function calls other than Scheduler_Start(), + * and can be omitted if no such functions could be called before the scheduler is started. + */ + void Scheduler_Init(void); + #else + #define Scheduler_Start() Scheduler_GoSchedule(TOTAL_TASKS); + #define Scheduler_Init() Scheduler_InitScheduler(TOTAL_TASKS); + #endif + + /* Type Defines: */ + /** Type define for a pointer to a scheduler task. */ + typedef void (*TaskPtr_t)(void); + + /** Type define for a variable which can hold a tick delay value for the scheduler up to the maximum delay + * possible. + */ + typedef uint16_t SchedulerDelayCounter_t; + + /** \brief Scheduler Task List Entry Structure. + * + * Structure for holding a single task's information in the scheduler task list. + */ + typedef struct + { + TaskPtr_t Task; /**< Pointer to the task to execute. */ + bool TaskStatus; /**< Status of the task (either TASK_RUN or TASK_STOP). */ + uint8_t GroupID; /**< Group ID of the task so that its status can be changed as a group. */ + } TaskEntry_t; + + /* Global Variables: */ + /** Task entry list, containing the scheduler tasks, task statuses and group IDs. Each entry is of type + * TaskEntry_t and can be manipulated as desired, although it is preferential that the proper Scheduler + * functions should be used instead of direct manipulation. + */ + exter TaskEntry_t Scheduler_TaskList[]; + + /** Contains the total number of tasks in the task list, irrespective of if the task's status is set to + * \ref TASK_RUN or \ref TASK_STOP. + * + * \note This value should be treated as read-only, and never altered in user-code. + */ + extern volatile uint8_t Scheduler_TotalTasks; + + /** Contains the current scheduler tick count, for use with the delay functions. If the delay functions + * are used in the user code, this should be incremented each tick period so that the delays can be + * calculated. + */ + extern volatile SchedulerDelayCounter_t Scheduler_TickCounter; + + /* Inline Functions: */ + /** Resets the delay counter value to the current tick count. This should be called to reset the period + * for a delay in a task which is dependant on the current tick value. + * + * \param[out] DelayCounter Counter which is storing the starting tick count for a given delay. + */ + static inline void Scheduler_ResetDelay(SchedulerDelayCounter_t* const DelayCounter) + ATTR_NON_NULL_PTR_ARG(1) ATTR_ALWAYS_INLINE; + static inline void Scheduler_ResetDelay(SchedulerDelayCounter_t* const DelayCounter) + { + ATOMIC_BLOCK(ATOMIC_RESTORESTATE) + { + *DelayCounter = Scheduler_TickCounter; + } + } + + /* Function Prototypes: */ + /** Determines if the given tick delay has elapsed, based on the given delay period and tick counter value. + * + * \param[in] Delay The delay to test for, measured in ticks. + * \param[in] DelayCounter The counter which is storing the starting tick value for the delay. + * + * \return Boolean true if the delay has elapsed, false otherwise. + * + * Usage Example: + * \code + * static SchedulerDelayCounter_t DelayCounter = 10000; // Force immediate run on start-up + * + * // Task runs every 10000 ticks, 10 seconds for this demo + * if (Scheduler_HasDelayElapsed(10000, &DelayCounter)) + * { + * // Code to execute after delay interval elapsed here + * } + * \endcode + */ + bool Scheduler_HasDelayElapsed(const uint16_t Delay, + SchedulerDelayCounter_t* const DelayCounter) + ATTR_WARN_UNUSED_RESULT ATTR_NON_NULL_PTR_ARG(2); + + /** Sets the task mode for a given task. + * + * \param[in] Task Name of the task whose status is to be changed. + * \param[in] TaskStatus New task status for the task (\ref TASK_RUN or \ref TASK_STOP). + */ + void Scheduler_SetTaskMode(const TaskPtr_t Task, + const bool TaskStatus); + + /** Sets the task mode for a given task group ID, allowing for an entire group of tasks to have their + * statuses changed at once. + * + * \param[in] GroupID Value of the task group ID whose status is to be changed. + * \param[in] TaskStatus New task status for tasks in the specified group (\ref TASK_RUN or \ref TASK_STOP). + */ + void Scheduler_SetGroupTaskMode(const uint8_t GroupID, + const bool TaskStatus); + + /* Private Interface - For use in library only: */ + #if !defined(__DOXYGEN__) + /* Macros: */ + #define TOTAL_TASKS (sizeof(Scheduler_TaskList) / sizeof(TaskEntry_t)) + #define MAX_DELAYCTR_COUNT 0xFFFF + + /* Inline Functions: */ + static inline void Scheduler_InitScheduler(const uint8_t TotalTasks) ATTR_ALWAYS_INLINE; + static inline void Scheduler_InitScheduler(const uint8_t TotalTasks) + { + Scheduler_TotalTasks = TotalTasks; + } + + static inline void Scheduler_GoSchedule(const uint8_t TotalTasks) ATTR_NO_RETURN ATTR_ALWAYS_INLINE ATTR_DEPRECATED; + static inline void Scheduler_GoSchedule(const uint8_t TotalTasks) + { + Scheduler_InitScheduler(TotalTasks); + + for (;;) + { + TaskEntry_t* CurrTask = &Scheduler_TaskList[0]; + + while (CurrTask != &Scheduler_TaskList[TotalTasks]) + { + if (CurrTask->TaskStatus == TASK_RUN) + CurrTask->Task(); + + CurrTask++; + } + } + } + #endif + + /* Disable C linkage for C++ Compilers: */ + #if defined(__cplusplus) + } + #endif + +#endif + +/** @} */ diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/Version.h b/Tools/ArduPPM/ATMega32U2/LUFA/Version.h new file mode 100644 index 0000000000..ed8af11f47 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/Version.h @@ -0,0 +1,51 @@ +/* + 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 LUFA library version constants. + * + * Version constants for informational purposes and version-specific macro creation. This header file contains the + * current LUFA version number in several forms, for use in the user-application (for example, for printing out + * whilst debugging, or for testing for version compatibility). + */ + +#ifndef __LUFA_VERSION_H__ +#define __LUFA_VERSION_H__ + + /* Public Interface - May be used in end-application: */ + /* Macros: */ + /** Indicates the version number of the library, as an integer. */ + #define LUFA_VERSION_INTEGER 0x100807 + + /** Indicates the version number of the library, as a string. */ + #define LUFA_VERSION_STRING "100807" + +#endif diff --git a/Tools/ArduPPM/ATMega32U2/LUFA/makefile b/Tools/ArduPPM/ATMega32U2/LUFA/makefile new file mode 100644 index 0000000000..0ce283edbb --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/LUFA/makefile @@ -0,0 +1,75 @@ +# +# LUFA Library +# Copyright (C) Dean Camera, 2010. +# +# dean [at] fourwalledcubicle [dot] com +# www.fourwalledcubicle.com +# + +# Makefile for the LUFA library itself. This can be used to generate the library documentation. + + +# Check to see if the LUFA_PATH variable has not been set (the makefile is not being included from a project makefile) +ifeq ($(origin LUFA_PATH), undefined) + LUFA_ROOT_PATH = . +else + LUFA_ROOT_PATH = $(LUFA_PATH)/LUFA +endif + +# Define module source file lists +LUFA_SRC_USB = $(LUFA_ROOT_PATH)/Drivers/USB/LowLevel/Device.c \ + $(LUFA_ROOT_PATH)/Drivers/USB/LowLevel/Endpoint.c \ + $(LUFA_ROOT_PATH)/Drivers/USB/LowLevel/Host.c \ + $(LUFA_ROOT_PATH)/Drivers/USB/LowLevel/Pipe.c \ + $(LUFA_ROOT_PATH)/Drivers/USB/LowLevel/USBController.c \ + $(LUFA_ROOT_PATH)/Drivers/USB/LowLevel/USBInterrupt.c \ + $(LUFA_ROOT_PATH)/Drivers/USB/HighLevel/ConfigDescriptor.c \ + $(LUFA_ROOT_PATH)/Drivers/USB/HighLevel/DeviceStandardReq.c \ + $(LUFA_ROOT_PATH)/Drivers/USB/HighLevel/Events.c \ + $(LUFA_ROOT_PATH)/Drivers/USB/HighLevel/HostStandardReq.c \ + $(LUFA_ROOT_PATH)/Drivers/USB/HighLevel/USBTask.c \ + $(LUFA_ROOT_PATH)/Drivers/USB/Class/Host/HIDParser.c +LUFA_SRC_USBCLASS = $(LUFA_ROOT_PATH)/Drivers/USB/Class/Device/Audio.c \ + $(LUFA_ROOT_PATH)/Drivers/USB/Class/Device/CDC.c \ + $(LUFA_ROOT_PATH)/Drivers/USB/Class/Device/HID.c \ + $(LUFA_ROOT_PATH)/Drivers/USB/Class/Device/MassStorage.c \ + $(LUFA_ROOT_PATH)/Drivers/USB/Class/Device/MIDI.c \ + $(LUFA_ROOT_PATH)/Drivers/USB/Class/Device/RNDIS.c \ + $(LUFA_ROOT_PATH)/Drivers/USB/Class/Host/CDC.c \ + $(LUFA_ROOT_PATH)/Drivers/USB/Class/Host/HID.c \ + $(LUFA_ROOT_PATH)/Drivers/USB/Class/Host/MassStorage.c \ + $(LUFA_ROOT_PATH)/Drivers/USB/Class/Host/MIDI.c \ + $(LUFA_ROOT_PATH)/Drivers/USB/Class/Host/Printer.c \ + $(LUFA_ROOT_PATH)/Drivers/USB/Class/Host/RNDIS.c \ + $(LUFA_ROOT_PATH)/Drivers/USB/Class/Host/StillImage.c +LUFA_SRC_TEMPERATURE = $(LUFA_ROOT_PATH)/Drivers/Board/Temperature.c +LUFA_SRC_SERIAL = $(LUFA_ROOT_PATH)/Drivers/Peripheral/Serial.c +LUFA_SRC_SERIALSTREAM = $(LUFA_ROOT_PATH)/Drivers/Peripheral/SerialStream.c +LUFA_SRC_TWI = $(LUFA_ROOT_PATH)/Drivers/Peripheral/TWI.c +LUFA_SRC_SCHEDULER = $(LUFA_ROOT_PATH)/Scheduler/Scheduler.c + + +# Check to see if the LUFA_PATH variable has not been set (the makefile is not being included from a project makefile) +ifeq ($(origin LUFA_PATH), undefined) + LUFA_SRC_ALL_FILES = $(LUFA_SRC_USB) $(LUFA_SRC_USBCLASS) \ + $(LUFA_SRC_TEMPERATURE) $(LUFA_SRC_SERIAL) \ + $(LUFA_SRC_SERIALSTREAM) $(LUFA_SRC_TWI) \ + $(LUFA_SRC_SCHEDULER) + + all: + + clean: + rm -f $(LUFA_SRC_ALL_FILES:%.c=%.o) + + clean_list: + + doxygen: + @echo Generating Library Documentation... + ( cat Doxygen.conf ; echo "PROJECT_NUMBER=`grep LUFA_VERSION_STRING Version.h | cut -d'"' -f2`" ) | doxygen - + @echo Documentation Generation Complete. + + clean_doxygen: + rm -rf Documentation + + .PHONY: all clean clean_list doxygen clean_doxygen +endif \ No newline at end of file diff --git a/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/Arduino-usbserial.c b/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/Arduino-usbserial.c new file mode 100644 index 0000000000..bac01b76f5 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/Arduino-usbserial.c @@ -0,0 +1,256 @@ +/* + 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 Arduino-usbserial project. This file contains the main tasks of + * the project and is responsible for the initial application hardware configuration. + */ + +#include "Arduino-usbserial.h" +#include "..\..\..\Libraries\ppm_encoder.h" + + +/** Circular buffer to hold data from the host before it is sent to the device via the serial port. */ +RingBuff_t USBtoUSART_Buffer; + +/** Circular buffer to hold data from the serial port before it is sent to the host. */ +RingBuff_t USARTtoUSB_Buffer; + +/** 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; + +/** LUFA CDC Class driver interface configuration and state information. This structure is + * passed to all CDC Class driver functions, so that multiple instances of the same class + * within a device can be differentiated from one another. + */ +USB_ClassInfo_CDC_Device_t VirtualSerial_CDC_Interface = + { + .Config = + { + .ControlInterfaceNumber = 0, + + .DataINEndpointNumber = CDC_TX_EPNUM, + .DataINEndpointSize = CDC_TXRX_EPSIZE, + .DataINEndpointDoubleBank = false, + + .DataOUTEndpointNumber = CDC_RX_EPNUM, + .DataOUTEndpointSize = CDC_TXRX_EPSIZE, + .DataOUTEndpointDoubleBank = false, + + .NotificationEndpointNumber = CDC_NOTIFICATION_EPNUM, + .NotificationEndpointSize = CDC_NOTIFICATION_EPSIZE, + .NotificationEndpointDoubleBank = false, + }, + }; + +/** Main program entry point. This routine contains the overall program flow, including initial + * setup of all components and the main program loop. + */ +int main(void) +{ + // Start PPM Encoder + ppm_encoder_init(); + + + // Unmodified Arduino code from here + // -------------------------------------------- + + SetupHardware(); + + RingBuffer_InitBuffer(&USBtoUSART_Buffer); + RingBuffer_InitBuffer(&USARTtoUSB_Buffer); + + sei(); + + + for (;;) + { + + // Only try to read in bytes from the CDC interface if the transmit buffer is not full + if (!(RingBuffer_IsFull(&USBtoUSART_Buffer))) + { + int16_t ReceivedByte = CDC_Device_ReceiveByte(&VirtualSerial_CDC_Interface); + + // Read bytes from the USB OUT endpoint into the USART transmit buffer + if (!(ReceivedByte < 0)) + RingBuffer_Insert(&USBtoUSART_Buffer, ReceivedByte); + } + + // Check if the UART receive buffer flush timer has expired or the buffer is nearly full + RingBuff_Count_t BufferCount = RingBuffer_GetCount(&USARTtoUSB_Buffer); + if ((TIFR0 & (1 << TOV0)) || (BufferCount > BUFFER_NEARLY_FULL)) + { + TIFR0 |= (1 << TOV0); + + if (USARTtoUSB_Buffer.Count) { + LEDs_TurnOnLEDs(LEDMASK_TX); + PulseMSRemaining.TxLEDPulse = TX_RX_LED_PULSE_MS; + } + + // Read bytes from the USART receive buffer into the USB IN endpoint + while (BufferCount--) + CDC_Device_SendByte(&VirtualSerial_CDC_Interface, RingBuffer_Remove(&USARTtoUSB_Buffer)); + + // 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); + } + + // Load the next byte from the USART transmit buffer into the USART + if (!(RingBuffer_IsEmpty(&USBtoUSART_Buffer))) { + Serial_TxByte(RingBuffer_Remove(&USBtoUSART_Buffer)); + + LEDs_TurnOnLEDs(LEDMASK_RX); + PulseMSRemaining.RxLEDPulse = TX_RX_LED_PULSE_MS; + } + + CDC_Device_USBTask(&VirtualSerial_CDC_Interface); + USB_USBTask(); + } + +} + +/** Configures the board hardware and chip peripherals for the demo's functionality. */ +void SetupHardware(void) +{ + /* Disable watchdog if enabled by bootloader/fuses */ + + // Watchdog used by PPM Encoder to set failsafe values + //MCUSR &= ~(1 << WDRF); + //wdt_disable(); + + /* Hardware Initialization */ + Serial_Init(9600, false); + LEDs_Init(); + USB_Init(); + + /* Start the flush timer so that overflows occur rapidly to push received bytes to the USB interface */ + TCCR0B = (1 << CS02); + + /* Pull target /RESET line high */ + AVR_RESET_LINE_PORT |= AVR_RESET_LINE_MASK; + AVR_RESET_LINE_DDR |= AVR_RESET_LINE_MASK; +} + +/** Event handler for the library USB Configuration Changed event. */ +void EVENT_USB_Device_ConfigurationChanged(void) +{ + CDC_Device_ConfigureEndpoints(&VirtualSerial_CDC_Interface); +} + +/** Event handler for the library USB Unhandled Control Request event. */ +void EVENT_USB_Device_UnhandledControlRequest(void) +{ + CDC_Device_ProcessControlRequest(&VirtualSerial_CDC_Interface); +} + +/** Event handler for the CDC Class driver Line Encoding Changed event. + * + * \param[in] CDCInterfaceInfo Pointer to the CDC class interface configuration structure being referenced + */ +void EVENT_CDC_Device_LineEncodingChanged(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo) +{ + uint8_t ConfigMask = 0; + + switch (CDCInterfaceInfo->State.LineEncoding.ParityType) + { + case CDC_PARITY_Odd: + ConfigMask = ((1 << UPM11) | (1 << UPM10)); + break; + case CDC_PARITY_Even: + ConfigMask = (1 << UPM11); + break; + } + + if (CDCInterfaceInfo->State.LineEncoding.CharFormat == CDC_LINEENCODING_TwoStopBits) + ConfigMask |= (1 << USBS1); + + switch (CDCInterfaceInfo->State.LineEncoding.DataBits) + { + case 6: + ConfigMask |= (1 << UCSZ10); + break; + case 7: + ConfigMask |= (1 << UCSZ11); + break; + case 8: + ConfigMask |= ((1 << UCSZ11) | (1 << UCSZ10)); + break; + } + + /* Must turn off USART before reconfiguring it, otherwise incorrect operation may occur */ + UCSR1B = 0; + UCSR1A = 0; + UCSR1C = 0; + + /* Special case 57600 baud for compatibility with the ATmega328 bootloader. */ + UBRR1 = (CDCInterfaceInfo->State.LineEncoding.BaudRateBPS == 57600) + ? SERIAL_UBBRVAL(CDCInterfaceInfo->State.LineEncoding.BaudRateBPS) + : SERIAL_2X_UBBRVAL(CDCInterfaceInfo->State.LineEncoding.BaudRateBPS); + + UCSR1C = ConfigMask; + UCSR1A = (CDCInterfaceInfo->State.LineEncoding.BaudRateBPS == 57600) ? 0 : (1 << U2X1); + UCSR1B = ((1 << RXCIE1) | (1 << TXEN1) | (1 << RXEN1)); +} + +/** ISR to manage the reception of data from the serial port, placing received bytes into a circular buffer + * for later transmission to the host. + */ +ISR(USART1_RX_vect, ISR_BLOCK) +{ + uint8_t ReceivedByte = UDR1; + + if (USB_DeviceState == DEVICE_STATE_Configured) + RingBuffer_Insert(&USARTtoUSB_Buffer, ReceivedByte); +} + +/** Event handler for the CDC Class driver Host-to-Device Line Encoding Changed event. + * + * \param[in] CDCInterfaceInfo Pointer to the CDC class interface configuration structure being referenced + */ +void EVENT_CDC_Device_ControLineStateChanged(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo) +{ + bool CurrentDTRState = (CDCInterfaceInfo->State.ControlLineStates.HostToDevice & CDC_CONTROL_LINE_OUT_DTR); + + if (CurrentDTRState) + AVR_RESET_LINE_PORT &= ~AVR_RESET_LINE_MASK; + else + AVR_RESET_LINE_PORT |= AVR_RESET_LINE_MASK; +} diff --git a/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/Arduino-usbserial.h b/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/Arduino-usbserial.h new file mode 100644 index 0000000000..2183512c89 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/Arduino-usbserial.h @@ -0,0 +1,79 @@ +/* + 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-usbserial.c. + */ + +#ifndef _ARDUINO_USBSERIAL_H_ +#define _ARDUINO_USBSERIAL_H_ + + /* Includes: */ + #include + #include + #include + #include + + #include "Descriptors.h" + + #include "Lib/LightweightRingBuff.h" + + #include + #include + #include + #include + #include + + /* 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) + + /* Function Prototypes: */ + void SetupHardware(void); + + void EVENT_USB_Device_Connect(void); + void EVENT_USB_Device_Disconnect(void); + void EVENT_USB_Device_ConfigurationChanged(void); + void EVENT_USB_Device_UnhandledControlRequest(void); + + void EVENT_CDC_Device_LineEncodingChanged(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo); + void EVENT_CDC_Device_ControLineStateChanged(USB_ClassInfo_CDC_Device_t* const CDCInterfaceInfo); + +#endif /* _ARDUINO_USBSERIAL_H_ */ diff --git a/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/Board/LEDs.h b/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/Board/LEDs.h new file mode 100644 index 0000000000..41465f22dd --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/Board/LEDs.h @@ -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 + +/* 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 diff --git a/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/Descriptors.c b/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/Descriptors.c new file mode 100644 index 0000000000..ddab0c9ca8 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/Descriptors.c @@ -0,0 +1,286 @@ +/* + 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" + +/* On some devices, there is a factory set internal serial number which can be automatically sent to the host as + * the device's serial number when the Device Descriptor's .SerialNumStrIndex entry is set to USE_INTERNAL_SERIAL. + * This allows the host to track a device across insertions on different ports, allowing them to retain allocated + * resources like COM port numbers and drivers. On demos using this feature, give a warning on unsupported devices + * so that the user can supply their own serial number descriptor instead or remove the USE_INTERNAL_SERIAL value + * from the Device Descriptor (forcing the host to generate a serial number for each device from the VID, PID and + * port location). + */ +#if (USE_INTERNAL_SERIAL == NO_DESCRIPTOR) + #warning USE_INTERNAL_SERIAL is not available on this AVR - please manually construct a device serial descriptor. +#endif + +/** 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 PROGMEM DeviceDescriptor = +{ + .Header = {.Size = sizeof(USB_Descriptor_Device_t), .Type = DTYPE_Device}, + + .USBSpecification = VERSION_BCD(01.10), + .Class = 0x02, + .SubClass = 0x00, + .Protocol = 0x00, + + .Endpoint0Size = FIXED_CONTROL_ENDPOINT_SIZE, + +#if (ARDUINO_MODEL_PID == ARDUINO_MEGA2560_PID) + + .VendorID = 0x2341, // Arduino + .ProductID = 0x0010, // Arduino Meha 2560 + +#else + + .VendorID = 0x03EB, // Atmel + .ProductID = 0x204B, // LUFA USB to Serial Demo Application + +#endif + + .ReleaseNumber = 0x0001, + + .ManufacturerStrIndex = 0x01, + .ProductStrIndex = 0x02, + .SerialNumStrIndex = USE_INTERNAL_SERIAL, + + .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 PROGMEM ConfigurationDescriptor = +{ + .Config = + { + .Header = {.Size = sizeof(USB_Descriptor_Configuration_Header_t), .Type = DTYPE_Configuration}, + + .TotalConfigurationSize = sizeof(USB_Descriptor_Configuration_t), + .TotalInterfaces = 2, + + .ConfigurationNumber = 1, + .ConfigurationStrIndex = NO_DESCRIPTOR, + + .ConfigAttributes = (USB_CONFIG_ATTR_BUSPOWERED | USB_CONFIG_ATTR_SELFPOWERED), + + .MaxPowerConsumption = USB_CONFIG_POWER_MA(100) + }, + + .CDC_CCI_Interface = + { + .Header = {.Size = sizeof(USB_Descriptor_Interface_t), .Type = DTYPE_Interface}, + + .InterfaceNumber = 0, + .AlternateSetting = 0, + + .TotalEndpoints = 1, + + .Class = 0x02, + .SubClass = 0x02, + .Protocol = 0x01, + + .InterfaceStrIndex = NO_DESCRIPTOR + }, + + .CDC_Functional_IntHeader = + { + .Header = {.Size = sizeof(CDC_FUNCTIONAL_DESCRIPTOR(2)), .Type = 0x24}, + .SubType = 0x00, + + .Data = {0x01, 0x10} + }, + + .CDC_Functional_AbstractControlManagement = + { + .Header = {.Size = sizeof(CDC_FUNCTIONAL_DESCRIPTOR(1)), .Type = 0x24}, + .SubType = 0x02, + + .Data = {0x06} + }, + + .CDC_Functional_Union = + { + .Header = {.Size = sizeof(CDC_FUNCTIONAL_DESCRIPTOR(2)), .Type = 0x24}, + .SubType = 0x06, + + .Data = {0x00, 0x01} + }, + + .CDC_NotificationEndpoint = + { + .Header = {.Size = sizeof(USB_Descriptor_Endpoint_t), .Type = DTYPE_Endpoint}, + + .EndpointAddress = (ENDPOINT_DESCRIPTOR_DIR_IN | CDC_NOTIFICATION_EPNUM), + .Attributes = (EP_TYPE_INTERRUPT | ENDPOINT_ATTR_NO_SYNC | ENDPOINT_USAGE_DATA), + .EndpointSize = CDC_NOTIFICATION_EPSIZE, + .PollingIntervalMS = 0xFF + }, + + .CDC_DCI_Interface = + { + .Header = {.Size = sizeof(USB_Descriptor_Interface_t), .Type = DTYPE_Interface}, + + .InterfaceNumber = 1, + .AlternateSetting = 0, + + .TotalEndpoints = 2, + + .Class = 0x0A, + .SubClass = 0x00, + .Protocol = 0x00, + + .InterfaceStrIndex = NO_DESCRIPTOR + }, + + .CDC_DataOutEndpoint = + { + .Header = {.Size = sizeof(USB_Descriptor_Endpoint_t), .Type = DTYPE_Endpoint}, + + .EndpointAddress = (ENDPOINT_DESCRIPTOR_DIR_OUT | CDC_RX_EPNUM), + .Attributes = (EP_TYPE_BULK | ENDPOINT_ATTR_NO_SYNC | ENDPOINT_USAGE_DATA), + .EndpointSize = CDC_TXRX_EPSIZE, + .PollingIntervalMS = 0x01 + }, + + .CDC_DataInEndpoint = + { + .Header = {.Size = sizeof(USB_Descriptor_Endpoint_t), .Type = DTYPE_Endpoint}, + + .EndpointAddress = (ENDPOINT_DESCRIPTOR_DIR_IN | CDC_TX_EPNUM), + .Attributes = (EP_TYPE_BULK | ENDPOINT_ATTR_NO_SYNC | ENDPOINT_USAGE_DATA), + .EndpointSize = CDC_TXRX_EPSIZE, + .PollingIntervalMS = 0x01 + } +}; + +/** 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 PROGMEM LanguageString = +{ + .Header = {.Size = USB_STRING_LEN(1), .Type = DTYPE_String}, + + .UnicodeString = {LANGUAGE_ID_ENG} +}; + +/** Manufacturer descriptor string. This is a Unicode string containing the manufacturer'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 PROGMEM ManufacturerString = +{ + .Header = {.Size = USB_STRING_LEN(24), .Type = DTYPE_String}, + + .UnicodeString = L"Arduino (www.arduino.cc)" +}; + +/** 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 PROGMEM ProductString = +{ + #if (ARDUINO_MODEL_PID == ARDUINO_UNO_PID) + .Header = {.Size = USB_STRING_LEN(11), .Type = DTYPE_String}, + + .UnicodeString = L"Arduino Uno" + #elif (ARDUINO_MODEL_PID == ARDUINO_MEGA2560_PID) + .Header = {.Size = USB_STRING_LEN(17), .Type = DTYPE_String}, + + .UnicodeString = L"Arduino Mega 2560" + #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 = (void*)&DeviceDescriptor; + Size = sizeof(USB_Descriptor_Device_t); + break; + case DTYPE_Configuration: + Address = (void*)&ConfigurationDescriptor; + Size = sizeof(USB_Descriptor_Configuration_t); + break; + case DTYPE_String: + switch (DescriptorNumber) + { + case 0x00: + Address = (void*)&LanguageString; + Size = pgm_read_byte(&LanguageString.Header.Size); + break; + case 0x01: + Address = (void*)&ManufacturerString; + Size = pgm_read_byte(&ManufacturerString.Header.Size); + break; + case 0x02: + Address = (void*)&ProductString; + Size = pgm_read_byte(&ProductString.Header.Size); + break; + } + + break; + } + + *DescriptorAddress = Address; + return Size; +} diff --git a/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/Descriptors.h b/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/Descriptors.h new file mode 100644 index 0000000000..2bce3d78ef --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/Descriptors.h @@ -0,0 +1,88 @@ +/* + 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 + + #include + #include + + /* Product-specific definitions: */ + #define ARDUINO_UNO_PID 0x0001 + #define ARDUINO_MEGA2560_PID 0x0010 + + /* Macros: */ + /** Endpoint number of the CDC device-to-host notification IN endpoint. */ + #define CDC_NOTIFICATION_EPNUM 2 + + /** Endpoint number of the CDC device-to-host data IN endpoint. */ + #define CDC_TX_EPNUM 3 + + /** Endpoint number of the CDC host-to-device data OUT endpoint. */ + #define CDC_RX_EPNUM 4 + + /** Size in bytes of the CDC device-to-host notification IN endpoint. */ + #define CDC_NOTIFICATION_EPSIZE 8 + + /** Size in bytes of the CDC data IN and OUT endpoints. */ + #define CDC_TXRX_EPSIZE 64 + + /* Type Defines: */ + /** 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 CDC_CCI_Interface; + CDC_FUNCTIONAL_DESCRIPTOR(2) CDC_Functional_IntHeader; + CDC_FUNCTIONAL_DESCRIPTOR(1) CDC_Functional_AbstractControlManagement; + CDC_FUNCTIONAL_DESCRIPTOR(2) CDC_Functional_Union; + USB_Descriptor_Endpoint_t CDC_NotificationEndpoint; + USB_Descriptor_Interface_t CDC_DCI_Interface; + USB_Descriptor_Endpoint_t CDC_DataOutEndpoint; + USB_Descriptor_Endpoint_t CDC_DataInEndpoint; + } 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 diff --git a/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/Lib/LightweightRingBuff.h b/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/Lib/LightweightRingBuff.h new file mode 100644 index 0000000000..5a9a125c18 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/Lib/LightweightRingBuff.h @@ -0,0 +1,197 @@ +/* + 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 + * + * Ultra lightweight ring buffer, for fast insertion/deletion. + */ + +#ifndef _ULW_RING_BUFF_H_ +#define _ULW_RING_BUFF_H_ + + /* Includes: */ + #include + + #include + #include + + /* Defines: */ + /** Size of each ring buffer, in data elements - must be between 1 and 255. */ + #define BUFFER_SIZE 128 + + /** Maximum number of data elements to buffer before forcing a flush. + * Must be less than BUFFER_SIZE + */ + #define BUFFER_NEARLY_FULL 96 + + /** Type of data to store into the buffer. */ + #define RingBuff_Data_t uint8_t + + /** Datatype which may be used to store the count of data stored in a buffer, retrieved + * via a call to \ref RingBuffer_GetCount(). + */ + #if (BUFFER_SIZE <= 0xFF) + #define RingBuff_Count_t uint8_t + #else + #define RingBuff_Count_t uint16_t + #endif + + /* Type Defines: */ + /** Type define for a new ring buffer object. Buffers should be initialized via a call to + * \ref RingBuffer_InitBuffer() before use. + */ + typedef struct + { + RingBuff_Data_t Buffer[BUFFER_SIZE]; /**< Internal ring buffer data, referenced by the buffer pointers. */ + RingBuff_Data_t* In; /**< Current storage location in the circular buffer */ + RingBuff_Data_t* Out; /**< Current retrieval location in the circular buffer */ + RingBuff_Count_t Count; + } RingBuff_t; + + /* Inline Functions: */ + /** Initializes a ring buffer ready for use. Buffers must be initialized via this function + * before any operations are called upon them. Already initialized buffers may be reset + * by re-initializing them using this function. + * + * \param[out] Buffer Pointer to a ring buffer structure to initialize + */ + static inline void RingBuffer_InitBuffer(RingBuff_t* const Buffer) + { + ATOMIC_BLOCK(ATOMIC_RESTORESTATE) + { + Buffer->In = Buffer->Buffer; + Buffer->Out = Buffer->Buffer; + } + } + + /** Retrieves the minimum number of bytes stored in a particular buffer. This value is computed + * by entering an atomic lock on the buffer while the IN and OUT locations are fetched, so that + * the buffer cannot be modified while the computation takes place. This value should be cached + * when reading out the contents of the buffer, so that as small a time as possible is spent + * in an atomic lock. + * + * \note The value returned by this function is guaranteed to only be the minimum number of bytes + * stored in the given buffer; this value may change as other threads write new data and so + * the returned number should be used only to determine how many successive reads may safely + * be performed on the buffer. + * + * \param[in] Buffer Pointer to a ring buffer structure whose count is to be computed + */ + static inline RingBuff_Count_t RingBuffer_GetCount(RingBuff_t* const Buffer) + { + RingBuff_Count_t Count; + + ATOMIC_BLOCK(ATOMIC_RESTORESTATE) + { + Count = Buffer->Count; + } + + return Count; + } + + /** Atomically determines if the specified ring buffer contains any free space. This should + * be tested before storing data to the buffer, to ensure that no data is lost due to a + * buffer overrun. + * + * \param[in,out] Buffer Pointer to a ring buffer structure to insert into + * + * \return Boolean true if the buffer contains no free space, false otherwise + */ + static inline bool RingBuffer_IsFull(RingBuff_t* const Buffer) + { + return (RingBuffer_GetCount(Buffer) == BUFFER_SIZE); + } + + /** Atomically determines if the specified ring buffer contains any data. This should + * be tested before removing data from the buffer, to ensure that the buffer does not + * underflow. + * + * If the data is to be removed in a loop, store the total number of bytes stored in the + * buffer (via a call to the \ref RingBuffer_GetCount() function) in a temporary variable + * to reduce the time spent in atomicity locks. + * + * \param[in,out] Buffer Pointer to a ring buffer structure to insert into + * + * \return Boolean true if the buffer contains no free space, false otherwise + */ + static inline bool RingBuffer_IsEmpty(RingBuff_t* const Buffer) + { + return (RingBuffer_GetCount(Buffer) == 0); + } + + /** Inserts an element into the ring buffer. + * + * \note Only one execution thread (main program thread or an ISR) may insert into a single buffer + * otherwise data corruption may occur. Insertion and removal may occur from different execution + * threads. + * + * \param[in,out] Buffer Pointer to a ring buffer structure to insert into + * \param[in] Data Data element to insert into the buffer + */ + static inline void RingBuffer_Insert(RingBuff_t* const Buffer, + const RingBuff_Data_t Data) + { + *Buffer->In = Data; + + if (++Buffer->In == &Buffer->Buffer[BUFFER_SIZE]) + Buffer->In = Buffer->Buffer; + + ATOMIC_BLOCK(ATOMIC_RESTORESTATE) + { + Buffer->Count++; + } + } + + /** Removes an element from the ring buffer. + * + * \note Only one execution thread (main program thread or an ISR) may remove from a single buffer + * otherwise data corruption may occur. Insertion and removal may occur from different execution + * threads. + * + * \param[in,out] Buffer Pointer to a ring buffer structure to retrieve from + * + * \return Next data element stored in the buffer + */ + static inline RingBuff_Data_t RingBuffer_Remove(RingBuff_t* const Buffer) + { + RingBuff_Data_t Data = *Buffer->Out; + + if (++Buffer->Out == &Buffer->Buffer[BUFFER_SIZE]) + Buffer->Out = Buffer->Buffer; + + ATOMIC_BLOCK(ATOMIC_RESTORESTATE) + { + Buffer->Count--; + } + + return Data; + } + +#endif diff --git a/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/makefile b/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/makefile new file mode 100644 index 0000000000..0460f0ea65 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/makefile @@ -0,0 +1,779 @@ +# Hey Emacs, this is a -*- makefile -*- +#---------------------------------------------------------------------------- +# WinAVR Makefile Template written by Eric B. Weddington, Jrg 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 dfu = Download the hex file to the device, using dfu-programmer (must +# have dfu-programmer installed). +# +# make flip = Download the hex file to the device, using Atmel FLIP (must +# have Atmel FLIP installed). +# +# make dfu-ee = Download the eeprom file to the device, using dfu-programmer +# (must have dfu-programmer installed). +# +# make flip-ee = Download the eeprom file to the device, using Atmel FLIP +# (must have Atmel FLIP installed). +# +# 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(s) +# Since the ATMEGA8U2 part is not directly supported by the current +# versions of either avrdude or dfu-programmer, we specify a dummy +# part; AT90USB82 which is close enough in memory size and organization + +#MCU = atmega16u2 +MCU = atmega32u2 + +MCU_AVRDUDE = $(MCU) +MCU_DFU = $(MCU) + +# Specify the Arduino model using the assigned PID. This is used by Descriptors.c +# to set PID and product descriptor string +# 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 + + +# 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) + + +# Output format. (can be srec, ihex, binary) +FORMAT = ihex + + +# Target file name (without extension). +TARGET = Arduino-usbserial + + +# 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 +LUFA_OPTS = -D USB_DEVICE_ONLY +LUFA_OPTS += -D FIXED_CONTROL_ENDPOINT_SIZE=8 +LUFA_OPTS += -D FIXED_NUM_CONFIGURATIONS=1 +LUFA_OPTS += -D USE_FLASH_DESCRIPTORS +LUFA_OPTS += -D INTERRUPT_CONTROL_ENDPOINT +LUFA_OPTS += -D DEVICE_STATE_AS_GPIOR=0 +LUFA_OPTS += -D USE_STATIC_OPTIONS="(USB_DEVICE_OPT_FULLSPEED | USB_OPT_REG_ENABLED | USB_OPT_AUTO_PLL)" + + +# 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) \ + $(LUFA_SRC_USBCLASS) \ + $(LUFA_PATH)/LUFA/Drivers/USB/LowLevel/Device.c \ + $(LUFA_PATH)/LUFA/Drivers/USB/LowLevel/Endpoint.c \ + $(LUFA_PATH)/LUFA/Drivers/USB/HighLevel/HostStandardReq.c \ + $(LUFA_PATH)/LUFA/Drivers/USB/LowLevel/Host.c \ + $(LUFA_PATH)/LUFA/Drivers/USB/LowLevel/Pipe.c \ + $(LUFA_PATH)/LUFA/Drivers/USB/LowLevel/USBController.c \ + $(LUFA_PATH)/LUFA/Drivers/USB/HighLevel/Events.c \ + $(LUFA_PATH)/LUFA/Drivers/USB/LowLevel/USBInterrupt.c \ + $(LUFA_PATH)/LUFA/Drivers/USB/HighLevel/USBTask.c \ + $(LUFA_PATH)/LUFA/Drivers/USB/HighLevel/DeviceStandardReq.c \ + $(LUFA_PATH)/LUFA/Drivers/USB/HighLevel/ConfigDescriptor.c \ + $(LUFA_PATH)/LUFA/Drivers/USB/Class/Device/CDC.c \ + $(LUFA_PATH)/LUFA/Drivers/USB/Class/Host/CDC.c + + +# 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=gnu99 + + +# Place -D or -U options here for C sources +CDEFS = -DF_CPU=$(F_CPU)UL +CDEFS += -DF_CLOCK=$(F_CLOCK)UL +CDEFS += -DARDUINO_MODEL_PID=$(ARDUINO_MODEL_PID) +CDEFS += -DBOARD=BOARD_$(BOARD) +CDEFS += $(LUFA_OPTS) +CDEFS += -DAVR_RESET_LINE_PORT="PORTD" +CDEFS += -DAVR_RESET_LINE_DDR="DDRD" +CDEFS += -DAVR_RESET_LINE_MASK="(1 << 7)" +CDEFS += -DTX_RX_LED_PULSE_MS=3 +CDEFS += -DPING_PONG_LED_PULSE_MS=100 + +# Place -D or -U options here for ASM sources +ADEFS = -DF_CPU=$(F_CPU) +ADEFS += -DF_CLOCK=$(F_CLOCK)UL +ADEFS += -DBOARD=BOARD_$(BOARD) +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) +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 +CFLAGS += -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,--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) ---------------- + +# 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 +# to submit bug reports. +#AVRDUDE_VERBOSE = -v -v + +AVRDUDE_FORCE = -F + +AVRDUDE_FLAGS = -p $(MCU_AVRDUDE) -P $(AVRDUDE_PORT) -c $(AVRDUDE_PROGRAMMER) +AVRDUDE_FLAGS += $(AVRDUDE_NO_VERIFY) +AVRDUDE_FLAGS += $(AVRDUDE_VERBOSE) +AVRDUDE_FLAGS += $(AVRDUDE_ERASE_COUNTER) +AVRDUDE_FLAGS += $(AVRDUDE_FORCE) + + + +#---------------- 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 checkinvalidevents showliboptions showtarget sizeafter end +all: begin gccversion sizebefore build showliboptions showtarget sizeafter end + +# Change the build target to build a HEX file or a library. +build: elf hex eep lss sym asm +#build: lib + + +elf: $(TARGET).elf +hex: $(TARGET).hex +eep: $(TARGET).eep +lss: $(TARGET).lss +sym: $(TARGET).sym +asm: $(TARGET).s +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 + +#$(LUFA_PATH)/LUFA/LUFA_Events.lst: +# @make -C $(LUFA_PATH)/LUFA/ LUFA_Events.lst + +#checkinvalidevents: $(LUFA_PATH)/LUFA/LUFA_Events.lst +# @echo +# @echo Checking for invalid events... +# @$(shell) avr-nm $(OBJ) | sed -n -e 's/^.*EVENT_/EVENT_/p' | \ +# grep -F -v --file=$(LUFA_PATH)/LUFA/LUFA_Events.lst > InvalidEvents.tmp || true +# @sed -n -e 's/^/ WARNING - INVALID EVENT NAME: /p' InvalidEvents.tmp +# @if test -s InvalidEvents.tmp; then exit 1; fi + +showliboptions: + @echo + @echo ---- Compile Time Library Options ---- + @for i in $(LUFA_OPTS:-D%=%); do \ + echo $$i; \ + done + @echo -------------------------------------- + +showtarget: + @echo + @echo --------- Target Information --------- + @echo AVR Model: $(MCU) + @echo Board: $(BOARD) + @echo Clock: $(F_CPU)Hz CPU, $(F_CLOCK)Hz Master + @echo -------------------------------------- + + +# Display compiler version information. +gccversion : + @$(CC) --version + + +# Program the device. +program: $(TARGET).hex $(TARGET).eep + $(AVRDUDE) $(AVRDUDE_FLAGS) $(AVRDUDE_WRITE_FLASH) $(AVRDUDE_WRITE_EEPROM) + +flip: $(TARGET).hex + batchisp -hardware usb -device $(MCU_DFU) -operation erase f + batchisp -hardware usb -device $(MCU_DFU) -operation loadbuffer $(TARGET).hex program + batchisp -hardware usb -device $(MCU_DFU) -operation start reset 0 + +dfu: $(TARGET).hex + dfu-programmer $(MCU_DFU) erase + dfu-programmer $(MCU_DFU) flash --debug 1 $(TARGET).hex + dfu-programmer $(MCU_DFU) reset + + +flip-ee: $(TARGET).hex $(TARGET).eep + $(COPY) $(TARGET).eep $(TARGET)eep.hex + batchisp -hardware usb -device $(MCU_DFU) -operation memory EEPROM erase + batchisp -hardware usb -device $(MCU_DFU) -operation memory EEPROM loadbuffer $(TARGET)eep.hex program + batchisp -hardware usb -device $(MCU_DFU) -operation start reset 0 + $(REMOVE) $(TARGET)eep.hex + +dfu-ee: $(TARGET).hex $(TARGET).eep + dfu-programmer $(MCU_DFU) flash-eeprom --debug 1 --suppress-bootloader-mem $(TARGET).eep + dfu-programmer $(MCU_DFU) reset + + +# 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 clean_binary end + +clean_binary: + $(REMOVE) $(TARGET).hex + +clean_list: + @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 dfu flip flip-ee dfu-ee \ +debug gdb-config diff --git a/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/ppm_encoder.txt b/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/ppm_encoder.txt new file mode 100644 index 0000000000..53a7cede0a --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/ppm_encoder.txt @@ -0,0 +1,26 @@ +Arduino USB-To-Serial & PPM_Encoder (atmega16u2 & atmega32u2). + +Instructions: +Make sure you have the latest avr-gcc / winavr installed. +Unzip the project and go to the < ./Projects/arduino-usbserial/ > directory. + +To compile the project type (makefile is set for atmega16u2): + +>make clean +>make + +Uploading firmware to atmega32u2 using the DFU bootloader (see ../arduino-usbserial/readme.txt for instructions). + +Source: +The PPM encoder code is located in the "ppm_encoder.h" file. + +What it does. +The original Arduino USB to serial code should run and operate just like before. +In addition there are now 8 servo inputs using (PB0:7) PCINT interrupts, and a PPM output (PC6) using PWM - OC1A for hardware driven pin toggle and timing. + +What needs to be tested: +Timing and Arduino compatibility. +Make sure that the USB-To-Serial works as it should at all baud rates, with PPM Encoder running in the background. +Also look for any timing issues with PPM Encoder when the USB-To-Serial is busy transferring data. + +Happy bug hunting! \ No newline at end of file diff --git a/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/readme.txt b/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/readme.txt new file mode 100644 index 0000000000..7d58a73821 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/readme.txt @@ -0,0 +1,14 @@ +To setup the project and upload the Arduino usbserial application firmware to an ATMEGA32U2 using the Arduino USB DFU bootloader: +1. unpack the source into LUFA's Projects directory +2. set ARDUINO_MODEL_PID in the makefile as appropriate +3. do "make clean; make" +4. put the 32U2 into USB DFU mode: +4.a. assert and hold the 32U2's RESET line +4.b. assert and hold the 32U2's HWB line +4.c. release the 32U2's RESET line +4.d. release the 32U2's HWB line +5. confirm that the board enumerates as "ATmega32u2" +6. do "make dfu" (OS X or Linux - dfu-programmer must be installed first) or "make flip" (Windows - Flip must be installed first) + +Check that the board enumerates as "Arduino Mega 2560". +Test by uploading a new Arduino sketch from the Arduino IDE. diff --git a/Tools/ArduPPM/ATMega32U2/ppm_encoder.txt b/Tools/ArduPPM/ATMega32U2/ppm_encoder.txt new file mode 100644 index 0000000000..c656dbe81f --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/ppm_encoder.txt @@ -0,0 +1,19 @@ +Arduino USB-To-Serial & PPM_Encoder (atmega16u2 & atmega32u2). + +Instructions: +Make sure you have the latest avr-gcc / winavr installed. +Unzip the project and go to the < ./Projects/arduino-usbserial/ > directory. + +To compile the project type (makefile is set for atmega32u2): + +>make clean +>make + +Uploading firmware to atmega32u2 using the DFU bootloader (see ../arduino-usbserial/readme.txt for instructions). + +Source: +The PPM encoder code is located in the "ppm_encoder.h" file. + +What it does. +The original Arduino USB to serial code should run and operate just like before. +In addition there are now 8 servo inputs using (PB0:7) PCINT interrupts, and a PPM output (PC6) using PWM - OC1A for hardware driven pin toggle and timing. diff --git a/Tools/ArduPPM/ATMega32U2/readme.txt b/Tools/ArduPPM/ATMega32U2/readme.txt new file mode 100644 index 0000000000..44cceaf071 --- /dev/null +++ b/Tools/ArduPPM/ATMega32U2/readme.txt @@ -0,0 +1,52 @@ + + _ _ _ ___ _ + | | | | | __/ \ + | |_| U | _| o | - The Lightweight USB + |___|___|_||_n_| Framework for AVRs + ========================================= + Written by Dean Camera + dean [at] fourwalledcubicle [dot] com + + http://www.fourwalledcubicle.com/LUFA.php + ========================================= + + LUFA is donation supported. To support LUFA, + please donate at http://www.fourwalledcubicle.com. + + For Commercial Licensing information, see + http://fourwalledcubicle.com/PurchaseLUFA.php + + +This package contains the complete LUFA library, demos, user-submitted +projects and bootloaders for use with compatible microcontroller models. +LUFA is a simple to use, lightweight framework which sits atop the hardware +USB controller in specific AVR microcontroller models, and allows for the +quick and easy creation of complex USB devices and hosts. + +To get started, you will need to install the "Doxygen" documentation +generation tool. If you use Linux, this can be installed via the "doxygen" +package in your chosen package management tool - under Ubuntu, this can be +achieved by running the following command in the terminal: + + sudo apt-get install doxygen + +Other package managers and distributions will have similar methods to +install Doxygen. In Windows, you can download a prebuilt installer for +Doxygen from its website, www.doxygen.org. + +Once installed, you can then use the Doxygen tool to generate the library +documentation from the command line or terminal of your operating system. To +do this, open your terminal or command line to the root directory of the +LUFA package, and type the following command: + + make doxygen + +Which will recursively generate documentation for all elements in the +library - the core, plus all demos, projects and bootloaders. Generated +documentation will then be available by opening the file "index.html" of the +created Documentation/html/ subdirectories inside each project folder. + +The documentation for the library itself (but not the documentation for the +individual demos, projects or bootloaders) is also available as a separate +package from the project webpage for convenience if Doxygen cannot be +installed. diff --git a/Tools/ArduPPM/Libraries/PPM_Encoder.h b/Tools/ArduPPM/Libraries/PPM_Encoder.h new file mode 100644 index 0000000000..3a6089b0be --- /dev/null +++ b/Tools/ArduPPM/Libraries/PPM_Encoder.h @@ -0,0 +1,718 @@ +// Warning : Untested - Please use version 2.2.63 for field use. +// ------------------------------------------------------------- +// PPM ENCODER V2.2.65 (25-09-2011) +// ------------------------------------------------------------- +// Improved servo to ppm for ArduPilot MEGA v1.x (ATmega328p) +// and PhoneDrone (ATmega32u2) + +// By: John Arne Birkeland - 2011 +// APM v1.x adaptation and "difficult" receiver testing by Olivier ADLER +// ------------------------------------------------------------- +// Changelog: + +// 01-08-2011 +// V2.2.3 - Changed back to BLOCKING interrupts. +// Assembly PPM compare interrupt can be switch back to non-blocking, but not recommended. +// V2.2.3 - Implemented 0.5us cut filter to remove servo input capture jitter. + +// 04-08-2011 +// V2.2.4 - Implemented PPM passtrough funtion. +// Shorting channel 2&3 enabled ppm passtrough on channel 1. + +// 04-08-2011 +// V2.2.5 - Implemented simple average filter to smooth servo input capture jitter. +// Takes fewer clocks to execute and has better performance then cut filter. + +// 05-08-2011 +// V2.2.51 - Minor bug fixes. + +// 06-08-2011 +// V2.2.6 - PPM passtrough failsafe implemented. +// The PPM generator will be activated and output failsafe values while ppm passtrough signal is missing. + +// 01-09-2011 +// V2.2.61 - Temporary MUX pin always high patch for APM beta board + +// 22-09-2011 +// V2.2.62 - ATmegaXXU2 USB connection status pin (PC2) for APM UART MUX selection (removed temporary high patch) +// - Removed assembly optimized PPM generator (not usable for production release) + +// 23-09-2011 +// V2.2.63 - Average filter disabled + +// 24-09-2011 +// V2.2.64 - Added distincts Power on / Failsafe PPM values +// - Changed CH5 (mode selection) PPM Power on and Failsafe values to 1555 (Flight mode 4) +// - Added brownout detection : Failsafe values are copied after a brownout reset instead of power on values + +// 25-09-2011 +// V2.2.65 - Implemented PPM output delay until input signal is detected (PWM and PPM pass-trough mode) +// - Changed brownout detection and FailSafe handling to work with XXU2 chips +// - Minor variable and define naming changes to enhance readability + +// ------------------------------------------------------------- + +#ifndef _PPM_ENCODER_H_ +#define _PPM_ENCODER_H_ + +#include + +// ------------------------------------------------------------- + +#include +#include +#include + +// ------------------------------------------------------------- +// SERVO INPUT FILTERS +// ------------------------------------------------------------- +// Using both filters is not recommended and may reduce servo input resolution + +// #define _AVERAGE_FILTER_ // Average filter to smooth servo input capture jitter +// #define _JITTER_FILTER_ // Cut filter to remove 0,5us servo input capture jitter +// ------------------------------------------------------------- + +#ifndef F_CPU +#define F_CPU 16000000UL +#endif + +#ifndef true +#define true 1 +#endif + +#ifndef false +#define false 0 +#endif + +#ifndef bool +#define bool _Bool +#endif + +// ------------------------------------------------------------- +// SERVO INPUT MODE - !EXPERIMENTAL! +// ------------------------------------------------------------- + +#define JUMPER_SELECT_MODE 0 // Default - PPM passtrough mode selected if channel 2&3 shorted. Normal servo input (pwm) if not shorted. +#define SERVO_PWM_MODE 1 // Normal 8 channel servo (pwm) input +#define PPM_PASSTROUGH_MODE 2 // PPM signal passtrough on channel 1 +#define JETI_MODE 3 // JETI on channel 1 (reserved but not implemented yet) +#define SPEKTRUM_MODE 4 // Spektrum satelitte on channel 1 (reserved but not implemented yet) + +// Servo input mode (jumper (default), pwm, ppm, jeti or spektrum) +volatile uint8_t servo_input_mode = JUMPER_SELECT_MODE; +// ------------------------------------------------------------- + +// Number of Timer1 ticks in one microsecond +#define ONE_US F_CPU / 8 / 1000 / 1000 + +// 400us PPM pre pulse +#define PPM_PRE_PULSE ONE_US * 400 + +// ------------------------------------------------------------- +// SERVO LIMIT VALUES +// ------------------------------------------------------------- + +// Servo minimum position +#define PPM_SERVO_MIN ONE_US * 900 - PPM_PRE_PULSE + +// Servo center position +#define PPM_SERVO_CENTER ONE_US * 1500 - PPM_PRE_PULSE + +// Servo maximum position +#define PPM_SERVO_MAX ONE_US * 2100 - PPM_PRE_PULSE + +// Throttle default at power on +#define PPM_THROTTLE_DEFAULT ONE_US * 1100 - PPM_PRE_PULSE + +// Throttle during failsafe +#define PPM_THROTTLE_FAILSAFE ONE_US * 900 - PPM_PRE_PULSE + +// CH5 power on values (mode selection channel) +#define PPM_CH5_MODE_4 ONE_US * 1555 - PPM_PRE_PULSE + +// ------------------------------------------------------------- + +// Number of servo input channels +#define SERVO_CHANNELS 8 + +// PPM period 18.5ms - 26.5ms (54hz - 37Hz) +#define PPM_PERIOD ONE_US * ( 22500 - ( 8 * 1500 ) ) + +// Size of ppm[..] data array ( servo channels * 2 + 2) +#define PPM_ARRAY_MAX 18 + + +// Data array for storing ppm (8 channels) pulse widths. +volatile uint16_t ppm[ PPM_ARRAY_MAX ] = +{ + PPM_PRE_PULSE, + PPM_SERVO_CENTER, // Channel 1 + PPM_PRE_PULSE, + PPM_SERVO_CENTER, // Channel 2 + PPM_PRE_PULSE, + PPM_THROTTLE_DEFAULT, // Channel 3 (throttle) + PPM_PRE_PULSE, + PPM_SERVO_CENTER, // Channel 4 + PPM_PRE_PULSE, + PPM_CH5_MODE_4, // Channel 5 + PPM_PRE_PULSE, + PPM_SERVO_CENTER, // Channel 6 + PPM_PRE_PULSE, + PPM_SERVO_CENTER, // Channel 7 + PPM_PRE_PULSE, + PPM_SERVO_CENTER, // Channel 8 + PPM_PRE_PULSE, + PPM_PERIOD +}; + +// ------------------------------------------------------------- +// SERVO POWER ON VALUES +// ------------------------------------------------------------- +/* +const uint16_t power_on_ppm[ PPM_ARRAY_MAX ] = +{ + PPM_PRE_PULSE, + PPM_SERVO_CENTER, // Channel 1 + PPM_PRE_PULSE, + PPM_SERVO_CENTER, // Channel 2 + PPM_PRE_PULSE, + PPM_THROTTLE_DEFAULT, // Channel 3 (throttle) + PPM_PRE_PULSE, + PPM_SERVO_CENTER, // Channel 4 + PPM_PRE_PULSE, + PPM_CH5_MODE_4, // Channel 5 + PPM_PRE_PULSE, + PPM_SERVO_CENTER, // Channel 6 + PPM_PRE_PULSE, + PPM_SERVO_CENTER, // Channel 7 + PPM_PRE_PULSE, + PPM_SERVO_CENTER, // Channel 8 + PPM_PRE_PULSE, + PPM_PERIOD +}; +*/ +// ------------------------------------------------------------- + +// ------------------------------------------------------------- +// SERVO FAILSAFE VALUES +// ------------------------------------------------------------- +const uint16_t failsafe_ppm[ PPM_ARRAY_MAX ] = +{ + PPM_PRE_PULSE, + PPM_SERVO_CENTER, // Channel 1 + PPM_PRE_PULSE, + PPM_SERVO_CENTER, // Channel 2 + PPM_PRE_PULSE, + PPM_THROTTLE_FAILSAFE, // Channel 3 (throttle) + PPM_PRE_PULSE, + PPM_SERVO_CENTER, // Channel 4 + PPM_PRE_PULSE, + PPM_CH5_MODE_4, // Channel 5 + PPM_PRE_PULSE, + PPM_SERVO_CENTER, // Channel 6 + PPM_PRE_PULSE, + PPM_SERVO_CENTER, // Channel 7 + PPM_PRE_PULSE, + PPM_SERVO_CENTER, // Channel 8 + PPM_PRE_PULSE, + PPM_PERIOD +}; +// ------------------------------------------------------------- + +// AVR parameters for PhoneDrone PPM Encoder and future boards also using ATmega16-32u2 +#if defined (__AVR_ATmega16U2__) || defined (__AVR_ATmega32U2__) + +#define SERVO_DDR DDRB +#define SERVO_PORT PORTB +#define SERVO_INPUT PINB +#define SERVO_INT_VECTOR PCINT0_vect +#define SERVO_INT_MASK PCMSK0 +#define SERVO_INT_CLEAR_FLAG PCIF0 +#define SERVO_INT_ENABLE PCIE0 +#define SERVO_TIMER_CNT TCNT1 + +#define PPM_DDR DDRC +#define PPM_PORT PORTC +#define PPM_OUTPUT_PIN PC6 +#define PPM_INT_VECTOR TIMER1_COMPA_vect +#define PPM_COMPARE OCR1A +#define PPM_COMPARE_FLAG COM1A0 +#define PPM_COMPARE_ENABLE OCIE1A + +#define USB_DDR DDRC +#define USB_PORT PORTC +#define USB_PIN PC2 + +// USB connected event +void EVENT_USB_Device_Connect(void) +{ + // Toggle USB pin high if USB is connected + USB_PORT |= (1 << USB_PIN); +} + +// USB dosconnect event +void EVENT_USB_Device_Disconnect(void) +{ + // toggle USB pin low if USB is disconnected + USB_PORT &= ~(1 << USB_PIN); +} + +// AVR parameters for ArduPilot MEGA v1.4 PPM Encoder (ATmega328P) +#elif defined (__AVR_ATmega328P__) || defined (__AVR_ATmega328__) + +#define SERVO_DDR DDRD +#define SERVO_PORT PORTD +#define SERVO_INPUT PIND +#define SERVO_INT_VECTOR PCINT2_vect +#define SERVO_INT_MASK PCMSK2 +#define SERVO_INT_CLEAR_FLAG PCIF2 +#define SERVO_INT_ENABLE PCIE2 +#define SERVO_TIMER_CNT TCNT1 + +#define PPM_DDR DDRB +#define PPM_PORT PORTB +#define PPM_OUTPUT_PIN PB2 +#define PPM_INT_VECTOR TIMER1_COMPB_vect +#define PPM_COMPARE OCR1B +#define PPM_COMPARE_FLAG COM1B0 +#define PPM_COMPARE_ENABLE OCIE1B + +#else +#error NO SUPPORTED DEVICE FOUND! (ATmega16u2 / ATmega32u2 / ATmega328p) +#endif + +// Used to indicate invalid SERVO input signals +volatile uint8_t servo_input_errors = 0; + +// Used to indicate missing SERVO input signals +volatile bool servo_input_missing = true; + +// Used to indicate if PPM generator is active +volatile bool ppm_generator_active = false; + +// Used to indicate a brownout restart +volatile bool brownout_reset = false; + +// ------------------------------------------------------------------------------ +// PPM GENERATOR START - TOGGLE ON COMPARE INTERRUPT ENABLE +// ------------------------------------------------------------------------------ +void ppm_start( void ) +{ + // Prevent reenabling an already active PPM generator + if( ppm_generator_active ) return; + + // Store interrupt status and register flags + uint8_t SREG_tmp = SREG; + + // Stop interrupts + cli(); + + + // Make sure initial output state is low + PPM_PORT &= ~(1 << PPM_OUTPUT_PIN); + + // Wait for output pin to settle + //_delay_us( 1 ); + + // Set initial compare toggle to maximum (32ms) to give other parts of the system time to start + SERVO_TIMER_CNT = 0; + PPM_COMPARE = 0xFFFF; + + // Set toggle on compare output + TCCR1A = (1 << PPM_COMPARE_FLAG); + + // Set TIMER1 8x prescaler + TCCR1B = ( 1 << CS11 ); + + // Enable output compare interrupt + TIMSK1 |= (1 << PPM_COMPARE_ENABLE); + + // Indicate that PPM generator is active + ppm_generator_active = true; + + // Restore interrupt status and register flags + SREG = SREG_tmp; +} + +// ------------------------------------------------------------------------------ +// PPM GENERATOR STOP - TOGGLE ON COMPARE INTERRUPT DISABLE +// ------------------------------------------------------------------------------ +void ppm_stop( void ) +{ + // Store interrupt status and register flags + uint8_t SREG_tmp = SREG; + + // Stop interrupts + cli(); + + // Disable output compare interrupt + TIMSK1 &= ~(1 << PPM_COMPARE_ENABLE); + + // Reset TIMER1 registers + TCCR1A = 0; + TCCR1B = 0; + + // Indicate that PPM generator is not active + ppm_generator_active = false; + + // Restore interrupt status and register flags + SREG = SREG_tmp; +} + +// ------------------------------------------------------------------------------ +// Watchdog Interrupt (interrupt only mode, no reset) +// ------------------------------------------------------------------------------ +ISR( WDT_vect ) // If watchdog is triggered then enable missing signal flag and copy power on or failsafe positions +{ + // Use failsafe values if PPM generator is active or if chip has been reset from a brown-out + if ( ppm_generator_active || brownout_reset ) + { + // Copy failsafe values to ppm[..] + for ( uint8_t i = 0; i < PPM_ARRAY_MAX; i++ ) + { + ppm[ i ] = failsafe_ppm[ i ]; + } + } + + // If we are in PPM passtrough mode and a input signal has been detected, or if chip has been reset from a brown_out then start the PPM generator. + if( ( servo_input_mode == PPM_PASSTROUGH_MODE && servo_input_missing == false ) || brownout_reset ) + { + // Start PPM generator + ppm_start(); + brownout_reset = false; + } + + // Set missing receiver signal flag + servo_input_missing = true; + + // Reset servo input error flag + servo_input_errors = 0; +} +// ------------------------------------------------------------------------------ + + +// ------------------------------------------------------------------------------ +// SERVO/PPM INPUT - PIN CHANGE INTERRUPT +// ------------------------------------------------------------------------------ +ISR( SERVO_INT_VECTOR ) +{ + // Servo pulse start timing + static uint16_t servo_start[ SERVO_CHANNELS ] = { 0, 0, 0, 0, 0, 0, 0, 0 }; + + // Servo input pin storage + static uint8_t servo_pins_old = 0; + + // Used to store current servo input pins + uint8_t servo_pins; + + // Read current servo pulse change time + uint16_t servo_time = SERVO_TIMER_CNT; + + // ------------------------------------------------------------------------------ + // PPM passtrough mode ( signal passtrough from channel 1 to ppm output pin) + // ------------------------------------------------------------------------------ + if( servo_input_mode == PPM_PASSTROUGH_MODE ) + { + // Has watchdog timer failsafe started PPM generator? If so we need to stop it. + if( ppm_generator_active ) + { + // Stop PPM generator + ppm_stop(); + } + + // PPM (channel 1) input pin is high + if( SERVO_INPUT & 1 ) + { + // Set PPM output pin high + PPM_PORT |= (1 << PPM_OUTPUT_PIN); + } + // PPM (channel 1) input pin is low + else + { + // Set PPM output pin low + PPM_PORT &= ~(1 << PPM_OUTPUT_PIN); + } + + // Reset Watchdog Timer + wdt_reset(); + + // Set servo input missing flag false to indicate that we have received servo input signals + servo_input_missing = false; + + // Leave interrupt + return; + } + + // ------------------------------------------------------------------------------ + // SERVO PWM MODE + // ------------------------------------------------------------------------------ +CHECK_PINS_START: // Start of servo input check + + // Store current servo input pins + servo_pins = SERVO_INPUT; + + // Calculate servo input pin change mask + uint8_t servo_change = servo_pins ^ servo_pins_old; + + // Set initial servo pin and channel + uint8_t servo_pin = 1; + uint8_t servo_channel = 0; + +CHECK_PINS_LOOP: // Input servo pin check loop + + // Check for pin change on current servo channel + if( servo_change & servo_pin ) + { + // High (raising edge) + if( servo_pins & servo_pin ) + { + servo_start[ servo_channel ] = servo_time; + } + else + { + + // Get servo pulse width + uint16_t servo_width = servo_time - servo_start[ servo_channel ] - PPM_PRE_PULSE; + + // Check that servo pulse signal is valid before sending to ppm encoder + if( servo_width > PPM_SERVO_MAX ) goto CHECK_PINS_ERROR; + if( servo_width < PPM_SERVO_MIN ) goto CHECK_PINS_ERROR; + + // Calculate servo channel position in ppm[..] + uint8_t _ppm_channel = ( servo_channel << 1 ) + 1; + + #ifdef _AVERAGE_FILTER_ + // Average filter to smooth input jitter + servo_width += ppm[ _ppm_channel ]; + servo_width >>= 1; + #endif + + #ifdef _JITTER_FILTER_ + // 0.5us cut filter to remove input jitter + int16_t ppm_tmp = ppm[ _ppm_channel ] - servo_width; + if( ppm_tmp == 1 ) goto CHECK_PINS_NEXT; + if( ppm_tmp == -1 ) goto CHECK_PINS_NEXT; + #endif + + // Update ppm[..] + ppm[ _ppm_channel ] = servo_width; + } + } + +CHECK_PINS_NEXT: + + // Select next servo pin + servo_pin <<= 1; + + // Select next servo channel + servo_channel++; + + // Check channel and process if needed + if( servo_channel < SERVO_CHANNELS ) goto CHECK_PINS_LOOP; + + goto CHECK_PINS_DONE; + +CHECK_PINS_ERROR: + + // Used to indicate invalid servo input signals + servo_input_errors++; + + goto CHECK_PINS_NEXT; + + // All servo input pins has now been processed + +CHECK_PINS_DONE: + + // Reset Watchdog Timer + wdt_reset(); + + // Set servo input missing flag false to indicate that we have received servo input signals + servo_input_missing = false; + + // Store current servo input pins for next check + servo_pins_old = servo_pins; + + // Start PPM generator if not already running + if( ppm_generator_active == false ) ppm_start(); + + //Has servo input changed while processing pins, if so we need to re-check pins + if( servo_pins != SERVO_INPUT ) goto CHECK_PINS_START; + + // Clear interrupt event from already processed pin changes + PCIFR |= (1 << SERVO_INT_CLEAR_FLAG); +} +// ------------------------------------------------------------------------------ + + +// ------------------------------------------------------------------------------ +// PPM OUTPUT - TIMER1 COMPARE INTERRUPT +// ------------------------------------------------------------------------------ +ISR( PPM_INT_VECTOR ) +{ + // Current active ppm channel + static uint8_t ppm_channel = PPM_ARRAY_MAX - 1; + + // Update timing for next compare toggle + PPM_COMPARE += ppm[ ppm_channel ]; + + // Select the next ppm channel + if( ++ppm_channel >= PPM_ARRAY_MAX ) ppm_channel = 0; + +} +// ------------------------------------------------------------------------------ + +// ------------------------------------------------------------------------------ +// PPM READ - INTERRUPT SAFE PPM SERVO CHANNEL READ +// ------------------------------------------------------------------------------ +uint16_t ppm_read_channel( uint8_t channel ) +{ + // Limit channel to valid value + uint8_t _channel = channel; + if( _channel == 0 ) _channel = 1; + if( _channel > SERVO_CHANNELS ) _channel = SERVO_CHANNELS; + + // Calculate ppm[..] position + uint8_t ppm_index = ( _channel << 1 ) + 1; + + // Read ppm[..] in a non blocking interrupt safe manner + uint16_t ppm_tmp = ppm[ ppm_index ]; + while( ppm_tmp != ppm[ ppm_index ] ) ppm_tmp = ppm[ ppm_index ]; + + // Return as normal servo value + return ppm_tmp + PPM_PRE_PULSE; +} +// ------------------------------------------------------------------------------ + +// ------------------------------------------------------------------------------ +// PPM ENCODER INIT +// ------------------------------------------------------------------------------ +void ppm_encoder_init( void ) +{ + // ATmegaXXU2 only init code + // ------------------------------------------------------------------------------ + #if defined (__AVR_ATmega16U2__) || defined (__AVR_ATmega32U2__) + // ------------------------------------------------------------------------------ + // 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 + } + + // APM USB connection status UART MUX selector pin + // ------------------------------------------------------------------------------ + USB_DDR |= (1 << USB_PIN); // Set USB pin to output + #endif + + + // USE JUMPER TO CHECK FOR PWM OR PPM PASSTROUGH MODE (channel 2&3 shorted) + // ------------------------------------------------------------------------------ + if( servo_input_mode == JUMPER_SELECT_MODE ) + { + // channel 3 status counter + uint8_t channel3_status = 0; + + // Set channel 3 to input + SERVO_DDR &= ~(1 << 2); + + // Enable channel 3 pullup + SERVO_PORT |= (1 << 2); + + // Set channel 2 to output + SERVO_DDR |= (1 << 1); + + // Set channel 2 output low + SERVO_PORT &= ~(1 << 1); + + _delay_us (10); + + // Increment channel3_status if channel 3 is set low by channel 2 + if( ( SERVO_INPUT & (1 << 2) ) == 0 ) channel3_status++; + + // Set channel 2 output high + SERVO_PORT |= (1 << 1); + + _delay_us (10); + + // Increment channel3_status if channel 3 is set high by channel 2 + if( ( SERVO_INPUT & (1 << 2) ) != 0 ) channel3_status++; + + // Set channel 2 output low + SERVO_PORT &= ~(1 << 1); + + _delay_us (10); + + // Increment channel3_status if channel 3 is set low by channel 2 + if( ( SERVO_INPUT & (1 << 2) ) == 0 ) channel3_status++; + + // Set servo input mode based on channel3_status + if( channel3_status == 3 ) servo_input_mode = PPM_PASSTROUGH_MODE; + else servo_input_mode = SERVO_PWM_MODE; + + } + + + // SERVO/PPM INPUT PINS + // ------------------------------------------------------------------------------ + // Set all servo input pins to inputs + SERVO_DDR = 0; + + // Activate pullups on all input pins + SERVO_PORT |= 0xFF; + + + // SERVO/PPM INPUT - PIN CHANGE INTERRUPT + // ------------------------------------------------------------------------------ + if( servo_input_mode == SERVO_PWM_MODE ) + { + // Set servo input interrupt pin mask to all 8 servo input channels + SERVO_INT_MASK = 0xFF; + } + + if( servo_input_mode == PPM_PASSTROUGH_MODE ) + { + // Set servo input interrupt pin mask to servo input channel 1 + SERVO_INT_MASK = 0x01; + } + + // Enable servo input interrupt + PCICR |= (1 << SERVO_INT_ENABLE); + + + // PPM OUTPUT PIN + // ------------------------------------------------------------------------------ + // Set PPM pin to output + PPM_DDR |= (1 << PPM_OUTPUT_PIN); + + // ------------------------------------------------------------------------------ + // Enable watchdog interrupt mode + // ------------------------------------------------------------------------------ + // Disable watchdog + wdt_disable(); + // Reset watchdog timer + wdt_reset(); + // Start timed watchdog setup sequence + WDTCSR |= (1< +#include +#include "wiring.h" +#include "mySerial0.h" +#include "JetiBox.h" + +#define LCDLine1 1 +#define LCDLine2 17 +#define LCDMaxChar 32 + +//define Jeti-Box Display +struct jeti_box { + unsigned char lcd[32]; + volatile unsigned char lcdpos; + volatile unsigned char keys; + volatile unsigned char sendpos; +}; + +// create jbox +jeti_box jb = {{0},0,0,0}; +unsigned char dummy; +unsigned char lastkey = 0; + +ISR(USART3_RX_vect) //serial data available +{ + // save response data to keys + dummy = UDR3; + if (dummy != 0xFF) + { + jb.keys = dummy; + // disable this interrupt + UCSR3B &= ~(1< interrupt is enabled (function start() ), send startbyte with 9.bit=0 + * jbox.sendpos = 1-32 -> send display data with 9.bit=1 + * jbox.sendpos = 33 -> send endbyte with 9.bit=0 + * jbox.sendpos = 34 -> reset sendpos=0 -> disable this interrupt + */ +{ + switch (jb.sendpos) + { + case 0: + // send start byte with 9.bit=0 + UCSR3B &= ~(1< 0 + jb.sendpos = 0; + // enable receiver interrupt for reading key byte + UCSR3B |= (1<>8); //high byte + UBRR3L=_UBRR3; //low byte + + // Set frame format: 9data, odd parity, 2stop bit + UCSR3C = (0<>4) xor 0x0F; + if (lastkey==c) + { + return 0; + }else{ + return lastkey = c; + } + +} + +void JetiBox::write(uint8_t c) +{ + jb.lcd[jb.lcdpos] = c; + if (jb.lcdpos < LCDMaxChar) + { + jb.lcdpos++; + } +} + +void JetiBox::line1() +{ + jb.lcdpos = LCDLine1; +} + +void JetiBox::line2() +{ + jb.lcdpos = LCDLine2; +} + +// Preinstantiate Objects ////////////////////////////////////////////////////// +JetiBox JBox; + + + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/Jetibox/JetiBox.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/Jetibox/JetiBox.h new file mode 100644 index 0000000000..ee39e5a2e8 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/Jetibox/JetiBox.h @@ -0,0 +1,51 @@ +/* + JetiBox.h, Version 1.0 beta + July 2010, by Uwe Gartmann + + Library acts as a Sensor when connected to a Jeti Receiver + written for Arduino Mega / ArduPilot Mega + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library 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 + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef JetiBox_h +#define JetiBox_h + +#include +#include "Print.h" + +#define jbox_key_up 0b0010 +#define jbox_key_right 0b0001 +#define jbox_key_down 0b0100 +#define jbox_key_left 0b1000 + +struct jeti_box; + +class JetiBox : public Print +{ + public: + JetiBox(); + void begin(); + void refresh(); + uint8_t keys(void); + virtual void write(uint8_t); + using Print::write; // pull in write(str) and write(buf, size) from Print + void line1(); + void line2(); +}; + +extern JetiBox JBox; + +#endif diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/APM_Config.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/APM_Config.h new file mode 100644 index 0000000000..e75fb175cf --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/APM_Config.h @@ -0,0 +1,925 @@ +// +// Example and reference ArduPilot Mega configuration file +// ======================================================= +// +// This file contains documentation and examples for configuration options +// supported by the ArduPilot Mega software. +// +// Most of these options are just that - optional. You should create +// the APM_Config.h file and use this file as a reference for options +// that you want to change. Don't copy this file directly; the options +// described here and their default values may change over time. +// +// Each item is marked with a keyword describing when you should set it: +// +// REQUIRED +// You must configure this in your APM_Config.h file. The +// software will not compile if the option is not set. +// +// OPTIONAL +// The option has a sensible default (which will be described +// here), but you may wish to override it. +// +// EXPERIMENTAL +// You should configure this option unless you are prepared +// to deal with potential problems. It may relate to a feature +// still in development, or which is not yet adequately tested. +// +// DEBUG +// The option should only be set if you are debugging the +// software, or if you are gathering information for a bug +// report. +// +// NOTE: +// Many of these settings are considered 'factory defaults', and the +// live value is stored and managed in the ArduPilot Mega EEPROM. +// Use the setup 'factoryreset' command after changing options in +// your APM_Config.h file. +// +// Units +// ----- +// +// Unless indicated otherwise, numeric quantities use the following units: +// +// Measurement | Unit +// ------------+------------------------------------- +// angle | degrees +// distance | metres +// speed | metres per second +// servo angle | microseconds +// voltage | volts +// times | seconds +// throttle | percent +// + +////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////// +// HARDWARE CONFIGURATION AND CONNECTIONS +////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////// + +////////////////////////////////////////////////////////////////////////////// +// GPS_PROTOCOL REQUIRED +// +// GPS configuration, must be one of: +// +// GPS_PROTOCOL_NONE No GPS attached +// GPS_PROTOCOL_IMU X-Plane interface or ArduPilot IMU. +// GPS_PROTOCOL_MTK MediaTek-based GPS. +// GPS_PROTOCOL_UBLOX UBLOX GPS +// GPS_PROTOCOL_SIRF SiRF-based GPS in Binary mode. NOT TESTED +// GPS_PROTOCOL_NMEA Standard NMEA GPS. NOT SUPPORTED (yet?) +// +#define GPS_PROTOCOL GPS_PROTOCOL_UBLOX +// + +////////////////////////////////////////////////////////////////////////////// +// AIRSPEED_SENSOR OPTIONAL +// AIRSPEED_RATIO OPTIONAL +// +// Set AIRSPEED_SENSOR to ENABLED if you have an airspeed sensor attached. +// Adjust AIRSPEED_RATIO in small increments to calibrate the airspeed +// sensor relative to your GPS. The calculation and default value are optimized for speeds around 12 m/s +// +// The default assumes that an airspeed sensor is connected. +// +#define AIRSPEED_SENSOR ENABLED +#define AIRSPEED_RATIO 1.9936 +// +#define MAGNETOMETER 1 +#define USE_MAGNETOMETER ENABLED + +////////////////////////////////////////////////////////////////////////////// +// GCS_PROTOCOL OPTIONAL +// GCS_PORT OPTIONAL +// +// The GCS_PROTOCOL option determines which (if any) ground control station +// protocol will be used. Must be one of: +// +// GCS_PROTOCOL_NONE No GCS output +// GCS_PROTOCOL_STANDARD standard APM protocol +// GCS_PROTOCOL_SPECIAL special test protocol (?) +// GCS_PROTOCOL_LEGACY legacy ArduPilot protocol +// GCS_PROTOCOL_XPLANE HIL simulation ground station +// GCS_PROTOCOL_IMU ArdiPilot IMU output +// GCS_PROTOCOL_JASON Jason's special secret GCS protocol +// GCS_PROTOCOL_DEBUGTERMINAL In-flight debug console (experimental) +// +// The GCS_PORT option determines which serial port will be used by the +// GCS protocol. The usual values are 0 for the console/USB port, +// or 3 for the telemetry port on the oilpan. Note that some protocols +// will ignore this value and always use the console port. +// +// The default GCS protocol is the standard ArduPilot Mega protocol. +// +// The default serial port is the telemetry port for GCS_PROTOCOL_STANDARD +// and GCS_PROTOCOL_LEGACY. For all other protocols, the default serial +// port is the FTDI/console port. GCS_PORT normally should not be set +// in your configuration. +// +#define GCS_PROTOCOL GCS_PROTOCOL_XDIY +#define GCS_PORT 0 +// + +////////////////////////////////////////////////////////////////////////////// +// Serial port speeds. +// +// SERIAL0_BAUD OPTIONAL +// +// Baudrate for the console port. Default is 38400bps. +// +// SERIAL3_BAUD OPTIONAL +// +// Baudrate for the telemetry port. Default is 115200bps. +// +//#define SERIAL0_BAUD 38400 +//#define SERIAL3_BAUD 115200 +// + +////////////////////////////////////////////////////////////////////////////// +// Battery monitoring OPTIONAL +// +// See the manual for details on selecting divider resistors for battery +// monitoring via the oilpan. +// +// BATTERY_EVENT OPTIONAL +// +// Set BATTERY_EVENT to ENABLED to enable battery monitoring. The default is +// DISABLED. +// +// BATTERY_TYPE OPTIONAL if BATTERY_EVENT is set +// +// Set to 0 for 3s LiPo, 1 for 4s LiPo. The default is 0, selecting a 3s +// battery. +// +// LOW_VOLTAGE OPTIONAL if BATTERY_EVENT is set. +// +// Normally derived from BATTERY_TYPE, the automatic value can be overridden +// here. Value in volts at which ArduPilot Mega should consider the +// battery to be "low". +// +// VOLT_DIV_RATIO OPTIONAL +// +// See the manual for details. The default value corresponds to the resistors +// recommended by the manual. +// +//#define BATTERY_EVENT DISABLED +//#define BATTERY_TYPE 0 +//#define LOW_VOLTAGE 11.4 +//#define VOLT_DIV_RATIO 3.0 +// + +////////////////////////////////////////////////////////////////////////////// +// INPUT_VOLTAGE OPTIONAL +// +// In order to have accurate pressure and battery voltage readings, this +// value should be set to the voltage measured on the 5V rail on the oilpan. +// +// See the manual for more details. The default value should be close. +// +#define INPUT_VOLTAGE 5.0 +// + + +////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////// +// RADIO CONFIGURATION +////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////// + +////////////////////////////////////////////////////////////////////////////// +// FLIGHT_MODE OPTIONAL +// FLIGHT_MODE_CHANNEL OPTIONAL +// +// Flight modes assigned to the control channel, and the input channel that +// is read for the control mode. +// +// Use a servo tester, or the ArduPilotMega_demo test program to check your +// switch settings. +// +// ATTENTION: Some ArduPilot Mega boards have radio channels marked 0-7, and +// others have them marked the standard 1-8. The FLIGHT_MODE_CHANNEL option +// uses channel numbers 1-8 (and defaults to 8). +// +// If you only have a three-position switch or just want three modes, set your +// switch to produce 1165, 1425, and 1815 microseconds and configure +// FLIGHT_MODE 1 & 2, 3 & 4 and 5 & 6 to be the same. This is the default. +// +// If you have FLIGHT_MODE_CHANNEL set to 8 (the default) and your control +// channel connected to input channel 8, the hardware failsafe mode will +// activate for any control input over 1750ms. +// +// For more modes (up to six), set your switch(es) to produce any of 1165, +// 1295, 1425, 1555, 1685, and 1815 microseconds. +// +// Flight mode | Switch Setting (ms) +// ------------+--------------------- +// 1 | 1165 +// 2 | 1295 +// 3 | 1425 +// 4 | 1555 +// 5 | 1685 +// 6 | 1815 (FAILSAFE if using channel 8) +// +// The following standard flight modes are available: +// +// Name | Description +// -----------------+-------------------------------------------- +// | +// MANUAL | Full manual control via the hardware multiplexer. +// | +// STABILIZE | Tries to maintain level flight, but can be overridden with radio control inputs. +// | +// FLY_BY_WIRE_A | Autopilot style control via user input, with manual throttle. +// | +// FLY_BY_WIRE_B | Autopilot style control via user input, aispeed controlled with throttle. +// | +// RTL | Returns to the Home location and then LOITERs at a safe altitude. +// | +// AUTO | Autonomous flight based on programmed waypoints. Use the WaypointWriter +// | application or your Ground Control System to edit and upload +// | waypoints and other commands. +// | +// +// +// The following non-standard modes are EXPERIMENTAL: +// +// Name | Description +// -----------------+-------------------------------------------- +// | +// LOITER | Flies in a circle around the current location. +// | +// CIRCLE | Flies in a stabilized 'dumb' circle. +// | +// +// +// If you are using channel 8 for mode switching then FLIGHT_MODE_5 and +// FLIGHT_MODE_6 should be MANUAL. +// +// +#define FLIGHT_MODE_CHANNEL 8 +// +//#define FLIGHT_MODE_1 RTL +//#define FLIGHT_MODE_2 RTL +//#define FLIGHT_MODE_3 FLY_BY_WIRE_A +//#define FLIGHT_MODE_4 FLY_BY_WIRE_A +//#define FLIGHT_MODE_5 MANUAL +//#define FLIGHT_MODE_6 MANUAL + +// Define the pulse width when to switch to next higher FLIGHT_MODE +#define FLIGHT_MODE_1_BOUNDARY 1125 +#define FLIGHT_MODE_2_BOUNDARY 1335 +#define FLIGHT_MODE_3_BOUNDARY 1550 +#define FLIGHT_MODE_4_BOUNDARY 1690 +#define FLIGHT_MODE_5_BOUNDARY 1880 + + + + +////////////////////////////////////////////////////////////////////////////// +// THROTTLE_FAILSAFE OPTIONAL +// THROTTLE_FS_VALUE OPTIONAL +// THROTTLE_FAILSAFE_ACTION OPTIONAL +// +// The throttle failsafe allows you to configure a software failsafe activated +// by a setting on the throttle input channel (channel 3). +// +// This can be used to achieve a failsafe override on loss of radio control +// without having to sacrifice one of your FLIGHT_MODE settings, as the +// throttle failsafe overrides the switch-selected mode. +// +// Throttle failsafe is enabled by setting THROTTLE_FAILSAFE to 1. The default +// is for it to be disabled. +// +// If the throttle failsafe is enabled, THROTTLE_FS_VALUE sets the channel value +// below which the failsafe engages. The default is 975ms, which is a very low +// throttle setting. Most transmitters will let you trim the manual throttle +// position up so that you cannot engage the failsafe with a regular stick movement. +// +// Configure your receiver's failsafe setting for the throttle channel to the +// absolute minimum, and use the ArduPilotMega_demo program to check that +// you cannot reach that value with the throttle control. Leave a margin of +// at least 50 microseconds between the lowest throttle setting and +// THROTTLE_FS_VALUE. +// +// The FAILSAFE_ACTION setting determines what APM will do when throttle failsafe +// mode is entered while flying in AUTO mode. This is important in order to avoid +// accidental failsafe behaviour when flying waypoints that take the aircraft +// temporarily out of radio range. +// +// If FAILSAFE_ACTION is 1, when failsafe is entered in AUTO or LOITER modes, +// the aircraft will head for home in RTL mode. If the throttle channel moves +// back up, it will return to AUTO or LOITER mode. +// +// The default behaviour is to ignore throttle failsafe in AUTO and LOITER modes. +// +//#define THROTTLE_FAILSAFE DISABLED +//#define THROTTLE_FS_VALUE 975 +//#define THROTTLE_FAILSAFE_ACTION 2 +// + +////////////////////////////////////////////////////////////////////////////// +// AUTO_TRIM OPTIONAL +// +// ArduPilot Mega can update its trim settings by looking at the +// radio inputs when switching out of MANUAL mode. This allows you to +// manually trim your aircraft before switching to an assisted mode, but it +// also means that you should avoid switching out of MANUAL while you have +// any control stick deflection. +// +// The default is to enable AUTO_TRIM. +// +#define AUTO_TRIM ENABLED +// + +////////////////////////////////////////////////////////////////////////////// +// THROTTLE_REVERSE OPTIONAL +// +// A few speed controls require the throttle servo signal be reversed. Setting +// this to ENABLED will reverse the throttle output signal. Ensure that your +// throttle needs to be reversed by using the hardware failsafe and the +// ArduPilotMega_demo program before setting this option. +// +// The default is to not reverse the signal. +// +//#define THROTTLE_REVERSE DISABLED +// + +////////////////////////////////////////////////////////////////////////////// +// ENABLE_STICK_MIXING OPTIONAL +// +// If this option is set to ENABLED, manual control inputs are are respected +// while in the autopilot modes (AUTO, RTL, LOITER, CIRCLE etc.) +// +// The default is to enable stick mixing, allowing the pilot to take +// emergency action without switching modes. +// +#define ENABLE_STICK_MIXING ENABLED +// + +////////////////////////////////////////////////////////////////////////////// +// THROTTLE_OUT DEBUG +// +// When debugging, it can be useful to disable the throttle output. Set +// this option to DISABLED to disable throttle output signals. +// +// The default is to not disable throttle output. +// +#define THROTTLE_OUT DISABLED +// + + +////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////// +// STARTUP BEHAVIOUR +////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////// + +////////////////////////////////////////////////////////////////////////////// +// GROUND_START_DELAY OPTIONAL +// +// If configured, inserts a delay between power-up and the beginning of IMU +// calibration during a ground start. +// +// Use this setting to give you time to position the aircraft horizontally +// for the IMU calibration. +// +// The default is to begin IMU calibration immediately at startup. +// +//#define GROUND_START_DELAY 0 +// + +////////////////////////////////////////////////////////////////////////////// +// ENABLE_AIR_START OPTIONAL +// +// If air start is disabled then you will get a ground start (including IMU +// calibration) every time the AP is powered up. This means that if you get +// a power glitch or reboot for some reason in the air, you will probably +// crash, but it prevents a lot of problems on the ground like unintentional +// motor start-ups, etc. +// +// If air start is enabled then you will get an air start at power up and a +// ground start will be performed if the speed is near zero when we get gps +// lock. +// +// The default is to disable air start. +// +#define ENABLE_AIR_START 0 +// + + +////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////// +// FLIGHT AND NAVIGATION CONTROL +////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////// + +////////////////////////////////////////////////////////////////////////////// +// Altitude measurement and control. +// +// AOA OPTIONAL +// +// The angle in 100ths of a degree that the nose of the aircraft should be +// raised from horizontal in level flight. The default is 1 degree. +// +//#define AOA 100 // note, 100ths of a degree +// +// ALT_EST_GAIN OPTIONAL +// +// The gain of the altitude estimation function; a lower number results +// in slower error correction and smoother output. The default is a +// reasonable starting point. +// +//#define ALT_EST_GAIN 0.01 +// +// ALTITUDE_MIX OPTIONAL +// +// Configures the blend between GPS and pressure altitude. +// 0 = GPS altitude, 1 = Press alt, 0.5 = half and half, etc. +// +// The default is to use only GPS altitude. +// +//#define ALTITUDE_MIX 0 +// + + +////////////////////////////////////////////////////////////////////////////// +// ENABLE_HIL OPTIONAL +// +// This will output a binary control string to for use in HIL sims +// such as Xplane 9 or FlightGear. +// +//#define ENABLE_HIL ENABLED +// + + +////////////////////////////////////////////////////////////////////////////// +// AIRSPEED_CRUISE OPTIONAL +// +// The speed in metres per second to maintain during cruise. The default +// is 10m/s, which is a conservative value suitable for relatively small, +// light aircraft. +// +#define AIRSPEED_CRUISE 15 +// + +////////////////////////////////////////////////////////////////////////////// +// FLY_BY_WIRE_B airspeed control +// +// AIRSPEED_FBW_MIN OPTIONAL +// AIRSPEED_FBW_MAX OPTIONAL +// +// Airspeed corresponding to minimum and maximum throttle in Fly By Wire B mode. +// The defaults are 6 and 30 metres per second. +// +// THROTTLE_ALT_P OPTIONAL +// THROTTLE_ALT_I OPTIONAL +// THROTTLE_ALT_D OPTIONAL +// +// P, I and D terms for the throttle control loop. Defaults are 0.5, 0, 0. +// +// THROTTLE_ALT_INT_MAX OPTIONAL +// +// Maximum throttle input due to the integral. Limits the throttle input +// due to persistent inability to maintain the commanded speed. Helps +// prevent the throttle from staying wide open when the control is reduced +// after a period at maxium speed. +// Default is 20 (20%). +// +//#define AIRSPEED_FBW_MIN 6 +//#define AIRSPEED_FBW_MAX 30 +//#define THROTTLE_ALT_P 0.32 +//#define THROTTLE_ALT_I 0.04 +//#define THROTTLE_ALT_D 0.0 +//#define THROTTLE_ALT_INT_MAX 20 +// + +////////////////////////////////////////////////////////////////////////////// +// Throttle control +// +// THROTTLE_MIN OPTIONAL +// +// The minimum throttle setting to which the autopilot will reduce the +// throttle while descending. The default is zero, which is +// suitable for aircraft with a steady power-off glide. Increase this +// value if your aircraft needs throttle to maintain a stable descent in +// level flight. +// +// THROTTLE_CRUISE OPTIONAL +// +// The approximate throttle setting to achieve AIRSPEED_CRUISE in level flight. +// The default is 45%, which is reasonable for a modestly powered aircraft. +// +// THROTTLE_MAX OPTIONAL +// +// The maximum throttle setting the autopilot will apply. The default is 75%. +// Reduce this value if your aicraft is overpowered, or has complex flight +// characteristics at high throttle settings. +// +//#define THROTTLE_MIN 0 +//#define THROTTLE_CRUISE 45 +//#define THROTTLE_MAX 75 +// + +////////////////////////////////////////////////////////////////////////////// +// Autopilot control limits +// +// HEAD_MAX OPTIONAL +// +// The maximum commanded bank angle in either direction. +// The default is 45 degrees. Decrease this value if your aircraft is not +// stable or has difficulty maintaining altitude in a steep bank. +// +// PITCH_MAX OPTIONAL +// +// The maximum commanded pitch up angle. +// The default is 15 degrees. Care should be taken not to set this value too +// large, as the aircraft may stall. +// +// PITCH_MIN +// +// The maximum commanded pitch down angle. Note that this value must be +// negative. The default is -25 degrees. Care should be taken not to set +// this value too large as it may result in overspeeding the aircraft. +// +//#define HEAD_MAX 45 +//#define PITCH_MAX 15 +//#define PITCH_MIN -25 + +////////////////////////////////////////////////////////////////////////////// +// Attitude control gains +// +// Tuning values for the attitude control PID loops. +// +// The P term is the primary tuning value. This determines how the control +// deflection varies in proportion to the required correction. +// +// The I term is used to help control surfaces settle. This value should +// normally be kept low. +// +// The D term is used to control overshoot. Avoid using or adjusting this +// term if you are not familiar with tuning PID loops. It should normally +// be zero for most aircraft. +// +// Note: When tuning these values, start with changes of no more than 25% at +// a time. +// +// SERVO_ROLL_P OPTIONAL +// SERVO_ROLL_I OPTIONAL +// SERVO_ROLL_D OPTIONAL +// +// P, I and D terms for roll control. Defaults are 0.4, 0, 0. +// +// SERVO_ROLL_INT_MAX OPTIONAL +// +// Maximum control offset due to the integral. This prevents the control +// output from being overdriven due to a persistent offset (e.g. crosstracking). +// Default is 5 degrees. +// +// ROLL_SLEW_LIMIT EXPERIMENTAL +// +// Limits the slew rate of the roll control in degrees per second. If zero, +// slew rate is not limited. Default is to not limit the roll control slew rate. +// (This feature is currently not implemented.) +// +// SERVO_PITCH_P OPTIONAL +// SERVO_PITCH_I OPTIONAL +// SERVO_PITCH_D OPTIONAL +// +// P, I and D terms for the pitch control. Defaults are 0.6, 0, 0. +// +// SERVO_PITCH_INT_MAX OPTIONAL +// +// Maximum control offset due to the integral. This prevents the control +// output from being overdriven due to a persistent offset (e.g. native flight +// AoA). If you find this value is insufficient, consider adjusting the AOA +// parameter. +// Default is 5 degrees. +// +// PITCH_COMP OPTIONAL +// +// Adds pitch input to compensate for the loss of lift due to roll control. +// Default is 0.20 (20% of roll control also applied to pitch control). +// +// SERVO_YAW_P OPTIONAL +// SERVO_YAW_I OPTIONAL +// SERVO_YAW_D OPTIONAL +// +// P, I and D terms for the YAW control. Defaults are 0.5, 0, 0. +// +// SERVO_YAW_INT_MAX OPTIONAL +// +// Maximum control offset due to the integral. This prevents the control +// output from being overdriven due to a persistent offset (e.g. crosstracking). +// Default is 5 degrees. +// +// RUDDER_MIX OPTIONAL +// +// Roll to yaw mixing. This allows for co-ordinated turns. +// Default is 0.50 (50% of roll control also applied to yaw control.) +// +//#define SERVO_ROLL_P 0.4 +//#define SERVO_ROLL_I 0.0 +//#define SERVO_ROLL_D 0.0 +//#define SERVO_ROLL_INT_MAX 5 +//#define ROLL_SLEW_LIMIT 0 +//#define SERVO_PITCH_P 0.6 +//#define SERVO_PITCH_I 0.0 +//#define SERVO_PITCH_D 0.0 +//#define SERVO_PITCH_INT_MAX 5 +//#define PITCH_COMP 0.2 +//#define SERVO_YAW_P 0.5 +//#define SERVO_YAW_I 0.0 +//#define SERVO_YAW_D 0.0 +//#define SERVO_YAW_INT_MAX 5 +//#define RUDDER_MIX 0.5 +// + +////////////////////////////////////////////////////////////////////////////// +// Navigation control gains +// +// Tuning values for the navigation control PID loops. +// +// The P term is the primary tuning value. This determines how the control +// deflection varies in proportion to the required correction. +// +// The I term is used to control drift. +// +// The D term is used to control overshoot. Avoid adjusting this term if +// you are not familiar with tuning PID loops. +// +// Note: When tuning these values, start with changes of no more than 25% at +// a time. +// +// NAV_ROLL_P OPTIONAL +// NAV_ROLL_I OPTIONAL +// NAV_ROLL_D OPTIONAL +// +// P, I and D terms for navigation control over roll, normally used for +// controlling the aircraft's course. The P term controls how aggressively +// the aircraft will bank to change or hold course. +// Defaults are 0.7, 0.01, 0.02. +// +// NAV_ROLL_INT_MAX OPTIONAL +// +// Maximum control offset due to the integral. This prevents the control +// output from being overdriven due to a persistent offset (e.g. crosstracking). +// Default is 5 degrees. +// +// NAV_PITCH_ASP_P OPTIONAL +// NAV_PITCH_ASP_I OPTIONAL +// NAV_PITCH_ASP_D OPTIONAL +// +// P, I and D terms for pitch adjustments made to maintain airspeed. +// Defaults are 0.65, 0, 0. +// +// NAV_PITCH_ASP_INT_MAX OPTIONAL +// +// Maximum pitch offset due to the integral. This limits the control +// output from being overdriven due to a persistent offset (eg. inability +// to maintain the programmed airspeed). +// Default is 5 degrees. +// +// NAV_PITCH_ALT_P OPTIONAL +// NAV_PITCH_ALT_I OPTIONAL +// NAV_PITCH_ALT_D OPTIONAL +// +// P, I and D terms for pitch adjustments made to maintain altitude. +// Defaults are 0.65, 0, 0. +// +// NAV_PITCH_ALT_INT_MAX OPTIONAL +// +// Maximum pitch offset due to the integral. This limits the control +// output from being overdriven due to a persistent offset (eg. inability +// to maintain the programmed altitude). +// Default is 5 degrees. +// +//#define NAV_ROLL_P 0.7 +//#define NAV_ROLL_I 0.01 +//#define NAV_ROLL_D 0.02 +//#define NAV_ROLL_INT_MAX 5 +//#define NAV_PITCH_ASP_P 0.65 +//#define NAV_PITCH_ASP_I 0.0 +//#define NAV_PITCH_ASP_D 0.0 +//#define NAV_PITCH_ASP_INT_MAX 5 +//#define NAV_PITCH_ALT_P 0.65 +//#define NAV_PITCH_ALT_I 0.0 +//#define NAV_PITCH_ALT_D 0.0 +//#define NAV_PITCH_ALT_INT_MAX 5 +// + +////////////////////////////////////////////////////////////////////////////// +// Energy/Altitude control gains +// +// The Energy/altitude control system uses throttle input to control aircraft +// altitude. +// +// The P term is the primary tuning value. This determines how the throttle +// setting varies in proportion to the required correction. +// +// The I term is used to compensate for small offsets. +// +// The D term is used to control overshoot. Avoid adjusting this term if +// you are not familiar with tuning PID loops. +// +// THROTTLE_TE_P OPTIONAL +// THROTTLE_TE_I OPTIONAL +// THROTTLE_TE_D OPTIONAL +// +// P, I and D terms for throttle adjustments made to control altitude. +// Defaults are 0.5, 0, 0. +// +// THROTTLE_TE_INT_MAX OPTIONAL +// +// Maximum throttle input due to the integral term. This limits the +// throttle from being overdriven due to a persistent offset (e.g. +// inability to maintain the programmed altitude). +// Default is 20%. +// +// THROTTLE_SLEW_LIMIT OPTIONAL +// +// Limits the slew rate of the throttle, in percent per second. Helps +// avoid sudden throttle changes, which can destabilise the aircraft. +// A setting of zero disables the feature. +// Default is zero (disabled). +// +// P_TO_T OPTIONAL +// +// Pitch to throttle feed-forward gain. Used when AIRSPEED_SENSOR +// is DISABLED. Default is 2.5. +// +//#define THROTTLE_TE_P 0.50 +//#define THROTTLE_TE_I 0.0 +//#define THROTTLE_TE_D 0.0 +//#define THROTTLE_TE_INT_MAX 20 +//#define THROTTLE_SLEW_LIMIT 0 +//#define P_TO_T 2.5 +// + +////////////////////////////////////////////////////////////////////////////// +// Crosstrack compensation +// +// XTRACK_GAIN OPTIONAL +// +// Crosstrack compensation in degrees per metre off track. +// Default value is 0.01 degrees per metre. Values lower than 0.001 will +// disable crosstrack compensation. +// +// XTRACK_ENTRY_ANGLE OPTIONAL +// +// Maximum angle used to correct for track following. +// Default value is 30 degrees. +// +//#define XTRACK_GAIN 0.01 +//#define XTRACK_ENTRY_ANGLE 30 +// + +////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////// +// DEBUGGING +////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////// + +////////////////////////////////////////////////////////////////////////////// +// Subsystem test and debug. +// +// DEBUG_SUBSYSTEM DEBUG +// +// Selects a subsystem debug mode. Default is 0. +// +// 0 = no debug +// 1 = Debug the Radio input +// 2 = Radio Setup / Servo output +// 4 = Debug the GPS input +// 5 = Debug the GPS input - RAW OUTPUT +// 6 = Debug the IMU +// 7 = Debug the Control Switch +// 8 = Debug the Servo DIP switches +// 9 = Debug the Relay out +// 10 = Debug the Magnetometer +// 11 = Debug the ABS pressure sensor +// 12 = Debug the stored waypoints +// 13 = Debug the Throttle +// 14 = Debug the Radio Min Max +// 15 = Debug the EEPROM - Hex Dump +// 16 = XBee X-CTU Range and RSSI Test +// 17 = Debug IMU - raw gyro and accel outputs +// 20 = Debug Analog Sensors +// +// +//#define DEBUG_SUBSYSTEM 0 +// + +////////////////////////////////////////////////////////////////////////////// +// DEBUG_LEVEL DEBUG +// +// Selects the lowest level of debug messages passed to the telemetry system. +// Default is SEVERITY_LOW. May be one of: +// +// SEVERITY_LOW +// SEVERITY_MEDIUM +// SEVERITY_HIGH +// SEVERITY_CRITICAL +// +//#define DEBUG_LEVEL SEVERITY_LOW +// + +////////////////////////////////////////////////////////////////////////////// +// Dataflash logging control +// +// Each of these logging options may be set to ENABLED to enable, or DISABLED +// to disable the logging of the respective data. +// +// LOG_ATTITUDE_FAST DEBUG +// +// Logs basic attitude info to the dataflash at 50Hz (uses more space). +// Defaults to DISABLED. +// +// LOG_ATTITUDE_MED OPTIONAL +// +// Logs basic attitude info to the dataflash at 10Hz (uses less space than +// LOG_ATTITUDE_FAST). Defaults to ENABLED. +// +// LOG_GPS OPTIONAL +// +// Logs GPS info to the dataflash at 10Hz. Defaults to ENABLED. +// +// LOG_PM OPTIONAL +// +// Logs IMU performance monitoring info every 20 seconds. +// Defaults to DISABLED. +// +// LOG_CTUN OPTIONAL +// +// Logs control loop tuning info at 10 Hz. This information is useful for tuning +// servo control loop gain values. Defaults to DISABLED. +// +// LOG_NTUN OPTIONAL +// +// Logs navigation tuning info at 10 Hz. This information is useful for tuning +// navigation control loop gain values. Defaults to DISABLED. +// +// LOG_ MODE OPTIONAL +// +// Logs changes to the flight mode upon occurrence. Defaults to ENABLED. +// +// LOG_RAW DEBUG +// +// Logs raw accelerometer and gyro data at 50 Hz (uses more space). +// Defaults to DISABLED. +// +// LOG_CMD OPTIONAL +// +// Logs new commands when they process. +// Defaults to ENABLED. +// +//#define LOG_ATTITUDE_FAST DISABLED +//#define LOG_ATTITUDE_MED ENABLED +//#define LOG_GPS ENABLED +//#define LOG_PM ENABLED +//#define LOG_CTUN DISABLED +//#define LOG_NTUN DISABLED +//#define LOG_MODE ENABLED +//#define LOG_RAW DISABLED +//#define LOG_CMD ENABLED +// + +////////////////////////////////////////////////////////////////////////////// +// Navigation defaults +// +// WP_RADIUS_DEFAULT OPTIONAL +// +// When the user performs a factory reset on the APM, set the waypoint radius +// (the radius from a target waypoint within which the APM will consider +// itself to have arrived at the waypoint) to this value in meters. This is +// mainly intended to allow users to start using the APM without running the +// WaypointWriter first. +// +// LOITER_RADIUS_DEFAULT OPTIONAL +// +// When the user performs a factory reset on the APM, set the loiter radius +// (the distance the APM will attempt to maintain from a waypoint while +// loitering) to this value in meters. This is mainly intended to allow +// users to start using the APM without running the WaypointWriter first. +// +//#define WP_RADIUS_DEFAULT 20 +//#define LOITER_RADIUS_DEFAULT 30 +// + +////////////////////////////////////////////////////////////////////////////// +// Debugging interface +// +// DEBUG_PORT OPTIONAL +// +// The APM will periodically send messages reporting what it is doing; this +// variable determines to which serial port they will be sent. Port 0 is the +// USB serial port on the shield, port 3 is the telemetry port. +// +//#define DEBUG_PORT 0 +// + +// +// Do not remove - this is to discourage users from copying this file +// and using it as-is rather than editing their own. +// + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/APM_Config.h.reference b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/APM_Config.h.reference new file mode 100644 index 0000000000..b05a3c2af5 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/APM_Config.h.reference @@ -0,0 +1,914 @@ +// +// Example and reference ArduPilot Mega configuration file +// ======================================================= +// +// This file contains documentation and examples for configuration options +// supported by the ArduPilot Mega software. +// +// Most of these options are just that - optional. You should create +// the APM_Config.h file and use this file as a reference for options +// that you want to change. Don't copy this file directly; the options +// described here and their default values may change over time. +// +// Each item is marked with a keyword describing when you should set it: +// +// REQUIRED +// You must configure this in your APM_Config.h file. The +// software will not compile if the option is not set. +// +// OPTIONAL +// The option has a sensible default (which will be described +// here), but you may wish to override it. +// +// EXPERIMENTAL +// You should configure this option unless you are prepared +// to deal with potential problems. It may relate to a feature +// still in development, or which is not yet adequately tested. +// +// DEBUG +// The option should only be set if you are debugging the +// software, or if you are gathering information for a bug +// report. +// +// NOTE: +// Many of these settings are considered 'factory defaults', and the +// live value is stored and managed in the ArduPilot Mega EEPROM. +// Use the setup 'factoryreset' command after changing options in +// your APM_Config.h file. +// +// Units +// ----- +// +// Unless indicated otherwise, numeric quantities use the following units: +// +// Measurement | Unit +// ------------+------------------------------------- +// angle | degrees +// distance | metres +// speed | metres per second +// servo angle | microseconds +// voltage | volts +// times | seconds +// throttle | percent +// + +////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////// +// HARDWARE CONFIGURATION AND CONNECTIONS +////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////// + +////////////////////////////////////////////////////////////////////////////// +// GPS_PROTOCOL REQUIRED +// +// GPS configuration, must be one of: +// +// GPS_PROTOCOL_NONE No GPS attached +// GPS_PROTOCOL_IMU X-Plane interface or ArduPilot IMU. +// GPS_PROTOCOL_MTK MediaTek-based GPS. +// GPS_PROTOCOL_UBLOX UBLOX GPS +// GPS_PROTOCOL_SIRF SiRF-based GPS in Binary mode. NOT TESTED +// GPS_PROTOCOL_NMEA Standard NMEA GPS. NOT SUPPORTED (yet?) +// +//#define GPS_PROTOCOL GPS_PROTOCOL_UBLOX +// + +////////////////////////////////////////////////////////////////////////////// +// AIRSPEED_SENSOR OPTIONAL +// AIRSPEED_RATIO OPTIONAL +// +// Set AIRSPEED_SENSOR to ENABLED if you have an airspeed sensor attached. +// Adjust AIRSPEED_RATIO in small increments to calibrate the airspeed +// sensor relative to your GPS. The calculation and default value are optimized for speeds around 12 m/s +// +// The default assumes that an airspeed sensor is connected. +// +//#define AIRSPEED_SENSOR ENABLED +//#define AIRSPEED_RATIO 1.9936 +// + +////////////////////////////////////////////////////////////////////////////// +// GCS_PROTOCOL OPTIONAL +// GCS_PORT OPTIONAL +// +// The GCS_PROTOCOL option determines which (if any) ground control station +// protocol will be used. Must be one of: +// +// GCS_PROTOCOL_NONE No GCS output +// GCS_PROTOCOL_STANDARD standard APM protocol +// GCS_PROTOCOL_SPECIAL special test protocol (?) +// GCS_PROTOCOL_LEGACY legacy ArduPilot protocol +// GCS_PROTOCOL_XPLANE HIL simulation ground station +// GCS_PROTOCOL_IMU ArdiPilot IMU output +// GCS_PROTOCOL_JASON Jason's special secret GCS protocol +// GCS_PROTOCOL_DEBUGTERMINAL In-flight debug console (experimental) +// +// The GCS_PORT option determines which serial port will be used by the +// GCS protocol. The usual values are 0 for the console/USB port, +// or 3 for the telemetry port on the oilpan. Note that some protocols +// will ignore this value and always use the console port. +// +// The default GCS protocol is the standard ArduPilot Mega protocol. +// +// The default serial port is the telemetry port for GCS_PROTOCOL_STANDARD +// and GCS_PROTOCOL_LEGACY. For all other protocols, the default serial +// port is the FTDI/console port. GCS_PORT normally should not be set +// in your configuration. +// +//#define GCS_PROTOCOL GCS_PROTOCOL_STANDARD +//#define GCS_PORT 3 +// + +////////////////////////////////////////////////////////////////////////////// +// Serial port speeds. +// +// SERIAL0_BAUD OPTIONAL +// +// Baudrate for the console port. Default is 38400bps. +// +// SERIAL3_BAUD OPTIONAL +// +// Baudrate for the telemetry port. Default is 115200bps. +// +//#define SERIAL0_BAUD 38400 +//#define SERIAL3_BAUD 115200 +// + +////////////////////////////////////////////////////////////////////////////// +// Battery monitoring OPTIONAL +// +// See the manual for details on selecting divider resistors for battery +// monitoring via the oilpan. +// +// BATTERY_EVENT OPTIONAL +// +// Set BATTERY_EVENT to ENABLED to enable battery monitoring. The default is +// DISABLED. +// +// BATTERY_TYPE OPTIONAL if BATTERY_EVENT is set +// +// Set to 0 for 3s LiPo, 1 for 4s LiPo. The default is 0, selecting a 3s +// battery. +// +// LOW_VOLTAGE OPTIONAL if BATTERY_EVENT is set. +// +// Normally derived from BATTERY_TYPE, the automatic value can be overridden +// here. Value in volts at which ArduPilot Mega should consider the +// battery to be "low". +// +// VOLT_DIV_RATIO OPTIONAL +// +// See the manual for details. The default value corresponds to the resistors +// recommended by the manual. +// +//#define BATTERY_EVENT DISABLED +//#define BATTERY_TYPE 0 +//#define LOW_VOLTAGE 11.4 +//#define VOLT_DIV_RATIO 3.0 +// + +////////////////////////////////////////////////////////////////////////////// +// INPUT_VOLTAGE OPTIONAL +// +// In order to have accurate pressure and battery voltage readings, this +// value should be set to the voltage measured on the 5V rail on the oilpan. +// +// See the manual for more details. The default value should be close. +// +//#define INPUT_VOLTAGE 5.0 +// + + +////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////// +// RADIO CONFIGURATION +////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////// + +////////////////////////////////////////////////////////////////////////////// +// FLIGHT_MODE OPTIONAL +// FLIGHT_MODE_CHANNEL OPTIONAL +// +// Flight modes assigned to the control channel, and the input channel that +// is read for the control mode. +// +// Use a servo tester, or the ArduPilotMega_demo test program to check your +// switch settings. +// +// ATTENTION: Some ArduPilot Mega boards have radio channels marked 0-7, and +// others have them marked the standard 1-8. The FLIGHT_MODE_CHANNEL option +// uses channel numbers 1-8 (and defaults to 8). +// +// If you only have a three-position switch or just want three modes, set your +// switch to produce 1165, 1425, and 1815 microseconds and configure +// FLIGHT_MODE 1 & 2, 3 & 4 and 5 & 6 to be the same. This is the default. +// +// If you have FLIGHT_MODE_CHANNEL set to 8 (the default) and your control +// channel connected to input channel 8, the hardware failsafe mode will +// activate for any control input over 1750ms. +// +// For more modes (up to six), set your switch(es) to produce any of 1165, +// 1295, 1425, 1555, 1685, and 1815 microseconds. +// +// Flight mode | Switch Setting (ms) +// ------------+--------------------- +// 1 | 1165 +// 2 | 1295 +// 3 | 1425 +// 4 | 1555 +// 5 | 1685 +// 6 | 1815 (FAILSAFE if using channel 8) +// +// The following standard flight modes are available: +// +// Name | Description +// -----------------+-------------------------------------------- +// | +// MANUAL | Full manual control via the hardware multiplexer. +// | +// STABILIZE | Tries to maintain level flight, but can be overridden with radio control inputs. +// | +// FLY_BY_WIRE_A | Autopilot style control via user input, with manual throttle. +// | +// FLY_BY_WIRE_B | Autopilot style control via user input, aispeed controlled with throttle. +// | +// RTL | Returns to the Home location and then LOITERs at a safe altitude. +// | +// AUTO | Autonomous flight based on programmed waypoints. Use the WaypointWriter +// | application or your Ground Control System to edit and upload +// | waypoints and other commands. +// | +// +// +// The following non-standard modes are EXPERIMENTAL: +// +// Name | Description +// -----------------+-------------------------------------------- +// | +// LOITER | Flies in a circle around the current location. +// | +// CIRCLE | Flies in a stabilized 'dumb' circle. +// | +// +// +// If you are using channel 8 for mode switching then FLIGHT_MODE_5 and +// FLIGHT_MODE_6 should be MANUAL. +// +// +//#define FLIGHT_MODE_CHANNEL 8 +// +//#define FLIGHT_MODE_1 RTL +//#define FLIGHT_MODE_2 RTL +//#define FLIGHT_MODE_3 FLY_BY_WIRE_A +//#define FLIGHT_MODE_4 FLY_BY_WIRE_A +//#define FLIGHT_MODE_5 MANUAL +//#define FLIGHT_MODE_6 MANUAL +// + +////////////////////////////////////////////////////////////////////////////// +// THROTTLE_FAILSAFE OPTIONAL +// THROTTLE_FS_VALUE OPTIONAL +// THROTTLE_FAILSAFE_ACTION OPTIONAL +// +// The throttle failsafe allows you to configure a software failsafe activated +// by a setting on the throttle input channel (channel 3). +// +// This can be used to achieve a failsafe override on loss of radio control +// without having to sacrifice one of your FLIGHT_MODE settings, as the +// throttle failsafe overrides the switch-selected mode. +// +// Throttle failsafe is enabled by setting THROTTLE_FAILSAFE to 1. The default +// is for it to be disabled. +// +// If the throttle failsafe is enabled, THROTTLE_FS_VALUE sets the channel value +// below which the failsafe engages. The default is 975ms, which is a very low +// throttle setting. Most transmitters will let you trim the manual throttle +// position up so that you cannot engage the failsafe with a regular stick movement. +// +// Configure your receiver's failsafe setting for the throttle channel to the +// absolute minimum, and use the ArduPilotMega_demo program to check that +// you cannot reach that value with the throttle control. Leave a margin of +// at least 50 microseconds between the lowest throttle setting and +// THROTTLE_FS_VALUE. +// +// The FAILSAFE_ACTION setting determines what APM will do when throttle failsafe +// mode is entered while flying in AUTO mode. This is important in order to avoid +// accidental failsafe behaviour when flying waypoints that take the aircraft +// temporarily out of radio range. +// +// If FAILSAFE_ACTION is 1, when failsafe is entered in AUTO or LOITER modes, +// the aircraft will head for home in RTL mode. If the throttle channel moves +// back up, it will return to AUTO or LOITER mode. +// +// The default behaviour is to ignore throttle failsafe in AUTO and LOITER modes. +// +//#define THROTTLE_FAILSAFE DISABLED +//#define THROTTLE_FS_VALUE 975 +//#define THROTTLE_FAILSAFE_ACTION 2 +// + +////////////////////////////////////////////////////////////////////////////// +// AUTO_TRIM OPTIONAL +// +// ArduPilot Mega can update its trim settings by looking at the +// radio inputs when switching out of MANUAL mode. This allows you to +// manually trim your aircraft before switching to an assisted mode, but it +// also means that you should avoid switching out of MANUAL while you have +// any control stick deflection. +// +// The default is to enable AUTO_TRIM. +// +//#define AUTO_TRIM ENABLED +// + +////////////////////////////////////////////////////////////////////////////// +// THROTTLE_REVERSE OPTIONAL +// +// A few speed controls require the throttle servo signal be reversed. Setting +// this to ENABLED will reverse the throttle output signal. Ensure that your +// throttle needs to be reversed by using the hardware failsafe and the +// ArduPilotMega_demo program before setting this option. +// +// The default is to not reverse the signal. +// +//#define THROTTLE_REVERSE DISABLED +// + +////////////////////////////////////////////////////////////////////////////// +// ENABLE_STICK_MIXING OPTIONAL +// +// If this option is set to ENABLED, manual control inputs are are respected +// while in the autopilot modes (AUTO, RTL, LOITER, CIRCLE etc.) +// +// The default is to enable stick mixing, allowing the pilot to take +// emergency action without switching modes. +// +//#define ENABLE_STICK_MIXING ENABLED +// + +////////////////////////////////////////////////////////////////////////////// +// THROTTLE_OUT DEBUG +// +// When debugging, it can be useful to disable the throttle output. Set +// this option to DISABLED to disable throttle output signals. +// +// The default is to not disable throttle output. +// +//#define THROTTLE_OUT ENABLED +// + + +////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////// +// STARTUP BEHAVIOUR +////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////// + +////////////////////////////////////////////////////////////////////////////// +// GROUND_START_DELAY OPTIONAL +// +// If configured, inserts a delay between power-up and the beginning of IMU +// calibration during a ground start. +// +// Use this setting to give you time to position the aircraft horizontally +// for the IMU calibration. +// +// The default is to begin IMU calibration immediately at startup. +// +//#define GROUND_START_DELAY 0 +// + +////////////////////////////////////////////////////////////////////////////// +// ENABLE_AIR_START OPTIONAL +// +// If air start is disabled then you will get a ground start (including IMU +// calibration) every time the AP is powered up. This means that if you get +// a power glitch or reboot for some reason in the air, you will probably +// crash, but it prevents a lot of problems on the ground like unintentional +// motor start-ups, etc. +// +// If air start is enabled then you will get an air start at power up and a +// ground start will be performed if the speed is near zero when we get gps +// lock. +// +// The default is to disable air start. +// +//#define ENABLE_AIR_START 0 +// + + +////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////// +// FLIGHT AND NAVIGATION CONTROL +////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////// + +////////////////////////////////////////////////////////////////////////////// +// Altitude measurement and control. +// +// AOA OPTIONAL +// +// The angle in 100ths of a degree that the nose of the aircraft should be +// raised from horizontal in level flight. The default is 1 degree. +// +//#define AOA 100 // note, 100ths of a degree +// +// ALT_EST_GAIN OPTIONAL +// +// The gain of the altitude estimation function; a lower number results +// in slower error correction and smoother output. The default is a +// reasonable starting point. +// +//#define ALT_EST_GAIN 0.01 +// +// ALTITUDE_MIX OPTIONAL +// +// Configures the blend between GPS and pressure altitude. +// 0 = GPS altitude, 1 = Press alt, 0.5 = half and half, etc. +// +// The default is to use only GPS altitude. +// +//#define ALTITUDE_MIX 0 +// + + +////////////////////////////////////////////////////////////////////////////// +// ENABLE_HIL OPTIONAL +// +// This will output a binary control string to for use in HIL sims +// such as Xplane 9 or FlightGear. +// +//#define ENABLE_HIL ENABLED +// + + +////////////////////////////////////////////////////////////////////////////// +// AIRSPEED_CRUISE OPTIONAL +// +// The speed in metres per second to maintain during cruise. The default +// is 10m/s, which is a conservative value suitable for relatively small, +// light aircraft. +// +//#define AIRSPEED_CRUISE 10 +// + +////////////////////////////////////////////////////////////////////////////// +// FLY_BY_WIRE_B airspeed control +// +// AIRSPEED_FBW_MIN OPTIONAL +// AIRSPEED_FBW_MAX OPTIONAL +// +// Airspeed corresponding to minimum and maximum throttle in Fly By Wire B mode. +// The defaults are 6 and 30 metres per second. +// +// THROTTLE_ALT_P OPTIONAL +// THROTTLE_ALT_I OPTIONAL +// THROTTLE_ALT_D OPTIONAL +// +// P, I and D terms for the throttle control loop. Defaults are 0.5, 0, 0. +// +// THROTTLE_ALT_INT_MAX OPTIONAL +// +// Maximum throttle input due to the integral. Limits the throttle input +// due to persistent inability to maintain the commanded speed. Helps +// prevent the throttle from staying wide open when the control is reduced +// after a period at maxium speed. +// Default is 20 (20%). +// +//#define AIRSPEED_FBW_MIN 6 +//#define AIRSPEED_FBW_MAX 30 +//#define THROTTLE_ALT_P 0.32 +//#define THROTTLE_ALT_I 0.04 +//#define THROTTLE_ALT_D 0.0 +//#define THROTTLE_ALT_INT_MAX 20 +// + +////////////////////////////////////////////////////////////////////////////// +// Throttle control +// +// THROTTLE_MIN OPTIONAL +// +// The minimum throttle setting to which the autopilot will reduce the +// throttle while descending. The default is zero, which is +// suitable for aircraft with a steady power-off glide. Increase this +// value if your aircraft needs throttle to maintain a stable descent in +// level flight. +// +// THROTTLE_CRUISE OPTIONAL +// +// The approximate throttle setting to achieve AIRSPEED_CRUISE in level flight. +// The default is 45%, which is reasonable for a modestly powered aircraft. +// +// THROTTLE_MAX OPTIONAL +// +// The maximum throttle setting the autopilot will apply. The default is 75%. +// Reduce this value if your aicraft is overpowered, or has complex flight +// characteristics at high throttle settings. +// +//#define THROTTLE_MIN 0 +//#define THROTTLE_CRUISE 45 +//#define THROTTLE_MAX 75 +// + +////////////////////////////////////////////////////////////////////////////// +// Autopilot control limits +// +// HEAD_MAX OPTIONAL +// +// The maximum commanded bank angle in either direction. +// The default is 45 degrees. Decrease this value if your aircraft is not +// stable or has difficulty maintaining altitude in a steep bank. +// +// PITCH_MAX OPTIONAL +// +// The maximum commanded pitch up angle. +// The default is 15 degrees. Care should be taken not to set this value too +// large, as the aircraft may stall. +// +// PITCH_MIN +// +// The maximum commanded pitch down angle. Note that this value must be +// negative. The default is -25 degrees. Care should be taken not to set +// this value too large as it may result in overspeeding the aircraft. +// +//#define HEAD_MAX 45 +//#define PITCH_MAX 15 +//#define PITCH_MIN -25 + +////////////////////////////////////////////////////////////////////////////// +// Attitude control gains +// +// Tuning values for the attitude control PID loops. +// +// The P term is the primary tuning value. This determines how the control +// deflection varies in proportion to the required correction. +// +// The I term is used to help control surfaces settle. This value should +// normally be kept low. +// +// The D term is used to control overshoot. Avoid using or adjusting this +// term if you are not familiar with tuning PID loops. It should normally +// be zero for most aircraft. +// +// Note: When tuning these values, start with changes of no more than 25% at +// a time. +// +// SERVO_ROLL_P OPTIONAL +// SERVO_ROLL_I OPTIONAL +// SERVO_ROLL_D OPTIONAL +// +// P, I and D terms for roll control. Defaults are 0.4, 0, 0. +// +// SERVO_ROLL_INT_MAX OPTIONAL +// +// Maximum control offset due to the integral. This prevents the control +// output from being overdriven due to a persistent offset (e.g. crosstracking). +// Default is 5 degrees. +// +// ROLL_SLEW_LIMIT EXPERIMENTAL +// +// Limits the slew rate of the roll control in degrees per second. If zero, +// slew rate is not limited. Default is to not limit the roll control slew rate. +// (This feature is currently not implemented.) +// +// SERVO_PITCH_P OPTIONAL +// SERVO_PITCH_I OPTIONAL +// SERVO_PITCH_D OPTIONAL +// +// P, I and D terms for the pitch control. Defaults are 0.6, 0, 0. +// +// SERVO_PITCH_INT_MAX OPTIONAL +// +// Maximum control offset due to the integral. This prevents the control +// output from being overdriven due to a persistent offset (e.g. native flight +// AoA). If you find this value is insufficient, consider adjusting the AOA +// parameter. +// Default is 5 degrees. +// +// PITCH_COMP OPTIONAL +// +// Adds pitch input to compensate for the loss of lift due to roll control. +// Default is 0.20 (20% of roll control also applied to pitch control). +// +// SERVO_YAW_P OPTIONAL +// SERVO_YAW_I OPTIONAL +// SERVO_YAW_D OPTIONAL +// +// P, I and D terms for the YAW control. Defaults are 0.5, 0, 0. +// +// SERVO_YAW_INT_MAX OPTIONAL +// +// Maximum control offset due to the integral. This prevents the control +// output from being overdriven due to a persistent offset (e.g. crosstracking). +// Default is 5 degrees. +// +// RUDDER_MIX OPTIONAL +// +// Roll to yaw mixing. This allows for co-ordinated turns. +// Default is 0.50 (50% of roll control also applied to yaw control.) +// +//#define SERVO_ROLL_P 0.4 +//#define SERVO_ROLL_I 0.0 +//#define SERVO_ROLL_D 0.0 +//#define SERVO_ROLL_INT_MAX 5 +//#define ROLL_SLEW_LIMIT 0 +//#define SERVO_PITCH_P 0.6 +//#define SERVO_PITCH_I 0.0 +//#define SERVO_PITCH_D 0.0 +//#define SERVO_PITCH_INT_MAX 5 +//#define PITCH_COMP 0.2 +//#define SERVO_YAW_P 0.5 +//#define SERVO_YAW_I 0.0 +//#define SERVO_YAW_D 0.0 +//#define SERVO_YAW_INT_MAX 5 +//#define RUDDER_MIX 0.5 +// + +////////////////////////////////////////////////////////////////////////////// +// Navigation control gains +// +// Tuning values for the navigation control PID loops. +// +// The P term is the primary tuning value. This determines how the control +// deflection varies in proportion to the required correction. +// +// The I term is used to control drift. +// +// The D term is used to control overshoot. Avoid adjusting this term if +// you are not familiar with tuning PID loops. +// +// Note: When tuning these values, start with changes of no more than 25% at +// a time. +// +// NAV_ROLL_P OPTIONAL +// NAV_ROLL_I OPTIONAL +// NAV_ROLL_D OPTIONAL +// +// P, I and D terms for navigation control over roll, normally used for +// controlling the aircraft's course. The P term controls how aggressively +// the aircraft will bank to change or hold course. +// Defaults are 0.7, 0.01, 0.02. +// +// NAV_ROLL_INT_MAX OPTIONAL +// +// Maximum control offset due to the integral. This prevents the control +// output from being overdriven due to a persistent offset (e.g. crosstracking). +// Default is 5 degrees. +// +// NAV_PITCH_ASP_P OPTIONAL +// NAV_PITCH_ASP_I OPTIONAL +// NAV_PITCH_ASP_D OPTIONAL +// +// P, I and D terms for pitch adjustments made to maintain airspeed. +// Defaults are 0.65, 0, 0. +// +// NAV_PITCH_ASP_INT_MAX OPTIONAL +// +// Maximum pitch offset due to the integral. This limits the control +// output from being overdriven due to a persistent offset (eg. inability +// to maintain the programmed airspeed). +// Default is 5 degrees. +// +// NAV_PITCH_ALT_P OPTIONAL +// NAV_PITCH_ALT_I OPTIONAL +// NAV_PITCH_ALT_D OPTIONAL +// +// P, I and D terms for pitch adjustments made to maintain altitude. +// Defaults are 0.65, 0, 0. +// +// NAV_PITCH_ALT_INT_MAX OPTIONAL +// +// Maximum pitch offset due to the integral. This limits the control +// output from being overdriven due to a persistent offset (eg. inability +// to maintain the programmed altitude). +// Default is 5 degrees. +// +//#define NAV_ROLL_P 0.7 +//#define NAV_ROLL_I 0.01 +//#define NAV_ROLL_D 0.02 +//#define NAV_ROLL_INT_MAX 5 +//#define NAV_PITCH_ASP_P 0.65 +//#define NAV_PITCH_ASP_I 0.0 +//#define NAV_PITCH_ASP_D 0.0 +//#define NAV_PITCH_ASP_INT_MAX 5 +//#define NAV_PITCH_ALT_P 0.65 +//#define NAV_PITCH_ALT_I 0.0 +//#define NAV_PITCH_ALT_D 0.0 +//#define NAV_PITCH_ALT_INT_MAX 5 +// + +////////////////////////////////////////////////////////////////////////////// +// Energy/Altitude control gains +// +// The Energy/altitude control system uses throttle input to control aircraft +// altitude. +// +// The P term is the primary tuning value. This determines how the throttle +// setting varies in proportion to the required correction. +// +// The I term is used to compensate for small offsets. +// +// The D term is used to control overshoot. Avoid adjusting this term if +// you are not familiar with tuning PID loops. +// +// THROTTLE_TE_P OPTIONAL +// THROTTLE_TE_I OPTIONAL +// THROTTLE_TE_D OPTIONAL +// +// P, I and D terms for throttle adjustments made to control altitude. +// Defaults are 0.5, 0, 0. +// +// THROTTLE_TE_INT_MAX OPTIONAL +// +// Maximum throttle input due to the integral term. This limits the +// throttle from being overdriven due to a persistent offset (e.g. +// inability to maintain the programmed altitude). +// Default is 20%. +// +// THROTTLE_SLEW_LIMIT OPTIONAL +// +// Limits the slew rate of the throttle, in percent per second. Helps +// avoid sudden throttle changes, which can destabilise the aircraft. +// A setting of zero disables the feature. +// Default is zero (disabled). +// +// P_TO_T OPTIONAL +// +// Pitch to throttle feed-forward gain. Used when AIRSPEED_SENSOR +// is DISABLED. Default is 2.5. +// +//#define THROTTLE_TE_P 0.50 +//#define THROTTLE_TE_I 0.0 +//#define THROTTLE_TE_D 0.0 +//#define THROTTLE_TE_INT_MAX 20 +//#define THROTTLE_SLEW_LIMIT 0 +//#define P_TO_T 2.5 +// + +////////////////////////////////////////////////////////////////////////////// +// Crosstrack compensation +// +// XTRACK_GAIN OPTIONAL +// +// Crosstrack compensation in degrees per metre off track. +// Default value is 0.01 degrees per metre. Values lower than 0.001 will +// disable crosstrack compensation. +// +// XTRACK_ENTRY_ANGLE OPTIONAL +// +// Maximum angle used to correct for track following. +// Default value is 30 degrees. +// +//#define XTRACK_GAIN 0.01 +//#define XTRACK_ENTRY_ANGLE 30 +// + +////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////// +// DEBUGGING +////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////// + +////////////////////////////////////////////////////////////////////////////// +// Subsystem test and debug. +// +// DEBUG_SUBSYSTEM DEBUG +// +// Selects a subsystem debug mode. Default is 0. +// +// 0 = no debug +// 1 = Debug the Radio input +// 2 = Radio Setup / Servo output +// 4 = Debug the GPS input +// 5 = Debug the GPS input - RAW OUTPUT +// 6 = Debug the IMU +// 7 = Debug the Control Switch +// 8 = Debug the Servo DIP switches +// 9 = Debug the Relay out +// 10 = Debug the Magnetometer +// 11 = Debug the ABS pressure sensor +// 12 = Debug the stored waypoints +// 13 = Debug the Throttle +// 14 = Debug the Radio Min Max +// 15 = Debug the EEPROM - Hex Dump +// 16 = XBee X-CTU Range and RSSI Test +// 17 = Debug IMU - raw gyro and accel outputs +// 20 = Debug Analog Sensors +// +// +//#define DEBUG_SUBSYSTEM 0 +// + +////////////////////////////////////////////////////////////////////////////// +// DEBUG_LEVEL DEBUG +// +// Selects the lowest level of debug messages passed to the telemetry system. +// Default is SEVERITY_LOW. May be one of: +// +// SEVERITY_LOW +// SEVERITY_MEDIUM +// SEVERITY_HIGH +// SEVERITY_CRITICAL +// +//#define DEBUG_LEVEL SEVERITY_LOW +// + +////////////////////////////////////////////////////////////////////////////// +// Dataflash logging control +// +// Each of these logging options may be set to ENABLED to enable, or DISABLED +// to disable the logging of the respective data. +// +// LOG_ATTITUDE_FAST DEBUG +// +// Logs basic attitude info to the dataflash at 50Hz (uses more space). +// Defaults to DISABLED. +// +// LOG_ATTITUDE_MED OPTIONAL +// +// Logs basic attitude info to the dataflash at 10Hz (uses less space than +// LOG_ATTITUDE_FAST). Defaults to ENABLED. +// +// LOG_GPS OPTIONAL +// +// Logs GPS info to the dataflash at 10Hz. Defaults to ENABLED. +// +// LOG_PM OPTIONAL +// +// Logs IMU performance monitoring info every 20 seconds. +// Defaults to DISABLED. +// +// LOG_CTUN OPTIONAL +// +// Logs control loop tuning info at 10 Hz. This information is useful for tuning +// servo control loop gain values. Defaults to DISABLED. +// +// LOG_NTUN OPTIONAL +// +// Logs navigation tuning info at 10 Hz. This information is useful for tuning +// navigation control loop gain values. Defaults to DISABLED. +// +// LOG_ MODE OPTIONAL +// +// Logs changes to the flight mode upon occurrence. Defaults to ENABLED. +// +// LOG_RAW DEBUG +// +// Logs raw accelerometer and gyro data at 50 Hz (uses more space). +// Defaults to DISABLED. +// +// LOG_CMD OPTIONAL +// +// Logs new commands when they process. +// Defaults to ENABLED. +// +//#define LOG_ATTITUDE_FAST DISABLED +//#define LOG_ATTITUDE_MED ENABLED +//#define LOG_GPS ENABLED +//#define LOG_PM ENABLED +//#define LOG_CTUN DISABLED +//#define LOG_NTUN DISABLED +//#define LOG_MODE ENABLED +//#define LOG_RAW DISABLED +//#define LOG_CMD ENABLED +// + +////////////////////////////////////////////////////////////////////////////// +// Navigation defaults +// +// WP_RADIUS_DEFAULT OPTIONAL +// +// When the user performs a factory reset on the APM, set the waypoint radius +// (the radius from a target waypoint within which the APM will consider +// itself to have arrived at the waypoint) to this value in meters. This is +// mainly intended to allow users to start using the APM without running the +// WaypointWriter first. +// +// LOITER_RADIUS_DEFAULT OPTIONAL +// +// When the user performs a factory reset on the APM, set the loiter radius +// (the distance the APM will attempt to maintain from a waypoint while +// loitering) to this value in meters. This is mainly intended to allow +// users to start using the APM without running the WaypointWriter first. +// +//#define WP_RADIUS_DEFAULT 20 +//#define LOITER_RADIUS_DEFAULT 30 +// + +////////////////////////////////////////////////////////////////////////////// +// Debugging interface +// +// DEBUG_PORT OPTIONAL +// +// The APM will periodically send messages reporting what it is doing; this +// variable determines to which serial port they will be sent. Port 0 is the +// USB serial port on the shield, port 3 is the telemetry port. +// +//#define DEBUG_PORT 0 +// + +// +// Do not remove - this is to discourage users from copying this file +// and using it as-is rather than editing their own. +// +#error You should not copy APM_Config.h.reference - make your own APM_Config.h file with just the options you need. diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/APM_Config_xplane.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/APM_Config_xplane.h new file mode 100644 index 0000000000..06a3078582 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/APM_Config_xplane.h @@ -0,0 +1,19 @@ +#define DEBUG_SUBSYSTEM 0 + +#define FLIGHT_MODE_CHANNEL 8 +#define FLIGHT_MODE_1 AUTO +#define FLIGHT_MODE_2 RTL +#define FLIGHT_MODE_3 FLY_BY_WIRE_A +#define FLIGHT_MODE_4 FLY_BY_WIRE_B +#define FLIGHT_MODE_5 STABILIZE +#define FLIGHT_MODE_6 MANUAL + +#define GCS_PROTOCOL GCS_PROTOCOL_DEBUGTERMINAL +#define ENABLE_HIL ENABLED +#define GCS_PORT 3 +#define GPS_PROTOCOL GPS_PROTOCOL_IMU +#define AIRSPEED_CRUISE 25 + +#define THROTTLE_FAILSAFE ENABLED +#define AIRSPEED_SENSOR ENABLED + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/ArduPilotMega.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/ArduPilotMega.pde new file mode 100644 index 0000000000..f5dfaef424 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/ArduPilotMega.pde @@ -0,0 +1,845 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- + +/* +ArduPilotMega Version 1.0.3 Public Alpha +Authors: Doug Weibel, Jose Julio, Jordi Munoz, Jason Short +Thanks to: Chris Anderson, HappyKillMore, Bill Premerlani, James Cohen, JB from rotorFX, Automatik, Fefenin, Peter Meister, Remzibi +Please contribute your ideas! + + +This firmware is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. +*/ + +// Libraries +#include +#include +#include +#include // ArduPilot Mega RC Library +#include // ArduPilot Mega Analog to Digital Converter Library +#include // ArduPilot GPS library +#include +#include // ArduPilot Mega BMP085 Library +#include // ArduPilot Mega Flash Memory Library +#include // ArduPilot Mega Magnetometer Library + +// AVR runtime +#include +#include +#include +#include + +// Configuration +#include "config.h" + +// Local modules +#include "defines.h" + +// Serial ports +// +// Note that FastSerial port buffers are allocated at ::begin time, +// so there is not much of a penalty to defining ports that we don't +// use. +// +FastSerialPort0(Serial); // FTDI/console +FastSerialPort1(Serial1); // GPS port (except for GPS_PROTOCOL_IMU) +//FastSerialPort3(Serial3); // Telemetry port (optional, Standard and ArduPilot protocols only) + +// GPS selection +#if GPS_PROTOCOL == GPS_PROTOCOL_NMEA +AP_GPS_NMEA GPS(&Serial1); +#elif GPS_PROTOCOL == GPS_PROTOCOL_SIRF +AP_GPS_SIRF GPS(&Serial1); +#elif GPS_PROTOCOL == GPS_PROTOCOL_UBLOX +AP_GPS_UBLOX GPS(&Serial1); +#elif GPS_PROTOCOL == GPS_PROTOCOL_IMU +AP_GPS_IMU GPS(&Serial); // note, console port +#elif GPS_PROTOCOL == GPS_PROTOCOL_MTK +AP_GPS_MTK GPS(&Serial1); +#elif GPS_PROTOCOL == GPS_PROTOCOL_NONE +AP_GPS_NONE GPS(NULL); +#else +# error Must define GPS_PROTOCOL in your configuration file. +#endif + +// The X-Plane GCS requires the IMU GPS configuration +#if (ENABLE_HIL == ENABLED) && (GPS_PROTOCOL != GPS_PROTOCOL_IMU) +# error Must select GPS_PROTOCOL_IMU when configuring for X-Plane +#endif + +// GENERAL VARIABLE DECLARATIONS +// -------------------------------------------- +byte control_mode = MANUAL; +boolean failsafe = false; // did our throttle dip below the failsafe value? +boolean ch3_failsafe = false; +byte crash_timer; +byte oldSwitchPosition; // for remembering the control mode switch +boolean reverse_switch = 1; // do we read the reversing switches after startup? + +byte ground_start_count = 6; // have we achieved first lock and set Home? +int ground_start_avg; // 5 samples to avg speed for ground start +boolean ground_start = false; // have we started on the ground? +char *comma = ","; + +char* flight_mode_strings[] = { + "Manual", + "Circle", + "Stabilize", + "", + "", + "FBW_A", + "FBW_B", + "", + "", + "", + "Auto", + "RTL", + "Loiter", + "Takeoff", + "Land"}; + + +/* Radio values + Channel assignments + 1 Ailerons (rudder if no ailerons) + 2 Elevator + 3 Throttle + 4 Rudder (if we have ailerons) + 5 Mode + 6 TBD + 7 TBD + 8 TBD +*/ + +int radio_min[8]; // may be reset by init sequence +int radio_trim[8]; // may be reset by init sequence +int radio_max[8]; // may be reset by init sequence +int radio_in[8]; // current values from the transmitter - microseconds +int radio_out[8]; // Send to the PWM library +int servo_out[8]; // current values to the servos - degrees * 100 (approx assuming servo is -45 to 45 degrees except [3] is 0 to 100 + +int elevon1_trim = 1500; +int elevon2_trim = 1500; +int ch1_temp = 1500; // Used for elevon mixing +int ch2_temp = 1500; + +int reverse_roll = 1; +int reverse_pitch = 1; +int reverse_rudder = 1; +byte mix_mode = 0; // 0 = normal , 1 = elevons +int reverse_elevons = 1; +int reverse_ch1_elevon = 1; +int reverse_ch2_elevon = 1; +byte yaw_mode; + +byte flight_mode_channel; +byte flight_modes[6]; +byte auto_trim; + +// for elevons radio_in[CH_ROLL] and radio_in[CH_PITCH] are equivalent aileron and elevator, not left and right elevon + + +/* PID Control variables + Cases + 1 Aileron servo control (rudder if no ailerons) + 2 Elevator servo control + 3 Rudder servo control (if we have ailerons) + 4 Roll set-point control + 5 Pitch set-point based on airspeed error control + 6 Pitch set-point based on altitude error control (if we do not have airspeed sensor) + 7 Throttle based on Energy Height (Total Energy) error control + 8 Throttle based on altitude error control +*/ + +float kp[8]; +float ki[8]; +float kd[8]; +uint16_t integrator_max[8]; // PID Integrator Max deg * 100 +float integrator[8]; // PID Integrators deg * 100 +long last_error[8]; // PID last error for derivative +float nav_gain_scaler = 1; // Gain scaling for headwind/tailwind + + +/* Feed Forward gains + Cases + 1 Bank angle to desired pitch (Pitch Comp) + 2 Aileron Servo to Rudder Servo + 3 Pitch to Throttle +*/ + +float kff[3]; + + +// GPS variables +// ------------- +const float t7 = 10000000.0; // used to scale GPS values for EEPROM storage +float scaleLongUp; // used to reverse longtitude scaling +float scaleLongDown; // used to reverse longtitude scaling +boolean GPS_light = false; // status of the GPS light + +// Location & Navigation +// --------------------- +byte wp_radius = 20; // meters +long hold_course = -1; // deg * 100 dir of plane +long nav_bearing; // deg * 100 : 0 to 360 current desired bearing to navigate +long target_bearing; // deg * 100 : 0 to 360 location of the plane to the target +long crosstrack_bearing; // deg * 100 : 0 to 360 desired angle of plane to target +int climb_rate; // m/s * 100 - For future implementation of controlled ascent/descent by rate +byte loiter_radius; // meters +float x_track_gain; +int x_track_angle; + +long head_max; +long pitch_max; +long pitch_min; +float altitude_mix; + +byte command_must_index; // current command memory location +byte command_may_index; // current command memory location +byte command_must_ID; // current command ID +byte command_may_ID; // current command ID +//byte EEPROM_command // 1 = from the list, 0 = generated + + +// Airspeed +// -------- +int airspeed; // m/s * 100 +int airspeed_cruise; // m/s * 100 : target airspeed sensor value +float airspeed_ratio; // used to scale airspeed +byte airspeed_fbw_min; // m/s +byte airspeed_fbw_max; // m/s + +// Throttle Failsafe +// ------------------ +byte throttle_failsafe_enabled; +int throttle_failsafe_value; +byte throttle_failsafe_action; +uint16_t log_bitmask; + +// Location Errors +// --------------- +long bearing_error; // deg * 100 : 0 to 36000 +long altitude_error; // meters * 100 we are off in altitude +float airspeed_error; // m/s * 100 +float crosstrack_error; // meters we are off trackline +long energy_error; // energy state error (kinetic + potential) for altitude hold +long airspeed_energy_error; // kinetic portion of energy error + +// Sensors +// -------- +float airpressure_raw; // Airspeed Sensor - is a float to better handle filtering +int airpressure_offset; // analog air pressure sensor while still +int airpressure; // airspeed as a pressure value +float battery_voltage = LOW_VOLTAGE * 1.05; // Battery Voltage of total battery, initialized above threshold for filter +float battery_voltage1 = LOW_VOLTAGE * 1.05; // Battery Voltage of cell 1, initialized above threshold for filter +float battery_voltage2 = LOW_VOLTAGE * 1.05; // Battery Voltage of cells 1+2, initialized above threshold for filter +float battery_voltage3 = LOW_VOLTAGE * 1.05; // Battery Voltage of cells 1+2+3, initialized above threshold for filter +float battery_voltage4 = LOW_VOLTAGE * 1.05; // Battery Voltage of cells 1+2+3+4, initialized above threshold for filter + +// From IMU +long roll_sensor; // degrees * 100 +long pitch_sensor; // degrees * 100 +long yaw_sensor; // degrees * 100 + +float roll; // radians +float pitch; // radians +float yaw; // radians + + +// Magnetometer variables +int magnetom_x; // Doug to do +int magnetom_y; +int magnetom_z; +float MAG_Heading; + +// Pressure Sensor variables +unsigned long abs_press; +unsigned long abs_press_filt; +unsigned long abs_press_gnd; +int ground_temperature; +int temp_unfilt; +long ground_alt; // Ground altitude from gps at startup in centimeters +long press_alt; // Pressure altitude + +// flight mode specific +// -------------------- +//boolean takeoff_complete = false; // Flag for using take-off controls +boolean land_complete = false; +int landing_pitch; // pitch for landing set by commands +int takeoff_pitch; +int takeoff_altitude; +int landing_distance; // meters; + +// Loiter management +// ----------------- +long old_target_bearing; // deg * 100 +int loiter_total; // deg : how many times to loiter * 360 +int loiter_delta; // deg : how far we just turned +int loiter_sum; // deg : how far we have turned around a waypoint +long loiter_time; // millis : when we started LOITER mode +int loiter_time_max; // millis : how long to stay in LOITER mode + +// these are the values for navigation control functions +// ---------------------------------------------------- +long nav_roll; // deg * 100 : target roll angle +long nav_pitch; // deg * 100 : target pitch angle +long altitude_estimate; // for smoothing GPS output + +int throttle_min; // 0-100 : target throttle output for average speed +int throttle_cruise; // 0-100 : target throttle output for average speed +int throttle_max; // 0-100 : target throttle output for average speed + +// Waypoints +// --------- +long wp_distance; // meters - distance between plane and next waypoint +long wp_totalDistance; // meters - distance between old and next waypoint +byte wp_total; // # of Commands total including way +byte wp_index; // Current active command index +byte next_wp_index; // Current active command index + +// repeating event control +// ----------------------- +byte event_id; // what to do - see defines +long event_timer; // when the event was asked for in ms +int event_delay; // how long to delay the next firing of event in millis +int event_repeat; // how many times to fire : 0 = forever, 1 = do once, 2 = do twice +int event_value; // per command value, such as PWM for servos +int event_undo_value; // the value used to undo commands +byte repeat_forever; +byte undo_event; // counter for timing the undo + +// delay command +// -------------- +int delay_timeout = 0; // used to delay commands +long delay_start = 0; // used to delay commands + +// 3D Location vectors +// ------------------- +struct Location home; // home location +struct Location prev_WP; // last waypoint +struct Location current_loc; // current location +struct Location next_WP; // next waypoint +struct Location tell_command; // command for telemetry +struct Location next_command; // command preloaded +long target_altitude; // used for +long offset_altitude; // used for +int hold_alt_above_home; +boolean home_is_set = false; // Flag for if we have gps lock and have set the home location + + +// IMU variables +// ------------- + +//Sensor: GYROX, GYROY, GYROZ, ACCELX, ACCELY, ACCELZ +uint8_t sensors[6] = {1,2,0,4,5,6}; // For ArduPilot Mega Sensor Shield Hardware +int SENSOR_SIGN[] = { 1, -1, -1, + -1, 1, 1, + -1, -1, -1}; + +// Temp compensation curve constants +// These must be produced by measuring data and curve fitting +// [X / Y/Z gyro][A / B/C or 0 order / 1st order / 2nd order constants] +// values may migrate to a Config file +float GTC[3][3]={{1665, 0, 0}, + {1665, 0, 0}, + {1665, 0, 0}}; + +float AN[6]; // array that store the 6 ADC channels used by IMU +float AN_OFFSET[6]; // Array that store the Offset of the gyros and accelerometers +float G_Dt = 0.02; // Integration time for the gyros (DCM algorithm) +float Accel_Vector[3]; // Store the acceleration in a vector +float Accel_Vector_unfiltered[3]; // Store the acceleration in a vector +float Gyro_Vector[3]; // Store the gyros turn rate in a vector +float Omega_Vector[3]; // Corrected Gyro_Vector data +float Omega_P[3]; // Omega Proportional correction +float Omega_I[3]; // Omega Integrator +float Omega[3]; +float errorRollPitch[3]; +float errorYaw[3]; +float errorCourse; +float COGX; // Course overground X axis +float COGY = 1; // Course overground Y axis + +float DCM_Matrix[3][3] = {{1,0,0}, + {0,1,0}, + {0,0,1}}; + +float Update_Matrix[3][3] = {{0,1,2}, + {3,4,5}, + {6,7,8}}; + +float Temporary_Matrix[3][3]; + +// Performance monitoring +// ---------------------- +long perf_mon_timer; +float imu_health; // Metric based on accel gain deweighting +int G_Dt_max; // Max main loop cycle time in milliseconds +byte gyro_sat_count; +byte adc_constraints; +byte renorm_sqrt_count; +byte renorm_blowup_count; +int gps_fix_count; +byte gcs_messages_sent; + + +// GCS +// --- +char GCS_buffer[53]; + +// System Timers +// -------------- +unsigned long fast_loopTimer; // Time in miliseconds of main control loop +unsigned long medium_loopTimer; // Time in miliseconds of navigation control loop +byte medium_loopCounter = 0; // Counters for branching from main control loop to slower loops +byte slow_loopCounter = 0; +byte superslow_loopCounter = 0; +unsigned long deltaMiliSeconds; // Delta Time in miliseconds +unsigned long dTnav; // Delta Time in milliseconds for navigation computations +int mainLoop_count; +unsigned long elapsedTime; // for doing custom events +unsigned int GPS_timer; + +//******************************************************************************************************************************** +//******************************************************************************************************************************** +//******************************************************************************************************************************** +//******************************************************************************************************************************** +//******************************************************************************************************************************** + +// Basic Initialization +//--------------------- +void setup() { + jeti_init(); + jeti_status(" ** X-DIY **"); + jeti_update; + init_ardupilot(); +} + +void loop() +{ + // We want this to execute at 50Hz if possible + // ------------------------------------------- + if (millis()-fast_loopTimer > 19) { + deltaMiliSeconds = millis() - fast_loopTimer; + G_Dt = (float)deltaMiliSeconds / 1000.f; + fast_loopTimer = millis(); + mainLoop_count++; + + // Execute the fast loop + // --------------------- + fast_loop(); + + // Execute the medium loop + // ----------------------- + medium_loop(); + + if (millis()- perf_mon_timer > 20000) { + if (mainLoop_count != 0) { + send_message(MSG_PERF_REPORT); + if (log_bitmask & MASK_LOG_PM) + Log_Write_Performance(); + + resetPerfData(); + } + } + } +} + +void fast_loop() +{ + // This is the fast loop - we want it to execute at 50Hz if possible + // ----------------------------------------------------------------- + if (deltaMiliSeconds > G_Dt_max) + G_Dt_max = deltaMiliSeconds; + + // Read radio + // ---------- + read_radio(); + + // check for throttle failsafe condition + // ------------------------------------ +#if THROTTLE_FAILSAFE == 1 + set_failsafe(ch3_failsafe); +#endif + + + // read in the plane's attitude + // ---------------------------- +#if GPS_PROTOCOL == GPS_PROTOCOL_IMU + GPS.update(); + airspeed = (float)GPS.airspeed; //airspeed is * 100 coming in from Xplane for accuracy + calc_airspeed_errors(); + + if(digitalRead(SLIDE_SWITCH_PIN) == 0) { + read_AHRS(); + roll_sensor = -roll_sensor; + pitch_sensor = -pitch_sensor; + //yaw_sensor = -yaw_sensor; + }else{ + roll_sensor = GPS.roll_sensor; + pitch_sensor = GPS.pitch_sensor; + yaw_sensor = GPS.ground_course; + } + +#else + // Read Airspeed + // ------------- + #if AIRSPEED_SENSOR == 1 + read_airspeed(); + #endif + + read_AHRS(); + + if (log_bitmask & MASK_LOG_ATTITUDE_FAST) + Log_Write_Attitude((int)roll_sensor, (int)pitch_sensor, (uint16_t)yaw_sensor); + + if (log_bitmask & MASK_LOG_RAW) + Log_Write_Raw(); +#endif + + // altitude smoothing + // ------------------ + if (control_mode != FLY_BY_WIRE_B) + calc_altitude_error(); + + // custom code/exceptions for flight modes + // --------------------------------------- + update_current_flight_mode(); + + // apply desired roll, pitch and yaw to the plane + // ---------------------------------------------- + if (control_mode > MANUAL) + stabilize(); + + // write out the servo PWM values + // ------------------------------ + set_servos_4(); + +#if ENABLE_HIL + output_HIL(); +#endif + +#if GCS_PROTOCOL == GCS_PROTOCOL_DEBUGTERMINAL + readgcsinput(); +#endif +} + +void medium_loop() +{ + // This is the start of the medium (10 Hz) loop pieces + // ----------------------------------------- + switch(medium_loopCounter) { + + // This case deals with the GPS + //------------------------------- + case 0: + medium_loopCounter++; + update_GPS(); + + #if MAGNETOMETER == 1 + APM_Compass.Read(); // Read magnetometer + APM_Compass.Calculate(roll,pitch); // Calculate heading + #endif + + break; + + // This case performs some navigation computations + //------------------------------------------------ + case 1: + medium_loopCounter++; + + if(GPS.new_data){ + dTnav = millis() - medium_loopTimer; + medium_loopTimer = millis(); + } + + // calculate the plane's desired bearing + // ------------------------------------- + navigate(); + break; + + // unused? no, jeti gets updated :-) + //------------------------------ + case 2: + medium_loopCounter++; + + // perform next command + // -------------------- + update_commands(); + jeti_update(); + break; + + // This case deals with sending high rate telemetry + //------------------------------------------------- + case 3: + medium_loopCounter++; + + if ((log_bitmask & MASK_LOG_ATTITUDE_MED) && !(log_bitmask & MASK_LOG_ATTITUDE_FAST)) + Log_Write_Attitude((int)roll_sensor, (int)pitch_sensor, (uint16_t)yaw_sensor); + + if (log_bitmask & MASK_LOG_CTUN) + Log_Write_Control_Tuning(); + + if (log_bitmask & MASK_LOG_NTUN) + Log_Write_Nav_Tuning(); + + if (log_bitmask & MASK_LOG_GPS) + Log_Write_GPS(GPS.time, current_loc.lat, current_loc.lng, GPS.altitude, current_loc.alt, (long) GPS.ground_speed, GPS.ground_course, GPS.fix, GPS.num_sats); + + send_message(MSG_ATTITUDE); // Sends attitude data + break; + + // This case controls the slow loop + //--------------------------------- + case 4: + medium_loopCounter=0; + slow_loop(); + break; + } +} + +void slow_loop() +{ + // This is the slow (3 1/3 Hz) loop pieces + //---------------------------------------- + switch (slow_loopCounter){ + case 0: + slow_loopCounter++; + superslow_loopCounter++; + if(superslow_loopCounter >=15) { + // keep track of what page is in use in the log + // *** We need to come up with a better scheme to handle this... + eeprom_write_word((uint16_t *) EE_LAST_LOG_PAGE, DataFlash.GetWritePage()); + superslow_loopCounter = 0; + } + break; + + case 1: + slow_loopCounter++; + + // Read 3-position switch on radio + // ------------------------------- + read_control_switch(); + + // Read Control Surfaces/Mix switches + // ---------------------------------- + if(reverse_switch){ + update_servo_switches(); + } + + // Read main battery voltage if hooked up - does not read the 5v from radio + // ------------------------------------------------------------------------ + #if BATTERY_EVENT == 1 + read_battery(); + #endif + + // Read Baro pressure + // ------------------ + read_airpressure(); + break; + + case 2: + slow_loopCounter = 0; + update_events(); + break; + } +} + + +void update_GPS(void) +{ + GPS.update(); + update_GPS_light(); + + if (GPS.new_data && GPS.fix) { + GPS_timer = millis(); + send_message(MSG_LOCATION); + + // for performance + // --------------- + gps_fix_count++; + + if(ground_start_count > 1){ + ground_start_count--; + ground_start_avg += GPS.ground_speed; + + } else if (ground_start_count == 1) { + // We countdown N number of good GPS fixes + // so that the altitude is more accurate + // ------------------------------------- + if (current_loc.lat == 0) { + SendDebugln("!! bad loc"); + ground_start_count = 5; + + } else { + if(ENABLE_AIR_START == 1 && (ground_start_avg / 5) < SPEEDFILT) { + startup_ground(); + + if (log_bitmask & MASK_LOG_CMD) + Log_Write_Startup(TYPE_GROUNDSTART_MSG); + + init_home(); + } else if (ENABLE_AIR_START == 0) { + init_home(); + } + + ground_start_count = 0; + } + } + + + current_loc.lng = GPS.longitude; // Lon * 10**7 + current_loc.lat = GPS.latitude; // Lat * 10**7 + +#if GPS_PROTOCOL == GPS_PROTOCOL_IMU + current_loc.alt = GPS.altitude; +#else + current_loc.alt = ((1 - altitude_mix) * GPS.altitude) + (altitude_mix * press_alt); // alt_MSL centimeters (meters * 100) +#endif + + COGX = cos(ToRad(GPS.ground_course/100.0)); + COGY = sin(ToRad(GPS.ground_course/100.0)); + } +} + +void update_current_flight_mode(void) +{ + if(control_mode == AUTO){ + crash_checker(); + + switch(command_must_ID){ + case CMD_TAKEOFF: + #if USE_MAGNETOMETER == ENABLED + calc_nav_roll(); + #else + nav_roll = 0; + #endif + float scaler; + #if AIRSPEED_SENSOR == 1 + scaler = (float)airspeed / (float)airspeed_cruise; + nav_pitch = scaler * takeoff_pitch * 50; + #else + scaler = (float)GPS.ground_speed / (float)airspeed_cruise; + nav_pitch = scaler * takeoff_pitch * 50; + #endif + + nav_pitch = constrain(nav_pitch, 0l, (long)takeoff_pitch); + + servo_out[CH_THROTTLE] = throttle_max; //TODO: Replace with THROTTLE_TAKEOFF or other method of controlling throttle + // ****************************** + + // override pitch_sensor to limit porpoising + // pitch_sensor = constrain(pitch_sensor, -6000, takeoff_pitch * 100); + // throttle = passthrough + break; + + case CMD_LAND: + calc_nav_roll(); + + #if AIRSPEED_SENSOR == 1 + calc_nav_pitch(); + calc_throttle(); + #else + calc_nav_pitch(); // calculate nav_pitch just to use for calc_throttle + calc_throttle(); // throttle basedtest landing_pitch; // pitch held constant + #endif + + if (land_complete) { + servo_out[CH_THROTTLE] = 0; + } + break; + + default: + hold_course = -1; + calc_nav_roll(); + calc_nav_pitch(); + calc_throttle(); + break; + } + }else{ + switch(control_mode){ + case RTL: + case LOITER: + hold_course = -1; + crash_checker(); + calc_nav_roll(); + calc_nav_pitch(); + calc_throttle(); + break; + + case FLY_BY_WIRE_A: + // fake Navigation output using sticks + nav_roll = ((radio_in[CH_ROLL] - radio_trim[CH_ROLL]) * head_max * reverse_roll) / 350; + nav_pitch = ((radio_in[CH_PITCH] - radio_trim[CH_PITCH]) * 3500l * reverse_pitch) / 350; + + nav_roll = constrain(nav_roll, -head_max, head_max); + nav_pitch = constrain(nav_pitch, -3000, 3000); // trying to give more pitch authority + break; + + case FLY_BY_WIRE_B: + // fake Navigation output using sticks + // We use pitch_min because its magnitude is normally greater than pitch_max + nav_roll = ((radio_in[CH_ROLL] - radio_trim[CH_ROLL]) * head_max * reverse_roll) / 350; + altitude_error = ((radio_in[CH_PITCH] - radio_trim[CH_PITCH]) * pitch_min * -reverse_pitch) / 350; + nav_roll = constrain(nav_roll, -head_max, head_max); + + #if AIRSPEED_SENSOR == 1 + //airspeed_error = ((AIRSPEED_FBW_MAX - AIRSPEED_FBW_MIN) * servo_out[CH_THROTTLE] / 100) + AIRSPEED_FBW_MIN; + airspeed_error = ((int)(airspeed_fbw_max - airspeed_fbw_min) * servo_out[CH_THROTTLE]) + ((int)airspeed_fbw_min * 100); + // Intermediate calculation - airspeed_error is just desired airspeed at this point + airspeed_energy_error = (long)(((long)airspeed_error * (long)airspeed_error) - ((long)airspeed * (long)airspeed))/20000; //Changed 0.00005f * to / 20000 to avoid floating point calculation + airspeed_error = (airspeed_error - airspeed); + + #endif + + calc_throttle(); + calc_nav_pitch(); + break; + + case STABILIZE: + nav_roll = 0; + nav_pitch = 0; + // throttle is passthrough + break; + + case CIRCLE: + // we have no GPS installed and have lost radio contact + // or we just want to fly around in a gentle circle w/o GPS + // ---------------------------------------------------- + nav_roll = head_max / 3; + nav_pitch = 0; + + if (failsafe == true){ + servo_out[CH_THROTTLE] = throttle_cruise; + } + break; + + case MANUAL: + // servo_out is for Sim control only + // --------------------------------- + servo_out[CH_ROLL] = reverse_roll * (radio_in[CH_ROLL] - radio_trim[CH_ROLL]) * 9; + servo_out[CH_PITCH] = reverse_pitch * (radio_in[CH_PITCH] - radio_trim[CH_PITCH]) * 9; + servo_out[CH_RUDDER] = reverse_rudder * (radio_in[CH_RUDDER] - radio_trim[CH_RUDDER]) * 9; + break; + //roll: -13788.000, pitch: -13698.000, thr: 0.000, rud: -13742.000 + + } + } +} + +void read_AHRS(void) +{ + // Get gyro and accel data and perform IMU calculations + //----------------------------------------------------- + Read_adc_raw(); // Get current values for IMU sensors + Matrix_update(); // Integrate the DCM matrix + Normalize(); // Normalize the DCM matrix + Drift_correction(); // Perform drift correction + Euler_angles(); // Calculate pitch, roll, yaw for stabilization and navigation +} + + + + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/Attitude.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/Attitude.pde new file mode 100644 index 0000000000..97850fa696 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/Attitude.pde @@ -0,0 +1,343 @@ +//**************************************************************** +// Function that controls aileron/rudder, elevator, rudder (if 4 channel control) and throttle to produce desired attitude and airspeed. +//**************************************************************** + +void stabilize() +{ + float ch1_inf = 1.0; + float ch2_inf = 1.0; + float ch4_inf = 1.0; + + if(crash_timer > 0){ + nav_roll = 0; + } + + // For Testing Only + // roll_sensor = (radio_in[CH_RUDDER] - radio_trim[CH_RUDDER]) * 10; + // Serial.print(" roll_sensor "); + // Serial.print(roll_sensor,DEC); + + // Calculate dersired servo output for the roll + // --------------------------------------------- + servo_out[CH_ROLL] = PID((nav_roll - roll_sensor), deltaMiliSeconds, CASE_SERVO_ROLL, 1.0); + servo_out[CH_PITCH] = PID((nav_pitch + abs(roll_sensor * kff[CASE_PITCH_COMP]) - pitch_sensor), deltaMiliSeconds, CASE_SERVO_PITCH, 1.0); + //Serial.print(" servo_out[CH_ROLL] "); + //Serial.print(servo_out[CH_ROLL],DEC); + + // Mix Stick input to allow users to override control surfaces + // ----------------------------------------------------------- + if ((control_mode < FLY_BY_WIRE_A) || (ENABLE_STICK_MIXING == 1 && control_mode > FLY_BY_WIRE_B)) { + + ch1_inf = (float)radio_in[CH_ROLL] - (float)radio_trim[CH_ROLL]; + ch1_inf = abs(ch1_inf); + ch1_inf = min(ch1_inf, 400.0); + ch1_inf = ((400.0 - ch1_inf) /400.0); + + ch2_inf = (float)radio_in[CH_PITCH] - radio_trim[CH_PITCH]; + ch2_inf = abs(ch2_inf); + ch2_inf = min(ch2_inf, 400.0); + ch2_inf = ((400.0 - ch2_inf) /400.0); + + // scale the sensor input based on the stick input + // ----------------------------------------------- + servo_out[CH_ROLL] *= ch1_inf; + servo_out[CH_PITCH] *= ch2_inf; + + // Mix in stick inputs + // ------------------- + servo_out[CH_ROLL] += reverse_roll * (radio_in[CH_ROLL] - radio_trim[CH_ROLL]) * 9; + servo_out[CH_PITCH] += reverse_pitch * (radio_in[CH_PITCH] - radio_trim[CH_PITCH]) * 9; + + //Serial.print(" servo_out[CH_ROLL] "); + //Serial.println(servo_out[CH_ROLL],DEC); + } + + // stick mixing performed for rudder for all cases including FBW unless disabled for higher modes + // important for steering on the ground during landing + // ----------------------------------------------- + if (control_mode <= FLY_BY_WIRE_B || ENABLE_STICK_MIXING == 1) { + ch4_inf = (float)radio_in[CH_RUDDER] - (float)radio_trim[CH_RUDDER]; + ch4_inf = abs(ch4_inf); + ch4_inf = min(ch4_inf, 400.0); + ch4_inf = ((400.0 - ch4_inf) /400.0); + } + + // Apply output to Rudder + // ---------------------- + calc_nav_yaw(); + servo_out[CH_RUDDER] *= ch4_inf; + servo_out[CH_RUDDER] += reverse_rudder * (radio_in[CH_RUDDER] - radio_trim[CH_RUDDER]) * 9; + + // Call slew rate limiter if used + // ------------------------------ + //#if(ROLL_SLEW_LIMIT != 0) + // servo_out[CH_ROLL] = roll_slew_limit(servo_out[CH_ROLL]); + //#endif +} + +void crash_checker() +{ + if(pitch_sensor < -4500){ + crash_timer = 255; + } + if(crash_timer > 0) + crash_timer--; +} + + +#if AIRSPEED_SENSOR == 0 +void calc_throttle() +{ + // no airspeed sensor, we use nav pitch to determin the proper throttle output + // AUTO, RTL, etc + // --------------------------------------------------------------------------- + if (nav_pitch >= 0) { + servo_out[CH_THROTTLE] = throttle_cruise + (THROTTLE_MAX - throttle_cruise) * nav_pitch / pitch_max; + } else { + servo_out[CH_THROTTLE] = throttle_cruise - (throttle_cruise - THROTTLE_MIN) * nav_pitch / pitch_min; + } + servo_out[CH_THROTTLE] = max(servo_out[CH_THROTTLE], 0); + + // are we going too slow? up the throttle to get some more groundspeed + // move into PID loop in the future + // lower the contstant value to limit the effect : 50 = default + int gs_boost = 30 * (1.0 - ((float)GPS.ground_speed / (float)airspeed_cruise)); + gs_boost = max(0, gs_boost); + servo_out[CH_THROTTLE] += gs_boost; + servo_out[CH_THROTTLE] = constrain(servo_out[CH_THROTTLE], THROTTLE_MIN, THROTTLE_MAX); +} +#endif + +#if AIRSPEED_SENSOR == 1 +void calc_throttle() +{ + // throttle control with airspeed compensation + // ------------------------------------------- + energy_error = airspeed_energy_error + (float)altitude_error * 0.098f; + + // positive energy errors make the throttle go higher + servo_out[CH_THROTTLE] = throttle_cruise + PID(energy_error, dTnav, CASE_TE_THROTTLE, 1.0); + servo_out[CH_THROTTLE] = max(servo_out[CH_THROTTLE], 0); + + // are we going too slow? up the throttle to get some more groundspeed + // move into PID loop in the future + // lower the contstant value to limit the effect : 50 = default + + //JASON - We really should change this to act on airspeed in this case. Let's visit about it.... + /*int gs_boost = 30 * (1.0 - ((float)GPS.ground_speed / (float)airspeed_cruise)); + gs_boost = max(0,gs_boost); + servo_out[CH_THROTTLE] += gs_boost;*/ + servo_out[CH_THROTTLE] = constrain(servo_out[CH_THROTTLE], THROTTLE_MIN, THROTTLE_MAX); +} +#endif + + + +/***************************************** + * Calculate desired roll angle (in medium freq loop) + *****************************************/ +// Yaw is separated into a function for future implementation of heading hold on take-off +// ---------------------------------------------------------------------------------------- +void calc_nav_yaw() +{ + // read_adc(4) is y axis accel; + // Control is a feedforward from the aileron control + a PID to coordinate the turn (drive y axis accel to zero) + servo_out[CH_RUDDER] = kff[CASE_RUDDER_MIX] * servo_out[CH_ROLL] + PID((long)read_adc(4), deltaMiliSeconds, CASE_SERVO_RUDDER, 1.0); + +} + + +#if AIRSPEED_SENSOR == 1 +void calc_nav_pitch() +{ + // Calculate the Pitch of the plane + // -------------------------------- + nav_pitch = -PID(airspeed_error, dTnav, CASE_NAV_PITCH_ASP, 1.0); + nav_pitch = constrain(nav_pitch, pitch_min, pitch_max); +} +#endif + +#if AIRSPEED_SENSOR == 0 +void calc_nav_pitch() +{ + // Calculate the Pitch of the plane + // -------------------------------- + nav_pitch = PID(altitude_error, dTnav, CASE_NAV_PITCH_ALT, 1.0); + nav_pitch = constrain(nav_pitch, pitch_min, pitch_max); +} +#endif + + +void calc_nav_roll() +{ + + // Adjust gain based on ground speed - We need lower nav gain going in to a headwind, etc. + // This does not make provisions for wind speed in excess of airframe speed + nav_gain_scaler = (float)GPS.ground_speed / (float)(AIRSPEED_CRUISE * 100); + nav_gain_scaler = constrain(nav_gain_scaler, 0.2, 1.4); + + // Jason -> I will implement the servo gain scaler some time, but it is independant of this scaling. + // Doug to implement the high speed servo gain scale + // use head max to limit turns, make a var + + // negative error = left turn + // positive error = right turn + // Calculate the required roll of the plane + // ---------------------------------------- + nav_roll = PID(bearing_error, dTnav, CASE_NAV_ROLL, nav_gain_scaler); //returns desired bank angle in degrees*100 + nav_roll = constrain(nav_roll,-head_max, head_max); + +} + + +/***************************************** + * Roll servo slew limit + *****************************************/ +/* +float roll_slew_limit(float servo) +{ + static float last; + float temp = constrain(servo, last-ROLL_SLEW_LIMIT * deltaMiliSeconds/1000.f, last + ROLL_SLEW_LIMIT * deltaMiliSeconds/1000.f); + last = servo; + return temp; +}*/ + +/***************************************** + * Throttle slew limit + *****************************************/ +/*float throttle_slew_limit(float throttle) +{ + static float last; + float temp = constrain(throttle, last-THROTTLE_SLEW_LIMIT * deltaMiliSeconds/1000.f, last + THROTTLE_SLEW_LIMIT * deltaMiliSeconds/1000.f); + last = throttle; + return temp; +} +*/ + +/***************************************** + * Proportional Integrator Derivative Control + *****************************************/ + +float PID(long PID_error, long dt, int PID_case, float scaler) +{ + // PID_case is used to keep track of which PID controller is being used - e.g. PID_servo_out[CH_ROLL] + float output, derivative; + + derivative = 1000.0f * (float)(PID_error - last_error[PID_case]) / (float)dt; + last_error[PID_case] = PID_error; + output = (kp[PID_case] * scaler * (float)PID_error); // Compute proportional component + //Positive error produces positive output + + integrator[PID_case] += (float)PID_error * ki[PID_case] * scaler * (float)dt / 1000.0f; + integrator[PID_case] = constrain(integrator[PID_case], -1.0*(float)integrator_max[PID_case], (float)integrator_max[PID_case]); + + output += integrator[PID_case]; // Add the integral component + output += kd[PID_case] * scaler * derivative; // Add the derivative component + return output; +} + +// Zeros out navigation Integrators if we are changing mode, have passed a waypoint, etc. +// Keeps outdated data out of our calculations +void reset_I(void) +{ + integrator[CASE_NAV_ROLL] = 0; + integrator[CASE_NAV_PITCH_ASP] = 0; + integrator[CASE_NAV_PITCH_ALT] = 0; + integrator[CASE_TE_THROTTLE] = 0; + integrator[CASE_ALT_THROTTLE] = 0; + + last_error[CASE_NAV_ROLL] = 0; + last_error[CASE_NAV_PITCH_ASP] = 0; + last_error[CASE_NAV_PITCH_ALT] = 0; + last_error[CASE_TE_THROTTLE] = 0; + last_error[CASE_ALT_THROTTLE] = 0; +} + +/***************************************** +* Set the flight control servos based on the current calculated values +*****************************************/ +void set_servos_4(void) +{ + if(control_mode == MANUAL){ + // do a direct pass through of radio values + for(int y=0; y<4; y++) { + radio_out[y] = radio_in[y]; + } + + } else { + if (mix_mode == 0){ + radio_out[CH_ROLL] = radio_trim[CH_ROLL] + (reverse_roll * ((float)servo_out[CH_ROLL] * 0.11111)); + radio_out[CH_PITCH] = radio_trim[CH_PITCH] + (reverse_pitch * ((float)servo_out[CH_PITCH] * 0.11111)); + radio_out[CH_RUDDER] = radio_trim[CH_RUDDER] + (reverse_rudder * ((float)servo_out[CH_RUDDER] * 0.11111)); + }else{ + /*Elevon mode*/ + float ch1; + float ch2; + ch1 = reverse_elevons * (servo_out[CH_PITCH] - servo_out[CH_ROLL]); + ch2 = servo_out[CH_PITCH] + servo_out[CH_ROLL]; + radio_out[CH_ROLL] = elevon1_trim + (reverse_ch1_elevon * (ch1 * 0.11111)); + radio_out[CH_PITCH] = elevon2_trim + (reverse_ch2_elevon * (ch2 * 0.11111)); + } + + #if THROTTLE_OUT == 0 + radio_out[CH_THROTTLE] = 0; + #endif + + + // convert 0 to 100% into PWM + servo_out[CH_THROTTLE] = constrain(servo_out[CH_THROTTLE], 0, 100); + radio_out[CH_THROTTLE] = servo_out[CH_THROTTLE] * ((radio_max[CH_THROTTLE] - radio_min[CH_THROTTLE]) / 100); + radio_out[CH_THROTTLE] += radio_min[CH_THROTTLE]; + + //Radio_in: 1763 PWM output: 2000 Throttle: 78.7695999145 PWM Min: 1110 PWM Max: 1938 + + #if THROTTLE_REVERSE == 1 + radio_out[CH_THROTTLE] = radio_max[CH_THROTTLE] + radio_min[CH_THROTTLE] - radio_out[CH_THROTTLE]; + #endif + } + + // send values to the PWM timers for output + // ---------------------------------------- + for(int y=0; y<4; y++) { + //radio_out[y] = constrain(radio_out[y], radio_min[y], radio_max[y]); + APM_RC.OutputCh(y, radio_out[y]); // send to Servos + //Serial.print(radio_out[y],DEC); + //Serial.print(", "); + } + //Serial.println(" "); + } + +void demo_servos(byte i) { + + while(i > 0){ + send_message(SEVERITY_LOW,"Demo Servos!"); + APM_RC.OutputCh(1, 1400); + delay(400); + APM_RC.OutputCh(1, 1600); + delay(200); + APM_RC.OutputCh(1, 1500); + delay(400); + i--; + } +} + +int readOutputCh(unsigned char ch) +{ + int pwm; + switch(ch) + { + case 0: pwm = OCR5B; break; // ch0 + case 1: pwm = OCR5C; break; // ch1 + case 2: pwm = OCR1B; break; // ch2 + case 3: pwm = OCR1C; break; // ch3 + case 4: pwm = OCR4C; break; // ch4 + case 5: pwm = OCR4B; break; // ch5 + case 6: pwm = OCR3C; break; // ch6 + case 7: pwm = OCR3B; break; // ch7 + case 8: pwm = OCR5A; break; // ch8, PL3 + case 9: pwm = OCR1A; break; // ch9, PB5 + case 10: pwm = OCR3A; break; // ch10, PE3 + } + pwm >>= 1; // pwm / 2; + return pwm; +} diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/DCM.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/DCM.pde new file mode 100644 index 0000000000..07e0bb8df9 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/DCM.pde @@ -0,0 +1,387 @@ + +// Read the 6 ADC channels needed for the IMU +// ----------------- +void Read_adc_raw(void) +{ + int tc_temp = APM_ADC.Ch(GYRO_TEMP_CH); + for (int i = 0; i < 6; i++) { + AN[i] = APM_ADC.Ch(sensors[i]); + if (i < 3) { + AN[i] -= gyro_temp_comp(i, tc_temp); // Subtract temp compensated typical gyro bias + } else { + AN[i] -= 2025; // Subtract typical accel bias + } + } +} + +// Returns the temperature compensated raw gyro value +//--------------------------------------------------- +float gyro_temp_comp(int i, int temp) +{ + // We use a 2nd order curve of the form Gtc = A + B * Graw + C * (Graw)**2 + //------------------------------------------------------------------------ + return GTC[i][0] + GTC[i][1] * temp + GTC[i][2] * temp * temp; +} + +// Returns an analog value with the offset removed +// ----------------- +float read_adc(int select) +{ + float temp; + if (SENSOR_SIGN[select] < 0) + temp = (AN_OFFSET[select]-AN[select]); + else + temp = (AN[select]-AN_OFFSET[select]); + + if (abs(temp) > ADC_CONSTRAINT) + adc_constraints++; // We keep track of the number of times we constrain the ADC output for performance reporting + +/* +// For checking the pitch/roll drift correction gain time constants +switch (select) { + case 3: + return 0; + break; + case 4: + return 0; + break; + case 5: + return 400; + break; +} +*/ + + +//End of drift correction gain test code + + return constrain(temp, -ADC_CONSTRAINT, ADC_CONSTRAINT); // Throw out nonsensical values +} + +/**************************************************/ +void Normalize(void) +{ + float error = 0; + float temporary[3][3]; + float renorm = 0; + boolean problem = FALSE; + + error= -Vector_Dot_Product(&DCM_Matrix[0][0], &DCM_Matrix[1][0]) * .5; // eq.19 + + Vector_Scale(&temporary[0][0], &DCM_Matrix[1][0], error); // eq.19 + Vector_Scale(&temporary[1][0], &DCM_Matrix[0][0], error); // eq.19 + + Vector_Add(&temporary[0][0], &temporary[0][0], &DCM_Matrix[0][0]); //eq.19 + Vector_Add(&temporary[1][0], &temporary[1][0], &DCM_Matrix[1][0]); //eq.19 + + Vector_Cross_Product(&temporary[2][0], &temporary[0][0], &temporary[1][0]); // c= a x b // eq.20 + + renorm = Vector_Dot_Product(&temporary[0][0], &temporary[0][0]); + if (renorm < 1.5625f && renorm > 0.64f) { // Check if we are OK with Taylor expansion + renorm = .5 * (3 - renorm); // eq.21 + } else if (renorm < 100.0f && renorm > 0.01f) { + renorm = 1. / sqrt(renorm); + renorm_sqrt_count++; + } else { + problem = TRUE; + renorm_blowup_count++; + } + Vector_Scale(&DCM_Matrix[0][0], &temporary[0][0], renorm); + + renorm = Vector_Dot_Product(&temporary[1][0], &temporary[1][0]); + if (renorm < 1.5625f && renorm > 0.64f) { // Check if we are OK with Taylor expansion + renorm = .5 * (3 - renorm); // eq.21 + } else if (renorm < 100.0f && renorm > 0.01f) { + renorm = 1. / sqrt(renorm); + renorm_sqrt_count++; + } else { + problem = TRUE; + renorm_blowup_count++; + } + Vector_Scale(&DCM_Matrix[1][0], &temporary[1][0], renorm); + + renorm = Vector_Dot_Product(&temporary[2][0], &temporary[2][0]); + if (renorm < 1.5625f && renorm > 0.64f) { // Check if we are OK with Taylor expansion + renorm = .5 * (3 - renorm); // eq.21 + } else if (renorm < 100.0f && renorm > 0.01f) { + renorm = 1. / sqrt(renorm); + renorm_sqrt_count++; + } else { + problem = TRUE; + renorm_blowup_count++; + } + Vector_Scale(&DCM_Matrix[2][0], &temporary[2][0], renorm); + + if (problem) { // Our solution is blowing up and we will force back to initial condition. Hope we are not upside down! + DCM_Matrix[0][0] = 1.0f; + DCM_Matrix[0][1] = 0.0f; + DCM_Matrix[0][2] = 0.0f; + DCM_Matrix[1][0] = 0.0f; + DCM_Matrix[1][1] = 1.0f; + DCM_Matrix[1][2] = 0.0f; + DCM_Matrix[2][0] = 0.0f; + DCM_Matrix[2][1] = 0.0f; + DCM_Matrix[2][2] = 1.0f; + problem = FALSE; + } +} + +/**************************************************/ +void Drift_correction(void) +{ + //Compensation the Roll, Pitch and Yaw drift. + float mag_heading_x; + float mag_heading_y; + float errorCourse = 0; + static float Scaled_Omega_P[3]; + static float Scaled_Omega_I[3]; + float Accel_magnitude; + float Accel_weight; + float Integrator_magnitude; + + //*****Roll and Pitch*************** + + // Calculate the magnitude of the accelerometer vector + Accel_magnitude = sqrt(Accel_Vector[0] * Accel_Vector[0] + Accel_Vector[1] * Accel_Vector[1] + Accel_Vector[2] * Accel_Vector[2]); + Accel_magnitude = Accel_magnitude / GRAVITY; // Scale to gravity. + + // Dynamic weighting of accelerometer info (reliability filter) + // Weight for accelerometer info (<0.5G = 0.0, 1G = 1.0 , >1.5G = 0.0) + Accel_weight = constrain(1 - 2 * abs(1 - Accel_magnitude), 0, 1); // + + // We monitor the amount that the accelerometer based drift correction is deweighted for performanc reporting + imu_health = imu_health + 0.02 * (Accel_weight-.5); + imu_health = constrain(imu_health, 0, 1); + + Vector_Cross_Product(&errorRollPitch[0], &Accel_Vector[0], &DCM_Matrix[2][0]); // adjust the ground of reference + // errorRollPitch are in Accel ADC units + // Limit max errorRollPitch to limit max Omega_P and Omega_I + errorRollPitch[0] = constrain(errorRollPitch[0], -50, 50); + errorRollPitch[1] = constrain(errorRollPitch[1], -50, 50); + errorRollPitch[2] = constrain(errorRollPitch[2], -50, 50); + + Vector_Scale(&Omega_P[0], &errorRollPitch[0], Kp_ROLLPITCH * Accel_weight); + + Vector_Scale(&Scaled_Omega_I[0], &errorRollPitch[0], Ki_ROLLPITCH * Accel_weight); + Vector_Add(Omega_I, Omega_I, Scaled_Omega_I); + + //*****YAW*************** + + #if MAGNETOMETER == ENABLED + // We make the gyro YAW drift correction based on compass magnetic heading + errorCourse= (DCM_Matrix[0][0] * APM_Compass.Heading_Y) - (DCM_Matrix[1][0] * APM_Compass.Heading_X); // Calculating YAW error + #else // Use GPS Ground course to correct yaw gyro drift= + if(GPS.ground_speed >= SPEEDFILT){ + // Optimization: We have precalculated COGX and COGY (Course over Ground X and Y) from GPS info + errorCourse = (DCM_Matrix[0][0] * COGY) - (DCM_Matrix[1][0] * COGX); // Calculating YAW error + } + #endif + + Vector_Scale(errorYaw, &DCM_Matrix[2][0], errorCourse); // Applys the yaw correction to the XYZ rotation of the aircraft, depeding the position. + + Vector_Scale(&Scaled_Omega_P[0], &errorYaw[0], Kp_YAW); + Vector_Add(Omega_P, Omega_P, Scaled_Omega_P); //Adding Proportional. + + Vector_Scale(&Scaled_Omega_I[0], &errorYaw[0], Ki_YAW); + Vector_Add(Omega_I, Omega_I, Scaled_Omega_I); //adding integrator to the Omega_I + + + // Here we will place a limit on the integrator so that the integrator cannot ever exceed half the saturation limit of the gyros + Integrator_magnitude = sqrt(Vector_Dot_Product(Omega_I, Omega_I)); + if (Integrator_magnitude > ToRad(300)) { + Vector_Scale(Omega_I, Omega_I, 0.5f * ToRad(300) / Integrator_magnitude); + } +} + +/**************************************************/ +void Accel_adjust(void) +{ + Accel_Vector[1] += Accel_Scale((GPS.ground_speed / 100) * Omega[2]); // Centrifugal force on Acc_y = GPS_speed * GyroZ + Accel_Vector[2] -= Accel_Scale((GPS.ground_speed / 100) * Omega[1]); // Centrifugal force on Acc_z = GPS_speed * GyroY +} + + +/**************************************************/ +void Matrix_update(void) +{ + Gyro_Vector[0] = Gyro_Scaled_X(read_adc(0)); // gyro x roll + Gyro_Vector[1] = Gyro_Scaled_Y(read_adc(1)); // gyro y pitch + Gyro_Vector[2] = Gyro_Scaled_Z(read_adc(2)); // gyro Z yaw + + //Record when you saturate any of the gyros. + if((abs(Gyro_Vector[0]) >= ToRad(300)) || (abs(Gyro_Vector[1]) >= ToRad(300)) || (abs(Gyro_Vector[2]) >= ToRad(300))) + gyro_sat_count++; + +/* +Serial.print (AN[0]); +Serial.print (" "); +Serial.print (AN_OFFSET[0]); +Serial.print (" "); +Serial.print (Gyro_Vector[0]); +Serial.print (" "); +Serial.print (AN[1]); +Serial.print (" "); +Serial.print (AN_OFFSET[1]); +Serial.print (" "); +Serial.print (Gyro_Vector[1]); +Serial.print (" "); +Serial.print (AN[2]); +Serial.print (" "); +Serial.print (AN_OFFSET[2]); +Serial.print (" "); +Serial.println (Gyro_Vector[2]); +*/ + +// Accel_Vector[0]=read_adc(3); // acc x +// Accel_Vector[1]=read_adc(4); // acc y +// Accel_Vector[2]=read_adc(5); // acc z + // Low pass filter on accelerometer data (to filter vibrations) + Accel_Vector[0] = Accel_Vector[0] * 0.6 + (float)read_adc(3) * 0.4; // acc x + Accel_Vector[1] = Accel_Vector[1] * 0.6 + (float)read_adc(4) * 0.4; // acc y + Accel_Vector[2] = Accel_Vector[2] * 0.6 + (float)read_adc(5) * 0.4; // acc z + + + Vector_Add(&Omega[0], &Gyro_Vector[0], &Omega_I[0]); // adding proportional term + Vector_Add(&Omega_Vector[0], &Omega[0], &Omega_P[0]); // adding Integrator term + + Accel_adjust(); // Remove centrifugal acceleration. + + #if OUTPUTMODE == 1 + Update_Matrix[0][0] = 0; + Update_Matrix[0][1] = -G_Dt * Omega_Vector[2]; // -z + Update_Matrix[0][2] = G_Dt * Omega_Vector[1]; // y + Update_Matrix[1][0] = G_Dt * Omega_Vector[2]; // z + Update_Matrix[1][1] = 0; + Update_Matrix[1][2] = -G_Dt * Omega_Vector[0]; // -x + Update_Matrix[2][0] = -G_Dt * Omega_Vector[1]; // -y + Update_Matrix[2][1] = G_Dt * Omega_Vector[0]; // x + Update_Matrix[2][2] = 0; + #else // Uncorrected data (no drift correction) + Update_Matrix[0][0] = 0; + Update_Matrix[0][1] = -G_Dt * Gyro_Vector[2]; // -z + Update_Matrix[0][2] = G_Dt * Gyro_Vector[1]; // y + Update_Matrix[1][0] = G_Dt * Gyro_Vector[2]; // z + Update_Matrix[1][1] = 0; + Update_Matrix[1][2] = -G_Dt * Gyro_Vector[0]; + Update_Matrix[2][0] = -G_Dt * Gyro_Vector[1]; + Update_Matrix[2][1] = G_Dt * Gyro_Vector[0]; + Update_Matrix[2][2] = 0; + #endif + + Matrix_Multiply(DCM_Matrix, Update_Matrix, Temporary_Matrix); // a * b = c + + for(int x = 0; x < 3; x++){ // Matrix Addition (update) + for(int y = 0; y < 3; y++){ + DCM_Matrix[x][y] += Temporary_Matrix[x][y]; + } + } + +/* +Serial.print (G_Dt * 1000); +Serial.print (" "); +Serial.print (DCM_Matrix[0][0]); +Serial.print (" "); +Serial.print (DCM_Matrix[0][1]); +Serial.print (" "); +Serial.print (DCM_Matrix[0][2]); +Serial.print (" "); +Serial.print (DCM_Matrix[1][0]); +Serial.print (" "); +Serial.print (DCM_Matrix[1][1]); +Serial.print (" "); +Serial.print (DCM_Matrix[1][2]); +Serial.print (" "); +Serial.print (DCM_Matrix[2][0]); +Serial.print (" "); +Serial.print (DCM_Matrix[2][1]); +Serial.print (" "); +Serial.println (DCM_Matrix[2][2]); +*/ +} + +/**************************************************/ +void Euler_angles(void) +{ + #if (OUTPUTMODE == 2) // Only accelerometer info (debugging purposes) + roll = atan2(Accel_Vector[1], Accel_Vector[2]); // atan2(acc_y, acc_z) + pitch = -asin((Accel_Vector[0]) / (double)GRAVITY); // asin(acc_x) + yaw = 0; + roll_sensor = ToDeg(roll) * 100; + pitch_sensor = ToDeg(pitch) * 100; + #else + pitch = -asin(DCM_Matrix[2][0]); + roll = atan2(DCM_Matrix[2][1], DCM_Matrix[2][2]); + yaw = atan2(DCM_Matrix[1][0], DCM_Matrix[0][0]); + pitch_sensor = ToDeg(pitch) * 100; + roll_sensor = ToDeg(roll) * 100; + yaw_sensor = ToDeg(yaw) * 100; + if (yaw_sensor < 0) yaw_sensor += 36000; + #endif + + /* + Serial.print ("Roll "); + Serial.print (roll_sensor / 100); + Serial.print (", Pitch "); + Serial.print (pitch_sensor / 100); + Serial.print (", Yaw "); + Serial.println (yaw_sensor / 100); + */ +} + +/**************************************************/ +//Computes the dot product of two vectors +float Vector_Dot_Product(float vector1[3], float vector2[3]) +{ + float op = 0; + + for(int c = 0; c < 3; c++) + { + op += vector1[c] * vector2[c]; + } + + return op; +} + +/**************************************************/ +//Computes the cross product of two vectors +void Vector_Cross_Product(float vectorOut[3], float v1[3], float v2[3]) +{ + vectorOut[0]= (v1[1] * v2[2]) - (v1[2] * v2[1]); + vectorOut[1]= (v1[2] * v2[0]) - (v1[0] * v2[2]); + vectorOut[2]= (v1[0] * v2[1]) - (v1[1] * v2[0]); +} + +/**************************************************/ +//Multiply the vector by a scalar. +void Vector_Scale(float vectorOut[3], float vectorIn[3], float scale2) +{ + for(int c = 0; c < 3; c++) + { + vectorOut[c] = vectorIn[c] * scale2; + } +} + +/**************************************************/ +void Vector_Add(float vectorOut[3], float vectorIn1[3], float vectorIn2[3]) +{ + for(int c = 0; c < 3; c++) + { + vectorOut[c] = vectorIn1[c]+vectorIn2[c]; + } +} + +/********* MATRIX FUNCTIONS *****************************************/ +//Multiply two 3x3 matrixs. This function developed by Jordi can be easily adapted to multiple n*n matrix's. (Pero me da flojera!). +void Matrix_Multiply(float a[3][3], float b[3][3], float mat[3][3]) +{ + float op[3]; + for(int x = 0; x < 3; x++){ + for(int y = 0; y < 3; y++){ + for(int w = 0; w < 3; w++){ + op[w] = a[x][w] * b[w][y]; + } + mat[x][y] = 0; + mat[x][y] = op[0] + op[1] + op[2]; + float test = mat[x][y]; + } + } +} diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/EEPROM map.txt b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/EEPROM map.txt new file mode 100644 index 0000000000..b7586d293d --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/EEPROM map.txt @@ -0,0 +1,389 @@ +0 0000 16 int radio_trim 1 +1 0001 .. +2 0002 16 int radio_trim 2 +3 0003 .. +4 0004 16 int radio_trim 3 +5 0005 .. +6 0006 16 int radio_trim 4 +7 0007 .. +8 0008 16 int radio_trim 5 +9 0009 .. +10 000A 16 int radio_trim 6 +11 000B .. +12 000C 16 int radio_trim 7 +13 000D .. +14 000E 16 int radio_trim 8 +15 000F .. +16 0010 16 int radio_min 1 +17 0011 .. +18 0012 16 int radio_min 2 +19 0013 .. +20 0014 16 int radio_min 3 +21 0015 .. +22 0016 16 int radio_min 4 +23 0017 .. +24 0018 16 int radio_min 5 +25 0019 .. +26 001A 16 int radio_min 6 +27 001B .. +28 001C 16 int radio_min 7 +29 001D .. +30 001E 16 int radio_min 8 +31 001F .. +32 0020 16 int radio_max 1 +33 0021 .. +34 0022 16 int radio_max 2 +35 0023 .. +36 0024 16 int radio_max 3 +37 0025 .. +38 0026 16 int radio_max 4 +39 0027 .. +40 0028 16 int radio_max 5 +41 0029 .. +42 002A 16 int radio_max 6 +43 002B .. +44 002C 16 int radio_max 7 +45 002D .. +46 002E 16 int radio_max 8 +47 002F .. +48 0030 16 int elevon_trim 1 +49 0031 .. +50 0032 16 int elevon_trim 2 +51 0033 .. +52 0034 16 int XTRACK_GAIN +53 0035 .. +54 0036 16 int XTRACK_ENTRY_ANGLE +55 0037 .. +56 0038 8 int HEAD_MAX +57 0039 8 int PITCH_MAX +58 003A 8 int Pitch_min +59 003B 32 float EE_ALT_MIX +60 003C .. +61 003D .. +62 003E .. +63 003F +64 0040 32 float Kp 0 +65 0041 .. +66 0042 .. +67 0043 .. +68 0044 32 float Kp 1 +69 0045 .. +70 0046 .. +71 0047 .. +72 0048 32 float Kp 2 +73 0049 .. +74 004A .. +75 004B .. +76 004C 32 float Kp 3 +77 004D .. +78 004E .. +79 004F .. +80 0050 32 float Kp 4 +81 0051 .. +82 0052 .. +83 0053 .. +84 0054 32 float Kp 5 +85 0055 .. +86 0056 .. +87 0057 .. +88 0058 32 float Kp 6 +89 0059 .. +90 005A .. +91 005B .. +92 005C 32 float Kp 7 +93 005D .. +94 005E .. +95 005F .. +96 0060 32 float Ki 0 +97 0061 .. +98 0062 .. +99 0063 .. +100 0064 32 float Ki 1 +101 0065 .. +102 0066 .. +103 0067 .. +104 0068 32 float Ki 2 +105 0069 .. +106 006A .. +107 006B .. +108 006C 32 float Ki 3 +109 006D .. +110 006E .. +111 006F .. +112 0070 32 float Ki 4 +113 0071 .. +114 0072 .. +115 0073 .. +116 0074 32 float Ki 5 +117 0075 .. +118 0076 .. +119 0077 .. +120 0078 32 float Ki 6 +121 0079 .. +122 007A .. +123 007B .. +124 007C 32 float Ki 7 +125 007D .. +126 007E .. +127 007F .. +128 0080 32 float kd 0 +129 0081 .. +130 0082 .. +131 0083 .. +132 0084 32 float kd 1 +133 0085 .. +134 0086 .. +135 0087 .. +136 0088 32 float kd 2 +137 0089 .. +138 008A .. +139 008B .. +140 008C 32 float kd 3 +141 008D .. +142 008E .. +143 008F .. +144 0090 32 float kd 4 +145 0091 .. +146 0092 .. +147 0093 .. +148 0094 32 float kd 5 +149 0095 .. +150 0096 .. +151 0097 .. +152 0098 32 float kd 6 +153 0099 .. +154 009A .. +155 009B .. +156 009C 32 float kd 7 +157 009D .. +158 009E .. +159 009F .. +160 00A0 32 float integrator_max 0 +161 00A1 .. +162 00A2 .. +163 00A3 .. +164 00A4 32 float integrator_max 1 +165 00A5 .. +166 00A6 .. +167 00A7 .. +168 00A8 32 float integrator_max 2 +169 00A9 .. +170 00AA .. +171 00AB .. +172 00AC 32 float integrator_max 3 +173 00AD .. +174 00AE .. +175 00AF .. +176 00B0 32 float integrator_max 4 +177 00B1 .. +178 00B2 .. +179 00B3 .. +180 00B4 32 float integrator_max 5 +181 00B5 .. +182 00B6 .. +183 00B7 .. +184 00B8 32 float integrator_max 6 +185 00B9 .. +186 00BA .. +187 00BB .. +188 00BC 32 float integrator_max 7 +189 00BD .. +190 00BE .. +191 00BF .. +192 00C0 32 float Kff 0 +193 00C1 .. +194 00C2 .. +195 00C3 .. +196 00C4 32 float Kff 1 +197 00C5 .. +198 00C6 .. +199 00C7 .. +200 00C8 32 float Kff 2 +201 00C9 .. +202 00CA .. +203 00CB .. +204 00CC 32 float Kff 3 +205 00CD .. +206 00CE .. +207 00CF .. +208 00D0 32 float Kff 4 +209 00D1 .. +210 00D2 .. +211 00D3 .. +212 00D4 32 float Kff 5 +213 00D5 .. +214 00D6 .. +215 00D7 .. +216 00D8 32 float Kff 6 +217 00D9 .. +218 00DA .. +219 00DB .. +220 00DC 32 float Kff 7 +221 00DD .. +222 00DE .. +223 00DF .. +224 00E0 32 int EE_ACCEL_OFFSET 0 +225 00E1 .. +226 00E2 .. +227 00E3 .. +228 00E4 32 int EE_ACCEL_OFFSET 1 +229 00E5 .. +230 00E6 .. +231 00E7 .. +232 00E8 32 int EE_ACCEL_OFFSET 2 +233 00E9 .. +234 00EA .. +235 00EB .. +236 00EC 32 int EE_ACCEL_OFFSET 3 +237 00ED .. +238 00EE .. +239 00EF .. +240 00F0 32 int EE_ACCEL_OFFSET 4 +241 00F1 .. +242 00F2 .. +243 00F3 .. +244 00F4 32 int EE_ACCEL_OFFSET 5 +245 00F5 .. +246 00F6 .. +247 00F7 .. +248 00F8 8 EE_CONFIG +249 00F9 8 EE_WP_MODE +250 00FA 8 EE_YAW_MODE +251 00FB 8 EE_WP_TOTAL 0x106 +252 00FC 8 EE_WP_INDEX 0x107 +253 00FD 8 EE_WP_RADIUS 0x108 +254 00FE 8 EE_LOITER_RADIUS 0x109 +255 00FF 32 EE_ALT_HOLD_HOME 0x10A +256 0100 .. +257 0101 .. +258 0102 .. +259 0103 8 AIRSPEED_CRUISE +260 0104 32 AIRSPEED_RATIO +261 0105 .. +262 0106 .. +263 0107 .. +264 0108 AIRSPEED_FBW_MIN +265 0109 AIRSPEED_FBW_MAX +266 010A 8 THROTTLE_MIN +267 010B 8 THROTTLE_CRUISE +268 010C 8 THROTTLE_MAX +269 010D 8 THROTTLE_FAILSAFE +270 010E 16 THROTTLE_FS_VALUE +271 010F .. +272 0110 8 THROTTLE_FAILSAFE_ACTION +273 0111 +274 0112 8 FLIGHT_MODE_CHANNEL +275 0113 8 AUTO_TRIM +276 0114 uint16 LOGging Bitmask +277 0115 .. +278 0116 uint32 EE_ABS_PRESS_GND +279 0117 .. +280 0118 .. +281 0119 .. +282 011A 16 int EE_GND_TEMP +283 011B .. +284 011C 16 int EE_GND_ALT +285 011D .. +286 011E 16 int EE_AP_OFFSET +287 011F .. +288 0120 8 byte EE_SWITCH_ENABLE +289 0121 8 ARRAY FLIGHT_MODES_1 +290 0122 8 ARRAY FLIGHT_MODES_2 +291 0123 8 ARRAY FLIGHT_MODES_3 +292 0124 8 ARRAY FLIGHT_MODES_4 +293 0125 8 ARRAY FLIGHT_MODES_5 +294 0126 8 ARRAY FLIGHT_MODES_6 +295 0127 +296 0128 +297 0129 +298 012A +299 012B +300 012C +301 012D +302 012E +303 012F (0x130 is the Start Byte for commands) +304 0130 byte Command id (Home) 0 +305 0131 byte Parameter 1 +306 0132 long Altitude, Parameter 2 +307 0133 .. +308 0134 .. +309 0135 .. +310 0136 long Latitude, Parameter 3 +311 0137 .. +312 0138 .. +313 0139 .. +314 013A long Longitude, Parameter 3 +315 013B .. +316 013C .. +317 013D byte Command id (WP 1) 1 +318 013E byte Parameter 1 +319 013F long Altitude, Parameter 2 +320 0140 .. +321 0141 .. +322 0142 .. +323 0143 long Latitude, Parameter 3 +324 0144 .. +325 0145 .. +326 0146 .. +327 0147 long Longitude, Parameter 3 +328 0148 .. +329 0149 .. +330 014A .. +331 014B +332 014C +333 014D +334 014E +335 014F + + + + + +********************************************************************************************** +SECTION 6 - LOGS + +3584 0xE00 int Last log page used +3585 0xE01 .. +3587 0xE02 byte last log number +3588 0xE03 unused +3589 0xE04 int Log 1 start page +3590 0xE05 .. +3591 0xE06 int Log 2 start page +3592 0xE07 .. +3593 0xE08 int Log 3 start page +3594 0xE09 .. +3595 0xE0A int Log 4 start page +3596 0xE0B .. +3597 0xE0C int Log 5 start page +3598 0xE0D .. +3599 0xE0E int Log 6 start page +3600 0xE0F .. +3601 0xE10 int Log 7 start page +3602 0xE11 .. +3603 0xE12 int Log 8 start page +3604 0xE13 .. +3605 0xE14 int Log 9 start page +3606 0xE15 .. +3607 0xE16 int Log 10 start page +3608 0xE17 .. +3609 0xE18 int Log 11 start page +3610 0xE19 .. +3611 0xE1A int Log 12 start page +3612 0xE1B .. +3613 0xE1C int Log 13 start page +3614 0xE1D .. +3615 0xE1E int Log 14 start page +3616 0xE1F .. +3617 0xE20 int Log 15 start page +3618 0xE21 .. +3619 0xE22 int Log 16 start page +3620 0xE23 .. +3621 0xE24 int Log 17 start page +3622 0xE25 .. +3623 0xE26 int Log 18 start page +3624 0xE27 .. +3625 0xE28 int Log 19 start page +3626 0xE29 .. + + + \ No newline at end of file diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/EEPROM.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/EEPROM.pde new file mode 100644 index 0000000000..9cf861f3bc --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/EEPROM.pde @@ -0,0 +1,286 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- +// ************************************************************************************ +// This function gets critical data from EEPROM to get us underway if restarting in air +// ************************************************************************************ +void read_EEPROM_startup(void) +{ + read_EEPROM_gains(); + read_EEPROM_radio_minmax(); // read Radio limits + read_EEPROM_trims(); // read Radio trims + read_user_configs(); + read_EEPROM_waypoint_info(); +} + +void read_EEPROM_airstart_critical(void) +{ + int16_t temp = 0; + read_EEPROM_IMU_offsets(); + + // For debugging only + /* + Serial.print ("Offsets "); Serial.print (AN_OFFSET[0]); + Serial.print (" "); Serial.print (AN_OFFSET[1]); + Serial.print (" "); Serial.print (AN_OFFSET[2]); + Serial.print (" "); Serial.print (AN_OFFSET[3]); + Serial.print (" "); Serial.print (AN_OFFSET[4]); + Serial.print (" "); Serial.println (AN_OFFSET[5]); + */ + + // Read the home location + //----------------------- + home = get_wp_with_index(0); + + // Read pressure sensor values + //---------------------------- + read_pressure_data(); +} + +void save_EEPROM_groundstart(void) +{ + save_EEPROM_trims(); + save_EEPROM_IMU_offsets(); + // pressure sensor data saved by init_home +} + + +/********************************************************************************/ +long read_alt_to_hold() +{ + byte options = eeprom_read_byte((byte *) EE_CONFIG); + + // save the alitude above home option + if(options & HOLD_ALT_ABOVE_HOME){ + int32_t temp = eeprom_read_dword((const uint32_t *) EE_ALT_HOLD_HOME); + return temp + home.alt; + }else{ + return current_loc.alt; + } +} + +long save_alt_to_hold(int32_t alt_to_hold) +{ + byte options = eeprom_read_byte((byte *) EE_CONFIG); + + // save the alitude above home option + if(options & HOLD_ALT_ABOVE_HOME) + eeprom_write_block((const void *)&alt_to_hold, (void *)EE_ALT_HOLD_HOME, sizeof (alt_to_hold)); +} + + +/********************************************************************************/ +void read_EEPROM_waypoint_info(void) +{ + wp_total = eeprom_read_byte((uint8_t *) EE_WP_TOTAL); + wp_radius = eeprom_read_byte((uint8_t *) EE_WP_RADIUS); + loiter_radius = eeprom_read_byte((uint8_t *) EE_LOITER_RADIUS); +} + +void save_EEPROM_waypoint_info(void) +{ + eeprom_write_byte((uint8_t *) EE_WP_TOTAL, wp_total); + eeprom_write_byte((uint8_t *) EE_WP_RADIUS, wp_radius); + eeprom_write_byte((uint8_t *) EE_LOITER_RADIUS, loiter_radius); +} + +/********************************************************************************/ +void read_EEPROM_gains(void) +{ + eeprom_read_block((void*)&kp, (const void*)EE_KP, sizeof(kp)); + eeprom_read_block((void*)&ki, (const void*)EE_KI, sizeof(ki)); + eeprom_read_block((void*)&kd, (const void*)EE_KD, sizeof(kd)); + eeprom_read_block((void*)&integrator_max, (const void*)EE_IMAX, sizeof(integrator_max)); + eeprom_read_block((void*)&kff, (const void*)EE_KFF, sizeof(kff)); + + // stored as degree * 100 + x_track_gain = eeprom_read_word((uint16_t *) EE_XTRACK_GAIN); + + // stored as degrees + x_track_angle = eeprom_read_word((uint16_t *) EE_XTRACK_ANGLE) * 100; + + // stored as degrees + head_max = eeprom_read_byte((uint8_t *) EE_HEAD_MAX) * 100; // scale to degress * 100 + pitch_max = eeprom_read_byte((uint8_t *) EE_PITCH_MAX) * 100; // scale to degress * 100 + pitch_min = -eeprom_read_byte((uint8_t *) EE_PITCH_MIN) * 100; // scale to degress * 100 + + // stored as a float + eeprom_read_block((void*)&altitude_mix, (const void*)EE_ALT_MIX, sizeof(altitude_mix)); +} + +void save_EEPROM_gains(void) +{ + eeprom_write_block((const void *)&kp, (void *)EE_KP, sizeof (kp)); + eeprom_write_block((const void *)&ki, (void *)EE_KI, sizeof (ki)); + eeprom_write_block((const void *)&kd, (void *)EE_KD, sizeof (kd)); + eeprom_write_block((const void *)&integrator_max, (void *)EE_IMAX, sizeof (integrator_max)); + eeprom_write_block((const void *)&kff, (void *)EE_KFF, sizeof (kff)); + + // stored as degree * 100 + eeprom_write_word((uint16_t *) EE_XTRACK_GAIN, x_track_gain); + + // stored as degrees + eeprom_write_word((uint16_t *) EE_XTRACK_ANGLE, x_track_angle / 100); + + // stored as degrees + eeprom_write_byte((uint8_t *) EE_HEAD_MAX, head_max / 100); + eeprom_write_byte((uint8_t *) EE_PITCH_MAX, pitch_max / 100); + eeprom_write_byte((uint8_t *) EE_PITCH_MIN, -pitch_min / 100); + + // stored as a float + eeprom_write_block((const void*)&altitude_mix, (void*)EE_ALT_MIX, sizeof(altitude_mix)); +} + + +/********************************************************************************/ + +void read_EEPROM_trims(void) +{ + // Read Radio trim settings + eeprom_read_block((void*)&radio_trim, (const void*)EE_TRIM, sizeof(radio_trim)); + elevon1_trim = eeprom_read_word((uint16_t *) EE_ELEVON1_TRIM); + elevon2_trim = eeprom_read_word((uint16_t *) EE_ELEVON2_TRIM); +} + +void save_EEPROM_trims(void) +{ + // Save Radio trim settings + eeprom_write_block((const void *)&radio_trim, (void *)EE_TRIM, sizeof(radio_trim)); + eeprom_write_word((uint16_t *) EE_ELEVON1_TRIM, elevon1_trim); + eeprom_write_word((uint16_t *) EE_ELEVON2_TRIM, elevon2_trim); +} + +/********************************************************************************/ + +void save_EEPROM_IMU_offsets(void) +{ + eeprom_write_block((const void *)&AN_OFFSET, (void *)EE_AN_OFFSET, sizeof (AN_OFFSET)); +} + +void read_EEPROM_IMU_offsets(void) +{ + eeprom_read_block((void*)&AN_OFFSET, (const void*)EE_AN_OFFSET, sizeof(AN_OFFSET)); +} + +/********************************************************************************/ + +void save_command_index(void) +{ + eeprom_write_byte((uint8_t *) EE_WP_INDEX, command_must_index); +} + +void read_command_index(void) +{ + wp_index = command_must_index = eeprom_read_byte((uint8_t *) EE_WP_INDEX); +} + +/********************************************************************************/ + +void save_pressure_data(void) +{ + eeprom_write_dword((uint32_t *)EE_ABS_PRESS_GND, abs_press_gnd); + eeprom_write_word((uint16_t *)EE_GND_TEMP, ground_temperature); + eeprom_write_word((uint16_t *)EE_GND_ALT, (ground_alt / 100)); + + #if AIRSPEED_SENSOR == 1 + eeprom_write_word((uint16_t *)EE_AP_OFFSET, airpressure_offset); + #endif +} + +void read_pressure_data(void) +{ + abs_press_gnd = eeprom_read_dword((uint32_t *) EE_ABS_PRESS_GND); + abs_press_filt = abs_press_gnd; // Better than zero for an air start value + ground_temperature = eeprom_read_word((uint16_t *) EE_GND_TEMP); + ground_alt = eeprom_read_word((uint16_t *) EE_GND_ALT) * 100; + + #if AIRSPEED_SENSOR == 1 + airpressure_offset = eeprom_read_word((uint16_t *) EE_AP_OFFSET); + #endif +} + + + +/********************************************************************************/ + +void read_EEPROM_radio_minmax(void) +{ + // Read Radio min/max settings + eeprom_read_block((void*)&radio_max, (const void*)EE_MAX, sizeof(radio_max)); + eeprom_read_block((void*)&radio_min, (const void*)EE_MIN, sizeof(radio_min)); +} + + +void save_EEPROM_radio_minmax(void) +{ + // Save Radio min/max settings + eeprom_write_block((const void *)&radio_max, (void *)EE_MAX, sizeof(radio_max)); + eeprom_write_block((const void *)&radio_min, (void *)EE_MIN, sizeof(radio_min)); +} + + + +/********************************************************************************/ + +void read_user_configs(void) +{ + // Read Radio min/max settings + airspeed_cruise = eeprom_read_byte((byte *) EE_AIRSPEED_CRUISE)*100; + eeprom_read_block((void*)&airspeed_ratio, (const void*)EE_AIRSPEED_RATIO, sizeof(airspeed_ratio)); + + throttle_min = eeprom_read_byte((byte *) EE_THROTTLE_MIN); + throttle_max = eeprom_read_byte((byte *) EE_THROTTLE_MAX); + throttle_cruise = eeprom_read_byte((byte *) EE_THROTTLE_CRUISE); + + airspeed_fbw_min = eeprom_read_byte((byte *) EE_AIRSPEED_FBW_MIN); + airspeed_fbw_max = eeprom_read_byte((byte *) EE_AIRSPEED_FBW_MAX); + + throttle_failsafe_enabled = eeprom_read_byte((byte *) EE_THROTTLE_FAILSAFE); + throttle_failsafe_action = eeprom_read_byte((byte *) EE_THROTTLE_FAILSAFE_ACTION); + throttle_failsafe_value = eeprom_read_word((uint16_t *) EE_THROTTLE_FS_VALUE); + + //flight_mode_channel = eeprom_read_byte((byte *) EE_FLIGHT_MODE_CHANNEL); + auto_trim = eeprom_read_byte((byte *) EE_AUTO_TRIM); + log_bitmask = eeprom_read_word((uint16_t *) EE_LOG_BITMASK); + + read_EEPROM_flight_modes(); + reverse_switch = eeprom_read_byte((byte *) EE_REVERSE_SWITCH); +} + + +void save_user_configs(void) +{ + eeprom_write_byte((byte *) EE_AIRSPEED_CRUISE, airspeed_cruise/100); + eeprom_write_block((const void *)&airspeed_ratio, (void *)EE_AIRSPEED_RATIO, sizeof(airspeed_ratio)); + + eeprom_write_byte((byte *) EE_THROTTLE_MIN, throttle_min); + eeprom_write_byte((byte *) EE_THROTTLE_MAX, throttle_max); + eeprom_write_byte((byte *) EE_THROTTLE_CRUISE, throttle_cruise); + + eeprom_write_byte((byte *) EE_AIRSPEED_FBW_MIN, airspeed_fbw_min); + eeprom_write_byte((byte *) EE_AIRSPEED_FBW_MAX, airspeed_fbw_max); + + eeprom_write_byte((byte *) EE_THROTTLE_FAILSAFE, throttle_failsafe_enabled); + eeprom_write_byte((byte *) EE_THROTTLE_FAILSAFE_ACTION,throttle_failsafe_action); + eeprom_write_word((uint16_t *) EE_THROTTLE_FS_VALUE, throttle_failsafe_value); + + //eeprom_write_byte((byte *) EE_FLIGHT_MODE_CHANNEL, flight_mode_channel); + eeprom_write_byte((byte *) EE_AUTO_TRIM, auto_trim); + eeprom_write_word((uint16_t *) EE_LOG_BITMASK, log_bitmask); + + //save_EEPROM_flight_modes(); + eeprom_write_byte((byte *) EE_REVERSE_SWITCH, reverse_switch); +} + +/********************************************************************************/ +void read_EEPROM_flight_modes(void) +{ + // Read Radio min/max settings + eeprom_read_block((void*)&flight_modes, (const void*)EE_FLIGHT_MODES, sizeof(flight_modes)); +} + + +void save_EEPROM_flight_modes(void) +{ + // Save Radio min/max settings + eeprom_write_block((const void *)&flight_modes, (void *)EE_FLIGHT_MODES, sizeof(flight_modes)); +} + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/GCS_Ardupilot.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/GCS_Ardupilot.pde new file mode 100644 index 0000000000..4cc892f32c --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/GCS_Ardupilot.pde @@ -0,0 +1,176 @@ + +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- + +#if GCS_PROTOCOL == GCS_PROTOCOL_LEGACY + +#if GCS_PORT == 3 +# define SendSer Serial3.print +# define SendSerln Serial3.println +#else +# define SendSer Serial.print +# define SendSerln Serial.println +#endif + +// This is the standard GCS output file for ArduPilot + +/* +Message Prefixes +!!! Position Low rate telemetry ++++ Attitude High rate telemetry +### Mode Change in control mode +%%% Waypoint Current and previous waypoints +XXX Alert Text alert - NOTE: Alert message generation is not localized to a function +PPP IMU Performance Sent every 20 seconds for performance monitoring + +Message Suffix +*** All messages use this suffix +*/ + +/* +void acknowledge(byte id, byte check1, byte check2) {} +void send_message(byte id) {} +void send_message(byte id, long param) {} +void send_message(byte severity, const char *str) {} +*/ + +void acknowledge(byte id, byte check1, byte check2) +{ +} + +void send_message(byte severity, const char *str) // This is the instance of send_message for message 0x05 +{ + if(severity >= DEBUG_LEVEL){ + SendSer("MSG: "); + SendSerln(str); + } +} + +void send_message(byte id) +{ + send_message(id,0l); +} + +void send_message(byte id, long param) +{ + switch(id) { + case MSG_ATTITUDE: // ** Attitude message + print_attitude(); + break; + case MSG_LOCATION: // ** Location/GPS message + print_position(); + break; + case MSG_HEARTBEAT: // ** Location/GPS message + print_control_mode(); + break; + //case MSG_PERF_REPORT: + // printPerfData(); + } +} + +void print_current_waypoints() +{ +} + +void print_attitude(void) +{ + SendSer("+++"); + SendSer("ASP:"); + SendSer((int)airspeed / 100, DEC); + SendSer(",THH:"); + SendSer(servo_out[CH_THROTTLE], DEC); + SendSer (",RLL:"); + SendSer(roll_sensor / 100, DEC); + SendSer (",PCH:"); + SendSer(pitch_sensor / 100, DEC); + SendSerln(",***"); +} + +void print_control_mode(void) +{ + switch (control_mode){ + case MANUAL: + SendSerln("###MANUAL***"); + break; + case STABILIZE: + SendSerln("###STABILIZE***"); + break; + case CIRCLE: + SendSerln("###CIRCLE***"); + break; + case FLY_BY_WIRE_A: + SendSerln("###FBW A***"); + break; + case FLY_BY_WIRE_B: + SendSerln("###FBW B***"); + break; + case AUTO: + SendSerln("###AUTO***"); + break; + case RTL: + SendSerln("###RTL***"); + break; + case LOITER: + SendSerln("###LOITER***"); + break; + case TAKEOFF: + SendSerln("##TAKEOFF***"); + break; + case LAND: + SendSerln("##LAND***"); + break; + } +} + +void print_position(void) +{ + SendSer("!!!"); + SendSer("LAT:"); + SendSer(current_loc.lat/10,DEC); + SendSer(",LON:"); + SendSer(current_loc.lng/10,DEC); //wp_current_lat + SendSer(",SPD:"); + SendSer(GPS.ground_speed/100,DEC); + SendSer(",CRT:"); + SendSer(climb_rate,DEC); + SendSer(",ALT:"); + SendSer(current_loc.alt/100,DEC); + SendSer(",ALH:"); + SendSer(next_WP.alt/100,DEC); + SendSer(",CRS:"); + SendSer(yaw_sensor/100,DEC); + SendSer(",BER:"); + SendSer(target_bearing/100,DEC); + SendSer(",WPN:"); + SendSer(wp_index,DEC);//Actually is the waypoint. + SendSer(",DST:"); + SendSer(wp_distance,DEC); + SendSer(",BTV:"); + SendSer(battery_voltage,DEC); + SendSer(",RSP:"); + SendSer(servo_out[CH_ROLL]/100,DEC); + SendSer(",TOW:"); + SendSer(GPS.time); + SendSerln(",***"); +} + +void print_waypoint(struct Location *cmd,byte index) +{ + SendSer("command #: "); + SendSer(index, DEC); + SendSer(" id: "); + SendSer(cmd->id,DEC); + SendSer(" p1: "); + SendSer(cmd->p1,DEC); + SendSer(" p2: "); + SendSer(cmd->alt,DEC); + SendSer(" p3: "); + SendSer(cmd->lat,DEC); + SendSer(" p4: "); + SendSerln(cmd->lng,DEC); +} + +void print_waypoints() +{ +} + +#endif diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/GCS_DebugTerminal.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/GCS_DebugTerminal.pde new file mode 100644 index 0000000000..8bd08bc1b2 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/GCS_DebugTerminal.pde @@ -0,0 +1,1258 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- + +#if GCS_PROTOCOL == GCS_PROTOCOL_DEBUGTERMINAL + +/* This GCS protocol sends text-base information over the telemetry port +*/ + +#include //Allow us to store string constants (there are a lot!) in program memory to avoid using up valuable RAM + +#define ERR(a) ((DEBUGTERMINAL_VERBOSE)>0?(PSTR(a)):(0)) + +#if GCS_PORT == 3 +# define DTSTREAM Serial3 +#else +# define DTSTREAM Serial +#endif + +//Read buffer +#define DEBUGTERM_BUFFERSIZE (120) +char gcsinputbuffer[DEBUGTERM_BUFFERSIZE]; +byte bufferidx; + +//Reporting flags +byte report_heartbeat = 1; +byte report_attitude = 0; +byte report_location = 0; +byte report_command = 1; +byte report_severity = 0; +byte first_location = 0; + +void readgcsinput() { + byte numc, i, c; + + numc = DTSTREAM.available(); + for (i=0;i 0) bufferidx--; + } else if (c==10) { + //Received a linefeed; do nothing + } else if (c==13) { + //Received a carriage return; process command + gcsinputbuffer[bufferidx] = 0; + run_debugt_command(gcsinputbuffer); + bufferidx = 0; + } else { + gcsinputbuffer[bufferidx++] = c; + if (bufferidx >= DEBUGTERM_BUFFERSIZE) bufferidx = 0; + } +} + +void run_debugt_command(char *buf) { + //*********** Ignore comments *********** + if (strmatch(buf, PSTR("//"))) { + + //*********** Process 'show' commands *********** + } else if (strmatch(buf, PSTR("show "))) { + if (strmatch(buf+5, PSTR("heartbeat"))) + report_heartbeat = 1; + else if (strmatch(buf+5, PSTR("attitude"))) + report_attitude = 1; + else if (strmatch(buf+5, PSTR("location"))) + report_location = 1; + else if (strmatch(buf+5, PSTR("command"))) + report_command = 1; + else if (strmatch(buf+5, PSTR("severity"))) + report_severity = atoi(buf+14); + else + print_error(ERR("USAGE: show {heartbeat|attitude|location|command|severity }")); + + //*********** Process 'hide' commands *********** + } else if (strmatch(buf, PSTR("hide "))) { + if (strmatch(buf+5, PSTR("heartbeat"))) + report_heartbeat = 0; + else if (strmatch(buf+5, PSTR("attitude"))) + report_attitude = 0; + else if (strmatch(buf+5, PSTR("location"))) + report_location = 0; + else if (strmatch(buf+5, PSTR("command"))) + report_command = 0; + else if (strmatch(buf+5, PSTR("all"))) { + report_heartbeat = 0; + report_attitude = 0; + report_location = 0; + report_command = 0; + } else + print_error(ERR("USAGE: hide {heartbeat|attitude|location|command|all}")); + + //*********** Process 'echo' command *********** + } else if (strmatch(buf, PSTR("echo "))) { + DTSTREAM.println(buf+5); + + //*********** Process 'groundstart' command *********** + } else if (strmatch(buf, PSTR("groundstart"))) { + startup_ground(); + + //*********** Process 'inithome' command *********** + } else if (strmatch(buf, PSTR("inithome"))) { + init_home(); + DTSTREAM.println_P("Home set."); + + //*********** Process 'print' commands *********** + } else if (strmatch(buf, PSTR("print "))) { + //------- print altitude ------- + if (strmatch(buf+6, PSTR("altitude"))) { + DTSTREAM.println_P("Altitude:"); + DTSTREAM.print_P(" Pressure: "); DTSTREAM.print(((float)press_alt)/100,2); DTSTREAM.println_P(" m"); + DTSTREAM.print_P(" GPS: "); DTSTREAM.print(((float)GPS.altitude)/100,2); DTSTREAM.println_P(" m"); + DTSTREAM.print_P(" Mix ratio: "); DTSTREAM.println(altitude_mix,3); + DTSTREAM.print_P(" Mix: "); DTSTREAM.print((float)(((1 - altitude_mix) * GPS.altitude) + (altitude_mix * press_alt))/100,2); DTSTREAM.println_P(" m"); + + //------- print attitude ------- + } else if (strmatch(buf+6, PSTR("attitude"))) { + print_attitude(); + + //------- print commands ------- + } else if (strmatch(buf+6, PSTR("commands"))) { + print_waypoints(); + + //------- print ctrlmode ------- + } else if (strmatch(buf+6, PSTR("ctrlmode"))) { + print_control_mode(); + + //------- print curwaypts ------- + } else if (strmatch(buf+6, PSTR("curwaypts"))) { + print_current_waypoints(); + + //------- print flightmodes ------- + } else if (strmatch(buf+6, PSTR("flightmodes"))) { + int i; + DTSTREAM.print_P("EEPROM read: "); + for (i=0; i<6; i++) { + DTSTREAM.print_P("Ch "); DTSTREAM.print(i,DEC); DTSTREAM.print_P(" = "); DTSTREAM.print(flight_modes[i],DEC); DTSTREAM.print_P(", "); + } + DTSTREAM.println(" "); + + //------- print k -? ------- + } else if (strmatch(buf+6, PSTR("k -?"))) { + print_error(ERR("USAGE: print k{p|i|d} {servoroll|servopitch|servorudder|navroll|navpitchasp|navpitchalt|throttlete|throttlealt}")); + print_error(ERR("USAGE: print kff {pitchcomp|ruddermix|pitchtothrottle}")); + + //------- print kp ------- + } else if (strmatch(buf+6, PSTR("kp "))) { + int i; + unsigned char j; + if (get_pid_offset_name(buf+9, &i, &j)) { + DTSTREAM.print_P("P gain for "); + DTSTREAM.print(buf+9); + DTSTREAM.print_P(" = "); + DTSTREAM.println(kp[i],DEC); + } else + print_error(ERR("ERROR: Did not recognize P keyword; type print k -? for more information")); + + //------- print ki ------- + } else if (strmatch(buf+6, PSTR("ki "))) { + int i; + unsigned char j; + if (get_pid_offset_name(buf+9, &i, &j)) { + DTSTREAM.print_P("I gain for "); + DTSTREAM.print(buf+9); + DTSTREAM.print_P(" = "); + DTSTREAM.println(ki[i],DEC); + } else + print_error(ERR("ERROR: Did not recognize I keyword; type print k -? for more information")); + + //------- print kd ------- + } else if (strmatch(buf+6, PSTR("kd "))) { + int i; + unsigned char j; + if (get_pid_offset_name(buf+9, &i, &j)) { + DTSTREAM.print_P("D gain for "); + DTSTREAM.print(buf+9); + DTSTREAM.print_P(" = "); + DTSTREAM.println(kd[i],DEC); + } else + print_error(ERR("ERROR: Did not recognize D keyword; type print k -? for more information")); + + //------- print kff ------- + } else if (strmatch(buf+6, PSTR("kff "))) { + if (strmatch(buf+10, PSTR("pitchcomp"))) { + DTSTREAM.print_P("FF gain for pitchcomp = "); + DTSTREAM.println(kff[CASE_PITCH_COMP],DEC); + } else if (strmatch(buf+10, PSTR("ruddermix"))) { + DTSTREAM.print_P("FF gain for ruddermix = "); + DTSTREAM.println(kff[CASE_RUDDER_MIX],DEC); + } else if (strmatch(buf+10, PSTR("pitchtothrottle"))) { + DTSTREAM.print_P("FF gain for pitchtothrottle = "); + DTSTREAM.println(kff[CASE_P_TO_T],DEC); + } else + print_error(ERR("ERROR: Did not recognize FF keyword; type print k -? for more information")); + + //------- print location ------- + } else if (strmatch(buf+6, PSTR("location"))) { + print_position(); + + //------- print navsettings ------- + } else if (strmatch(buf+6, PSTR("navsettings"))) { + DTSTREAM.println_P("Navigation settings:"); +#if AIRSPEED_SENSOR == 1 + DTSTREAM.print_P(" Cruise airspeed: "); DTSTREAM.println((float)airspeed_cruise/100.0,2); +#else + DTSTREAM.print_P(" Cruise throttle: "); DTSTREAM.println(throttle_cruise,DEC); +#endif + DTSTREAM.print_P(" Hold altitude above home: "); DTSTREAM.println(read_alt_to_hold(),DEC); + DTSTREAM.print_P(" Loiter radius: "); DTSTREAM.println(loiter_radius,DEC); + DTSTREAM.print_P(" Waypoint radius: "); DTSTREAM.println(wp_radius,DEC); + + //------- print pressure ------- + } else if (strmatch(buf+6, PSTR("pressure"))) { + DTSTREAM.println_P("BMP085 pressure sensor:"); + DTSTREAM.print_P(" Temperature: "); DTSTREAM.println(APM_BMP085.Temp,DEC); + DTSTREAM.print_P(" Pressure: "); DTSTREAM.println(APM_BMP085.Press,DEC); + + //------- print rlocation home ------- + } else if (strmatch(buf+6, PSTR("rlocation home"))) { + print_rlocation(&home); + + //------- print rlocation ------- + //(implication is "relative to next waypoint") + } else if (strmatch(buf+6, PSTR("rlocation"))) { + print_rlocation(&next_WP); + + //------- print speed ------- + } else if (strmatch(buf+6, PSTR("speed"))) { + DTSTREAM.println_P("Speed:"); + DTSTREAM.print_P(" Ground: "); DTSTREAM.println((float)GPS.ground_speed/100.0,2); +#if AIRSPEED_SENSOR == 1 + DTSTREAM.print_P(" Air: "); DTSTREAM.println((float)airspeed/100.0,2); + DTSTREAM.print_P(" Cruise: "); DTSTREAM.println((float)airspeed_cruise/100.0,2); +#endif + + //------- print tuning ------- + } else if (strmatch(buf+6, PSTR("tuning"))) { + print_tuning(); + + } else + print_error(ERR("USAGE: print {altitude|attitude|commands|ctrlmode|curwaypts|flightmodes|k -?|kp|ki|kd|kff|location|navsettings|pressure|rlocation [home]|speed|tuning|}")); + + //*********** Process 'reset' commands *********** + } else if (strmatch(buf, PSTR("reset "))) { + //------- reset commands ------- + if (strmatch(buf+6, PSTR("commands"))) { + reload_commands(); + DTSTREAM.println_P("Commands reloaded."); + } else + print_error(ERR("USAGE: reset commands")); + + //*********** Process 'rtl' command *********** + } else if (strmatch(buf, PSTR("rtl"))) { + return_to_launch(); + DTSTREAM.println_P("Returning to launch..."); + + //*********** Process 'set' commands *********** + } else if (strmatch(buf, PSTR("set "))) { + //------- set cmd ------- + if (strmatch(buf+4, PSTR("cmd "))) { + process_set_cmd(buf+8, bufferidx-8); + + //------- set cmdcount ------- + } else if (strmatch(buf+4, PSTR("cmdcount "))) { + wp_total = atoi(buf+13); + save_EEPROM_waypoint_info(); + DTSTREAM.print_P("wp_total = "); DTSTREAM.println(wp_total,DEC); + + //------- set cmdindex ------- + } else if (strmatch(buf+4, PSTR("cmdindex "))) { + wp_index = atoi(buf+13); + decrement_WP_index(); + next_command = get_wp_with_index(wp_index+1); + DTSTREAM.print_P("Command set to index "); DTSTREAM.print(wp_index,DEC); + if (next_command.id >= 0x10 && next_command.id <= 0x1F) { //TODO: create a function the defines what type of command each command ID is + command_must_index = 0; + DTSTREAM.println_P(" (must)"); + } else if (next_command.id >= 0x20 && next_command.id <= 0x2F) { + command_may_index = 0; + DTSTREAM.println_P(" (may)"); + } else + DTSTREAM.println_P(" (now)"); + + next_command.id = CMD_BLANK; + if (wp_index > wp_total) { + wp_total = wp_index; + DTSTREAM.print_P(" The total number of commands is now "); + DTSTREAM.println(wp_total,DEC); + } + update_commands(); + + //------- set cruise ------- + } else if (strmatch(buf+4, PSTR("cruise "))) { + unsigned char j = 4+7; +#if AIRSPEED_SENSOR == 1 + DTSTREAM.print_P("airspeed_cruise changed from "); + DTSTREAM.print((float)airspeed_cruise/100,2); + DTSTREAM.print_P(" to "); + airspeed_cruise = (int)(readfloat(buf, &j)/100000); + airspeed_cruise = constrain(airspeed_cruise,0,9000); //TODO: constrain minimum as stall speed, maximum as Vne + DTSTREAM.println(((float)airspeed_cruise)/100,2); +#else + DTSTREAM.print_P("throttle_cruise changed from "); + DTSTREAM.print(throttle_cruise,DEC); + DTSTREAM.print_P(" to "); + throttle_cruise = constrain((int)(readfloat(buf, &j)/10000000),0,200); + DTSTREAM.println(throttle_cruise,DEC); +#endif + + //------- set holdalt ------- + } else if (strmatch(buf+4, PSTR("holdalt "))) { + int tempalt = atoi(buf+12)*100; + save_alt_to_hold((int32_t)tempalt); + DTSTREAM.println_P("Hold altitude above home set."); + + //------- set k -? ------- + } else if (strmatch(buf+4, PSTR("k -?"))) { + print_error(ERR("USAGE: set k{p|i|d} {servoroll|servopitch|servorudder|navroll|navpitchasp|navpitchalt|throttlete|throttlealt} ")); + print_error(ERR("USAGE: set kff {pitchcomp|ruddermix|pitchtothrottle} ")); + + //------- set kp ------- + } else if (strmatch(buf+4, PSTR("kp "))) { + int i; + unsigned char j = 0; + if (get_pid_offset_name(buf+7, &i, &j)) { + buf[7+j] = 0; + DTSTREAM.print_P("P gain for "); + DTSTREAM.print(buf+7); + DTSTREAM.print_P(" changed from "); + DTSTREAM.print(kp[i],DEC); + DTSTREAM.print_P(" to "); + j += 7+1; + kp[i] = ((float)readfloat(buf, &j))/10000000; + DTSTREAM.println(kp[i],DEC); + } else + print_error(ERR("ERROR: Did not recognize P keyword; type set k -? for more information")); + + //------- set ki ------- + } else if (strmatch(buf+4, PSTR("ki "))) { + int i; + unsigned char j = 0; + if (get_pid_offset_name(buf+7, &i, &j)) { + buf[7+j] = 0; + DTSTREAM.print_P("I gain for "); + DTSTREAM.print(buf+7); + DTSTREAM.print_P(" changed from "); + DTSTREAM.print(ki[i],DEC); + DTSTREAM.print_P(" to "); + j += 7+1; + ki[i] = ((float)readfloat(buf, &j))/10000000; + DTSTREAM.println(ki[i],DEC); + } else + print_error(ERR("ERROR: Did not recognize I keyword; type set k -? for more information")); + + //------- set kd ------- + } else if (strmatch(buf+4, PSTR("kd "))) { + int i; + unsigned char j = 0; + if (get_pid_offset_name(buf+7, &i, &j)) { + buf[7+j] = 0; + DTSTREAM.print_P("D gain for "); + DTSTREAM.print(buf+7); + DTSTREAM.print_P(" changed from "); + DTSTREAM.print(kd[i],DEC); + DTSTREAM.print_P(" to "); + j += 7+1; + kd[i] = ((float)readfloat(buf, &j))/10000000; + DTSTREAM.println(kd[i],DEC); + } else + print_error(ERR("ERROR: Did not recognize D keyword; type set k -? for more information")); + + //------- set kff ------- + } else if (strmatch(buf+4, PSTR("kff "))) { + unsigned char j = 0; + if (strmatch(buf+8, PSTR("pitchcomp"))) { + buf[8+9] = 0; + DTSTREAM.print_P("FF gain for "); + DTSTREAM.print(buf+8); + DTSTREAM.print_P(" changed from "); + DTSTREAM.print(kff[CASE_PITCH_COMP],DEC); + DTSTREAM.print_P(" to "); + j = 8+9+1; + kff[CASE_PITCH_COMP] = ((float)readfloat(buf, &j))/10000000; + DTSTREAM.println(kff[CASE_PITCH_COMP],DEC); + } else if (strmatch(buf+8, PSTR("ruddermix"))) { + buf[8+9] = 0; + DTSTREAM.print_P("FF gain for "); + DTSTREAM.print(buf+8); + DTSTREAM.print_P(" changed from "); + DTSTREAM.print(kff[CASE_RUDDER_MIX],DEC); + DTSTREAM.print_P(" to "); + j = 8+9+1; + kff[CASE_RUDDER_MIX] = ((float)readfloat(buf, &j))/10000000; + DTSTREAM.println(kff[CASE_RUDDER_MIX],DEC); + } else if (strmatch(buf+8, PSTR("pitchtothrottle"))) { + buf[8+15] = 0; + DTSTREAM.print_P("FF gain for "); + DTSTREAM.print(buf+8); + DTSTREAM.print_P(" changed from "); + DTSTREAM.print(kff[CASE_P_TO_T],DEC); + DTSTREAM.print_P(" to "); + j = 8+15+1; + kff[CASE_P_TO_T] = ((float)readfloat(buf, &j))/10000000; + DTSTREAM.println(kff[CASE_P_TO_T],DEC); + } else + print_error(ERR("ERROR: Did not recognize FF keyword; type print k -? for more information")); + + //------- set loiterradius ------- + } else if (strmatch(buf+4, PSTR("loiterradius "))) { + loiter_radius = atoi(buf+17); + save_EEPROM_waypoint_info(); + DTSTREAM.print_P("Set loiter radius to "); DTSTREAM.print(loiter_radius,DEC); DTSTREAM.println_P(" meters"); + + //------- set rcin ------- + } else if (strmatch(buf+4, PSTR("rcin"))) { + unsigned char index = buf[8]-'1'; + if (index < 8) { + radio_in[index] = atoi(buf+9); + } else + print_error(ERR("USAGE: set rcin ")); + + //------- set rcout ------- + } else if (strmatch(buf+4, PSTR("rcout"))) { + unsigned char index = buf[9]-'1'; + if (index < 8) { + radio_out[index] = atoi(buf+10); + APM_RC.OutputCh(index, radio_out[index]); + } else + print_error(ERR("USAGE: set rcout ")); + + //------- set wpradius ------- + } else if (strmatch(buf+4, PSTR("wpradius "))) { + wp_radius = atoi(buf+13); + save_EEPROM_waypoint_info(); + DTSTREAM.print_P("Set waypoint radius to "); DTSTREAM.print(wp_radius,DEC); DTSTREAM.println_P(" meters"); + + //------- set xtrackentryangle ------- + } else if (strmatch(buf+4, PSTR("xtrackentryangle "))) { + unsigned char j = 21; + x_track_angle = readfloat(buf, &j)/100000; + DTSTREAM.print_P("Crosstrack entry angle set to "); DTSTREAM.println((float)x_track_angle/100,2); + + //------- set xtrackgain ------- + } else if (strmatch(buf+4, PSTR("xtrackgain "))) { + unsigned char j = 15; + x_track_gain = ((float)readfloat(buf, &j))/10000000; + DTSTREAM.print_P("Crosstrack gain set to "); DTSTREAM.println(x_track_gain,2); + + } else + print_error(ERR("USAGE: set {cmd|cmdcount|cmdindex|cruise|holdalt|kp|ki|kd|kff|loiterradius|rcin|rcout|wpradius}")); + + //*********** Process 'status' commands *********** + } else if (strmatch(buf, PSTR("status "))) { + //------- status control ------- + if (strmatch(buf+7, PSTR("control"))) { + DTSTREAM.println_P("Control status:"); + DTSTREAM.print_P(" Roll: nav="); DTSTREAM.print(nav_roll/100.0,2); DTSTREAM.print_P(", servo_out="); DTSTREAM.println((float)servo_out[CH_ROLL]/100.0,2); + DTSTREAM.print_P(" Pitch: nav="); DTSTREAM.print(nav_pitch/100.0,2); DTSTREAM.print_P(", servo_out="); DTSTREAM.println((float)servo_out[CH_PITCH]/100.0,2); + DTSTREAM.print_P(" Throttle: nav="); DTSTREAM.print(throttle_cruise,DEC); DTSTREAM.print_P(", servo_out="); DTSTREAM.println(servo_out[CH_THROTTLE],DEC); + + //------- status gps ------- + } else if (strmatch(buf+7, PSTR("gps"))) { + DTSTREAM.println_P("GPS status:"); + DTSTREAM.print_P(" Fix: "); + if (GPS.fix == 0) + DTSTREAM.print_P("INVALID ("); + else + DTSTREAM.print_P("Valid ("); + DTSTREAM.print(GPS.fix,DEC); + DTSTREAM.println_P(")"); + DTSTREAM.print_P(" Satellites: "); DTSTREAM.println(GPS.num_sats,DEC); + DTSTREAM.print_P(" Fix count: "); DTSTREAM.println(gps_fix_count,DEC); + + //------- status landing ------- + } else if (strmatch(buf+7, PSTR("landing"))) { + DTSTREAM.println_P("Landing status:"); + DTSTREAM.print_P(" land_complete = "); DTSTREAM.println(land_complete,DEC); + DTSTREAM.print_P(" landing_pitch = "); DTSTREAM.println(landing_pitch,DEC); + DTSTREAM.print_P(" nav_pitch = "); DTSTREAM.println(nav_pitch,DEC); + DTSTREAM.print_P(" airspeed_cruise = "); DTSTREAM.println(airspeed_cruise,DEC); + DTSTREAM.print_P(" throttle_cruise = "); DTSTREAM.println(throttle_cruise,DEC); + DTSTREAM.print_P(" hold_course = "); DTSTREAM.println(hold_course,DEC); + DTSTREAM.print_P(" nav_bearing = "); DTSTREAM.println(nav_bearing,DEC); + DTSTREAM.print_P(" bearing_error = "); DTSTREAM.println(bearing_error,DEC); + + //------- status loiter ------- + } else if (strmatch(buf+7, PSTR("loiter"))) { + DTSTREAM.println_P("Loiter status:"); + DTSTREAM.print_P(" Loiter radius: "); DTSTREAM.println(loiter_radius,DEC); + DTSTREAM.print_P(" Progress: "); DTSTREAM.print(loiter_sum,DEC); DTSTREAM.print_P("°/"); DTSTREAM.print(loiter_total,DEC); DTSTREAM.println_P("°"); + DTSTREAM.print_P(" Time: "); DTSTREAM.print(loiter_time,DEC); DTSTREAM.print_P("ms/"); DTSTREAM.print(loiter_time_max,DEC); DTSTREAM.println_P("ms"); + + //------- status navigation ------- + } else if (strmatch(buf+7, PSTR("navigation"))) { + DTSTREAM.println_P("Navigation status:"); + DTSTREAM.print_P(" From <"); DTSTREAM.print((float)prev_WP.lat/10000000.0,6); DTSTREAM.print_P(", "); DTSTREAM.print((float)prev_WP.lng/10000000.0,6); DTSTREAM.print_P(", "); DTSTREAM.print((float)prev_WP.alt/100.0,1); DTSTREAM.print_P(">: "); print_rlocation(&prev_WP); + DTSTREAM.print_P(" At <"); DTSTREAM.print((float)current_loc.lat/10000000.0,6); DTSTREAM.print_P(", "); DTSTREAM.print((float)current_loc.lng/10000000.0,6); DTSTREAM.print_P(", "); DTSTREAM.print((float)current_loc.alt/100.0,1); DTSTREAM.println_P(">"); + DTSTREAM.print_P(" To <"); DTSTREAM.print((float)next_WP.lat/10000000.0,6); DTSTREAM.print_P(", "); DTSTREAM.print((float)next_WP.lng/10000000.0,6); DTSTREAM.print_P(", "); DTSTREAM.print((float)next_WP.alt/100.0,1); DTSTREAM.print_P(">: "); print_rlocation(&next_WP); + DTSTREAM.print_P(" Distance: "); DTSTREAM.print(100.0*(float)(wp_totalDistance-wp_distance)/(float)wp_totalDistance,1); DTSTREAM.print_P("% "); DTSTREAM.print(wp_totalDistance-wp_distance,DEC); DTSTREAM.print_P("m / "); DTSTREAM.print(wp_totalDistance,DEC); DTSTREAM.print_P("m; "); DTSTREAM.print(altitude_error/100.0,2); DTSTREAM.println_P("m vertically"); + DTSTREAM.print_P(" Nav bearing: "); DTSTREAM.print(nav_bearing/100.0,2); DTSTREAM.print_P("; error = "); DTSTREAM.println(bearing_error/100.0,2); + DTSTREAM.print_P(" Ground course: "); DTSTREAM.print(GPS.ground_course/100.0,1); DTSTREAM.print_P(" (current), "); DTSTREAM.print(target_bearing/100.0,1); DTSTREAM.println_P(" (target)"); + if (hold_course >= 0) { + DTSTREAM.print_P(" HOLD COURSE: "); DTSTREAM.println(hold_course/100.0,2); + } + + /*DTSTREAM.print_P(" Crosstrack bearing: "); DTSTREAM.println(crosstrack_bearing/100.0,DEC); + DTSTREAM.print_P(" Crosstrack error: "); DTSTREAM.println(crosstrack_error/100.0,DEC); + DTSTREAM.print_P(" Climb rate: "); DTSTREAM.println(climb_rate/100.0,DEC);*/ + + + //------- status navpitch ------- + } else if (strmatch(buf+7, PSTR("navpitch"))) { +#if AIRSPEED_SENSOR == 1 + DTSTREAM.print_P("nav_pitch = PID[airspeed_error ("); DTSTREAM.print(airspeed_error/100.0,2); DTSTREAM.print_P(") = airspeed_cruise ("); DTSTREAM.print((float)airspeed_cruise/100.0,2); DTSTREAM.print_P(") - airspeed ("); DTSTREAM.print((float)airspeed/100.0,2); DTSTREAM.println_P(")]"); +#else + DTSTREAM.print_P("nav_pitch = PID[altitude_error ("); DTSTREAM.print(altitude_error,DEC); DTSTREAM.print_P(") = target_altitude ("); DTSTREAM.print(target_altitude,DEC); DTSTREAM.print_P(") - current_loc.alt ("); DTSTREAM.print(current_loc.alt,DEC); DTSTREAM.println_P(")]"); +#endif + DTSTREAM.print_P("nav_pitch ("); DTSTREAM.print((float)nav_pitch/100.0,2); DTSTREAM.print_P(") - pitch_sensor ("); DTSTREAM.print((float)pitch_sensor/100.0,2); DTSTREAM.print_P(") + pitch_comp ("); DTSTREAM.print(abs(roll_sensor*kff[CASE_PITCH_COMP])/100.0,2); DTSTREAM.print_P(") = "); DTSTREAM.println((float)(nav_pitch-pitch_sensor+abs(roll_sensor*kff[CASE_PITCH_COMP]))/100.0,2); + DTSTREAM.print_P("servo_out[CH_PITCH] ("); DTSTREAM.print((float)servo_out[CH_PITCH]/100.0,2); DTSTREAM.println_P(") = PID[nav_pitch + pitch_comp - pitch_sensor]"); + + //------- status navroll ------- + } else if (strmatch(buf+7, PSTR("navroll"))) { + print_rlocation(&next_WP); + DTSTREAM.print_P("bearing_error ("); DTSTREAM.print(bearing_error,DEC); DTSTREAM.print_P(") = nav_bearing ("); DTSTREAM.print(nav_bearing,DEC); DTSTREAM.print_P(") - yaw_sensor ("); DTSTREAM.print(yaw_sensor,DEC); DTSTREAM.println_P(")"); + DTSTREAM.print_P("nav_roll ("); DTSTREAM.print(nav_roll,DEC); DTSTREAM.print_P(") - roll_sensor ("); DTSTREAM.print(roll_sensor,DEC); DTSTREAM.print_P(") = "); DTSTREAM.print(nav_roll-roll_sensor,DEC); DTSTREAM.println_P(")"); + DTSTREAM.print_P("servo_out[CH_ROLL] = "); DTSTREAM.println(servo_out[CH_ROLL],DEC); + + //------- status rcinputch ------- + } else if (strmatch(buf+7, PSTR("rcinputch"))) { + unsigned char i; + DTSTREAM.println_P("RC hardware input:"); + for (i=0; i<8; i++) { + DTSTREAM.print_P(" Ch"); + DTSTREAM.print(i+1,DEC); + DTSTREAM.print_P(": "); + DTSTREAM.println(APM_RC.InputCh(i)); + } + + //------- status rcin ------- + } else if (strmatch(buf+7, PSTR("rcin"))) { + unsigned char i; + DTSTREAM.println_P("RC software input:"); + for (i=0; i<8; i++) { + DTSTREAM.print_P(" Ch"); + DTSTREAM.print(i+1,DEC); + DTSTREAM.print_P(": "); + DTSTREAM.println(radio_in[i]); + } + + //------- status rcout ------- + } else if (strmatch(buf+7, PSTR("rcout"))) { + unsigned char i; + DTSTREAM.println_P("RC software output:"); + for (i=0; i<8; i++) { + DTSTREAM.print_P(" Ch"); + DTSTREAM.print(i+1,DEC); + DTSTREAM.print_P(": "); + DTSTREAM.println(radio_out[i]); + } + + //------- status rcpwm ------- + } else if (strmatch(buf+7, PSTR("rcpwm"))) { + unsigned char i; + DTSTREAM.println_P("RC hardware output:"); + for (i=0; i<8; i++) { + DTSTREAM.print_P(" Ch"); + DTSTREAM.print(i+1,DEC); + DTSTREAM.print_P(": "); + DTSTREAM.println(readOutputCh(i)); + } + + //------- status rctrim ------- + } else if (strmatch(buf+7, PSTR("rctrim"))) { + unsigned char i; + DTSTREAM.println_P("RC trim:"); + for (i=0; i<8; i++) { + DTSTREAM.print_P(" Ch"); + DTSTREAM.print(i+1,DEC); + DTSTREAM.print_P(": "); + DTSTREAM.println(radio_trim[i]); + } + DTSTREAM.print_P(" elevon1_trim = "); DTSTREAM.println(elevon1_trim,DEC); + DTSTREAM.print_P(" elevon2_trim = "); DTSTREAM.println(elevon2_trim,DEC); + + //------- status rc ------- + } else if (strmatch(buf+7, PSTR("rc"))) { + unsigned char i; + DTSTREAM.println_P("RC:\tCh\tHWin\tSWtrim\tSWin\tServo\tSWout\tHWout\t"); + for (i=0; i<8; i++) { + DTSTREAM.print_P("\t"); DTSTREAM.print(i+1,DEC); + DTSTREAM.print_P("\t"); DTSTREAM.print(APM_RC.InputCh(i),DEC); + DTSTREAM.print_P("\t"); DTSTREAM.print(radio_trim[i],DEC); + DTSTREAM.print_P("\t"); DTSTREAM.print(radio_in[i],DEC); + DTSTREAM.print_P("\t"); DTSTREAM.print(((float)servo_out[i])/100,2); + DTSTREAM.print_P("\t"); DTSTREAM.print(radio_out[i],DEC); + DTSTREAM.print_P("\t"); DTSTREAM.println(readOutputCh(i),DEC); + } + + //------- status system ------- + } else if (strmatch(buf+7, PSTR("system"))) { + DTSTREAM.println_P("System status:"); + DTSTREAM.print_P(" Ground start: "); if (ground_start) DTSTREAM.print_P("YES ("); else DTSTREAM.print_P("NO ("); + DTSTREAM.print(ground_start,DEC); DTSTREAM.println_P(")"); + DTSTREAM.print_P(" Home: "); if (home_is_set) DTSTREAM.print_P(" SET("); else DTSTREAM.print_P("NOT SET ("); + DTSTREAM.print(home_is_set,DEC); DTSTREAM.println_P(")"); + + //------- status takeoff ------- + } else if (strmatch(buf+7, PSTR("takeoff"))) { + DTSTREAM.println_P("Takeoff status:"); + DTSTREAM.print_P(" takeoff_pitch = "); DTSTREAM.println((float)takeoff_pitch/100.0,2); + DTSTREAM.print_P(" scaler = "); DTSTREAM.println((float)airspeed/(float)airspeed_cruise,3); + DTSTREAM.print_P(" nav_pitch = "); DTSTREAM.println((float)nav_pitch/100.0,2); + DTSTREAM.print_P(" throttle = "); DTSTREAM.println(servo_out[CH_THROTTLE],DEC); + DTSTREAM.print_P(" hold_course = "); DTSTREAM.println((float)hold_course/100.0,2); + DTSTREAM.print_P(" nav_bearing = "); DTSTREAM.println(nav_bearing,DEC); + DTSTREAM.print_P(" bearing_error = "); DTSTREAM.println(bearing_error,DEC); + DTSTREAM.print_P(" current_loc.alt = "); DTSTREAM.println(current_loc.alt,DEC); + DTSTREAM.print_P(" home.alt + takeoff_altitude = "); DTSTREAM.println(home.alt + takeoff_altitude,DEC); + + //nav_pitch = constrain(nav_pitch, 0, takeoff_pitch * 100); + //calc_nav_pitch(); + nav_pitch = constrain(nav_pitch, 0, takeoff_pitch * 100); + + //------- status telemetry ------- + } else if (strmatch(buf+7, PSTR("telemetry"))) { + DTSTREAM.println_P("Telemetry status:"); + if (report_heartbeat) DTSTREAM.print_P(" Show "); else DTSTREAM.print_P(" Hide "); DTSTREAM.println_P("heartbeat"); + if (report_location) DTSTREAM.print_P(" Show "); else DTSTREAM.print_P(" Hide "); DTSTREAM.println_P("location"); + if (report_attitude) DTSTREAM.print_P(" Show "); else DTSTREAM.print_P(" Hide "); DTSTREAM.println_P("attitude"); + if (report_command) DTSTREAM.print_P(" Show "); else DTSTREAM.print_P(" Hide "); DTSTREAM.println_P("command"); + DTSTREAM.print_P(" Severity report level "); DTSTREAM.println(report_severity,DEC); + + //------- status throttle ------- + } else if (strmatch(buf+7, PSTR("throttle"))) { +#if AIRSPEED_SENSOR == 1 + DTSTREAM.print_P("airspeed_energy_error ("); DTSTREAM.print(airspeed_energy_error,DEC); DTSTREAM.print_P(") = 0.5 * (airspeed_cruise ("); DTSTREAM.print((float)airspeed_cruise/100.0,2); DTSTREAM.print_P(")^2 - airspeed ("); DTSTREAM.print((float)airspeed/100.0,2); DTSTREAM.println_P(")^2)"); + DTSTREAM.print_P("energy_error ("); DTSTREAM.print(energy_error,DEC); DTSTREAM.print_P(") = airspeed_energy_error ("); DTSTREAM.print(airspeed_energy_error,DEC); DTSTREAM.print_P(") + altitude_error*0.098 ("); DTSTREAM.print((long)((float)altitude_error*0.098),DEC); DTSTREAM.println_P(")"); + DTSTREAM.print_P("servo_out[CH_THROTTLE] ("); DTSTREAM.print(servo_out[CH_THROTTLE],DEC); DTSTREAM.println_P(") = PID[energy_error]"); +#else + DTSTREAM.print_P("altitude_error ("); DTSTREAM.print(altitude_error,DEC); DTSTREAM.print_P(") = target_altitude ("); DTSTREAM.print(target_altitude,DEC); DTSTREAM.print_P(") - current_loc.alt ("); DTSTREAM.print(current_loc.alt,DEC); DTSTREAM.println_P(")"); + DTSTREAM.print_P("servo_out[CH_THROTTLE] ("); DTSTREAM.print(servo_out[CH_THROTTLE],DEC); DTSTREAM.println_P(") = PID[altitude_error]"); +#endif + + //------- status waypoints ------- + } else if (strmatch(buf+7, PSTR("waypoints"))) { + DTSTREAM.println_P("Waypoints status:"); + DTSTREAM.print_P(" Distance: "); DTSTREAM.print(wp_distance,DEC); DTSTREAM.print_P("/"); DTSTREAM.println(wp_totalDistance,DEC); + DTSTREAM.print_P(" Index: "); DTSTREAM.print(wp_index,DEC); DTSTREAM.print_P("/"); DTSTREAM.println(wp_total,DEC); + DTSTREAM.print_P(" Next: "); DTSTREAM.println(next_wp_index,DEC); + + } else if (strmatch(buf+7, PSTR("james"))) { + DTSTREAM.println_P("James is a monkey"); + } else { + print_error(ERR("USAGE: status {control|gps|landing|loiter|mixing|navigation|navpitch|navroll|rc|rcinputch|rcin|rcout|rcpwm|rctrim|system|takeoff|telemetry|throttle|waypoints}")); + } + } else { + print_error(ERR("USAGE: {echo |groundstart|inithome|show|hide|print|status|set|reset|rtl}")); + print_error(ERR("Type -? for specific usage guidance")); + } +} + +/* strmatch compares two strings and returns 1 if they match and 0 if they don't + s2 must be stored in program memory (via PSTR) rather than RAM (like standard strings) + s1 must be at least as long as s2 for a valid match + if s1 is longer than s2, then only the beginning of s1 (the length of s2) must match s2 for a valid match */ +int strmatch(char* s1, const char* s2) { + int i = 0; + char c1 = s1[0], c2 = pgm_read_byte(s2); + + while (c1 != 0 && c2 != 0) { + if (c1 < c2) + return 0; + if (c1 > c2) + return 0; + i++; + c1 = s1[i]; + c2 = pgm_read_byte(s2+i); + } + + if (c2==0) + return 1; + else + return 0; +} + +/* readfloat parses a string written as a float starting at the offset in *i and updates *i as it parses + numbers without a decimal place are read as integers + numbers with a decimial place are multiplied by 10,000,000 and decimals beyond 7 places are discarded + parsing is terminated with either a space or a null, other characters are ignored */ +long readfloat(char* s, unsigned char* i) { + long result = 0, multiplier = 0; + char c, neg = 0; + + for (;;(*i)++) { + c = s[*i]; + if (c == ' ') + break; + else if (c == 0) + break; + else if (c == '-') + neg = 1-neg; + else if (c == '.') { + result *= 10000000; + multiplier = 1000000; + } else if (c >= '0' && c <= '9') { + if (multiplier == 0) + result = (result*10) + c-'0'; + else { + result += (c-'0')*multiplier; + multiplier /= 10; + } + } + } + + if (multiplier == 0) + result *= 10000000; + + if (neg) + return -result; + else + return result; +} + +/* process_set_cmd processing the parameters of a 'set cmd' command and takes the appropriate action + *buffer is the buffer containing the parameters of the command; it should start after the space after 'set cmd' + bufferlen is the length of the buffer; the routine will stop looking for parameters after the offset index reaches this value +*/ +#define SETPARAM_NONE (0) +#define SETPARAM_ID (1) +#define SETPARAM_P1 (2) +#define SETPARAM_LAT (3) +#define SETPARAM_LNG (4) +#define SETPARAM_ALT (5) +#define SETPARAM_P2 (6) +#define SETPARAM_P3 (7) +#define SETPARAM_P4 (8) + +void process_set_cmd(char *buffer, int bufferlen) { + unsigned char i, j, err=1, setparam=SETPARAM_NONE; + unsigned char cmdindex=0, p1=0, cmdid; + long lat, lng, alt; + Location temp; + + //Parse the command index + for (i=0; i= '0' && buffer[i] <= '9') + cmdindex = (cmdindex*10) + buffer[i]-'0'; + else + break; + + if (buffer[i] == ' ') { + //Find the end of the command-type string + i++; + for (j=i; j SETPARAM_NONE) { + //Process new parameter value + i = j+1; + lat = readfloat(buffer, &i); + temp = get_wp_with_index(cmdindex); + if (setparam == SETPARAM_ID) + temp.id = lat/10000000; + else if (setparam == SETPARAM_P1) + temp.p1 = lat/10000000; + else if (setparam == SETPARAM_ALT) + temp.alt = lat/100000; + else if (setparam == SETPARAM_LAT) + temp.lat = lat; + else if (setparam == SETPARAM_LNG) + temp.lng = lat; + else if (setparam == SETPARAM_P2) + temp.alt = lat/10000000; + else if (setparam == SETPARAM_P3) + temp.lat = lat/10000000; + else if (setparam == SETPARAM_P4) + temp.lng = lat/10000000; + cmdid = temp.id; + p1 = temp.p1; + lat = temp.lat; + lng = temp.lng; + alt = temp.alt; + err = 0; + } else { + //Process param 1 + for (i=j+1; i= '0' && buffer[i] <= '9') + p1 = (p1*10) + buffer[i]-'0'; + else + break; + } + + if (buffer[i] == ' ') { + //Process altitude + i++; + if (strmatch(buffer+i, PSTR("here"))) { + lat = GPS.latitude; + lng = GPS.longitude; + alt = get_altitude_above_home(); //GPS.altitude; + err = 0; + } else { + alt = readfloat(buffer, &i)/100000; + + if (buffer[i] == ' ') { + //Process latitude + i++; + lat = readfloat(buffer, &i); + if (strmatch(buffer+i, PSTR("here"))) { + lat = GPS.latitude; + lng = GPS.longitude; + err = 0; + } else { + if (buffer[i] == ' ') { + //Process longitude + i++; + lng = readfloat(buffer, &i); + err = 0; + } else + print_error(ERR("Error processing set cmd: Could not find longitude parameter")); + } + } else + print_error(ERR("Error processing set cmd: Could not find latitude parameter")); + } + } else + print_error(ERR("Error processing set cmd: Could not find altitude parameter")); + } + } else + print_error(ERR("Error processing set cmd: Could not find command type")); + } else + print_error(ERR("Error processing set cmd: Could not find command index")); + + if (err == 0) { + temp.id = cmdid; + if (cmdid == CMD_LAND_OPTIONS) { + temp.p1 = p1; + temp.alt = alt; + temp.lat = lat / 10000000; + temp.lng = lng / 10000000; + } else { + temp.p1 = p1; + temp.lat = lat; + temp.lng = lng; + temp.alt = alt; + } + if (cmdindex >= wp_total) { + wp_total = cmdindex+1; + save_EEPROM_waypoint_info(); + } + set_wp_with_index(temp, cmdindex); + + DTSTREAM.print_P("Set command "); + DTSTREAM.print((int)cmdindex); + DTSTREAM.print_P(" to "); + DTSTREAM.print((int)temp.id); + DTSTREAM.print_P(" with p1="); + DTSTREAM.print((int)temp.p1); + DTSTREAM.print_P(", lat="); + DTSTREAM.print(temp.lat); + DTSTREAM.print_P(", lng="); + DTSTREAM.print(temp.lng); + DTSTREAM.print_P(", alt="); + DTSTREAM.println(temp.alt); + } +} + +/* get_pid_offset_name matches a string expressed in *buffer with a pid keyword and returns the k-array + gain offset in *offset, and the length of that string expression in *length. If a good keyword + match is found, 1 is returned; 0 otherwise +*/ +int get_pid_offset_name(char *buffer, int *offset, unsigned char *length) { + if (strmatch(buffer, PSTR("servoroll"))) { + *length += 9; *offset = CASE_SERVO_ROLL; + } else if (strmatch(buffer, PSTR("servopitch"))) { + *length += 10; *offset = CASE_SERVO_PITCH; + } else if (strmatch(buffer, PSTR("servorudder"))) { + *length += 11; *offset = CASE_SERVO_RUDDER; + } else if (strmatch(buffer, PSTR("navroll"))) { + *length += 7; *offset = CASE_NAV_ROLL; + } else if (strmatch(buffer, PSTR("navpitchasp"))) { + *length += 11; *offset = CASE_NAV_PITCH_ASP; + } else if (strmatch(buffer, PSTR("navpitchalt"))) { + *length += 11; *offset = CASE_NAV_PITCH_ALT; + } else if (strmatch(buffer, PSTR("throttlete"))) { + *length += 10; *offset = CASE_TE_THROTTLE; + } else if (strmatch(buffer, PSTR("throttlealt"))) { + *length += 11; *offset = CASE_ALT_THROTTLE; + } else { + return 0; + } + + return 1; +} + +/* print_rlocation prints the relative location of the specified waypoint from the plane in easy-to-read cartesian format +*/ +void print_rlocation(Location *wp) { + float x, y; + y = (float)(wp->lat - current_loc.lat) * 0.0111194927; + x = (float)(wp->lng - current_loc.lng) * cos(radians(current_loc.lat)) * 0.0111194927; + DTSTREAM.print_P("dP = <"); + DTSTREAM.print(abs((int)y),DEC); + if (y >= 0) DTSTREAM.print_P("N, "); else DTSTREAM.print_P("S, "); + DTSTREAM.print(abs((int)x),DEC); + if (x >= 0) DTSTREAM.print_P("E, "); else DTSTREAM.print_P("W, "); + DTSTREAM.print((float)(wp->alt - current_loc.alt)/100,1); + DTSTREAM.println_P("> meters"); +} + +/* print_error prints an error message if the user sends an invalid command +*/ +void print_error(const char *msg) { + if (msg == 0) + DTSTREAM.println_P(PSTR("ERROR: Invalid command")); + else + DTSTREAM.println_P(msg); +} + +void send_message(byte severity, const char *str) // This is the instance of send_message for message 0x05 +{ + if(severity >= DEBUG_LEVEL){ + DTSTREAM.print_P("MSG: "); + DTSTREAM.println(str); + } +} + +void send_message(byte id) { + send_message(id,(long)0); +} + +void send_message(byte id, long param) { + + switch(id) { + case MSG_HEARTBEAT: + if (report_heartbeat) + print_control_mode(); + break; + + case MSG_ATTITUDE: + if (report_attitude) + print_attitude(); + break; + + case MSG_LOCATION: + if (report_location) + print_position(); + if (first_location == 0) { + send_message(0,"First location received"); + first_location = 1; + } + break; + + case MSG_COMMAND: + struct Location cmd = get_wp_with_index(param); + print_waypoint(&cmd, param); + break; + + } +} + +void pipe() +{ + DTSTREAM.print_P("|"); +} + +void print_current_waypoints() +{ + DTSTREAM.println_P("Current waypoints:"); + DTSTREAM.print_P(" Prev:"); + DTSTREAM.print_P("\t"); + DTSTREAM.print(prev_WP.lat,DEC); + DTSTREAM.print_P(",\t"); + DTSTREAM.print(prev_WP.lng,DEC); + DTSTREAM.print_P(",\t"); + DTSTREAM.println(prev_WP.alt,DEC); + + DTSTREAM.print_P(" Cur: "); + DTSTREAM.print_P("\t"); + DTSTREAM.print(current_loc.lat,DEC); + DTSTREAM.print_P(",\t"); + DTSTREAM.print(current_loc.lng,DEC); + DTSTREAM.print_P(",\t"); + DTSTREAM.println(current_loc.alt,DEC); + + DTSTREAM.print_P(" Next:"); + DTSTREAM.print(wp_index,DEC); + DTSTREAM.print_P(",\t"); + DTSTREAM.print(next_WP.lat,DEC); + DTSTREAM.print_P(",\t"); + DTSTREAM.print(next_WP.lng,DEC); + DTSTREAM.print_P(",\t"); + DTSTREAM.println(next_WP.alt,DEC); +} + +void print_position(void) +{ + DTSTREAM.print_P("Pos: "); + DTSTREAM.print(current_loc.lat,DEC); // 0 + DTSTREAM.print_P(", "); //° + DTSTREAM.print(current_loc.lng,DEC); // 1 + DTSTREAM.print_P(", "); + DTSTREAM.print(current_loc.alt,DEC); // 2 + DTSTREAM.print_P("cm, "); + DTSTREAM.print(GPS.ground_speed,DEC); // 3 + DTSTREAM.print_P("cm/s GS, "); + DTSTREAM.print(airspeed,DEC); // 4 + DTSTREAM.print_P("cm/s AS, "); + DTSTREAM.print(get_altitude_above_home(),DEC); // 5 + DTSTREAM.print_P("cm above home, "); + DTSTREAM.print(climb_rate,DEC); // 6 + DTSTREAM.print_P("? climb, "); + DTSTREAM.print(wp_distance,DEC); // 7 + DTSTREAM.print_P("m from wp, "); + DTSTREAM.print(throttle_cruise,DEC); // 8 + DTSTREAM.print_P("% throttle, "); + DTSTREAM.print(altitude_error,DEC); // 9 + DTSTREAM.println_P("alt err"); +} + +void print_attitude(void) +{ + DTSTREAM.print_P("Att: "); + DTSTREAM.print(radio_in[CH_ROLL],DEC); // 0 + DTSTREAM.print_P(" roll in, "); + DTSTREAM.print(radio_in[CH_PITCH],DEC); // 1 + DTSTREAM.print_P(" pitch in, "); + DTSTREAM.print(radio_in[CH_THROTTLE],DEC); // 2 + DTSTREAM.print_P(" throttle in, "); + DTSTREAM.print(roll_sensor,DEC); // 3 + DTSTREAM.print_P(" roll sensor, "); + DTSTREAM.print(pitch_sensor,DEC); // 4 + DTSTREAM.print_P(" pitch sensor, "); + DTSTREAM.print(GPS.ground_course,DEC); // 6 + DTSTREAM.print_P(" ground course, "); + DTSTREAM.print(target_bearing,DEC); // 7 + DTSTREAM.print_P(" target bearing, "); + DTSTREAM.print(nav_roll,DEC); // 8 + DTSTREAM.print_P(" nav roll, "); + DTSTREAM.print(loiter_sum,DEC); // 8 + DTSTREAM.print_P(" loiter sum, "); + DTSTREAM.print(servo_out[CH_ROLL],DEC); + DTSTREAM.print_P(" roll servo_out, "); + DTSTREAM.print(servo_out[CH_PITCH],DEC); + DTSTREAM.println_P(" pitch servo_out"); +} + +// required by Groundstation to plot lateral tracking course +void print_new_wp_info() +{ + DTSTREAM.print_P("New waypt ("); + DTSTREAM.print(wp_index,DEC); //0 + DTSTREAM.print_P("): "); + DTSTREAM.print(prev_WP.lat,DEC); //1 + DTSTREAM.print_P(", "); //° + DTSTREAM.print(prev_WP.lng,DEC); //2 + DTSTREAM.print_P(", "); + DTSTREAM.print(prev_WP.alt,DEC); //3 + DTSTREAM.print_P("m -> "); + DTSTREAM.print(next_WP.lat,DEC); //4 + DTSTREAM.print_P("°, "); + DTSTREAM.print(next_WP.lng,DEC); //5 + DTSTREAM.print_P("°, "); + DTSTREAM.print(next_WP.alt,DEC); //6 + DTSTREAM.print_P("m; "); + DTSTREAM.print(wp_totalDistance,DEC); //7 + DTSTREAM.print_P("m dist, "); + DTSTREAM.print(radio_trim[CH_ROLL],DEC); //8 + DTSTREAM.print_P(" roll trim, "); + DTSTREAM.print(radio_trim[CH_PITCH],DEC); //9 + DTSTREAM.println_P(" pitch trim"); +} + +void print_control_mode(void) +{ + switch (control_mode){ + case MANUAL: + DTSTREAM.println_P("##MANUAL"); + break; + case STABILIZE: + DTSTREAM.println_P("##STABILIZE"); + break; + case FLY_BY_WIRE_A: + DTSTREAM.println_P("##FBW A"); + break; + case FLY_BY_WIRE_B: + DTSTREAM.println_P("##FBW B"); + break; + case AUTO: + DTSTREAM.println_P("##AUTO"); + break; + case RTL: + DTSTREAM.println_P("##RTL"); + break; + case LOITER: + DTSTREAM.println_P("##LOITER"); + break; + case 98: + DTSTREAM.println_P("##Air Start Complete"); + break; + case 99: + DTSTREAM.println_P("##Ground Start Complete"); + break; + } +} + +void print_tuning(void) { + DTSTREAM.print_P("TUN:"); + DTSTREAM.print(servo_out[CH_ROLL]); + DTSTREAM.print_P(", "); + DTSTREAM.print(nav_roll/100,DEC); + DTSTREAM.print_P(", "); + DTSTREAM.print(roll_sensor/100,DEC); + DTSTREAM.print_P(", "); + DTSTREAM.print(servo_out[CH_PITCH]); + DTSTREAM.print_P(", "); + DTSTREAM.print(nav_pitch/100,DEC); + DTSTREAM.print_P(", "); + DTSTREAM.println(pitch_sensor/100,DEC); +} + +void printPerfData(void) +{ +} + + +void print_waypoint(struct Location *cmd,byte index) +{ + //TODO: Why does this stop printing in the middle?? --BJP + DTSTREAM.print_P(" command #: "); + DTSTREAM.print(index, DEC); + DTSTREAM.print_P(" id: "); + switch (cmd->id) { + // Command IDs - Must + case CMD_BLANK: DTSTREAM.print_P("CMD_BLANK"); break; + case CMD_WAYPOINT: DTSTREAM.print_P("CMD_WAYPOINT"); break; + case CMD_LOITER: DTSTREAM.print_P("CMD_LOITER"); break; + case CMD_LOITER_N_TURNS: DTSTREAM.print_P("CMD_LOITER_N_TURNS"); break; + case CMD_LOITER_TIME: DTSTREAM.print_P("CMD_LOITER_TIME"); break; + case CMD_RTL: DTSTREAM.print_P("CMD_RTL"); break; + case CMD_LAND: DTSTREAM.print_P("CMD_LAND"); break; + case CMD_TAKEOFF: DTSTREAM.print_P("CMD_TAKEOFF"); break; + + // Command IDs - May + case CMD_DELAY: DTSTREAM.print_P("CMD_DELAY"); break; + case CMD_CLIMB: DTSTREAM.print_P("CMD_CLIMB"); break; + case CMD_LAND_OPTIONS: DTSTREAM.print_P("CMD_LAND_OPTIONS"); break; + + // Command IDs - Now + case CMD_RESET_INDEX: DTSTREAM.print_P("CMD_RESET_INDEX"); break; + case CMD_GOTO_INDEX: DTSTREAM.print_P("CMD_GOTO_INDEX"); break; + case CMD_GETVAR_INDEX: DTSTREAM.print_P("CMD_GETVAR_INDEX"); break; + case CMD_SENDVAR_INDEX: DTSTREAM.print_P("CMD_SENDVAR_INDEX"); break; + case CMD_TELEMETRY: DTSTREAM.print_P("CMD_TELEMETRY"); break; + + case CMD_THROTTLE_CRUISE: DTSTREAM.print_P("CMD_THROTTLE_CRUISE"); break; + case CMD_AIRSPEED_CRUISE: DTSTREAM.print_P("CMD_AIRSPEED_CRUISE"); break; + case CMD_RESET_HOME: DTSTREAM.print_P("CMD_RESET_HOME"); break; + + case CMD_KP_GAIN: DTSTREAM.print_P("CMD_KP_GAIN"); break; + case CMD_KI_GAIN: DTSTREAM.print_P("CMD_KI_GAIN"); break; + case CMD_KD_GAIN: DTSTREAM.print_P("CMD_KD_GAIN"); break; + case CMD_KI_MAX: DTSTREAM.print_P("CMD_KI_MAX"); break; + case CMD_KFF_GAIN: DTSTREAM.print_P("CMD_KFF_GAIN"); break; + + case CMD_RADIO_TRIM: DTSTREAM.print_P("CMD_RADIO_TRIM"); break; + case CMD_RADIO_MAX: DTSTREAM.print_P("CMD_RADIO_MAX"); break; + case CMD_RADIO_MIN: DTSTREAM.print_P("CMD_RADIO_MIN"); break; + case CMD_ELEVON_TRIM: DTSTREAM.print_P("CMD_ELEVON_TRIM"); break; + + case CMD_INDEX: DTSTREAM.print_P("CMD_INDEX"); break; + case CMD_REPEAT: DTSTREAM.print_P("CMD_REPEAT"); break; + case CMD_RELAY: DTSTREAM.print_P("CMD_RELAY"); break; + case CMD_SERVO: DTSTREAM.print_P("CMD_SERVO"); break; + + default: DTSTREAM.print(cmd->id,DEC); + } + DTSTREAM.print_P(" p1: "); + DTSTREAM.print(cmd->p1,DEC); + DTSTREAM.print_P(" p2/alt: "); + DTSTREAM.print(cmd->alt,DEC); + DTSTREAM.print_P(" p3/lat: "); + DTSTREAM.print(cmd->lat,DEC); + DTSTREAM.print_P(" p4/lng: "); + DTSTREAM.println(cmd->lng,DEC); +} + +void print_waypoints() +{ + DTSTREAM.println_P("Commands in memory:"); + DTSTREAM.print_P(" "); + DTSTREAM.print(wp_total, DEC); + DTSTREAM.println_P(" commands total"); + // create a location struct to hold the temp Waypoints for printing + //Location tmp; + DTSTREAM.println_P(" Home: "); + struct Location cmd = get_wp_with_index(0); + print_waypoint(&cmd, 0); + DTSTREAM.println_P(" Commands: "); + + for (int i=1; i= DEBUG_LEVEL){ + Serial.print("MSG: "); + Serial.println(str); + } +} + +void print_current_waypoints() +{ +} + +void print_control_mode(void) +{ +} + +void print_attitude(void) +{ + //Serial.print("!!!VER:"); + //Serial.print(SOFTWARE_VER); //output the software version + //Serial.print(","); + +// Analogs + Serial.print("AN0:"); + Serial.print(read_adc(0)); //Reversing the sign. + Serial.print(",AN1:"); + Serial.print(read_adc(1)); + Serial.print(",AN2:"); + Serial.print(read_adc(2)); + Serial.print(",AN3:"); + Serial.print(read_adc(3)); + Serial.print (",AN4:"); + Serial.print(read_adc(4)); + Serial.print (",AN5:"); + Serial.print(read_adc(5)); + Serial.print (","); + +// DCM + Serial.print ("EX0:"); + Serial.print(convert_to_dec(DCM_Matrix[0][0])); + Serial.print (",EX1:"); + Serial.print(convert_to_dec(DCM_Matrix[0][1])); + Serial.print (",EX2:"); + Serial.print(convert_to_dec(DCM_Matrix[0][2])); + Serial.print (",EX3:"); + Serial.print(convert_to_dec(DCM_Matrix[1][0])); + Serial.print (",EX4:"); + Serial.print(convert_to_dec(DCM_Matrix[1][1])); + Serial.print (",EX5:"); + Serial.print(convert_to_dec(DCM_Matrix[1][2])); + Serial.print (",EX6:"); + Serial.print(convert_to_dec(DCM_Matrix[2][0])); + Serial.print (",EX7:"); + Serial.print(convert_to_dec(DCM_Matrix[2][1])); + Serial.print (",EX8:"); + Serial.print(convert_to_dec(DCM_Matrix[2][2])); + Serial.print (","); + +// Euler + Serial.print("RLL:"); + Serial.print(ToDeg(roll)); + Serial.print(",PCH:"); + Serial.print(ToDeg(pitch)); + Serial.print(",YAW:"); + Serial.print(ToDeg(yaw)); + Serial.print(",IMUH:"); + Serial.print(((int)imu_health>>8)&0xff); + Serial.print (","); + + + /* + #if MAGNETOMETER == ENABLED + Serial.print("MGX:"); + Serial.print(magnetom_x); + Serial.print (",MGY:"); + Serial.print(magnetom_y); + Serial.print (",MGZ:"); + Serial.print(magnetom_z); + Serial.print (",MGH:"); + Serial.print(MAG_Heading); + Serial.print (","); + #endif + */ + + //Serial.print("Temp:"); + //Serial.print(temp_unfilt/20.0); // Convert into degrees C + //alti(); + //Serial.print(",Pressure: "); + //Serial.print(press); + //Serial.print(",Alt: "); + //Serial.print(press_alt/1000); // Original floating point full solution in meters + //Serial.print (","); + Serial.println("***"); +} + +void print_location(void) +{ + Serial.print("LAT:"); + Serial.print(current_loc.lat); + Serial.print(",LON:"); + Serial.print(current_loc.lng); + Serial.print(",ALT:"); + Serial.print(current_loc.alt/100); // meters + Serial.print(",COG:"); + Serial.print(GPS.ground_course); + Serial.print(",SOG:"); + Serial.print(GPS.ground_speed); + Serial.print(",FIX:"); + Serial.print((int)GPS.fix); + Serial.print(",SAT:"); + Serial.print((int)GPS.num_sats); + Serial.print (","); + Serial.print("TOW:"); + Serial.print(GPS.time); + Serial.println("***"); +} + +void print_waypoints() +{ +} + +void print_waypoint(struct Location *cmd,byte index) +{ + Serial.print("command #: "); + Serial.print(index, DEC); + Serial.print(" id: "); + Serial.print(cmd->id,DEC); + Serial.print(" p1: "); + Serial.print(cmd->p1,DEC); + Serial.print(" p2: "); + Serial.print(cmd->alt,DEC); + Serial.print(" p3: "); + Serial.print(cmd->lat,DEC); + Serial.print(" p4: "); + Serial.println(cmd->lng,DEC); + +} + +long convert_to_dec(float x) +{ + return x*10000000; +} + +#endif diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/GCS_Jason_text.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/GCS_Jason_text.pde new file mode 100644 index 0000000000..37c9de372c --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/GCS_Jason_text.pde @@ -0,0 +1,238 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- + + +#if GCS_PROTOCOL == GCS_PROTOCOL_JASON + +// this is my personal GCS - Jason + + +void send_message(byte severity, const char *str) // This is the instance of send_message for message 0x05 +{ + if(severity >= DEBUG_LEVEL){ + Serial.print("MSG: "); + Serial.println(str); + } +} + +void send_message(byte id) +{ + send_message(id,(long)0); +} + +void send_message(byte id, long param) +{ + + switch(id) { + case MSG_HEARTBEAT: + print_control_mode(); + break; + + case MSG_ATTITUDE: + print_attitude(); + break; + + case MSG_LOCATION: + print_position(); + break; + + case MSG_COMMAND: + struct Location cmd = get_wp_with_index(param); + print_waypoint(&cmd, param); + break; + + } +} + +void pipe() +{ + Serial.print("|"); +} + +void print_current_waypoints() +{ + Serial.print("MSG: "); + + Serial.print("CUR:"); + Serial.print("\t"); + Serial.print(current_loc.lat,DEC); + Serial.print(",\t"); + Serial.print(current_loc.lng,DEC); + Serial.print(",\t"); + Serial.println(current_loc.alt,DEC); + + Serial.print("NWP:"); + Serial.print(wp_index,DEC); + Serial.print(",\t"); + Serial.print(next_WP.lat,DEC); + Serial.print(",\t"); + Serial.print(next_WP.lng,DEC); + Serial.print(",\t"); + Serial.println(next_WP.alt,DEC); +} + +void print_position(void) +{ + Serial.print("!!"); + Serial.print(current_loc.lat,DEC); // 0 + pipe(); + Serial.print(current_loc.lng,DEC); // 1 + pipe(); + Serial.print(current_loc.alt,DEC); // 2 + pipe(); + Serial.print(GPS.ground_speed,DEC); // 3 + pipe(); + Serial.print(airspeed,DEC); // 4 + pipe(); + Serial.print(get_altitude_above_home(),DEC); // 5 + pipe(); + Serial.print(climb_rate,DEC); // 6 + pipe(); + Serial.print(wp_distance,DEC); // 7 + pipe(); + Serial.print(throttle_cruise,DEC); // 8 + pipe(); + Serial.println(altitude_error,DEC); // 9 + +} + +void print_attitude(void) +{ + //return; + + Serial.print("++"); + Serial.print(radio_in[0],DEC); // 0 + pipe(); + Serial.print(radio_in[1],DEC); // 1 + pipe(); + Serial.print(radio_in[CH_THROTTLE],DEC); // 2 + pipe(); + Serial.print(roll_sensor,DEC); // 3 + pipe(); + Serial.print(pitch_sensor,DEC); // 4 + pipe(); + Serial.print("0"); // 5 ir_max - removed, no longer applicable + pipe(); + Serial.print(yaw_sensor,DEC); // 6 + pipe(); + Serial.print(target_bearing,DEC); // 7 + pipe(); + Serial.print(nav_roll,DEC); // 8 + pipe(); + Serial.println(loiter_sum,DEC); // 8 + +} + +// required by Groundstation to plot lateral tracking course +void print_new_wp_info() +{ + Serial.print("??"); + Serial.print(wp_index,DEC); //0 + pipe(); + Serial.print(prev_WP.lat,DEC); //1 + pipe(); + Serial.print(prev_WP.lng,DEC); //2 + pipe(); + Serial.print(prev_WP.alt,DEC); //3 + pipe(); + Serial.print(next_WP.lat,DEC); //4 + pipe(); + Serial.print(next_WP.lng,DEC); //5 + pipe(); + Serial.print(next_WP.alt,DEC); //6 + pipe(); + Serial.print(wp_totalDistance,DEC); //7 + pipe(); + Serial.print(radio_trim[CH_ROLL],DEC); //8 + pipe(); + Serial.println(radio_trim[CH_PITCH],DEC); //9 +} + +void print_control_mode(void) +{ + switch (control_mode){ + case MANUAL: + Serial.println("##MANUAL"); + break; + case STABILIZE: + Serial.println("##STABILIZE"); + break; + case FLY_BY_WIRE_A: + Serial.println("##FBW A"); + break; + case FLY_BY_WIRE_B: + Serial.println("##FBW B"); + break; + case AUTO: + Serial.println("##AUTO"); + break; + case RTL: + Serial.println("##RTL"); + break; + case LOITER: + Serial.println("##LOITER"); + break; + case 98: + Serial.println("##Air Start Complete"); + break; + case 99: + Serial.println("##Ground Start Complete"); + break; + } +} + +void print_tuning(void) { + Serial.print("TUN:"); + Serial.print(servo_out[CH_ROLL]/100); + Serial.print(", "); + Serial.print(nav_roll/100,DEC); + Serial.print(", "); + Serial.print(roll_sensor/100,DEC); + Serial.print(", "); + Serial.print(servo_out[CH_PITCH]/100); + Serial.print(", "); + Serial.print(nav_pitch/100,DEC); + Serial.print(", "); + Serial.println(pitch_sensor/100,DEC); +} + +void printPerfData(void) +{ +} + + +void print_waypoint(struct Location *cmd,byte index) +{ + Serial.print("command #: "); + Serial.print(index, DEC); + Serial.print(" id: "); + Serial.print(cmd->id,DEC); + Serial.print(" p1: "); + Serial.print(cmd->p1,DEC); + Serial.print(" p2: "); + Serial.print(cmd->alt,DEC); + Serial.print(" p3: "); + Serial.print(cmd->lat,DEC); + Serial.print(" p4: "); + Serial.println(cmd->lng,DEC); +} + +void print_waypoints() +{ + Serial.println("Commands in memory"); + Serial.print("commands total: "); + Serial.println(wp_total, DEC); + // create a location struct to hold the temp Waypoints for printing + //Location tmp; + Serial.println("Home: "); + struct Location cmd = get_wp_with_index(0); + print_waypoint(&cmd, 0); + Serial.println("Commands: "); + + for (int i=1; i> 8) & 0xff; + tempint = battery_voltage1 * 100; // Battery voltage ( * 100) + mess_buffer[6] = tempint & 0xff; + mess_buffer[7] = (tempint >> 8) & 0xff; + tempint = command_must_index; // Command Index (waypoint level) + mess_buffer[8] = tempint & 0xff; + mess_buffer[9] = (tempint >> 8) & 0xff; + break; + + case MSG_ATTITUDE: // ** Attitude message + mess_buffer[0] = 0x06; + ck = 6; + tempint = roll_sensor; // Roll (degrees * 100) + mess_buffer[3] = tempint & 0xff; + mess_buffer[4] = (tempint >> 8) & 0xff; + tempint = pitch_sensor; // Pitch (degrees * 100) + mess_buffer[5] = tempint & 0xff; + mess_buffer[6] = (tempint >> 8) & 0xff; + tempint = yaw_sensor; // Yaw (degrees * 100) + mess_buffer[7] = tempint & 0xff; + mess_buffer[8] = (tempint >> 8) & 0xff; + break; + + case MSG_LOCATION: // ** Location / GPS message + mess_buffer[0] = 0x12; + ck = 18; + templong = current_loc.lat; // Latitude *10 * *7 in 4 bytes + mess_buffer[3] = templong & 0xff; + mess_buffer[4] = (templong >> 8) & 0xff; + mess_buffer[5] = (templong >> 16) & 0xff; + mess_buffer[6] = (templong >> 24) & 0xff; + + templong = current_loc.lng; // Longitude *10 * *7 in 4 bytes + mess_buffer[7] = templong & 0xff; + mess_buffer[8] = (templong >> 8) & 0xff; + mess_buffer[9] = (templong >> 16) & 0xff; + mess_buffer[10] = (templong >> 24) & 0xff; + + tempint = GPS.altitude / 100; // Altitude MSL in meters * 10 in 2 bytes + mess_buffer[11] = tempint & 0xff; + mess_buffer[12] = (tempint >> 8) & 0xff; + + tempint = GPS.ground_speed; // Speed in M / S * 100 in 2 bytes + mess_buffer[13] = tempint & 0xff; + mess_buffer[14] = (tempint >> 8) & 0xff; + + tempint = yaw_sensor; // Ground Course in degreees * 100 in 2 bytes + mess_buffer[15] = tempint & 0xff; + mess_buffer[16] = (tempint >> 8) & 0xff; + + templong = GPS.time; // Time of Week (milliseconds) in 4 bytes + mess_buffer[17] = templong & 0xff; + mess_buffer[18] = (templong >> 8) & 0xff; + mess_buffer[19] = (templong >> 16) & 0xff; + mess_buffer[20] = (templong >> 24) & 0xff; + break; + + case MSG_PRESSURE: // ** Pressure message + mess_buffer[0] = 0x04; + ck = 4; + tempint = current_loc.alt / 10; // Altitude MSL in meters * 10 in 2 bytes + mess_buffer[3] = tempint & 0xff; + mess_buffer[4] = (tempint >> 8) & 0xff; + tempint = (int)airspeed / 100; // Airspeed pressure + mess_buffer[5] = tempint & 0xff; + mess_buffer[6] = (tempint >> 8) & 0xff; + break; + +// case 0xMSG_STATUS_TEXT: // ** Status Text message +// mess_buffer[0]=sizeof(status_message[0])+1; +// ck=mess_buffer[0]; +// mess_buffer[2] = param&0xff; +// for (int i=3;i> 8) & 0xff; + mess_buffer[5] = (templong >> 16) & 0xff; + mess_buffer[6] = (templong >> 24) & 0xff; + tempint = mainLoop_count; // Main Loop cycles + mess_buffer[7] = tempint & 0xff; + mess_buffer[8] = (tempint >> 8) & 0xff; + mess_buffer[9] = G_Dt_max & 0xff; + mess_buffer[10] = gyro_sat_count; // Problem counts + mess_buffer[11] = adc_constraints; + mess_buffer[12] = renorm_sqrt_count; + mess_buffer[13] = renorm_blowup_count; + mess_buffer[14] = gps_fix_count; + tempint = (int)(imu_health * 1000); // IMU health metric + mess_buffer[15] = tempint & 0xff; + mess_buffer[16] = (tempint >> 8) & 0xff; + tempint = gcs_messages_sent; // GCS messages sent + mess_buffer[17] = tempint & 0xff; + mess_buffer[18] = (tempint >> 8) & 0xff; + break; + + case MSG_VALUE: // ** Requested Value message + mess_buffer[0] = 0x06; + ck = 6; + templong = param; // Parameter being sent + mess_buffer[3] = templong & 0xff; + mess_buffer[4] = (templong >> 8) & 0xff; + switch(param) { +// case 0x00: templong = roll_mode; break; +// case 0x01: templong = pitch_mode; break; + case 0x02: templong = yaw_mode; break; +// case 0x03: templong = throttle_mode; break; + case 0x04: templong = elevon1_trim; break; + case 0x05: templong = elevon2_trim; break; + case 0x10: templong = integrator[0] * 1000; break; + case 0x11: templong = integrator[1] * 1000; break; + case 0x12: templong = integrator[2] * 1000; break; + case 0x13: templong = integrator[3] * 1000; break; + case 0x14: templong = integrator[4] * 1000; break; + case 0x15: templong = integrator[5] * 1000; break; + case 0x16: templong = integrator[6] * 1000; break; + case 0x17: templong = integrator[7] * 1000; break; + case 0x1a: templong = kff[0]; break; + case 0x1b: templong = kff[1]; break; + case 0x1c: templong = kff[2]; break; + case 0x20: templong = target_bearing; break; + case 0x21: templong = nav_bearing; break; + case 0x22: templong = bearing_error; break; + case 0x23: templong = crosstrack_bearing; break; + case 0x24: templong = crosstrack_error; break; + case 0x25: templong = altitude_error; break; + case 0x26: templong = wp_radius; break; + case 0x27: templong = loiter_radius; break; +// case 0x28: templong = wp_mode; break; +// case 0x29: templong = loop_commands; break; + case 0x2a: templong = nav_gain_scaler; break; + } + mess_buffer[5] = templong & 0xff; + mess_buffer[6] = (templong >> 8) & 0xff; + mess_buffer[7] = (templong >> 16) & 0xff; + mess_buffer[8] = (templong >> 24) & 0xff; + break; + + case MSG_COMMAND: // Command list item message + mess_buffer[0] = 0x10; + ck = 16; + tempint = param; // item number + mess_buffer[3] = tempint & 0xff; + mess_buffer[4] = (tempint >> 8) & 0xff; + tempint = wp_total; // list length (# of commands in mission) + mess_buffer[5] = tempint & 0xff; + mess_buffer[6] = (tempint >> 8) & 0xff; + tell_command = get_wp_with_index((int)param); + mess_buffer[7] = tell_command.id; // command id + mess_buffer[8] = tell_command.p1; // P1 + tempint = tell_command.alt; // P2 + mess_buffer[9] = tempint & 0xff; + mess_buffer[10] = (tempint >> 8) & 0xff; + templong = tell_command.lat; // P3 + mess_buffer[11] = templong & 0xff; + mess_buffer[12] = (templong >> 8) & 0xff; + mess_buffer[13] = (templong >> 16) & 0xff; + mess_buffer[14] = (templong >> 24) & 0xff; + templong = tell_command.lng; // P4 + mess_buffer[15] = templong & 0xff; + mess_buffer[16] = (templong >> 8) & 0xff; + mess_buffer[17] = (templong >> 16) & 0xff; + mess_buffer[18] = (templong >> 24) & 0xff; + break; + + case MSG_TRIMS: // Radio Trims message + mess_buffer[0] = 0x10; + ck = 16; + for(int i = 0; i < 8; i++) { + tempint = radio_trim[i]; // trim values + mess_buffer[3 + 2 * i] = tempint & 0xff; + mess_buffer[4 + 2 * i] = (tempint >> 8) & 0xff; + } + break; + + case MSG_MINS: // Radio Mins message + mess_buffer[0] = 0x10; + ck = 16; + for(int i = 0; i < 8; i++) { + tempint = radio_min[i]; // min values + mess_buffer[3 + 2 * i] = tempint & 0xff; + mess_buffer[4 + 2 * i] = (tempint >> 8) & 0xff; + } + break; + + case MSG_MAXS: // Radio Maxs message + mess_buffer[0] = 0x10; + ck = 16; + for(int i = 0; i < 8; i++) { + tempint = radio_max[i]; // max values + mess_buffer[3 + 2 * i] = tempint & 0xff; + mess_buffer[4 + 2 * i] = (tempint >> 8) & 0xff; + } + break; + + case MSG_PID: // PID Gains message + mess_buffer[0] = 0x0f; + ck = 15; + mess_buffer[3] = param & 0xff; // PID set # + templong = (kp[param] * 1000000); // P gain + mess_buffer[4] = templong & 0xff; + mess_buffer[5] = (templong >> 8) & 0xff; + mess_buffer[6] = (templong >> 16) & 0xff; + mess_buffer[7] = (templong >> 24) & 0xff; + templong = (ki[param] * 1000000); // I gain + mess_buffer[8] = templong & 0xff; + mess_buffer[9] = (templong >> 8) & 0xff; + mess_buffer[10] = (templong >> 16) & 0xff; + mess_buffer[11] = (templong >> 24) & 0xff; + templong = (kd[param] * 1000000); // D gain + mess_buffer[12] = templong & 0xff; + mess_buffer[13] = (templong >> 8) & 0xff; + mess_buffer[14] = (templong >> 16) & 0xff; + mess_buffer[15] = (templong >> 24) & 0xff; + tempint = integrator_max[param]; // Integrator max value + mess_buffer[16] = tempint & 0xff; + mess_buffer[17] = (tempint >> 8) & 0xff; + break; + } + + mess_buffer[1] = id; // Message ID + mess_buffer[2] = 0x01; // Message version + + for (int i = 0; i < ck + 3; i++) SendSer (mess_buffer[i]); + + for (int i = 0; i < ck + 3; i++) { + mess_ck_a += mess_buffer[i]; // Calculates checksums + mess_ck_b += mess_ck_a; + } + + SendSer(mess_ck_a); + SendSer(mess_ck_b); + + gcs_messages_sent++; +} + +void send_message(byte severity, const char *str) // This is the instance of send_message for message MSG_STATUS_TEXT +{ + if(severity >= DEBUG_LEVEL){ + byte length = strlen(str) + 1; + + byte mess_buffer[54]; + byte mess_ck_a = 0; + byte mess_ck_b = 0; + int ck; + + SendSer("4D"); // This is the message preamble + if(length > 50) length = 50; + mess_buffer[0] = length; + ck = length; + mess_buffer[1] = 0x05; // Message ID + mess_buffer[2] = 0x01; // Message version + + mess_buffer[3] = severity; + + for (int i = 3; i < ck + 2; i++) + mess_buffer[i] = str[i - 3]; // places the text into mess_buffer at locations 3+ + + for (int i = 0; i < ck + 3; i++) + SendSer(mess_buffer[i]); + + for (int i = 0; i < ck + 3; i++) { + mess_ck_a += mess_buffer[i]; // Calculates checksums + mess_ck_b += mess_ck_a; + } + SendSer(mess_ck_a); + SendSer(mess_ck_b); + } +} + +void print_current_waypoints() +{ +} + +void print_waypoint(struct Location *cmd, byte index) +{ + Serial.print("command #: "); + Serial.print(index, DEC); + Serial.print(" id: "); + Serial.print(cmd->id, DEC); + Serial.print(" p1: "); + Serial.print(cmd->p1, DEC); + Serial.print(" p2: "); + Serial.print(cmd->alt, DEC); + Serial.print(" p3: "); + Serial.print(cmd->lat, DEC); + Serial.print(" p4: "); + Serial.println(cmd->lng, DEC); +} + +void print_waypoints() +{ +} + + +#endif + +#if GCS_PROTOCOL == GCS_PROTOCOL_NONE +void acknowledge(byte id, byte check1, byte check2) {} +void send_message(byte id) {} +void send_message(byte id, long param) {} +void send_message(byte severity, const char *str) {} +void print_current_waypoints(){} +void print_waypoint(struct Location *cmd, byte index){} +void print_waypoints(){} +#endif diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/GCS_XDIY.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/GCS_XDIY.pde new file mode 100644 index 0000000000..6f99c2efc1 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/GCS_XDIY.pde @@ -0,0 +1,9 @@ +#if GCS_PROTOCOL == GCS_PROTOCOL_XDIY +void acknowledge(byte id, byte check1, byte check2) {} +void send_message(byte id) {} +void send_message(byte id, long param) {} +void send_message(byte severity, const char *str) {} +void print_current_waypoints(){} +void print_waypoint(struct Location *cmd, byte index){} +void print_waypoints(){} +#endif \ No newline at end of file diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/GCS_Xplane.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/GCS_Xplane.pde new file mode 100644 index 0000000000..e6f4c2f235 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/GCS_Xplane.pde @@ -0,0 +1,127 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- + +#if GCS_PROTOCOL == GCS_PROTOCOL_XPLANE + + +void acknowledge(byte id, byte check1, byte check2) +{ +} + +void send_message(byte severity, const char *str) // This is the instance of send_message for message 0x05 +{ + if(severity >= DEBUG_LEVEL){ + Serial.print("MSG: "); + Serial.println(str); + } +} + +void send_message(byte id) { + send_message(id,0l); +} + +void send_message(byte id, long param) { + switch(id) { + case MSG_HEARTBEAT: + print_control_mode(); + break; + + case MSG_ATTITUDE: + //print_attitude(); + break; + + case MSG_LOCATION: + //print_position(); + break; + + case MSG_COMMAND: + struct Location cmd = get_wp_with_index(param); + print_waypoint(&cmd, param); + break; + + } +} + + +// required by Groundstation to plot lateral tracking course +void print_new_wp_info() +{ +} + +void print_control_mode(void) +{ + Serial.print("MSG: "); + Serial.print(flight_mode_strings[control_mode]); +} + + +void print_current_waypoints() +{ + Serial.print("MSG: "); + Serial.print("CUR:"); + Serial.print("\t"); + Serial.print(current_loc.lat,DEC); + Serial.print(",\t"); + Serial.print(current_loc.lng,DEC); + Serial.print(",\t"); + Serial.println(current_loc.alt,DEC); + + Serial.print("MSG: "); + Serial.print("NWP:"); + Serial.print(wp_index,DEC); + Serial.print(",\t"); + Serial.print(next_WP.lat,DEC); + Serial.print(",\t"); + Serial.print(next_WP.lng,DEC); + Serial.print(",\t"); + Serial.println(next_WP.alt,DEC); +} + +void print_position(void) +{ +} + +void printPerfData(void) +{ +} + +void print_attitude(void) +{ +} +void print_tuning(void) { +} +void print_waypoint(struct Location *cmd,byte index) +{ + Serial.print("MSG: command #: "); + Serial.print(index, DEC); + Serial.print(" id: "); + Serial.print(cmd->id,DEC); + Serial.print(" p1: "); + Serial.print(cmd->p1,DEC); + Serial.print(" p2: "); + Serial.print(cmd->alt,DEC); + Serial.print(" p3: "); + Serial.print(cmd->lat,DEC); + Serial.print(" p4: "); + Serial.println(cmd->lng,DEC); +} + +void print_waypoints() +{ + Serial.println("Commands in memory"); + Serial.print("commands total: "); + Serial.println(wp_total, DEC); + // create a location struct to hold the temp Waypoints for printing + //Location tmp; + Serial.println("Home: "); + struct Location cmd = get_wp_with_index(0); + print_waypoint(&cmd, 0); + Serial.println("Commands: "); + + for (int i=1; i> 8) & 0xff; +} + +void output_byte(byte value) +{ + out_buffer[buf_len++] = value; +} + +void print_buffer() +{ + byte ck_a = 0; + byte ck_b = 0; + for (byte i = 0;i < buf_len; i++){ + Serial.print (out_buffer[i]); + } + Serial.print('\r'); + Serial.print('\n'); + buf_len = 0; +} + + +#endif + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/Jeti.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/Jeti.pde new file mode 100644 index 0000000000..11dfcc9b39 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/Jeti.pde @@ -0,0 +1,264 @@ +// menu structure +// +// [status] - [data1] - [data2] - [data3] - [data4] - [dataXY] +// |_________| _______|_________|_________|_________| +// | +// [SETUP1] - [SETUP2] - [SETUPXY] +// | | | +// [para1.1] [PARAM2.1] [PARAMX.Y] +// | | | +// [para1.2] [PARAM2.2] [PARAMX.Y] +// | | | +// [para1.3] [PARAM2.3] [PARAMX.Y] + +// Statusmenu +const uint8_t mnuSTATUS = 0; +const uint8_t mnuGPS1 = 1; +const uint8_t mnuGPS2 = 2; +const uint8_t mnuIMU = 3; +const uint8_t mnuACC = 4; +const uint8_t mnuGYRO = 5; +const uint8_t mnuCOMPASS = 6; +const uint8_t mnuSERVO1 = 7; +const uint8_t mnuSERVO2 = 8; +const uint8_t mnuDATA9 = 9; + +// Setup 1 +const uint8_t mnuSETUP1 = 10; +const uint8_t mnuPARAM11 = 11; +const uint8_t mnuPARAM12 = 12; +const uint8_t mnuPARAM13 = 13; +const uint8_t mnuPARAM14 = 14; + +// Setup 2 +const uint8_t mnuSETUP2 = 20; +const uint8_t mnuPARAM21 = 21; +const uint8_t mnuPARAM22 = 22; +const uint8_t mnuPARAM23 = 23; +const uint8_t mnuPARAM24 = 24; + +// Setup 3 +const uint8_t mnuSETUP3 = 30; +const uint8_t mnuPARAM31 = 31; +const uint8_t mnuPARAM32 = 32; +const uint8_t mnuPARAM33 = 33; +const uint8_t mnuPARAM34 = 34; + +// Setup 4 +const uint8_t mnuSETUP4 = 40; +const uint8_t mnuPARAM41 = 41; +const uint8_t mnuPARAM42 = 42; +const uint8_t mnuPARAM43 = 43; +const uint8_t mnuPARAM44 = 44; + +#define LCDMaxPos 32 + +static uint8_t MnuPtr = 0; +static uint8_t statustxt[LCDMaxPos]; + +void jeti_status(const char *str) +{ + byte i; + byte length = strlen(str) + 1; + if (length > LCDMaxPos) length = LCDMaxPos; + for (i = 0; i fill up with SPACE + } + } +} + +void jeti_menuctrl(uint8_t btns) { + // Algorithm for menubuttons + // if MnuPtr == 0 then Status + // if MnuPtr <10 then Data + // if (MnuPtr mod 10) = 0 then Setupp + // if (MnuPtr mod 10) <> 0 then Parameter + + if (MnuPtr == mnuSTATUS) { // MnuPtr = Status + switch (btns) { + case JB_key_right: + MnuPtr += 1; + break; + + case JB_key_left: + MnuPtr = mnuDATA9; + break; + + case JB_key_down: + MnuPtr = mnuSETUP1; + break; + } + } + else if (MnuPtr < 10) { // MnuPtr = Data + switch (btns) { + case JB_key_right: + if (MnuPtr < mnuDATA9) MnuPtr += 1; else MnuPtr = mnuSTATUS; + break; + + case JB_key_left: + if (MnuPtr > mnuSTATUS) MnuPtr -= 1; else MnuPtr = mnuDATA9; + break; + } + } + else if (MnuPtr % 10 == 0) { // MnuPtr = Setup + switch (btns) { + case JB_key_right: + if (MnuPtr < mnuSETUP4) MnuPtr += 10; else MnuPtr = mnuSETUP1; + break; + + case JB_key_left: + if (MnuPtr > mnuSETUP1) MnuPtr -= 10; else MnuPtr = mnuSETUP4; + break; + + case JB_key_up: + MnuPtr = mnuSTATUS; + break; + + case JB_key_down: + MnuPtr += 1; + break; + } + } + else { // MnuPtr = Parameter + switch (btns) { + case JB_key_down: + if ((MnuPtr % 10) < 4) MnuPtr += 1; + break; + + case JB_key_up: + if ((MnuPtr % 10) > 0) MnuPtr -= 1; + break; + } + } +} + +void jeti_init() { + // Init Jeti Serial Port + JB.begin(); +} + +void jeti_update() { + JB.clear(0); + uint8_t Buttons = JB.readbuttons(); + jeti_menuctrl(Buttons); + switch (MnuPtr) { + case mnuGPS1: + JB.print("GPS> "); + if (GPS.fix == 1) { + JB.print("FIX"); + JB.print(" SAT>"); + JB.print((int)GPS.num_sats); + JB.setcursor(LCDLine2); + JB.print("Alt: "); + JB.print((int)GPS.altitude/100); + } else { + JB.print("no FIX"); + } + break; + + case mnuGPS2: + if (GPS.fix ==1 ) { + JB.print("Lat "); + JB.print((float)GPS.latitude/10000000, 9); + JB.setcursor(LCDLine2); + JB.print("Lon "); + JB.print((float)GPS.longitude/10000000, 9); + } else { + JB.print("no Data avail."); + } + break; + + case mnuIMU: + //read_AHRS(); + JB.print("IMU> R:"); + JB.print(roll_sensor/100,DEC); + JB.print(" P:"); + JB.print(pitch_sensor/100,DEC); + JB.setcursor(LCDLine2); + JB.print("Y:"); + JB.print(yaw_sensor/100,DEC); + break; + + case mnuACC: + for (int i = 0; i < 6; i++) { + AN[i] = APM_ADC.Ch(sensors[i]); + } + JB.print("ACC> X:"); + JB.print((int)AN[3]); + JB.setcursor(LCDLine2); + JB.print(" Y:"); + JB.print((int)AN[4]); + JB.print(" Z:"); + JB.print((int)AN[5]); + break; + + case mnuGYRO: + for (int i = 0; i < 6; i++) { + AN[i] = APM_ADC.Ch(sensors[i]); + } + JB.print("GYRO> Y:"); + JB.print((int)AN[0]); + JB.setcursor(LCDLine2); + JB.print(" R:"); + JB.print((int)AN[1]); + JB.print(" P:"); + JB.print((int)AN[2]); + break; + + case mnuCOMPASS: + JB.print("MAGN> Head:"); + JB.print((int)ToDeg(APM_Compass.Heading)); + JB.setcursor(LCDLine2); + JB.println("["); + JB.print((int)APM_Compass.Mag_X); + JB.print(comma); + JB.print((int)APM_Compass.Mag_Y); + JB.print(comma); + JB.print((int)APM_Compass.Mag_Z); + JB.println("]"); + break; + + case mnuSERVO1: + JB.print("#1:"); + JB.print((int)radio_in[CH_1]); + JB.print(" #2:"); + JB.print((int)radio_in[CH_2]); + JB.setcursor(LCDLine2); + JB.print("#3:"); + JB.print((int)radio_in[CH_3]); + JB.print(" #4:"); + JB.print((int)radio_in[CH_4]); + break; + + case mnuSERVO2: + JB.print("#Q:"); + JB.print((int)servo_out[CH_ROLL]/100); + JB.print(" #H:"); + JB.print((int)servo_out[CH_PITCH]/100); + JB.setcursor(LCDLine2); + JB.print("#G:"); + JB.print((int)servo_out[CH_THROTTLE]); + JB.print(" #S:"); + JB.print((int)servo_out[CH_RUDDER]/100); + break; + + case mnuSETUP1: + JB.print("SETUP 1"); + break; + + case mnuSTATUS: + for (byte i = 0; i<32; i++) { + JB.print(statustxt[i]); + } + //JB.print("STATUS*"); + break; + + default: + JB.print("Menu: n/a #"); + JB.print((int) MnuPtr); + break; + } +} diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/Log.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/Log.pde new file mode 100644 index 0000000000..348b815b83 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/Log.pde @@ -0,0 +1,596 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- + +// Code to Write and Read packets from DataFlash log memory +// Code to interact with the user to dump or erase logs + +#define HEAD_BYTE1 0xA3 // Decimal 163 +#define HEAD_BYTE2 0x95 // Decimal 149 +#define END_BYTE 0xBA // Decimal 186 + + +// These are function definitions so the Menu can be constructed before the functions +// are defined below. Order matters to the compiler. +static int8_t print_log_menu(uint8_t argc, const Menu::arg *argv); +static int8_t dump_log(uint8_t argc, const Menu::arg *argv); +static int8_t erase_logs(uint8_t argc, const Menu::arg *argv); +static int8_t select_logs(uint8_t argc, const Menu::arg *argv); + +// This is the help function +// PSTR is an AVR macro to read strings from flash memory +// printf_P is a version of print_f that reads from flash memory +static int8_t help_log(uint8_t argc, const Menu::arg *argv) +{ + Serial.printf_P(PSTR("\n" + "Commands:\n" + " dump dump log \n" + " erase erase all logs\n" + " enable |all enable logging or everything\n" + " disable |all disable logging or everything\n" + "\n")); +} + +// Creates a constant array of structs representing menu options +// and stores them in Flash memory, not RAM. +// User enters the string in the console to call the functions on the right. +// See class Menu in AP_Coommon for implementation details +const struct Menu::command log_menu_commands[] PROGMEM = { + {"dump", dump_log}, + {"erase", erase_logs}, + {"enable", select_logs}, + {"disable", select_logs}, + {"help", help_log} +}; + +// A Macro to create the Menu +MENU2(log_menu, "Log", log_menu_commands, print_log_menu); + +static bool +print_log_menu(void) +{ + int log_start; + int log_end; + byte last_log_num = eeprom_read_byte((uint8_t *) EE_LAST_LOG_NUM); + + Serial.printf_P(PSTR("logs enabled: ")); + if (0 == log_bitmask) { + Serial.printf_P(PSTR("none")); + } else { + // Macro to make the following code a bit easier on the eye. + // Pass it the capitalised name of the log option, as defined + // in defines.h but without the LOG_ prefix. It will check for + // the bit being set and print the name of the log option to suit. +#define PLOG(_s) if (log_bitmask & LOGBIT_ ## _s) Serial.printf_P(PSTR(" %S"), PSTR(#_s)) + PLOG(ATTITUDE_FAST); + PLOG(ATTITUDE_MED); + PLOG(GPS); + PLOG(PM); + PLOG(CTUN); + PLOG(NTUN); + PLOG(MODE); + PLOG(RAW); + PLOG(CMD); +#undef PLOG + } + Serial.println(); + + if (last_log_num == 0) { + Serial.printf_P(PSTR("\nNo logs available for download\n")); + } else { + + Serial.printf_P(PSTR("\n%d logs available for download\n"), last_log_num); + for(int i=1;i last_log_num)) { + Serial.printf_P(PSTR("bad log number\n")); + return(-1); + } + + dump_log_start = eeprom_read_word((uint16_t *) (EE_LOG_1_START+(dump_log-1)*0x02)); + dump_log_end = eeprom_read_word((uint16_t *) (EE_LOG_1_START+(dump_log)*0x02))-1; + if (dump_log == last_log_num) { + dump_log_end = eeprom_read_word((uint16_t *) EE_LAST_LOG_PAGE); + } + Serial.printf_P(PSTR("Dumping Log number %d, start page %d, end page %d\n"), + dump_log, dump_log_start, dump_log_end); + Log_Read(dump_log_start, dump_log_end); + Serial.printf_P(PSTR("Log read complete\n")); +} + +static int8_t +erase_logs(uint8_t argc, const Menu::arg *argv) +{ + for(int i = 10 ; i > 0; i--) { + Serial.printf_P(PSTR("ATTENTION - Erasing log in %d seconds. Power off now to save log! \n"), i); + delay(1000); + } + Serial.printf_P(PSTR("\nErasing log...\n")); + for(int j = 1; j < 4001; j++) + DataFlash.PageErase(j); + eeprom_write_byte((uint8_t *)EE_LAST_LOG_NUM, 0); + eeprom_write_byte((uint8_t *)EE_LAST_LOG_PAGE, 1); + Serial.printf_P(PSTR("\nLog erased.\n")); +} + +static int8_t +select_logs(uint8_t argc, const Menu::arg *argv) +{ + uint16_t bits; + + if (argc != 2) { + Serial.printf_P(PSTR("missing log type\n")); + return(-1); + } + + bits = 0; + + // Macro to make the following code a bit easier on the eye. + // Pass it the capitalised name of the log option, as defined + // in defines.h but without the LOG_ prefix. It will check for + // that name as the argument to the command, and set the bit in + // bits accordingly. + // + if (!strcasecmp_P(argv[1].str, PSTR("all"))) { + bits = ~(bits = 0); + } else { +#define TARG(_s) if (!strcasecmp_P(argv[1].str, PSTR(#_s))) bits |= LOGBIT_ ## _s + TARG(ATTITUDE_FAST); + TARG(ATTITUDE_MED); + TARG(GPS); + TARG(PM); + TARG(CTUN); + TARG(NTUN); + TARG(MODE); + TARG(RAW); + TARG(CMD); +#undef TARG + } + + if (!strcasecmp_P(argv[0].str, PSTR("enable"))) { + log_bitmask |= bits; + } else { + log_bitmask &= ~bits; + } + save_user_configs(); // XXX this is a bit heavyweight... + + return(0); +} + +int8_t +process_logs(uint8_t argc, const Menu::arg *argv) +{ + log_menu.run(); +} + +// Write an attitude packet. Total length : 10 bytes +void Log_Write_Attitude(int log_roll, int log_pitch, uint16_t log_yaw) +{ + DataFlash.WriteByte(HEAD_BYTE1); + DataFlash.WriteByte(HEAD_BYTE2); + DataFlash.WriteByte(LOG_ATTITUDE_MSG); + DataFlash.WriteInt(log_roll); + DataFlash.WriteInt(log_pitch); + DataFlash.WriteInt(log_yaw); + DataFlash.WriteByte(END_BYTE); +} + +// Write a performance monitoring packet. Total length : 19 bytes +void Log_Write_Performance() +{ + DataFlash.WriteByte(HEAD_BYTE1); + DataFlash.WriteByte(HEAD_BYTE2); + DataFlash.WriteByte(LOG_PERFORMANCE_MSG); + DataFlash.WriteLong(millis()- perf_mon_timer); + DataFlash.WriteInt(mainLoop_count); + DataFlash.WriteInt(G_Dt_max); + DataFlash.WriteByte(gyro_sat_count); + DataFlash.WriteByte(adc_constraints); + DataFlash.WriteByte(renorm_sqrt_count); + DataFlash.WriteByte(renorm_blowup_count); + DataFlash.WriteByte(gps_fix_count); + DataFlash.WriteInt((int)(imu_health*1000)); + DataFlash.WriteByte(END_BYTE); +} + +// Write a command processing packet. Total length : 19 bytes +//void Log_Write_Cmd(byte num, byte id, byte p1, long alt, long lat, long lng) +void Log_Write_Cmd(byte num, struct Location *wp) +{ + DataFlash.WriteByte(HEAD_BYTE1); + DataFlash.WriteByte(HEAD_BYTE2); + DataFlash.WriteByte(LOG_CMD_MSG); + DataFlash.WriteByte(num); + DataFlash.WriteByte(wp->id); + DataFlash.WriteByte(wp->p1); + DataFlash.WriteLong(wp->alt); + DataFlash.WriteLong(wp->lat); + DataFlash.WriteLong(wp->lng); + DataFlash.WriteByte(END_BYTE); +} + +void Log_Write_Startup(byte type) +{ + DataFlash.WriteByte(HEAD_BYTE1); + DataFlash.WriteByte(HEAD_BYTE2); + DataFlash.WriteByte(LOG_STARTUP_MSG); + DataFlash.WriteByte(type); + DataFlash.WriteByte(wp_total); + DataFlash.WriteByte(END_BYTE); + + // create a location struct to hold the temp Waypoints for printing + struct Location cmd = get_wp_with_index(0); + Log_Write_Cmd(0, &cmd); + + for (int i=1; i7) logvar = DataFlash.ReadInt(); + else logvar = DataFlash.ReadByte(); + //if(y > 7) logvar = logvar/1000.f; + Serial.print(logvar); + Serial.print(comma); + } + Serial.println(" "); +} + +// Read a command processing packet +void Log_Read_Cmd() +{ + byte logvarb; + long logvarl; + + Serial.print("CMD:"); + for(int i=1;i<4;i++) { + logvarb = DataFlash.ReadByte(); + Serial.print(logvarb,DEC); + Serial.print(comma); + } + for(int i=1;i<4;i++) { + logvarl = DataFlash.ReadLong(); + Serial.print(logvarl,DEC); + Serial.print(comma); + } + Serial.println(" "); +} + +void Log_Read_Startup() +{ + byte logbyte = DataFlash.ReadByte(); + if (logbyte == TYPE_AIRSTART_MSG) + Serial.print("AIR START - "); + else if (logbyte == TYPE_GROUNDSTART_MSG) + Serial.print("GROUND START - "); + else + Serial.print("UNKNOWN STARTUP TYPE -"); + Serial.print(DataFlash.ReadByte(), DEC); + Serial.println(" commands in memory"); +} + +// Read an attitude packet +void Log_Read_Attitude() +{ + int log_roll; + int log_pitch; + uint16_t log_yaw; + + log_roll = DataFlash.ReadInt(); + log_pitch = DataFlash.ReadInt(); + log_yaw = (uint16_t)DataFlash.ReadInt(); + + Serial.print("ATT:"); + Serial.print(log_roll); + Serial.print(comma); + Serial.print(log_pitch); + Serial.print(comma); + Serial.print(log_yaw); + Serial.println(); +} + +// Read a mode packet +void Log_Read_Mode() +{ + byte mode; + + mode = DataFlash.ReadByte(); + Serial.print("MOD:"); + switch (mode) { + case 0: + Serial.println("Manual"); + break; + case 1: + Serial.println("Stab"); + break; + case 5: + Serial.println("FBW_A"); + break; + case 6: + Serial.println("FBW_B"); + break; + case 10: + Serial.println("AUTO"); + break; + case 11: + Serial.println("RTL"); + break; + case 12: + Serial.println("Loiter"); + break; + case 98: + Serial.println("AS_COM"); + break; + case 99: + Serial.println("GS_COM"); + break; + } +} + +// Read a GPS packet +void Log_Read_GPS() +{ + + Serial.print("GPS:"); + Serial.print(DataFlash.ReadLong()); // Time + Serial.print(comma); + Serial.print((int)DataFlash.ReadByte()); // Fix + Serial.print(comma); + Serial.print((int)DataFlash.ReadByte()); // Num of Sats + Serial.print(comma); + Serial.print((float)DataFlash.ReadLong()/t7, 7); // Lattitude + Serial.print(comma); + Serial.print((float)DataFlash.ReadLong()/t7, 7); // Longitude + Serial.print(comma); + Serial.print((float)DataFlash.ReadLong()/100.0); // Baro/gps altitude mix + Serial.print(comma); + Serial.print((float)DataFlash.ReadLong()/100.0); // GPS altitude + Serial.print(comma); + Serial.print((float)DataFlash.ReadLong()/100.0); // Ground Speed + Serial.print(comma); + Serial.println((float)DataFlash.ReadLong()/100.0); // Ground Course + +} + +// Read a raw accel/gyro packet +void Log_Read_Raw() +{ + float logvar; + Serial.print("RAW:"); + for (int y=0;y<6;y++) { + logvar = DataFlash.ReadLong()/1000.f; + Serial.print(logvar); + Serial.print(comma); + } + Serial.println(" "); +} + +// Read the DataFlash log memory : Packet Parser +void Log_Read(int start_page, int end_page) +{ + byte data; + byte log_step=0; + int packet_count=0; + int page = start_page; + + + DataFlash.StartRead(start_page); + while (page < end_page && page != -1) + { + data = DataFlash.ReadByte(); + switch(log_step) //This is a state machine to read the packets + { + case 0: + if(data==HEAD_BYTE1) // Head byte 1 + log_step++; + break; + case 1: + if(data==HEAD_BYTE2) // Head byte 2 + log_step++; + else + log_step = 0; + break; + case 2: + if(data==LOG_ATTITUDE_MSG){ + Log_Read_Attitude(); + log_step++; + + }else if(data==LOG_MODE_MSG){ + Log_Read_Mode(); + log_step++; + + }else if(data==LOG_CONTROL_TUNING_MSG){ + Log_Read_Control_Tuning(); + log_step++; + + }else if(data==LOG_NAV_TUNING_MSG){ + Log_Read_Nav_Tuning(); + log_step++; + + }else if(data==LOG_PERFORMANCE_MSG){ + Log_Read_Performance(); + log_step++; + + }else if(data==LOG_RAW_MSG){ + Log_Read_Raw(); + log_step++; + + }else if(data==LOG_CMD_MSG){ + Log_Read_Cmd(); + log_step++; + + }else if(data==LOG_STARTUP_MSG){ + Log_Read_Startup(); + log_step++; + }else { + if(data==LOG_GPS_MSG){ + Log_Read_GPS(); + log_step++; + } else { + Serial.print("Error Reading Packet: "); + Serial.print(packet_count); + log_step=0; // Restart, we have a problem... + } + } + break; + case 3: + if(data==END_BYTE){ + packet_count++; + }else{ + Serial.print("Error Reading END_BYTE "); + Serial.println(data,DEC); + } + log_step=0; // Restart sequence: new packet... + break; + } + page = DataFlash.GetPage(); + } + Serial.print("Number of packets read: "); + Serial.println(packet_count); +} + + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/command description.txt b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/command description.txt new file mode 100644 index 0000000000..3e8c4edf45 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/command description.txt @@ -0,0 +1,75 @@ +ArduPilotMega 1.0.0 Commands + +Command Structure in bytes +0 0x00 byte Command ID +1 0x01 byte Parameter 1 +2 0x02 int Parameter 2 +3 0x03 .. +4 0x04 long Parameter 3 +5 0x05 .. +6 0x06 .. +7 0x07 .. +8 0x08 long Parameter 4 +9 0x09 .. +10 0x0A .. +11 0x0B .. + +0x00 Reserved +.... +0x0F Reserved + +*********************************** +Commands 0x10 to 0x2F are commands that have a end criteria, eg "reached waypoint" or "reached altitude" +*********************************** +Command ID Name Parameter 1 Altitude Latitude Longitude +0x10 CMD_WAYPOINT - altitude lat lon +0x11 CMD_LOITER (indefinitely) - altitude lat lon +0x12 CMD_LOITER_N_TURNS turns altitude lat lon +0x13 CMD_LOITER_TIME time (seconds*10) altitude lat lon +0x14 CMD_RTL - altitude lat lon +0x15 CMD_LAND - altitude lat lon +0x16 CMD_TAKEOFF angle - - - + + +*********************************** +May Commands - these commands are optional to finish +Command ID Name Parameter 1 Parameter 2 Parameter 3 Parameter 4 +0x20 CMD_DELAY - - time (milliseconds) - +0x21 CMD_CLIMB rate (cm/sec) alt (finish) - - +0x22 CMD_LAND_OPTIONS distance to WP airspeed m/s, throttle %, pitch deg + + + +*********************************** +Unexecuted commands >= 0x20 are dropped when ready for the next command <= 0x1F so plan/queue commands accordingly! +For example if you had a string of 0x21 commands following a 0x10 command that had not finished when the waypoint was +reached, the unexecuted 0x21 commands would be skipped and the next command <= 0x1F would be loaded +*********************************** +Now Commands - these commands are executed once until no more new now commands are available +0x31 CMD_RESET_INDEX +0x32 CMD_GOTO_INDEX index repeat count +0x33 CMD_GETVAR_INDEX variable ID +0x34 CMD_SENDVAR_INDEX off/on = 0/1 +0x35 CMD_TELEMETRY off/on = 0/1 + +0x40 CMD_THROTTLE_CRUISE speed +0x41 CMD_AIRSPEED_CRUISE speed +0x44 CMD_RESET_HOME altitude lat lon + +0x60 CMD_KP_GAIN array index gain value*100,000 +0x61 CMD_KI_GAIN array index gain value*100,000 +0x62 CMD_KD_GAIN array index gain value*100,000 +0x63 CMD_KI_MAX array index gain value*100,000 +0x64 CMD_KFF_GAIN array index gain value*100,000 + +0x70 CMD_RADIO_TRIM array index value +0x71 CMD_RADIO_MAX array index value +0x72 CMD_RADIO_MIN array index value +0x73 CMD_ELEVON_TRIM array index value (index 0 = elevon 1 trim, 1 = elevon 2 trim) +0x75 CMD_INDEX index + +0x80 CMD_REPEAT type value delay in sec repeat count +0x81 CMD_RELAY (0,1 to change swicth position) +0x82 CMD_SERVO number value + + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/commands.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/commands.pde new file mode 100644 index 0000000000..0d2a1c4ba2 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/commands.pde @@ -0,0 +1,228 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- + +void init_commands() +{ + read_EEPROM_waypoint_info(); + wp_index = 0; + command_must_index = 0; + command_may_index = 0; + next_command.id = CMD_BLANK; +} + +void update_auto() +{ + if (wp_index == wp_total){ + return_to_launch(); + //wp_index = 0; + } +} + +void reload_commands() +{ + init_commands(); + read_command_index(); // Get wp_index = command_must_index from EEPROM + if(wp_index > 0){ + decrement_WP_index; + } +} + +// Getters +// ------- +struct Location get_wp_with_index(int i) +{ + struct Location temp; + long mem; + + + // Find out proper location in memory by using the start_byte position + the index + // -------------------------------------------------------------------------------- + if (i > wp_total) { + temp.id = CMD_BLANK; + }else{ + // read WP position + mem = (WP_START_BYTE) + (i * WP_SIZE); + temp.id = eeprom_read_byte((uint8_t*)mem); + mem++; + temp.p1 = eeprom_read_byte((uint8_t*)mem); + mem++; + temp.alt = (long)eeprom_read_dword((uint32_t*)mem); + mem += 4; + temp.lat = (long)eeprom_read_dword((uint32_t*)mem); + mem += 4; + temp.lng = (long)eeprom_read_dword((uint32_t*)mem); + } + return temp; +} + +// Setters +// ------- +void set_wp_with_index(struct Location temp, int i) +{ + + i = constrain(i,0,wp_total); + uint32_t mem = WP_START_BYTE + (i * WP_SIZE); + + eeprom_write_byte((uint8_t *) mem, temp.id); + + mem++; + eeprom_write_byte((uint8_t *) mem, temp.p1); + + mem++; + eeprom_write_dword((uint32_t *) mem, temp.alt); + + mem += 4; + eeprom_write_dword((uint32_t *) mem, temp.lat); + + mem += 4; + eeprom_write_dword((uint32_t *) mem, temp.lng); +} + +void increment_WP_index() +{ + if(wp_index < wp_total){ + wp_index++; + SendDebug("MSG WP index is incremented to "); + SendDebugln(wp_index,DEC); + }else{ + SendDebug("MSG Failed to increment WP index of "); + SendDebugln(wp_index,DEC); + } +} +void decrement_WP_index() +{ + if(wp_index > 0){ + wp_index--; + } +} + +void loiter_at_location() +{ + next_WP = current_loc; +} + +// add a new command at end of command set to RTL. +void return_to_launch(void) +{ + // home is WP 0 + // ------------ + wp_index = 0; + + // Loads WP from Memory + // -------------------- + set_next_WP(&home); + + // Altitude to hold over home + // Set by configuration tool + // ------------------------- + next_WP.alt = read_alt_to_hold(); +} + +struct Location get_LOITER_home_wp() +{ + // read home position + struct Location temp = get_wp_with_index(0); + temp.id = CMD_LOITER; + + temp.alt = read_alt_to_hold(); + return temp; +} + +/* +This function stores waypoint commands +It looks to see what the next command type is and finds the last command. +*/ +void set_next_WP(struct Location *wp) +{ + //send_message(SEVERITY_LOW,"load WP"); + SendDebug("MSG wp_index: "); + SendDebugln(wp_index,DEC); + send_message(MSG_COMMAND, wp_index); + + // copy the current WP into the OldWP slot + // --------------------------------------- + prev_WP = current_loc; + // Load the next_WP slot + // --------------------- + next_WP = *wp; + // offset the altitude relative to home position + // --------------------------------------------- + next_WP.alt += home.alt; + + // used to control FBW and limit the rate of climb + // ----------------------------------------------- + target_altitude = current_loc.alt; + offset_altitude = next_WP.alt - prev_WP.alt; + + // zero out our loiter vals to watch for missed waypoints + loiter_delta = 0; + loiter_sum = 0; + loiter_total = 0; + + float rads = (abs(next_WP.lat)/t7) * 0.0174532925; + //377,173,810 / 10,000,000 = 37.717381 * 0.0174532925 = 0.658292482926943 + scaleLongDown = cos(rads); + scaleLongUp = 1.0f/cos(rads); + + // this is handy for the groundstation + wp_totalDistance = getDistance(¤t_loc, &next_WP); + wp_distance = wp_totalDistance; + + print_current_waypoints(); + + target_bearing = get_bearing(¤t_loc, &next_WP); + old_target_bearing = target_bearing; + // this is used to offset the shrinking longitude as we go towards the poles + + // set a new crosstrack bearing + // ---------------------------- + reset_crosstrack(); +} + + +// run this at setup on the ground +// ------------------------------- +void init_home() +{ + SendDebugln("MSG: init home"); + + // Extra read just in case + // ----------------------- + //GPS.Read(); + + // block until we get a good fix + // ----------------------------- + while (!GPS.new_data || !GPS.fix) { + GPS.update(); + } + home.id = CMD_WAYPOINT; + home.lng = GPS.longitude; // Lon * 10**7 + home.lat = GPS.latitude; // Lat * 10**7 + home.alt = GPS.altitude; + home_is_set = TRUE; + + // ground altitude in centimeters for pressure alt calculations + // ------------------------------------------------------------ + ground_alt = GPS.altitude; + press_alt = GPS.altitude; // Set initial value for filter + save_pressure_data(); + + // Save Home to EEPROM + // ------------------- + set_wp_with_index(home, 0); + + // Save prev loc + // ------------- + prev_WP = home; + + // Signal ready to fly + // Make the servos wiggle - 3 times + // ----------------------- + demo_servos(3); + send_message(SEVERITY_LOW,"\n\n Ready to FLY."); + // 12345678901234567890123456789012 + jeti_status(" X-DIY Ready to FLY"); + jeti_update(); +} + + + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/commands_process.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/commands_process.pde new file mode 100644 index 0000000000..93e1ae6c53 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/commands_process.pde @@ -0,0 +1,480 @@ +// called by 10 Hz loop +// -------------------- +void update_commands(void) +{ + // This function loads commands into three buffers + // when a new command is loaded, it is processed with process_XXX() + // ---------------------------------------------------------------- + if((home_is_set == FALSE) || (control_mode != AUTO)){ + return; // don't do commands + } + + if(control_mode == AUTO){ + load_next_command(); + process_next_command(); + } + + //verify_must(); + //verify_may(); +} + + +void load_next_command() +{ + // fetch next command if it's empty + // -------------------------------- + if(next_command.id == CMD_BLANK){ + next_command = get_wp_with_index(wp_index+1); + if(next_command.id != CMD_BLANK){ + //SendDebug("MSG fetch found new cmd from list at index "); + //SendDebug((wp_index+1),DEC); + //SendDebug(" with cmd id "); + //SendDebugln(next_command.id,DEC); + } + } + + // If the preload failed, return or just Loiter + // generate a dynamic command for RTL + // -------------------------------------------- + if(next_command.id == CMD_BLANK){ + // we are out of commands! + //send_message(SEVERITY_LOW,"out of commands!"); + //SendDebug("MSG out of commands, wp_index: "); + //SendDebugln(wp_index,DEC); + + + switch (control_mode){ + case LAND: + // don't get a new command + break; + + default: + next_command = get_LOITER_home_wp(); + //SendDebug("MSG Preload RTL cmd id: "); + //SendDebugln(next_command.id,DEC); + break; + } + } +} + +void process_next_command() +{ + // these are waypoint/Must commands + // --------------------------------- + if (command_must_index == 0){ // no current command loaded + if (next_command.id >= 0x10 && next_command.id <= 0x1F ){ + increment_WP_index(); + save_command_index(); // to Recover from in air Restart + command_must_index = wp_index; + + //SendDebug("MSG new command_must_id "); + //SendDebug(next_command.id,DEC); + //SendDebug(" index:"); + //SendDebugln(command_must_index,DEC); + if (log_bitmask & MASK_LOG_CMD) + Log_Write_Cmd(wp_index, &next_command); + process_must(); + } + } + + // these are May commands + // ---------------------- + if (command_may_index == 0){ + if (next_command.id >= 0x20 && next_command.id <= 0x2F ){ + increment_WP_index();// this command is from the command list in EEPROM + command_may_index = wp_index; + //Serial.print("new command_may_index "); + //Serial.println(command_may_index,DEC); + if (log_bitmask & MASK_LOG_CMD) + Log_Write_Cmd(wp_index, &next_command); + process_may(); + } + } + + // these are do it now commands + // --------------------------- + if (next_command.id >= 0x30){ + increment_WP_index();// this command is from the command list in EEPROM + if (log_bitmask & MASK_LOG_CMD) + Log_Write_Cmd(wp_index, &next_command); + process_now(); + } + +} + +/* +These functions implement the waypoint commands. +*/ +void process_must() +{ + //SendDebug("process must index: "); + //SendDebugln(command_must_index,DEC); + + send_message(SEVERITY_LOW,"New cmd: "); + send_message(MSG_COMMAND, wp_index); + + // clear May indexes + command_may_index = 0; + command_may_ID = 0; + + command_must_ID = next_command.id; + + // invalidate command so a new one is loaded + // ----------------------------------------- + next_command.id = 0; + + // reset navigation integrators + // ------------------------- + reset_I(); + + // loads the waypoint into Next_WP struct + // -------------------------------------- + set_next_WP(&next_command); + + switch(command_must_ID){ + + case CMD_TAKEOFF: // TAKEOFF! + // pitch in deg, airspeed m/s, throttle %, track WP 1 or 0 + takeoff_pitch = next_command.p1 * 100; + takeoff_altitude = next_WP.alt; // next_WP.alt is calculated by the set_next_WP command + 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 + break; + + case CMD_WAYPOINT: // Navigate to Waypoint + break; + + case CMD_LAND: // LAND to Waypoint + break; + + case CMD_LOITER: // Loiter indefinitely + break; + + case CMD_LOITER_N_TURNS: // Loiter N Times + loiter_total = next_command.p1 * 360; + break; + + case CMD_LOITER_TIME: + loiter_time = millis(); + loiter_time_max = next_command.p1 * 10000; // seconds * 10 * 1000 + break; + + case CMD_RTL: + break; + } +} + +void process_may() +{ + //Serial.print("process_may cmd# "); + //Serial.println(wp_index,DEC); + command_may_ID = next_command.id; + + // invalidate command so a new one is loaded + // ----------------------------------------- + next_command.id = 0; + + send_message(SEVERITY_LOW," New may command loaded:"); + send_message(MSG_COMMAND, wp_index); + + // do the command + // -------------- + switch(command_may_ID){ + + case CMD_DELAY: // Navigate to Waypoint + delay_start = millis(); + delay_timeout = next_command.lat; + break; + + case CMD_LAND_OPTIONS: // Land this puppy + //send_message(SEVERITY_LOW,"Landing"); + + // pitch in deg, airspeed m/s, throttle %, track WP 1 or 0 + landing_pitch = next_command.lng * 100; + airspeed_cruise = next_command.alt * 100; + throttle_cruise = next_command.lat; + landing_distance = next_command.p1; + //landing_roll = command.lng; + + SendDebug("MSG: throttle_cruise = "); + SendDebugln(throttle_cruise,DEC); + break; + + default: + break; + } +} + +void process_now() +{ + const float t5 = 100000.0; + //Serial.print("process_now cmd# "); + //Serial.println(wp_index,DEC); + + byte id = next_command.id; + + // invalidate command so a new one is loaded + // ----------------------------------------- + next_command.id = 0; + + send_message(SEVERITY_LOW, " New now command loaded: "); + send_message(MSG_COMMAND, wp_index); + + // do the command + // -------------- + switch(id){ + + //case CMD_AP_MODE: + //next_command.p1 = constrain(next_command.p1, MANUAL, LAND); + //set_mode(next_command.p1); + //break; + + case CMD_RESET_INDEX: + init_commands(); + break; + + case CMD_GETVAR_INDEX: + // + break; + + case CMD_SENDVAR_INDEX: + // + break; + + case CMD_TELEMETRY: + // + break; + + case CMD_AIRSPEED_CRUISE: + airspeed_cruise = next_command.p1 * 100; + // todo save to EEPROM + break; + + case CMD_THROTTLE_CRUISE: + throttle_cruise = next_command.p1; + // todo save to EEPROM + break; + + case CMD_RESET_HOME: + init_home(); + break; + + case CMD_KP_GAIN: + kp[next_command.p1] = next_command.alt/t5; + // todo save to EEPROM + break; + case CMD_KI_GAIN: + ki[next_command.p1] = next_command.alt/t5; + // todo save to EEPROM + break; + case CMD_KD_GAIN: + kd[next_command.p1] = next_command.alt/t5; + // todo save to EEPROM + break; + + case CMD_KI_MAX: + integrator_max[next_command.p1] = next_command.alt/t5; + // todo save to EEPROM + break; + + case CMD_KFF_GAIN: + kff[next_command.p1] = next_command.alt/t5; + // todo save to EEPROM + break; + + case CMD_RADIO_TRIM: + radio_trim[next_command.p1] = next_command.alt; + save_EEPROM_trims(); + break; + + case CMD_RADIO_MAX: + radio_max[next_command.p1] = next_command.alt; + save_EEPROM_radio_minmax(); + break; + + case CMD_RADIO_MIN: + radio_min[next_command.p1] = next_command.alt; + save_EEPROM_radio_minmax(); + break; + + case CMD_REPEAT: + new_event(&next_command); + break; + + case CMD_SERVO: + //Serial.print("CMD_SERVO "); + //Serial.print(next_command.p1,DEC); + //Serial.print(" PWM: "); + //Serial.println(next_command.alt,DEC); + APM_RC.OutputCh(next_command.p1, next_command.alt); + break; + + case CMD_INDEX: + command_must_index = 0; + command_may_index = 0; + wp_index = next_command.p1 - 1; + break; + + case CMD_RELAY: + if(next_command.p1 = 0){ + relay_A(); + }else{ + relay_B(); + } + break; + } +} + +// Verify commands +// --------------- +void verify_must() +{ + float power; + + switch(command_must_ID) { + + case CMD_TAKEOFF: // Takeoff! + //Serial.print("verify_must cmd# "); + //Serial.println(command_must_index,DEC); + + if (GPS.ground_speed > 3){ + if(hold_course == -1){ + // save our current course to land + hold_course = yaw_sensor; + } + } + if(hold_course > -1){ + // recalc bearing error with hold_course; + nav_bearing = hold_course; + // recalc bearing error + calc_bearing_error(); + } + if (current_loc.alt > (home.alt + takeoff_altitude)) { + command_must_index = 0; + hold_course = -1; + } + break; + + + + case CMD_LAND: + // we don't verify landing - we never go to a new Must command after Land. + if ( ((wp_distance > 0) && (wp_distance <= (2*GPS.ground_speed/100))) || (current_loc.alt <= next_WP.alt + 300) ) + { + land_complete = 1; //Set land_complete if we are within 2 seconds distance or within 3 meters altitude + if(hold_course == -1){ + // save our current course to land + //hold_course = yaw_sensor; + // save the course line of the runway to land + hold_course = crosstrack_bearing; + } + } + if(hold_course > -1){ + // recalc bearing error with hold_course; + nav_bearing = hold_course; + // recalc bearing error + calc_bearing_error(); + } + update_crosstrack(); + + break; + + case CMD_WAYPOINT: // reach a waypoint + hold_course == -1; + update_crosstrack(); + if ((wp_distance > 0) && (wp_distance <= wp_radius)) { + SendDebug("MSG REACHED_WAYPOINT #"); + SendDebugln(command_must_index,DEC); + // clear the command queue; + command_must_index = 0; + } + // add in a more complex case + // Doug to do + if(loiter_sum > 300){ + send_message(SEVERITY_MEDIUM," Missed WP"); + command_must_index = 0; + } + break; + + case CMD_LOITER_N_TURNS: // LOITER N times + if (wp_distance <= loiter_radius){ + nav_bearing -= 9000; + + }else if (wp_distance < (loiter_radius + LOITER_RANGE)){ + power = -((float)(wp_distance - loiter_radius - LOITER_RANGE) / LOITER_RANGE); + power = constrain(power, 0, 1); + nav_bearing -= power * 9000; + + }else{ + update_crosstrack(); + } + if(loiter_sum > loiter_total) { + loiter_total = 0; + send_message(SEVERITY_LOW," LOITER orbits complete "); + // clear the command queue; + command_must_index = 0; + } + // recalc bearing error + nav_bearing = wrap_360(nav_bearing); + calc_bearing_error(); + break; + + case CMD_LOITER_TIME: // loiter N milliseconds + + if (wp_distance <= loiter_radius){ + nav_bearing -= 9000; + + }else if (wp_distance < (loiter_radius + LOITER_RANGE)){ + power = -((float)(wp_distance - loiter_radius - LOITER_RANGE) / LOITER_RANGE); + power = constrain(power, 0, 1); + nav_bearing -= power * 9000; + + }else{ + update_crosstrack(); + } + + if ((millis() - loiter_time) > loiter_time_max) { + send_message(SEVERITY_LOW," LOITER time complete "); + command_must_index = 0; + } + nav_bearing = wrap_360(nav_bearing); + // recalc bearing error + calc_bearing_error(); + break; + + case CMD_RTL: + if (wp_distance <= 30) { + //Serial.println("REACHED_HOME"); + command_must_index = 0; + } + break; + + case CMD_LOITER: // Just plain LOITER + break; + + default: + send_message(SEVERITY_HIGH," No current Must commands"); + break; + } +} + +void verify_may() +{ + switch(command_may_ID) { + case CMD_DELAY: + if ((millis() - delay_start) > delay_timeout){ + command_may_index = 0; + delay_timeout = 0; + } + + case CMD_LAND_OPTIONS: + if ((wp_distance > 0) && (wp_distance <= landing_distance)) { + //Serial.print("XXX REACHED_WAYPOINT #"); + //Serial.println(command_must_index,DEC); + // clear the command queue; + command_may_index = 0; + } + break; + } +} + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/config.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/config.h new file mode 100644 index 0000000000..d3e3b0e2a4 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/config.h @@ -0,0 +1,569 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- +// +////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////// +// +// WARNING WARNING WARNING WARNING WARNING WARNING WARNING WARNING WARNING +// +// DO NOT EDIT this file to adjust your configuration. Create your own +// APM_Config.h and use APM_Config.h.example as a reference. +// +// WARNING WARNING WARNING WARNING WARNING WARNING WARNING WARNING WARNING +/// +////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////// +// +// Default and automatic configuration details. +// +// Notes for maintainers: +// +// - Try to keep this file organised in the same order as APM_Config.h.example +// + +#include "defines.h" + +/// +/// DO NOT EDIT THIS INCLUDE - if you want to make a local change, make that +/// change in your local copy of APM_Config.h. +/// +#include "APM_Config.h" // <== THIS INCLUDE, DO NOT EDIT IT +/// +/// DO NOT EDIT THIS INCLUDE - if you want to make a local change, make that +/// change in your local copy of APM_Config.h. +/// + +// Just so that it's completely clear... +#define ENABLED 1 +#define DISABLED 0 + +////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////// +// HARDWARE CONFIGURATION AND CONNECTIONS +////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////// + +////////////////////////////////////////////////////////////////////////////// +// ENABLE_HIL +// Hardware in the loop output +// +#ifndef ENABLE_HIL +# define ENABLE_HIL DISABLED +#endif + +////////////////////////////////////////////////////////////////////////////// +// GPS_PROTOCOL +// +#ifndef GPS_PROTOCOL +# error XXX +# error XXX You must define GPS_PROTOCOL in APM_Config.h +# error XXX +#endif + +// The X-Plane GCS requires the IMU GPS configuration +#if (ENABLE_HIL == ENABLED) && (GPS_PROTOCOL != GPS_PROTOCOL_IMU) +# error Must select GPS_PROTOCOL_IMU when configuring for X-Plane or Flight Gear HIL +#endif + + +////////////////////////////////////////////////////////////////////////////// +// AIRSPEED_SENSOR +// AIRSPEED_RATIO +// +#ifndef AIRSPEED_SENSOR +# define AIRSPEED_SENSOR DISABLED +#endif +#ifndef AIRSPEED_RATIO +# define AIRSPEED_RATIO 1.9936 // Note - this varies from the value in ArduPilot due to the difference in ADC resolution +#endif + + +////////////////////////////////////////////////////////////////////////////// +// GCS_PROTOCOL +// GCS_PORT +// +#ifndef GCS_PROTOCOL +# define GCS_PROTOCOL GCS_PROTOCOL_STANDARD +#endif + +#ifndef GCS_PORT +# if (GCS_PROTOCOL == GCS_PROTOCOL_STANDARD) || (GCS_PROTOCOL == GCS_PROTOCOL_LEGACY) || (GCS_PROTOCOL == GCS_PROTOCOL_DEBUGTERMINAL) +# define GCS_PORT 3 +# else +# define GCS_PORT 0 +# endif +#endif + +#ifndef DEBUGTERMINAL_VERBOSE +# define DEBUGTERMINAL_VERBOSE 1 //Set this to 1 to get more detail in DEBUGTERMINAL messages, or 0 to save flash space +#endif + + +////////////////////////////////////////////////////////////////////////////// +// Serial port speeds. +// +#ifndef SERIAL0_BAUD +# define SERIAL0_BAUD 38400 +#endif +#ifndef SERIAL3_BAUD +# define SERIAL3_BAUD 115200 +#endif + + +////////////////////////////////////////////////////////////////////////////// +// Battery monitoring +// +#ifndef BATTERY_EVENT +# define BATTERY_EVENT DISABLED +#endif +#ifndef BATTERY_TYPE +# define BATTERY_TYPE 0 +#endif +#ifndef LOW_VOLTAGE +# define LOW_VOLTAGE 11.4 +#endif +#ifndef VOLT_DIV_RATIO +# define VOLT_DIV_RATIO 3.0 +#endif + + +////////////////////////////////////////////////////////////////////////////// +// INPUT_VOLTAGE +// +#ifndef INPUT_VOLTAGE +# define INPUT_VOLTAGE 5.0 +#endif + + +////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////// +// RADIO CONFIGURATION +////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////// + + +////////////////////////////////////////////////////////////////////////////// +// Radio channel limits +// +// Note that these are not called out in APM_Config.h.example as there +// is currently no configured behaviour for these channels. +// +#ifndef CH5_MIN +# define CH5_MIN 1000 +#endif +#ifndef CH5_MAX +# define CH5_MAX 2000 +#endif +#ifndef CH6_MIN +# define CH6_MIN 1000 +#endif +#ifndef CH6_MAX +# define CH6_MAX 2000 +#endif +#ifndef CH7_MIN +# define CH7_MIN 1000 +#endif +#ifndef CH7_MAX +# define CH7_MAX 2000 +#endif +#ifndef CH8_MIN +# define CH8_MIN 1000 +#endif +#ifndef CH8_MAX +# define CH8_MAX 2000 +#endif + + +////////////////////////////////////////////////////////////////////////////// +// FLIGHT_MODE +// FLIGHT_MODE_CHANNEL +// +#ifndef FLIGHT_MODE_CHANNEL +# define FLIGHT_MODE_CHANNEL 8 +#endif +#if (FLIGHT_MODE_CHANNEL != 5) && (FLIGHT_MODE_CHANNEL != 6) && (FLIGHT_MODE_CHANNEL != 7) && (FLIGHT_MODE_CHANNEL != 8) +# error XXX +# error XXX You must set FLIGHT_MODE_CHANNEL to 5, 6, 7 or 8 +# error XXX +#endif + +#if !defined(FLIGHT_MODE_1) +# define FLIGHT_MODE_1 FLY_BY_WIRE_A +#endif +#if !defined(FLIGHT_MODE_2) +# define FLIGHT_MODE_2 FLY_BY_WIRE_A +#endif +#if !defined(FLIGHT_MODE_3) +# define FLIGHT_MODE_3 STABILIZE +#endif +#if !defined(FLIGHT_MODE_4) +# define FLIGHT_MODE_4 STABILIZE +#endif +#if !defined(FLIGHT_MODE_5) +# define FLIGHT_MODE_5 MANUAL +#endif +#if !defined(FLIGHT_MODE_6) +# define FLIGHT_MODE_6 MANUAL +#endif + + +////////////////////////////////////////////////////////////////////////////// +// THROTTLE_FAILSAFE +// THROTTLE_FS_VALUE +// THROTTLE_FAILSAFE_ACTION +// +#ifndef THROTTLE_FAILSAFE +# define THROTTLE_FAILSAFE DISABLED +#endif +#ifndef THROTTE_FS_VALUE +# define THROTTLE_FS_VALUE 975 +#endif +#ifndef THROTTLE_FAILSAFE_ACTION +# define THROTTLE_FAILSAFE_ACTION 2 +#endif + + +////////////////////////////////////////////////////////////////////////////// +// AUTO_TRIM +// +#ifndef AUTO_TRIM +# define AUTO_TRIM ENABLED +#endif + + +////////////////////////////////////////////////////////////////////////////// +// THROTTLE_REVERSE +// +#ifndef THROTTLE_REVERSE +# define THROTTLE_REVERSE DISABLED +#endif + + +////////////////////////////////////////////////////////////////////////////// +// ENABLE_STICK_MIXING +// +#ifndef ENABLE_STICK_MIXING +# define ENABLE_STICK_MIXING ENABLED +#endif + + +////////////////////////////////////////////////////////////////////////////// +// THROTTLE_OUT +// +#ifndef THROTTE_OUT +# define THROTTLE_OUT ENABLED +#endif + + +////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////// +// STARTUP BEHAVIOUR +////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////// + +////////////////////////////////////////////////////////////////////////////// +// GROUND_START_DELAY +// +#ifndef GROUND_START_DELAY +# define GROUND_START_DELAY 0 +#endif + + +////////////////////////////////////////////////////////////////////////////// +// ENABLE_AIR_START +// +#ifndef ENABLE_AIR_START +# define ENABLE_AIR_START DISABLED +#endif + +////////////////////////////////////////////////////////////////////////////// +// ENABLE REVERSE_SWITCH +// +#ifndef REVERSE_SWITCH +# define REVERSE_SWITCH ENABLED +#endif + + +////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////// +// FLIGHT AND NAVIGATION CONTROL +////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////// + +////////////////////////////////////////////////////////////////////////////// +// Altitude measurement and control. +// +#ifndef AOA +# define AOA 100 // XXX still 100ths of a degree +#endif +#ifndef ALT_EST_GAIN +# define ALT_EST_GAIN 0.01 +#endif +#ifndef ALTITUDE_MIX +# define ALTITUDE_MIX 0 +#endif + + +////////////////////////////////////////////////////////////////////////////// +// AIRSPEED_CRUISE +// +#ifndef AIRSPEED_CRUISE +# define AIRSPEED_CRUISE 10 +#endif + + +////////////////////////////////////////////////////////////////////////////// +// FLY_BY_WIRE_B airspeed control +// +#ifndef AIRSPEED_FBW_MIN +# define AIRSPEED_FBW_MIN 6 +#endif +#ifndef AIRSPEED_FBW_MAX +# define AIRSPEED_FBW_MAX 30 +#endif +#ifndef THROTTLE_ALT_P +# define THROTTLE_ALT_P 0.32 +#endif +#ifndef THROTTLE_ALT_I +# define THROTTLE_ALT_I 0.04 +#endif +#ifndef THROTTLE_ALT_D +# define THROTTLE_ALT_D 0.0 +#endif +#ifndef THROTTLE_ALT_INT_MAX +# define THROTTLE_ALT_INT_MAX 20 +#endif + + +////////////////////////////////////////////////////////////////////////////// +// Throttle control +// +#ifndef THROTTLE_MIN +# define THROTTLE_MIN 0 +#endif +#ifndef THROTTLE_CRUISE +# define THROTTLE_CRUISE 45 +#endif +#ifndef THROTTLE_MAX +# define THROTTLE_MAX 75 +#endif + + +////////////////////////////////////////////////////////////////////////////// +// Autopilot control limits +// +#ifndef HEAD_MAX +# define HEAD_MAX 45 +#endif +#ifndef PITCH_MAX +# define PITCH_MAX 15 +#endif +#ifndef PITCH_MIN +# define PITCH_MIN -25 +#endif + + +////////////////////////////////////////////////////////////////////////////// +// Attitude control gains +// +#ifndef SERVO_ROLL_P +# define SERVO_ROLL_P 0.4 +#endif +#ifndef SERVO_ROLL_I +# define SERVO_ROLL_I 0.0 +#endif +#ifndef SERVO_ROLL_D +# define SERVO_ROLL_D 0.0 +#endif +#ifndef SERVO_ROLL_INT_MAX +# define SERVO_ROLL_INT_MAX 5 +#endif +#ifndef ROLL_SLEW_LIMIT +# define ROLL_SLEW_LIMIT 0 +#endif +#ifndef SERVO_PITCH_P +# define SERVO_PITCH_P 0.6 +#endif +#ifndef SERVO_PITCH_I +# define SERVO_PITCH_I 0.0 +#endif +#ifndef SERVO_PITCH_D +# define SERVO_PITCH_D 0.0 +#endif +#ifndef SERVO_PITCH_INT_MAX +# define SERVO_PITCH_INT_MAX 5 +#endif +#ifndef PITCH_COMP +# define PITCH_COMP 0.2 +#endif +#ifndef SERVO_YAW_P +# define SERVO_YAW_P 0.5 +#endif +#ifndef SERVO_YAW_I +# define SERVO_YAW_I 0.0 +#endif +#ifndef SERVO_YAW_D +# define SERVO_YAW_D 0.0 +#endif +#ifndef SERVO_YAW_INT_MAX +# define SERVO_YAW_INT_MAX 5 +#endif +#ifndef RUDDER_MIX +# define RUDDER_MIX 0.5 +#endif + + +////////////////////////////////////////////////////////////////////////////// +// Navigation control gains +// +#ifndef NAV_ROLL_P +# define NAV_ROLL_P 0.7 +#endif +#ifndef NAV_ROLL_I +# define NAV_ROLL_I 0.01 +#endif +#ifndef NAV_ROLL_D +# define NAV_ROLL_D 0.02 +#endif +#ifndef NAV_ROLL_INT_MAX +# define NAV_ROLL_INT_MAX 5 +#endif +#ifndef NAV_PITCH_ASP_P +# define NAV_PITCH_ASP_P 0.65 +#endif +#ifndef NAV_PITCH_ASP_I +# define NAV_PITCH_ASP_I 0.0 +#endif +#ifndef NAV_PITCH_ASP_D +# define NAV_PITCH_ASP_D 0.0 +#endif +#ifndef NAV_PITCH_ASP_INT_MAX +# define NAV_PITCH_ASP_INT_MAX 5 +#endif +#ifndef NAV_PITCH_ALT_P +# define NAV_PITCH_ALT_P 0.65 +#endif +#ifndef NAV_PITCH_ALT_I +# define NAV_PITCH_ALT_I 0.0 +#endif +#ifndef NAV_PITCH_ALT_D +# define NAV_PITCH_ALT_D 0.0 +#endif +#ifndef NAV_PITCH_ALT_INT_MAX +# define NAV_PITCH_ALT_INT_MAX 5 +#endif + + +////////////////////////////////////////////////////////////////////////////// +// Energy/Altitude control gains +// +#ifndef THROTTLE_TE_P +# define THROTTLE_TE_P 0.50 +#endif +#ifndef THROTTLE_TE_I +# define THROTTLE_TE_I 0.0 +#endif +#ifndef THROTTLE_TE_D +# define THROTTLE_TE_D 0.0 +#endif +#ifndef THROTTLE_TE_INT_MAX +# define THROTTLE_TE_INT_MAX 20 +#endif +#ifndef THROTTLE_SLEW_LIMIT +# define THROTTLE_SLEW_LIMIT 0 +#endif +#ifndef P_TO_T +# define P_TO_T 2.5 +#endif + + +////////////////////////////////////////////////////////////////////////////// +// Crosstrack compensation +// +#ifndef XTRACK_GAIN +# define XTRACK_GAIN 0.01 +#endif +#ifndef XTRACK_ENTRY_ANGLE +# define XTRACK_ENTRY_ANGLE 30 +#endif + + +////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////// +// DEBUGGING +////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////// + +////////////////////////////////////////////////////////////////////////////// +// DEBUG_SUBSYSTEM +// +#ifndef DEBUG_SUBSYSTEM +# define DEBUG_SUBSYSTEM 0 +#endif + + +////////////////////////////////////////////////////////////////////////////// +// DEBUG_LEVEL +// +#ifndef DEBUG_LEVEL +# define DEBUG_LEVEL SEVERITY_LOW +#endif + + +////////////////////////////////////////////////////////////////////////////// +// Dataflash logging control +// +#ifndef LOG_ATTITUDE_FAST +# define LOG_ATTITUDE_FAST DISABLED +#endif +#ifndef LOG_ATTITUDE_MED +# define LOG_ATTITUDE_MED ENABLED +#endif +#ifndef LOG_GPS +# define LOG_GPS ENABLED +#endif +#ifndef LOG_PM +# define LOG_PM ENABLED +#endif +#ifndef LOG_CTUN +# define LOG_CTUN DISABLED +#endif +#ifndef LOG_NTUN +# define LOG_NTUN DISABLED +#endif +#ifndef LOG_MODE +# define LOG_MODE ENABLED +#endif +#ifndef LOG_RAW +# define LOG_RAW DISABLED +#endif +#ifndef LOG_CMD +# define LOG_CMD ENABLED +#endif + +#ifndef DEBUG_PORT +# define DEBUG_PORT 0 +#endif + +#if DEBUG_PORT == 0 +# define SendDebug Serial.print +# define SendDebugln Serial.println +#elif DEBUG_PORT == 1 +# define SendDebug Serial1.print +# define SendDebugln Serial1.println +#elif DEBUG_PORT == 2 +# define SendDebug Serial2.print +# define SendDebugln Serial2.println +#elif DEBUG_PORT == 3 +# define SendDebug Serial3.print +# define SendDebugln Serial3.println +#endif + +////////////////////////////////////////////////////////////////////////////// +// Navigation defaults +// +#ifndef WP_RADIUS_DEFAULT +# define WP_RADIUS_DEFAULT 20 +#endif +#ifndef LOITER_RADIUS_DEFAULT +# define LOITER_RADIUS_DEFAULT 30 +#endif diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/control_modes.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/control_modes.pde new file mode 100644 index 0000000000..d2d348e67f --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/control_modes.pde @@ -0,0 +1,58 @@ +void read_control_switch() +{ + byte switchPosition = readSwitch(); + if (oldSwitchPosition != switchPosition){ + + set_mode(flight_modes[switchPosition]); + + oldSwitchPosition = switchPosition; + + // reset navigation integrators + // ------------------------- + reset_I(); + } +} +/* +byte readSwitch(void){ + int pulsewidth = APM_RC.InputCh(FLIGHT_MODE_CHANNEL - 1); + if (pulsewidth > 1230 && pulsewidth <= 1360) return 1; + if (pulsewidth > 1360 && pulsewidth <= 1490) return 2; + if (pulsewidth > 1490 && pulsewidth <= 1620) return 3; + if (pulsewidth > 1620 && pulsewidth <= 1749) return 4; // Software Manual + if (pulsewidth >= 1750) return 5; // Hardware Manual + return 0; +} +*/ +byte readSwitch(void){ + int pulsewidth = APM_RC.InputCh(FLIGHT_MODE_CHANNEL - 1); + if (pulsewidth > FLIGHT_MODE_5_BOUNDARY) return 5; + if (pulsewidth > FLIGHT_MODE_4_BOUNDARY) return 4; + if (pulsewidth > FLIGHT_MODE_3_BOUNDARY) return 3; + if (pulsewidth > FLIGHT_MODE_2_BOUNDARY) return 2; + if (pulsewidth > FLIGHT_MODE_1_BOUNDARY) return 1; + return 0; +} + +void reset_control_switch() +{ + oldSwitchPosition = 0; + read_control_switch(); + SendDebug("MSG: reset_control_switch"); + SendDebugln(oldSwitchPosition , DEC); +} + +void update_servo_switches() +{ + // up is reverse + // up is elevon + mix_mode = (PINL & 128) ? 1 : 0; + if (mix_mode == 0) { + reverse_roll = (PINE & 128) ? 1 : -1; + reverse_pitch = (PINE & 64) ? 1 : -1; + reverse_rudder = (PINL & 64) ? 1 : -1; + } else { + reverse_elevons = (PINE & 128) ? 1 : -1; + reverse_ch1_elevon = (PINE & 64) ? 1 : -1; + reverse_ch2_elevon = (PINL & 64) ? 1 : -1; + } +} diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/debug.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/debug.pde new file mode 100644 index 0000000000..e090a763db --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/debug.pde @@ -0,0 +1,70 @@ +#if DEBUG_SUBSYSTEM == 1 +void debug_subsystem() +{ + Serial.println("GPS Subsystem, RAW OUTPUT"); + + while(1){ + if(Serial1.available() > 0) // Ok, let me see, the buffer is empty? + { + delay(60); // wait for it all + while(Serial1.available() > 0){ + byte incoming = Serial1.read(); + //Serial.print(incoming,DEC); + Serial.print(incoming, BYTE); // will output Hex values + //Serial.print(","); + } + Serial.println(" "); + } + + } +} +#endif + +#if DEBUG_SUBSYSTEM == 2 +void debug_subsystem() +{ + Serial.println("Control Switch"); + + Serial.print("Control CH "); + Serial.println(flight_mode_channel, DEC); + + while(1){ + delay(20); + byte switchPosition = readSwitch(); + if (oldSwitchPosition != switchPosition){ + Serial.printf_P(PSTR("Position %d\n"), i, switchPosition); + oldSwitchPosition = switchPosition; + } + } +} +#endif + +#if DEBUG_SUBSYSTEM == 3 +void debug_subsystem() +{ + Serial.println("DIP Switch Test"); + + while(1){ + delay(100); + update_servo_switches(); + if (mix_mode == 0) { + Serial.print("Mix:standard "); + Serial.print("\t reverse_roll: "); + Serial.print(reverse_roll, DEC); + Serial.print("\t reverse_pitch: "); + Serial.print(reverse_pitch, DEC); + Serial.print("\t reverse_rudder: "); + Serial.println(reverse_rudder, DEC); + } else { + Serial.print("Mix:elevons "); + Serial.print("\t reverse_elevons: "); + Serial.print(reverse_elevons, DEC); + Serial.print("\t reverse_ch1_elevon: "); + Serial.print(reverse_ch1_elevon, DEC); + Serial.print("\t reverse_ch2_elevon: "); + Serial.println(reverse_ch2_elevon, DEC); + } + } +} +#endif + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/defines.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/defines.h new file mode 100644 index 0000000000..878fdadf0a --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/defines.h @@ -0,0 +1,345 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- + +// Internal defines, don't edit and expect things to work +// ------------------------------------------------------- + +#define DEBUG 0 +#define LOITER_RANGE 30 // for calculating power outside of loiter radius + +// GPS baud rates +// -------------- +#define NO_GPS 38400 +#define NMEA_GPS 38400 +#define EM406_GPS 57600 +#define UBLOX_GPS 38400 +#define ARDU_IMU 38400 +#define MTK_GPS 38400 +#define SIM_GPS 38400 + +// GPS type codes - use the names, not the numbers +#define GPS_PROTOCOL_NONE -1 +#define GPS_PROTOCOL_NMEA 0 +#define GPS_PROTOCOL_SIRF 1 +#define GPS_PROTOCOL_UBLOX 2 +#define GPS_PROTOCOL_IMU 3 +#define GPS_PROTOCOL_MTK 4 + +// Radio channels +// Note channels are from 0! +// +// XXX these should be CH_n defines from RC.h at some point. +#define CH_ROLL 0 +#define CH_PITCH 1 +#define CH_THROTTLE 2 +#define CH_RUDDER 3 +#define CH_1 0 +#define CH_2 1 +#define CH_3 2 +#define CH_4 3 +#define CH_5 4 +#define CH_6 5 +#define CH_7 6 +#define CH_8 7 + +#define WP_START_BYTE 0x130 // where in memory home WP is stored + all other WP +#define WP_SIZE 14 + +// GCS enumeration +#define GCS_PROTOCOL_STANDARD 0 // standard APM protocol +#define GCS_PROTOCOL_SPECIAL 1 // special test protocol (?) +#define GCS_PROTOCOL_LEGACY 2 // legacy ArduPilot protocol +#define GCS_PROTOCOL_XPLANE 3 // X-Plane HIL simulation +#define GCS_PROTOCOL_IMU 4 // ArdiPilot IMU output +#define GCS_PROTOCOL_JASON 5 // Jason's special secret GCS protocol +#define GCS_PROTOCOL_DEBUGTERMINAL 6 //Human-readable debug interface for use with a dumb terminal +#define GCS_PROTOCOL_XDIY 7 // X-DIY custom protocol +#define GCS_PROTOCOL_NONE -1 // No GCS output + +// PID enumeration +// --------------- +#define CASE_SERVO_ROLL 0 +#define CASE_SERVO_PITCH 1 +#define CASE_SERVO_RUDDER 2 +#define CASE_NAV_ROLL 3 +#define CASE_NAV_PITCH_ASP 4 +#define CASE_NAV_PITCH_ALT 5 +#define CASE_TE_THROTTLE 6 +#define CASE_ALT_THROTTLE 7 + +// Feedforward cases +// ---------------- +#define CASE_PITCH_COMP 0 +#define CASE_RUDDER_MIX 1 +#define CASE_P_TO_T 2 + +// Auto Pilot modes +// ---------------- +#define MANUAL 0 +#define CIRCLE 1 // When flying sans GPS, and we loose the radio, just circle +#define STABILIZE 2 + +#define FLY_BY_WIRE_A 5 // Fly By Wire A has left stick horizontal => desired roll angle, left stick vertical => desired pitch angle, right stick vertical = manual throttle +#define FLY_BY_WIRE_B 6 // Fly By Wire B has left stick horizontal => desired roll angle, left stick vertical => desired pitch angle, right stick vertical => desired airspeed + // Fly By Wire B = Fly By Wire A if you have AIRSPEED_SENSOR 0 +#define AUTO 10 +#define RTL 11 +#define LOITER 12 +#define TAKEOFF 13 +#define LAND 14 + + +// Command IDs - Must +#define CMD_BLANK 0x00 // there is no command stored in the mem location requested +#define CMD_WAYPOINT 0x10 +#define CMD_LOITER 0x11 +#define CMD_LOITER_N_TURNS 0x12 +#define CMD_LOITER_TIME 0x13 +#define CMD_RTL 0x14 +#define CMD_LAND 0x15 +#define CMD_TAKEOFF 0x16 + +// Command IDs - May +#define CMD_DELAY 0x20 +#define CMD_CLIMB 0x21 // NOT IMPLEMENTED +#define CMD_LAND_OPTIONS 0x22 // pitch in deg, airspeed m/s, throttle %, track WP 1 or 0 + +// Command IDs - Now +//#define CMD_AP_MODE 0x30 +#define CMD_RESET_INDEX 0x31 +#define CMD_GOTO_INDEX 0x32 // NOT IMPLEMENTED +#define CMD_GETVAR_INDEX 0x33 +#define CMD_SENDVAR_INDEX 0x34 +#define CMD_TELEMETRY 0x35 + +#define CMD_THROTTLE_CRUISE 0x40 +#define CMD_AIRSPEED_CRUISE 0x41 +#define CMD_RESET_HOME 0x44 + +#define CMD_KP_GAIN 0x60 +#define CMD_KI_GAIN 0x61 +#define CMD_KD_GAIN 0x62 +#define CMD_KI_MAX 0x63 +#define CMD_KFF_GAIN 0x64 + +#define CMD_RADIO_TRIM 0x70 +#define CMD_RADIO_MAX 0x71 +#define CMD_RADIO_MIN 0x72 +#define CMD_RADIO_MIN 0x72 +#define CMD_ELEVON_TRIM 0x73 + +#define CMD_INDEX 0x75 // sets the current Must index +#define CMD_REPEAT 0x80 +#define CMD_RELAY 0x81 +#define CMD_SERVO 0x82 // move servo N to PWM value + +//repeating events +#define NO_REPEAT 0 +#define CH_4_TOGGLE 1 +#define CH_5_TOGGLE 2 +#define CH_6_TOGGLE 3 +#define CH_7_TOGGLE 4 +#define RELAY_TOGGLE 5 +#define STOP_REPEAT 10 + +// GCS Message ID's +#define MSG_ACKNOWLEDGE 0x00 +#define MSG_HEARTBEAT 0x01 +#define MSG_ATTITUDE 0x02 +#define MSG_LOCATION 0x03 +#define MSG_PRESSURE 0x04 +#define MSG_STATUS_TEXT 0x05 +#define MSG_PERF_REPORT 0x06 +#define MSG_COMMAND 0x22 +#define MSG_VALUE 0x32 +#define MSG_PID 0x42 +#define MSG_TRIMS 0x50 +#define MSG_MINS 0x51 +#define MSG_MAXS 0x52 +#define MSG_IMU_OUT 0x53 + +#define SEVERITY_LOW 1 +#define SEVERITY_MEDIUM 2 +#define SEVERITY_HIGH 3 +#define SEVERITY_CRITICAL 4 + +// Logging parameters +#define LOG_ATTITUDE_MSG 0x01 +#define LOG_GPS_MSG 0x02 +#define LOG_MODE_MSG 0X03 +#define LOG_CONTROL_TUNING_MSG 0X04 +#define LOG_NAV_TUNING_MSG 0X05 +#define LOG_PERFORMANCE_MSG 0X06 +#define LOG_RAW_MSG 0x07 +#define LOG_CMD_MSG 0x08 +#define LOG_STARTUP_MSG 0x09 +#define TYPE_AIRSTART_MSG 0x00 +#define TYPE_GROUNDSTART_MSG 0x01 + +#define MASK_LOG_ATTITUDE_FAST 0 +#define MASK_LOG_ATTITUDE_MED 2 +#define MASK_LOG_GPS 4 +#define MASK_LOG_PM 8 +#define MASK_LOG_CTUN 16 +#define MASK_LOG_NTUN 32 +#define MASK_LOG_MODE 64 +#define MASK_LOG_RAW 128 +#define MASK_LOG_CMD 256 + +// Yaw modes +#define YAW_MODE_COORDINATE_TURNS 0 +#define YAW_MODE_HOLD_HEADING 1 +#define YAW_MODE_SLIP 2 + +// Waypoint Modes +// ---------------- +#define ABS_WP 0 +#define REL_WP 1 + +// Command Queues +// --------------- +#define COMMAND_MUST 0 +#define COMMAND_MAY 1 +#define COMMAND_NOW 2 + +// Events +// ------ +#define EVENT_WILL_REACH_WAYPOINT 1 +#define EVENT_SET_NEW_WAYPOINT_INDEX 2 +#define EVENT_LOADED_WAYPOINT 3 +#define EVENT_LOOP 4 + +//GPS_fix +#define VALID_GPS 0x00 +#define BAD_GPS 0x01 +#define FAILED_GPS 0x03 + + + +#define BATTERY_VOLTAGE(x) (x*(INPUT_VOLTAGE/1024.0))*VOLT_DIV_RATIO + +#define AIRSPEED_CH 7 // The external ADC channel for the airspeed sensor +#define BATTERY_PIN1 0 // These are the pins for the voltage dividers +#define BATTERY_PIN2 1 +#define BATTERY_PIN3 2 +#define BATTERY_PIN4 3 +#define RELAY_PIN 47 + +// Hardware Parameters +#define SLIDE_SWITCH_PIN 40 +#define PUSHBUTTON_PIN 41 + +#define A_LED_PIN 37 //36 = B, 37 = A, 35 = C +#define B_LED_PIN 36 +#define C_LED_PIN 35 + +#define HOLD_ALT_ABOVE_HOME 8 // bitmask value + +// IMU Parameters + +#define ADC_CONSTRAINT 900 +#define TRUE 1 +#define FALSE 0 +#define ADC_WARM_CYCLES 200 +#define SPEEDFILT 400 // centimeters/second + +#define GYRO_TEMP_CH 3 // The ADC channel reading the gyro temperature + +// ADC : Voltage reference 3.3v / 12bits(4096 steps) => 0.8mV/ADC step +// ADXL335 Sensitivity(from datasheet) => 330mV/g, 0.8mV/ADC step => 330/0.8 = 412 +// Tested value : 418 +#define GRAVITY 418 //this equivalent to 1G in the raw data coming from the accelerometer +#define Accel_Scale(x) x*(GRAVITY/9.81)//Scaling the raw data of the accel to actual acceleration in meters for seconds square + +#define ToRad(x) (x*0.01745329252) // *pi/180 +#define ToDeg(x) (x*57.2957795131) // *180/pi + +// IDG500 Sensitivity (from datasheet) => 2.0mV/º/s, 0.8mV/ADC step => 0.8/3.33 = 0.4 +// Tested values : 0.4026, ?, 0.4192 +#define Gyro_Gain_X 0.4 //X axis Gyro gain +#define Gyro_Gain_Y 0.41 //Y axis Gyro gain +#define Gyro_Gain_Z 0.41 //Z axis Gyro gain +#define Gyro_Scaled_X(x) x*ToRad(Gyro_Gain_X) //Return the scaled ADC raw data of the gyro in radians for second +#define Gyro_Scaled_Y(x) x*ToRad(Gyro_Gain_Y) //Return the scaled ADC raw data of the gyro in radians for second +#define Gyro_Scaled_Z(x) x*ToRad(Gyro_Gain_Z) //Return the scaled ADC raw data of the gyro in radians for second + +#define Kp_ROLLPITCH 0.0014 // Pitch&Roll Drift Correction Proportional Gain +#define Ki_ROLLPITCH 0.0000003 // Pitch&Roll Drift Correction Integrator Gain +#define Kp_YAW 0.8 // Yaw Drift Correction Porportional Gain +#define Ki_YAW 0.00004 // Yaw Drift CorrectionIntegrator Gain + +/*For debugging purposes*/ +#define OUTPUTMODE 1 //If value = 1 will print the corrected data, 0 will print uncorrected data of the gyros (with drift), 2 Accel only data + + +#define EEPROM_MAX_ADDR 4096 + +// Radio setup +#define EE_TRIM 0x00 +#define EE_MIN 0x10 +#define EE_MAX 0x20 +#define EE_ELEVON1_TRIM 0x30 +#define EE_ELEVON2_TRIM 0x32 + +// user gains +#define EE_XTRACK_GAIN 0x34 +#define EE_XTRACK_ANGLE 0x36 +#define EE_ALT_MIX 0x3B +#define EE_HEAD_MAX 0x38 +#define EE_PITCH_MAX 0x39 +#define EE_PITCH_MIN 0x3A +#define EE_KP 0x40 +#define EE_KI 0x60 +#define EE_KD 0x80 +#define EE_IMAX 0xA0 +#define EE_KFF 0xC0 +#define EE_AN_OFFSET 0xE0 + +//mission specific +#define EE_CONFIG 0X0F8 +#define EE_WP_MODE 0x0F9 +#define EE_YAW_MODE 0x0FA // not used +#define EE_WP_TOTAL 0x0FB +#define EE_WP_INDEX 0x0FC +#define EE_WP_RADIUS 0x0FD +#define EE_LOITER_RADIUS 0x0FE +#define EE_ALT_HOLD_HOME 0x0FF + +// user configs +#define EE_AIRSPEED_CRUISE 0x103 +#define EE_AIRSPEED_RATIO 0x104 +#define EE_AIRSPEED_FBW_MIN 0x108 +#define EE_AIRSPEED_FBW_MAX 0x109 +#define EE_THROTTLE_MIN 0x10A +#define EE_THROTTLE_CRUISE 0x10B +#define EE_THROTTLE_MAX 0x10C +#define EE_THROTTLE_FAILSAFE 0x10D +#define EE_THROTTLE_FS_VALUE 0x10E +#define EE_THROTTLE_FAILSAFE_ACTION 0x110 +#define EE_FLIGHT_MODE_CHANNEL 0x112 +#define EE_AUTO_TRIM 0x113 +#define EE_LOG_BITMASK 0x114 +#define EE_REVERSE_SWITCH 0x120 +#define EE_FLIGHT_MODES 0x121 + +// sensors +#define EE_ABS_PRESS_GND 0x116 +#define EE_GND_TEMP 0x11A +#define EE_GND_ALT 0x11C +#define EE_AP_OFFSET 0x11E + +// log +#define EE_LAST_LOG_PAGE 0xE00 +#define EE_LAST_LOG_NUM 0xE02 +#define EE_LOG_1_START 0xE04 + +// bits in log_bitmask +#define LOGBIT_ATTITUDE_FAST (1<<0) +#define LOGBIT_ATTITUDE_MED (1<<1) +#define LOGBIT_GPS (1<<2) +#define LOGBIT_PM (1<<3) +#define LOGBIT_CTUN (1<<4) +#define LOGBIT_NTUN (1<<5) +#define LOGBIT_MODE (1<<6) +#define LOGBIT_RAW (1<<7) +#define LOGBIT_CMD (1<<8) + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/events.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/events.pde new file mode 100644 index 0000000000..c8f94d4f23 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/events.pde @@ -0,0 +1,226 @@ +/* + This event will be called when the failsafe changes + boolean failsafe reflects the current state +*/ +void failsafe_event() +{ + if (failsafe == true){ + + // This is how to handle a failsafe. + switch(control_mode) + { + case MANUAL: // First position + set_mode(STABILIZE); + break; + + case STABILIZE: + case FLY_BY_WIRE_A: // middle position + case FLY_BY_WIRE_B: // middle position + set_mode(RTL); + throttle_cruise = THROTTLE_CRUISE; + + case CIRCLE: // middle position + break; + + case AUTO: // middle position + case LOITER: // middle position + if (throttle_failsafe_action == 1){ + set_mode(RTL); + throttle_cruise = THROTTLE_CRUISE; + } + // 2 = Stay in AUTO and ignore failsafe + break; + + case RTL: // middle position + break; + + default: + set_mode(RTL); + throttle_cruise = THROTTLE_CRUISE; + break; + } + }else{ + reset_I(); + } +} + +void low_battery_event(void) +{ + send_message(SEVERITY_HIGH,"Low Battery!"); + set_mode(RTL); + throttle_cruise = THROTTLE_CRUISE; +} + + +/* +4 simultaneous events +int event_original - original time in seconds +int event_countdown - count down to zero +byte event_countdown - ID for what to do +byte event_countdown - how many times to loop, 0 = indefinite +byte event_value - specific information for an event like PWM value +byte counterEvent - undo the event if nescessary + +count down each one + + +new event +undo_event +*/ + +void new_event(struct Location *cmd) +{ + SendDebug("New Event Loaded "); + SendDebugln(cmd->p1,DEC); + + + if(cmd->p1 == STOP_REPEAT){ + SendDebugln("STOP repeat "); + event_id = NO_REPEAT; + event_timer = -1; + undo_event = 0; + event_value = 0; + event_delay = 0; + event_repeat = 0; // convert seconds to millis + event_undo_value = 0; + repeat_forever = 0; + }else{ + // reset the event timer + event_timer = millis(); + event_id = cmd->p1; + event_value = cmd->alt; + event_delay = cmd->lat; + event_repeat = cmd->lng; // convert seconds to millis + event_undo_value = 0; + repeat_forever = (event_repeat == 0) ? 1:0; + } + + /* + Serial.print("event_id: "); + Serial.println(event_id,DEC); + Serial.print("event_value: "); + Serial.println(event_value,DEC); + Serial.print("event_delay: "); + Serial.println(event_delay,DEC); + Serial.print("event_repeat: "); + Serial.println(event_repeat,DEC); + Serial.print("event_undo_value: "); + Serial.println(event_undo_value,DEC); + Serial.print("repeat_forever: "); + Serial.println(repeat_forever,DEC); + Serial.print("Event_timer: "); + Serial.println(event_timer,DEC); + */ + perform_event(); +} + +void perform_event() +{ + if (event_repeat > 0){ + event_repeat --; + } + switch(event_id) { + case CH_4_TOGGLE: + event_undo_value = readOutputCh(4); + + APM_RC.OutputCh(4, event_value); // send to Servos + undo_event = 2; + break; + case CH_5_TOGGLE: + event_undo_value = readOutputCh(5); + APM_RC.OutputCh(5, event_value); // send to Servos + undo_event = 2; + break; + case CH_6_TOGGLE: + event_undo_value = readOutputCh(6); + APM_RC.OutputCh(6, event_value); // send to Servos + undo_event = 2; + break; + case CH_7_TOGGLE: + event_undo_value = readOutputCh(7); + APM_RC.OutputCh(7, event_value); // send to Servos + undo_event = 2; + event_undo_value = 1; + break; + case RELAY_TOGGLE: + + event_undo_value = PORTL & B00000100 ? 1:0; + if(event_undo_value == 1){ + relay_A(); + }else{ + relay_B(); + } + SendDebug("toggle relay "); + SendDebugln(PORTL,BIN); + undo_event = 2; + break; + + } +} + +void relay_A() +{ + PORTL |= B00000100; +} + +void relay_B() +{ + PORTL ^= B00000100; +} + +void update_events() +{ + // repeating events + if(undo_event == 1){ + perform_event_undo(); + undo_event = 0; + }else if(undo_event > 1){ + undo_event --; + } + + if(event_timer == -1) + return; + + if((millis() - event_timer) > event_delay){ + perform_event(); + + if(event_repeat > 0 || repeat_forever == 1){ + event_repeat--; + event_timer = millis(); + }else{ + event_timer = -1; + } + } +} + +void perform_event_undo() +{ + switch(event_id) { + case CH_4_TOGGLE: + APM_RC.OutputCh(4, event_undo_value); // send to Servos + break; + + case CH_5_TOGGLE: + APM_RC.OutputCh(5, event_undo_value); // send to Servos + break; + + case CH_6_TOGGLE: + APM_RC.OutputCh(6, event_undo_value); // send to Servos + break; + + case CH_7_TOGGLE: + APM_RC.OutputCh(7, event_undo_value); // send to Servos + break; + + case RELAY_TOGGLE: + + if(event_undo_value == 1){ + relay_A(); + }else{ + relay_B(); + } + SendDebug("untoggle relay "); + SendDebugln(PORTL,BIN); + break; + } +} diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/navigation.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/navigation.pde new file mode 100644 index 0000000000..e7dbf3d2df --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/navigation.pde @@ -0,0 +1,230 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- + +//**************************************************************** +// Function that will calculate the desired direction to fly and altitude error +//**************************************************************** +void navigate() +{ + // do not navigate with corrupt data + // --------------------------------- + if (GPS.fix == 0) + { + GPS.new_data = false; + return; + } + if(next_WP.lat == 0){ + return; + } + + // We only perform most nav computations if we have new gps data to work with + // -------------------------------------------------------------------------- + if(GPS.new_data){ + GPS.new_data = false; + + // target_bearing is where we should be heading + // -------------------------------------------- + target_bearing = get_bearing(¤t_loc, &next_WP); + + // nav_bearing will includes xtrac correction + // ------------------------------------------ + nav_bearing = target_bearing; + + // waypoint distance from plane + // ---------------------------- + wp_distance = getDistance(¤t_loc, &next_WP); + + if (wp_distance < 0){ + send_message(SEVERITY_HIGH," WP error - distance < 0"); + //Serial.println(wp_distance,DEC); + //print_current_waypoints(); + return; + } + + // check if we have missed the WP + loiter_delta = (target_bearing - old_target_bearing)/100; + + // reset the old value + old_target_bearing = target_bearing; + + // wrap values + if (loiter_delta > 180) loiter_delta -= 360; + if (loiter_delta < -180) loiter_delta += 360; + loiter_sum += abs(loiter_delta); + + calc_bearing_error(); + + // control mode specific updates to nav_bearing + update_navigation(); + } +} + +void update_navigation() +{ + // wp_distance is in ACTUAL meters, not the *100 meters we get from the GPS + // ------------------------------------------------------------------------ + + // distance and bearing calcs only + if(control_mode == AUTO){ + verify_must(); + verify_may(); + }else{ + + switch(control_mode){ + case LOITER: + float power; + if (wp_distance <= loiter_radius){ + nav_bearing -= 9000; + + }else if (wp_distance < (loiter_radius + LOITER_RANGE)){ + power = -((float)(wp_distance - loiter_radius - LOITER_RANGE) / LOITER_RANGE); + power = constrain(power, 0, 1); + nav_bearing -= power * 9000; + + }else{ + update_crosstrack(); + } + nav_bearing = wrap_360(nav_bearing); + calc_bearing_error(); + break; + + case RTL: + if(wp_distance <= (loiter_radius + 10)) { // + 10 meters + set_mode(LOITER); + }else{ + update_crosstrack(); + } + break; + } + } +} + + +/* +Disabled for now +void calc_distance_error() +{ + //distance_estimate += (float)GPS.ground_speed * .0002 * cos(radians(bearing_error * .01)); + //distance_estimate -= DST_EST_GAIN * (float)(distance_estimate - GPS_wp_distance); + //wp_distance = max(distance_estimate,10); +} +*/ + +void calc_airspeed_errors() +{ + airspeed_error = airspeed_cruise - airspeed; + airspeed_energy_error = (long)(((long)airspeed_cruise * (long)airspeed_cruise) - ((long)airspeed * (long)airspeed))/20000; //Changed 0.00005f * to / 20000 to avoid floating point calculation +} + +void calc_bearing_error() +{ + bearing_error = nav_bearing - yaw_sensor; + bearing_error = wrap_180(bearing_error); +} + +void calc_altitude_error() +{ + // limit climb rates + target_altitude = next_WP.alt - ((float)((wp_distance -30) * offset_altitude) / (float)(wp_totalDistance - 30)); + 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); + } + + /* + // Disabled for now + #if AIRSPEED_SENSOR == 1 + // special thanks to Ryan Beall for this one + float pitch_angle = pitch_sensor - AOA; // pitch_angle = pitch sensor - angle of attack of your plane at level *100 (50 = .5°) + pitch_angle = constrain(pitch_angle, -2000, 2000); + float scale = sin(radians(pitch_angle * .01)); + altitude_estimate += (float)airspeed * .0002 * scale; + altitude_estimate -= ALT_EST_GAIN * (float)(altitude_estimate - current_loc.alt); + + // compute altitude error for throttle control + altitude_error = target_altitude - altitude_estimate; + #else + altitude_error = target_altitude - current_loc.alt; + #endif + */ + + altitude_error = target_altitude - current_loc.alt; +} + + +long wrap_360(long error) +{ + if (error > 36000) error -= 36000; + if (error < 0) error += 36000; + return error; +} + +long wrap_180(long error) +{ + if (error > 18000) error -= 36000; + if (error < -18000) error += 36000; + return error; +} + +/* +// disabled for now +void update_loiter() +{ + loiter_delta = (target_bearing - old_target_bearing)/100; + // reset the old value + old_target_bearing = target_bearing; + // wrap values + if (loiter_delta > 170) loiter_delta -= 360; + if (loiter_delta < -170) loiter_delta += 360; + loiter_sum += loiter_delta; +}*/ + +void update_crosstrack(void) +{ + // Crosstrack Error + // ---------------- + if (abs(target_bearing - crosstrack_bearing) < 4500) { // If we are too far off or too close we don't do track following + crosstrack_error = sin(radians((target_bearing - crosstrack_bearing)/100)) * wp_distance; // Meters we are off track line + nav_bearing += constrain(crosstrack_error * x_track_gain, -x_track_angle, x_track_angle); + nav_bearing = wrap_360(nav_bearing); + } +} + +void reset_crosstrack() +{ + crosstrack_bearing = get_bearing(¤t_loc, &next_WP); // Used for track following +} + +int get_altitude_above_home(void) +{ + // This is the altitude above the home location + // The GPS gives us altitude at Sea Level + // if you slope soar, you should see a negative number sometimes + // ------------------------------------------------------------- + return current_loc.alt - home.alt; +} + +long getDistance(struct Location *loc1, struct Location *loc2) +{ + if(loc1->lat == 0 || loc1->lng == 0) + return -1; + if(loc2->lat == 0 || loc2->lng == 0) + return -1; + float dlat = (float)(loc2->lat - loc1->lat); + float dlong = ((float)(loc2->lng - loc1->lng)) * scaleLongDown; + return sqrt(sq(dlat) + sq(dlong)) * .01113195; +} + +long get_alt_distance(struct Location *loc1, struct Location *loc2) +{ + return abs(loc1->alt - loc2->alt); +} + +long get_bearing(struct Location *loc1, struct Location *loc2) +{ + long off_x = loc2->lng - loc1->lng; + long off_y = (loc2->lat - loc1->lat) * scaleLongUp; + long bearing = 9000 + atan2(-off_y, off_x) * 5729.57795; + if (bearing < 0) bearing += 36000; + return bearing; +} diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/radio.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/radio.pde new file mode 100644 index 0000000000..89b81648e5 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/radio.pde @@ -0,0 +1,180 @@ +//Function that will read the radio data, limit servos and trigger a failsafe +// ---------------------------------------------------------------------------- +byte failsafeCounter = 0; // we wait a second to take over the throttle and send the plane circling + +void read_radio() +{ + ch1_temp = APM_RC.InputCh(CH_ROLL); + ch2_temp = APM_RC.InputCh(CH_PITCH); + + if(mix_mode == 0){ + radio_in[CH_ROLL] = ch1_temp; + radio_in[CH_PITCH] = ch2_temp; + }else{ + radio_in[CH_ROLL] = reverse_elevons * (reverse_ch2_elevon * (ch2_temp - elevon2_trim) - reverse_ch1_elevon * (ch1_temp - elevon1_trim)) / 2 + 1500; + radio_in[CH_PITCH] = (reverse_ch2_elevon * (ch2_temp - elevon2_trim) + reverse_ch1_elevon * (ch1_temp - elevon1_trim)) / 2 + 1500; + } + + for (int y = 2; y < 8; y++) + radio_in[y] = APM_RC.InputCh(y); + + #if THROTTLE_REVERSE == 1 + radio_in[CH_THROTTLE] = radio_max[CH_THROTTLE] + radio_min[CH_THROTTLE] - radio_in[CH_THROTTLE]; + #endif + + throttle_failsafe(radio_in[CH_THROTTLE]); + servo_out[CH_THROTTLE] = ((float)(radio_in[CH_THROTTLE] - radio_min[CH_THROTTLE]) / (float)(radio_max[CH_THROTTLE] - radio_min[CH_THROTTLE])) * 100; + servo_out[CH_THROTTLE] = constrain(servo_out[CH_THROTTLE], 0, 100); +} + +void throttle_failsafe(int pwm) +{ + if(throttle_failsafe_enabled == 0) + return; + + //check for failsafe and debounce funky reads + // ------------------------------------------ + if (pwm < throttle_failsafe_value){ + // we detect a failsafe from radio + // throttle has dropped below the mark + failsafeCounter++; + if (failsafeCounter == 9){ + SendDebug("MSG FS ON "); + SendDebugln(pwm, DEC); + }else if(failsafeCounter == 10) { + ch3_failsafe = true; + //set_failsafe(true); + //failsafeCounter = 10; + }else if (failsafeCounter > 10){ + failsafeCounter = 11; + } + + }else if(failsafeCounter > 0){ + // we are no longer in failsafe condition + // but we need to recover quickly + failsafeCounter--; + if (failsafeCounter > 3){ + failsafeCounter = 3; + } + if (failsafeCounter == 1){ + SendDebug("MSG FS OFF "); + SendDebugln(pwm, DEC); + }else if(failsafeCounter == 0) { + ch3_failsafe = false; + //set_failsafe(false); + //failsafeCounter = -1; + }else if (failsafeCounter <0){ + failsafeCounter = -1; + } + } +} + +void trim_control_surfaces() +{ + // Store control surface trim values + // --------------------------------- + if(mix_mode == 0){ + radio_trim[CH_ROLL] = radio_in[CH_ROLL]; + radio_trim[CH_PITCH] = radio_in[CH_PITCH]; + radio_trim[CH_RUDDER] = radio_in[CH_RUDDER]; + }else{ + elevon1_trim = ch1_temp; + elevon2_trim = ch2_temp; + //Recompute values here using new values for elevon1_trim and elevon2_trim + //We cannot use radio_in[CH_ROLL] and radio_in[CH_PITCH] values from read_radio() because the elevon trim values have changed + radio_trim[CH_ROLL] = 1500; + radio_trim[CH_PITCH] = 1500; + } + // disabled for now + //save_EEPROM_trims(); +} + +void trim_radio() +{ + for (int y = 0; y < 50; y++) { + read_radio(); + } + + // Store the trim values + // --------------------- + if(mix_mode == 0){ + for (int y = 0; y < 8; y++) radio_trim[y] = radio_in[y]; + }else{ + elevon1_trim = ch1_temp; + elevon2_trim = ch2_temp; + radio_trim[CH_ROLL] = 1500; + radio_trim[CH_PITCH] = 1500; + for (int y = 2; y < 8; y++) radio_trim[y] = radio_in[y]; + } + save_EEPROM_trims(); +} + + +#if SET_RADIO_LIMITS == 1 +void read_radio_limits() +{ + // set initial servo limits for calibration routine + // ------------------------------------------------- + radio_min[CH_ROLL] = radio_in[CH_ROLL] - 150; + radio_max[CH_ROLL] = radio_in[CH_ROLL] + 150; + + radio_min[CH_PITCH] = radio_in[CH_PITCH] - 150; + radio_max[CH_PITCH] = radio_in[CH_PITCH] + 150; + + // vars for the radio config routine + // --------------------------------- + int counter = 0; + long reminder; + reminder = millis() - 10000; + + // Allows user to set stick limits and calibrate the IR + // ---------------------------------------------------- + while(counter < 50){ + + if (millis() - reminder >= 10000) { // Remind user every 10 seconds what is going on + send_message(SEVERITY_LOW,"Reading radio limits:"); + send_message(SEVERITY_LOW,"Move sticks to: upper right and lower Left"); + send_message(SEVERITY_LOW,"To Continue, hold the stick in the corner for 2 seconds."); + send_message(SEVERITY_LOW," "); + //print_radio(); + demo_servos(1); + reminder = millis(); + } + + delay(40); + read_radio(); + + // AutoSet servo limits + // -------------------- + if (radio_in[CH_ROLL] > 1000 && radio_in[CH_ROLL] < 2000){ + radio_min[CH_ROLL] = min(radio_in[CH_ROLL], radio_min[CH_ROLL]); + radio_max[CH_ROLL] = max(radio_in[CH_ROLL], radio_max[CH_ROLL]); + } + + if (radio_in[CH_PITCH] > 1000 && radio_in[CH_PITCH]< 2000){ + radio_min[CH_PITCH] = min(radio_in[CH_PITCH], radio_min[CH_PITCH]); + radio_max[CH_PITCH] = max(radio_in[CH_PITCH], radio_max[CH_PITCH]); + } + if(radio_in[CH_PITCH] < (radio_min[CH_PITCH] + 30) || radio_in[CH_PITCH] > (radio_max[CH_PITCH] -30)){ + SendDebug("."); + counter++; + }else{ + if (counter > 0) + counter--; + } + } + + // contstrain min values + // --------------------- + radio_min[CH_ROLL] = constrain(radio_min[CH_ROLL], 800, 2200); + radio_max[CH_ROLL] = constrain(radio_max[CH_ROLL], 800, 2200); + radio_min[CH_PITCH] = constrain(radio_min[CH_PITCH], 800, 2200); + radio_max[CH_PITCH] = constrain(radio_max[CH_PITCH], 800, 2200); + + SendDebugln(" "); +} +#endif + + + + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/sensors.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/sensors.pde new file mode 100644 index 0000000000..c0b12e618e --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/sensors.pde @@ -0,0 +1,65 @@ +void ReadSCP1000(void) {} + + +void read_airpressure(void){ + double x; + + APM_BMP085.Read(); // Get new data from absolute pressure sensor + abs_press = APM_BMP085.Press; + abs_press_filt = (abs_press); // + 2l * abs_press_filt) / 3l; // Light filtering + //temperature = (temperature * 9 + temp_unfilt) / 10; We will just use the ground temp for the altitude calculation + + double p = (double)abs_press_gnd / (double)abs_press_filt; + double temp = (float)ground_temperature / 10.f + 273.15f; + x = log(p) * temp * 29271.267f; + //x = log(p) * temp * 29.271267 * 1000; + press_alt = (long)(x / 10) + ground_alt; // Pressure altitude in centimeters + // Need to add comments for theory..... +} + +// in M/S * 100 +void read_airspeed(void) +{ + #if GPS_PROTOCOL != GPS_PROTOCOL_IMU // Xplane will supply the airspeed + airpressure_raw = ((float)APM_ADC.Ch(AIRSPEED_CH) * .25) + (airpressure_raw * .75); + airpressure = (int)airpressure_raw - airpressure_offset; + airpressure = max(airpressure, 0); + airspeed = sqrt((float)airpressure * airspeed_ratio) * 100; + #endif + + calc_airspeed_errors(); +} + +#if BATTERY_EVENT == 1 +void read_battery(void) +{ + battery_voltage1 = BATTERY_VOLTAGE(analogRead(BATTERY_PIN1)) * .1 + battery_voltage1 * .9; + battery_voltage2 = BATTERY_VOLTAGE(analogRead(BATTERY_PIN2)) * .1 + battery_voltage2 * .9; + battery_voltage3 = BATTERY_VOLTAGE(analogRead(BATTERY_PIN3)) * .1 + battery_voltage3 * .9; + battery_voltage4 = BATTERY_VOLTAGE(analogRead(BATTERY_PIN4)) * .1 + battery_voltage4 * .9; + + #if BATTERY_TYPE == 0 + if(battery_voltage3 < LOW_VOLTAGE) + low_battery_event(); + battery_voltage = battery_voltage3; // set total battery voltage, for telemetry stream + #endif + + #if BATTERY_TYPE == 1 + if(battery_voltage4 < LOW_VOLTAGE) + low_battery_event(); + battery_voltage = battery_voltage4; // set total battery voltage, for telemetry stream + #endif +} +#endif + +void zero_airspeed(void) +{ + airpressure_raw = (float)APM_ADC.Ch(AIRSPEED_CH); + for(int c = 0; c < 50; c++){ + delay(20); + airpressure_raw = (airpressure_raw * .90) + ((float)APM_ADC.Ch(AIRSPEED_CH) * .10); + } + airpressure_offset = airpressure_raw; +} + + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/setup.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/setup.pde new file mode 100644 index 0000000000..4f29457ee1 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/setup.pde @@ -0,0 +1,410 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- + +// Functions called from the setup menu +static int8_t setup_radio(uint8_t argc, const Menu::arg *argv); +static int8_t setup_show(uint8_t argc, const Menu::arg *argv); +static int8_t setup_factory(uint8_t argc, const Menu::arg *argv); +static int8_t setup_flightmodes(uint8_t argc, const Menu::arg *argv); + +// Command/function table for the setup menu +const struct Menu::command setup_menu_commands[] PROGMEM = { + // command function called + // ======= =============== + {"reset", setup_factory}, + {"radio", setup_radio}, + {"modes", setup_flightmodes}, + {"show", setup_show}, +}; + +// Create the setup menu object. +MENU(setup_menu, "setup", setup_menu_commands); + +// Called from the top-level menu to run the setup menu. +int8_t +setup_mode(uint8_t argc, const Menu::arg *argv) +{ + // Give the user some guidance + Serial.printf_P(PSTR("Setup Mode\n" + "\n" + "IMPORTANT: if you have not previously set this system up, use the\n" + "'reset' command to initialize the EEPROM to sensible default values\n" + "and then the 'radio' command to configure for your radio.\n" + "\n")); + + // Run the setup menu. When the menu exits, we will return to the main menu. + setup_menu.run(); +} + +// Print the current configuration. +// Called by the setup menu 'show' command. +static int8_t +setup_show(uint8_t argc, const Menu::arg *argv) +{ + uint8_t i; + + Serial.printf_P(PSTR("\nRadio:\n")); + read_EEPROM_radio_minmax(); + for(i = 0; i < 8; i++) + Serial.printf_P(PSTR("CH%d: %d | %d\n"), i + 1, radio_min[i], radio_max[i]); + + Serial.printf_P(PSTR("\nGains:\n")); + read_EEPROM_gains(); + + for(i = 0; i < 8; i++){ + Serial.printf_P(PSTR("P,I,D,iMax:")); + Serial.print(kp[i],3); + Serial.print(","); + Serial.print(ki[i],3); + Serial.print(","); + Serial.print(kd[i],3); + Serial.print(","); + Serial.println(integrator_max[i]/100,DEC); + } + + Serial.printf_P(PSTR("kff:")); + Serial.print(kff[0],3); + Serial.print(","); + Serial.print(kff[1],3); + Serial.print(","); + Serial.println(kff[2],3); + + Serial.printf_P(PSTR("XTRACK_GAIN:")); + Serial.println(x_track_gain,DEC); + + Serial.printf_P(PSTR("XTRACK_ENTRY_ANGLE: %d\n"), x_track_angle); + Serial.printf_P(PSTR("HEAD_MAX: %d\n"), head_max); + Serial.printf_P(PSTR("PITCH_MAX: %d\n"), pitch_max); + Serial.printf_P(PSTR("PITCH_MIN: %d\n"), pitch_min); + + read_user_configs(); + Serial.printf_P(PSTR("\nUser config:\n")); + Serial.printf_P(PSTR("airspeed_cruise: %d\n"), airspeed_cruise); + Serial.printf_P(PSTR("airspeed_fbw_min: %d\n"), airspeed_fbw_min); + Serial.printf_P(PSTR("airspeed_fbw_max: %d\n"), airspeed_fbw_max); + Serial.printf_P(PSTR("airspeed_ratio: ")); + Serial.println(airspeed_ratio, 4); + + Serial.printf_P(PSTR("throttle_min: %d\n"), throttle_min); + Serial.printf_P(PSTR("throttle_max: %d\n"), throttle_max); + Serial.printf_P(PSTR("throttle_cruise: %d\n"), throttle_cruise); + Serial.printf_P(PSTR("throttle_failsafe_enabled: %d\n"), throttle_failsafe_enabled); + Serial.printf_P(PSTR("throttle_failsafe_value: %d\n"), throttle_failsafe_value); + Serial.printf_P(PSTR("flight_mode_channel: %d\n"), flight_mode_channel+1); //Add 1 to flight_mode_channel to change 0-based channels to 1-based channels + Serial.printf_P(PSTR("auto_trim: %d\n"), auto_trim); + Serial.printf_P(PSTR("log_bitmask: %d\n\n"), log_bitmask); + //Serial.printf_P(PSTR("Switch settings:\n")); + //for(i = 0; i < 6; i++){ + // print_switch(i+1, flight_modes[i]); + //} + + return(0); +} + +// Initialise the EEPROM to 'factory' settings (mostly defined in APM_Config.h or via defaults). +// Called by the setup menu 'factoryreset' command. +static int8_t +setup_factory(uint8_t argc, const Menu::arg *argv) +{ + uint8_t i; + int c; + + Serial.printf_P(PSTR("\nType 'Y' and hit Enter to perform factory reset, any other key to abort: ")); + + do { + c = Serial.read(); + } while (-1 == c); + + if (('y' != c) && ('Y' != c)) + return(-1); + + Serial.printf_P(PSTR("\nFACTORY RESET\n\n")); + + wp_radius = WP_RADIUS_DEFAULT; + loiter_radius = LOITER_RADIUS_DEFAULT; + + save_EEPROM_waypoint_info(); + + radio_min[CH_1] = 0; + radio_min[CH_2] = 0; + radio_min[CH_3] = 0; + radio_min[CH_4] = 0; + radio_min[CH_5] = CH5_MIN; + radio_min[CH_6] = CH6_MIN; + radio_min[CH_7] = CH7_MIN; + radio_min[CH_8] = CH8_MIN; + + radio_max[CH_1] = 0; + radio_max[CH_2] = 0; + radio_max[CH_3] = 0; + radio_max[CH_4] = 0; + radio_max[CH_5] = CH5_MAX; + radio_max[CH_6] = CH6_MAX; + radio_max[CH_7] = CH7_MAX; + radio_max[CH_8] = CH8_MAX; + + save_EEPROM_radio_minmax(); + + kp[0] = SERVO_ROLL_P; + kp[1] = SERVO_PITCH_P; + kp[2] = SERVO_YAW_P; + kp[3] = NAV_ROLL_P; + kp[4] = NAV_PITCH_ASP_P; + kp[5] = NAV_PITCH_ALT_P; + kp[6] = THROTTLE_TE_P; + kp[7] = THROTTLE_ALT_P; + + ki[0] = SERVO_ROLL_I; + ki[1] = SERVO_PITCH_I; + ki[2] = SERVO_YAW_I; + ki[3] = NAV_ROLL_I; + ki[4] = NAV_PITCH_ASP_I; + ki[5] = NAV_PITCH_ALT_I; + ki[6] = THROTTLE_TE_I; + ki[7] = THROTTLE_ALT_I; + + kd[0] = SERVO_ROLL_D; + kd[1] = SERVO_PITCH_D; + kd[2] = SERVO_YAW_D; + kd[3] = NAV_ROLL_D; + kd[4] = NAV_PITCH_ASP_D; + kd[5] = NAV_PITCH_ALT_D; + kd[6] = THROTTLE_TE_D; + kd[7] = THROTTLE_ALT_D; + + integrator_max[0] = SERVO_ROLL_INT_MAX; + integrator_max[1] = SERVO_PITCH_INT_MAX; + integrator_max[2] = SERVO_YAW_INT_MAX; + integrator_max[3] = NAV_ROLL_INT_MAX; + integrator_max[4] = NAV_PITCH_ASP_INT_MAX; + integrator_max[5] = NAV_PITCH_ALT_INT_MAX; + integrator_max[6] = THROTTLE_TE_INT_MAX; + integrator_max[7] = THROTTLE_ALT_INT_MAX; + + kff[0] = PITCH_COMP; + kff[1] = RUDDER_MIX; + kff[2] = P_TO_T; + + for(i = 0; i < 8; i++){ + // scale input to deg * 100; + integrator_max[i] *= 100; + } + x_track_gain = XTRACK_GAIN * 100; + x_track_angle = XTRACK_ENTRY_ANGLE * 100; + altitude_mix = ALTITUDE_MIX; + + head_max = HEAD_MAX * 100; + pitch_max = PITCH_MAX * 100; + pitch_min = PITCH_MIN * 100; + + save_EEPROM_gains(); + + airspeed_cruise = AIRSPEED_CRUISE*100; + airspeed_fbw_min = AIRSPEED_FBW_MIN; + airspeed_fbw_max = AIRSPEED_FBW_MAX; + airspeed_ratio = AIRSPEED_RATIO; + throttle_min = THROTTLE_MIN; + throttle_max = THROTTLE_MAX; + throttle_cruise = THROTTLE_CRUISE; + throttle_failsafe_enabled = THROTTLE_FAILSAFE; + throttle_failsafe_action = THROTTLE_FAILSAFE_ACTION; + throttle_failsafe_value = THROTTLE_FS_VALUE; + //flight_mode_channel = FLIGHT_MODE_CHANNEL - 1; + auto_trim = AUTO_TRIM; + + flight_modes[0] = FLIGHT_MODE_1; + flight_modes[1] = FLIGHT_MODE_2; + flight_modes[2] = FLIGHT_MODE_3; + flight_modes[3] = FLIGHT_MODE_4; + flight_modes[4] = FLIGHT_MODE_5; + flight_modes[5] = FLIGHT_MODE_6; + save_EEPROM_flight_modes(); + + // convenience macro for testing LOG_* and setting LOGBIT_* +#define LOGBIT(_s) (LOG_ ## _s ? LOGBIT_ ## _s : 0) + log_bitmask = + LOGBIT(ATTITUDE_FAST) | + LOGBIT(ATTITUDE_MED) | + LOGBIT(GPS) | + LOGBIT(PM) | + LOGBIT(CTUN) | + LOGBIT(NTUN) | + LOGBIT(MODE) | + LOGBIT(RAW) | + LOGBIT(CMD); +#undef LOGBIT + + save_user_configs(); + + return(0); +} + +// Perform radio setup. +// Called by the setup menu 'radio' command. +static int8_t +setup_radio(uint8_t argc, const Menu::arg *argv) +{ + Serial.println("\n\nRadio Setup:"); + uint8_t i; + + for(i = 0; i < 100;i++){ + delay(20); + read_radio(); + } + + if(radio_in[CH_ROLL] < 500){ + while(1){ + Serial.print("Radio error"); + delay(1000); + // stop here + } + } + + for(i = 0; i < 4; i++){ + radio_min[i] = radio_in[i]; + radio_max[i] = radio_in[i]; + } + + Serial.printf_P(PSTR("\nMove both sticks to each corner. Hit Enter to save: ")); + while(1){ + + delay(20); + // Filters radio input - adjust filters in the radio.pde file + // ---------------------------------------------------------- + read_radio(); + + for(i = 0; i < 4; i++){ + radio_min[i] = min(radio_min[i], radio_in[i]); + radio_max[i] = max(radio_max[i], radio_in[i]); + } + + if(Serial.available() > 0){ + Serial.flush(); + Serial.println("Saving:"); + + save_EEPROM_radio_minmax(); + delay(100); + read_EEPROM_radio_minmax(); + + for(i = 0; i < 8; i++) + Serial.printf_P(PSTR("CH%d: %d | %d\n"), i + 1, radio_min[i], radio_max[i]); + break; + } + } + + return(0); +} + + +static int8_t +setup_flightmodes(uint8_t argc, const Menu::arg *argv) +{ + byte switchPosition, oldSwitchPosition, mode; + + Serial.printf_P(PSTR("\nMove RC toggle switch to each position to edit, move aileron stick to select modes.")); + print_hit_enter(); + trim_radio(); + + while(1){ + delay(20); + read_radio(); + switchPosition = readSwitch(); + + + // look for control switch change + if (oldSwitchPosition != switchPosition){ + + // Override position 5 + if(switchPosition > 4){ + mode = flight_modes[switchPosition] = MANUAL; + }else{ + // update our current mode + mode = flight_modes[switchPosition]; + } + + // update the user + print_switch(switchPosition, mode); + + // Remember switch position + oldSwitchPosition = switchPosition; + } + + // look for stick input + if (radio_input_switch() == true){ + switch(mode){ + case MANUAL: + mode = STABILIZE; + break; + + case STABILIZE: + mode = FLY_BY_WIRE_A; + break; + + case FLY_BY_WIRE_A: + mode = FLY_BY_WIRE_B; + break; + + case FLY_BY_WIRE_B: + mode = AUTO; + break; + + case AUTO: + mode = RTL; + break; + + case RTL: + mode = LOITER; + break; + + case LOITER: + mode = MANUAL; + break; + + default: + mode = MANUAL; + break; + } + + // Override position 5 + if(switchPosition > 4) + mode = MANUAL; + + // save new mode + flight_modes[switchPosition] = mode; + + // print new mode + print_switch(switchPosition, mode); + } + + // escape hatch + if(Serial.available() > 0){ + save_EEPROM_flight_modes(); + return (0); + } + } +} + +void +print_switch(byte p, byte m) +{ + Serial.printf_P(PSTR("Pos %d: "),p); + Serial.println(flight_mode_strings[m]); +} + +boolean +radio_input_switch(void) +{ + static byte bouncer; + + if (abs(radio_in[0] - radio_trim[0]) > 200) + bouncer = 10; + + if (bouncer > 0) + bouncer--; + + if (bouncer == 1){ + return true; + }else{ + return false; + } +} + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/system.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/system.pde new file mode 100644 index 0000000000..56a44067da --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/system.pde @@ -0,0 +1,491 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- +/***************************************************************************** +The init_ardupilot function processes everything we need for an in - air restart + We will determine later if we are actually on the ground and process a + ground start in that case. + +*****************************************************************************/ + +// Functions called from the top-level menu +extern int8_t process_logs(uint8_t argc, const Menu::arg *argv); // in Log.pde +extern int8_t setup_mode(uint8_t argc, const Menu::arg *argv); // in setup.pde +extern int8_t test_mode(uint8_t argc, const Menu::arg *argv); // in test.cpp + +// This is the help function +// PSTR is an AVR macro to read strings from flash memory +// printf_P is a version of print_f that reads from flash memory +static int8_t main_menu_help(uint8_t argc, const Menu::arg *argv) +{ + Serial.printf_P(PSTR("Commands:\n" + " logs log readback/setup mode\n" + " setup setup mode\n" + " test test mode\n" + "\n" + "Move the slide switch and reset to FLY.\n" + "\n")); + return(0); +} + +// Command/function table for the top-level menu. +const struct Menu::command main_menu_commands[] PROGMEM = { +// command function called +// ======= =============== + {"logs", process_logs}, + {"setup", setup_mode}, + {"test", test_mode}, + {"help", main_menu_help} +}; + +// Create the top-level menu object. +MENU(main_menu, "ArduPilotMega", main_menu_commands); + +void init_ardupilot() +{ + + byte last_log_num; + int last_log_start; + int last_log_end; + + // Console serial port + // + // The console port buffers are defined to be sufficiently large to support + // the console's use as a logging device, optionally as the GPS port when + // GPS_PROTOCOL_IMU is selected, and as the telemetry port. + // + // XXX This could be optimised to reduce the buffer sizes in the cases + // where they are not otherwise required. + // + Serial.begin(SERIAL0_BAUD, 128, 128); + + // GPS serial port. + // + // Not used if the IMU/X-Plane GPS is in use. + // + // XXX currently the EM406 (SiRF receiver) is nominally configured + // at 57600, however it's not been supported to date. We should + // probably standardise on 38400. + // + // XXX the 128 byte receive buffer may be too small for NMEA, depending + // on the message set configured. + // +#if GPS_PROTOCOL != GPS_PROTOCOL_IMU + Serial1.begin(38400, 128, 16); +#endif + + // Telemetry port. + // + // Not used if telemetry is going to the console. + // + // XXX for unidirectional protocols, we could (should) minimize + // the receive buffer, and the transmit buffer could also be + // shrunk for protocols that don't send large messages. + // +#if GCS_PORT == 3 + Serial3.begin(SERIAL3_BAUD, 128, 128); +#endif + + Serial.printf_P(PSTR("\n\n" + "Init ArduPilotMega X-DIY\n\n" +#if TELEMETRY_PORT == 3 + "Telemetry is on the xbee port\n" +#endif + "freeRAM: %d\n"), freeRAM()); + + APM_RC.Init(); // APM Radio initialization + read_EEPROM_startup(); // Read critical config information to start + + APM_ADC.Init(); // APM ADC library initialization + APM_BMP085.Init(); // APM Abs Pressure sensor initialization + DataFlash.Init(); // DataFlash log initialization + GPS.init(); // GPS Initialization + + #if MAGNETOMETER == ENABLED + APM_Compass.Init(); // I2C initialization + #endif + + APM_RC.OutputCh(CH_ROLL, radio_trim[CH_ROLL]); // Initialization of servo outputs + APM_RC.OutputCh(CH_PITCH, radio_trim[CH_PITCH]); + APM_RC.OutputCh(CH_THROTTLE, radio_trim[CH_THROTTLE]); + APM_RC.OutputCh(CH_RUDDER, radio_trim[CH_RUDDER]); + + pinMode(C_LED_PIN, OUTPUT); // GPS status LED + pinMode(A_LED_PIN, OUTPUT); // GPS status LED + pinMode(B_LED_PIN, OUTPUT); // GPS status LED + pinMode(SLIDE_SWITCH_PIN, INPUT); // To enter interactive mode + pinMode(PUSHBUTTON_PIN, INPUT); // unused + + + // If the switch is in 'menu' mode, run the main menu. + // + // Since we can't be sure that the setup or test mode won't leave + // the system in an odd state, we don't let the user exit the top + // menu; they must reset in order to fly. + // + if (digitalRead(SLIDE_SWITCH_PIN) == 0) { + digitalWrite(A_LED_PIN,HIGH); // turn on setup-mode LED + Serial.printf_P(PSTR("\n" + "Entering interactive setup mode...\n" + "\n" + "If using the Arduino Serial Monitor, ensure Line Ending is set to Carriage Return.\n" + "Type 'help' to list commands, 'exit' to leave a submenu.\n" + "Visit the 'setup' menu for first-time configuration.\n")); + for (;;) { + Serial.printf_P(PSTR("\n" + "Move the slide switch and reset to FLY.\n" + "\n")); + main_menu.run(); + } + } + + + if(log_bitmask > 0){ + // Here we will check on the length of the last log + // We don't want to create a bunch of little logs due to powering on and off + last_log_num = eeprom_read_byte((uint8_t *) EE_LAST_LOG_NUM); + last_log_start = eeprom_read_word((uint16_t *) (EE_LOG_1_START+(last_log_num - 1) * 0x02)); + last_log_end = eeprom_read_word((uint16_t *) EE_LAST_LOG_PAGE); + + if(last_log_num == 0) { + // The log space is empty. Start a write session on page 1 + DataFlash.StartWrite(1); + eeprom_write_byte((uint8_t *) EE_LAST_LOG_NUM, (1)); + eeprom_write_word((uint16_t *) EE_LOG_1_START, (1)); + + } else if (last_log_end <= last_log_start + 10) { + // The last log is small. We consider it junk. Overwrite it. + DataFlash.StartWrite(last_log_start); + + } else { + // The last log is valid. Start a new log + if(last_log_num >= 19) { + Serial.println("Number of log files exceeds max. Log 19 will be overwritten."); + last_log_num --; + } + DataFlash.StartWrite(last_log_end + 1); + eeprom_write_byte((uint8_t *) EE_LAST_LOG_NUM, (last_log_num + 1)); + eeprom_write_word((uint16_t *) (EE_LOG_1_START+(last_log_num)*0x02), (last_log_end + 1)); + } + } + + // read in the flight switches + update_servo_switches(); + + if(DEBUG_SUBSYSTEM > 0){ + debug_subsystem(); + + } else if (ENABLE_AIR_START == 1) { + // Perform an air start and get back to flying + send_message(SEVERITY_LOW," AIR START"); + + // Get necessary data from EEPROM + //---------------- + read_EEPROM_airstart_critical(); + + // This delay is important for the APM_RC library to work. We need some time for the comm between the 328 and 1280 to be established. + int old_pulse = 0; + while (millis()<=1000 && (abs(old_pulse - APM_RC.InputCh(flight_mode_channel)) > 5 || APM_RC.InputCh(flight_mode_channel) == 1000 || APM_RC.InputCh(flight_mode_channel) == 1200)) { + old_pulse = APM_RC.InputCh(flight_mode_channel); + delay(25); + } + if (log_bitmask & MASK_LOG_CMD) + Log_Write_Startup(TYPE_AIRSTART_MSG); + reload_commands(); // Get set to resume AUTO from where we left off + + }else { + startup_ground(); + if (log_bitmask & MASK_LOG_CMD) + Log_Write_Startup(TYPE_GROUNDSTART_MSG); + } + + // set the correct flight mode + // --------------------------- + reset_control_switch(); +} + +//******************************************************************************** +//This function does all the calibrations, etc. that we need during a ground start +//******************************************************************************** +void startup_ground(void) +{ + send_message(SEVERITY_LOW," GROUND START"); + + #if(GROUND_START_DELAY > 0) + send_message(SEVERITY_LOW," With Delay"); + delay(GROUND_START_DELAY * 1000); + #endif + + // Output waypoints for confirmation + // -------------------------------- + for(int i = 1; i < wp_total + 1; i++) { + send_message(MSG_COMMAND, i); + } + + // Makes the servos wiggle + // step 1 = 1 wiggle + // ----------------------- + demo_servos(1); + + //IMU ground start + //------------------------ +#if GPS_PROTOCOL != GPS_PROTOCOL_IMU + startup_IMU_ground(); +#endif + + + // read the radio to set trims + // --------------------------- + trim_radio(); + + #if AIRSPEED_SENSOR == 1 + // initialize airspeed sensor + // -------------------------- + zero_airspeed(); + send_message(SEVERITY_LOW," zero airspeed calibrated"); + #else + send_message(SEVERITY_LOW," NO airspeed"); + #endif + + // Save the settings for in-air restart + // ------------------------------------ + save_EEPROM_groundstart(); + + // initialize commands + // ------------------- + init_commands(); + +} + +void set_mode(byte mode) +{ + if(control_mode == mode){ + // don't switch modes if we are already in the correct mode. + return; + } + if(auto_trim > 0 || control_mode == MANUAL) + trim_control_surfaces(); + + control_mode = mode; + crash_timer = 0; + + switch(control_mode) + { + case MANUAL: + break; + + case STABILIZE: + break; + + case FLY_BY_WIRE_A: + break; + + case FLY_BY_WIRE_B: + break; + + case AUTO: + update_auto(); + break; + + case RTL: + return_to_launch(); + break; + + case LOITER: + loiter_at_location(); + break; + + case TAKEOFF: + break; + + case LAND: + break; + + default: + return_to_launch(); + break; + } + + // output control mode to the ground station + send_message(MSG_HEARTBEAT); + + if (log_bitmask & MASK_LOG_MODE) + Log_Write_Mode(control_mode); +} + +void set_failsafe(boolean mode) +{ + // only act on changes + // ------------------- + if(failsafe != mode){ + + // store the value so we don't trip the gate twice + // ----------------------------------------------- + failsafe = mode; + + if (failsafe == false){ + // We're back in radio contact + // --------------------------- + + // re-read the switch so we can return to our preferred mode + reset_control_switch(); + + // Reset control integrators + // --------------------- + reset_I(); + + }else{ + // We've lost radio contact + // ------------------------ + // nothing to do right now + } + + // Let the user know what's up so they can override the behavior + // ------------------------------------------------------------- + failsafe_event(); + } +} + + +void startup_IMU_ground(void) +{ + uint16_t store = 0; + int flashcount = 0; + // 12345678901234567890123456789012 + jeti_status(" **** INIT **** Warming up ADC"); + jeti_update(); + SendDebugln(" Warming up ADC..."); + + for(int c = 0; c < ADC_WARM_CYCLES; c++) + { + digitalWrite(C_LED_PIN, LOW); + digitalWrite(A_LED_PIN, HIGH); + digitalWrite(B_LED_PIN, LOW); + delay(50); + Read_adc_raw(); + digitalWrite(C_LED_PIN, HIGH); + digitalWrite(A_LED_PIN, LOW); + digitalWrite(B_LED_PIN, HIGH); + delay(50); + } + + // Makes the servos wiggle twice - about to begin IMU calibration - HOLD LEVEL AND STILL!! + // ----------------------- + demo_servos(2); + SendDebugln(" Beginning IMU calibration; do not move plane"); + // 12345678901234567890123456789012 + jeti_status(" **** INIT **** Do not move!!!"); + jeti_update(); + + + for(int y = 0; y <= 5; y++){ // Read first initial ADC values for offset. + AN_OFFSET[y] = AN[y]; + } + + APM_BMP085.Read(); // Get initial data from absolute pressure sensor + abs_press_gnd = APM_BMP085.Press; + ground_temperature = APM_BMP085.Temp; + delay(20); + // *********** + + for(int i = 0; i < 400; i++){ // We take some readings... + Read_adc_raw(); + for(int y = 0; y <= 5; y++) // Read initial ADC values for offset (averaging). + AN_OFFSET[y] = AN_OFFSET[y] * 0.9 + AN[y] * 0.1; + + APM_BMP085.Read(); // Get initial data from absolute pressure sensor + abs_press_gnd = (abs_press_gnd * 9l + APM_BMP085.Press) / 10l; + ground_temperature = (ground_temperature * 9 + APM_BMP085.Temp) / 10; + + delay(20); + if(flashcount == 5) { + digitalWrite(C_LED_PIN, LOW); + digitalWrite(A_LED_PIN, HIGH); + digitalWrite(B_LED_PIN, LOW); + } + if(flashcount >= 10) { + flashcount = 0; + digitalWrite(C_LED_PIN, HIGH); + digitalWrite(A_LED_PIN, LOW); + digitalWrite(B_LED_PIN, HIGH); + } + flashcount++; + + } + SendDebugln(" Calibration complete."); + digitalWrite(B_LED_PIN, HIGH); // Set LED B high to indicate IMU ready + digitalWrite(A_LED_PIN, LOW); + digitalWrite(C_LED_PIN, LOW); + + AN_OFFSET[5] -= GRAVITY * SENSOR_SIGN[5]; +/* + Serial.print ("Offsets "); + Serial.print (AN_OFFSET[0]); + Serial.print (" "); + Serial.print (AN_OFFSET[1]); + Serial.print (" "); + Serial.print (AN_OFFSET[2]); + Serial.print (" "); + Serial.print (AN_OFFSET[3]); + Serial.print (" "); + Serial.print (AN_OFFSET[4]); + Serial.print (" "); + Serial.println (AN_OFFSET[5]); +*/ +} + + +void update_GPS_light(void) +{ + // GPS LED on if we have a fix or Blink GPS LED if we are receiving data + // --------------------------------------------------------------------- + switch (GPS.status()) { + case(2): + digitalWrite(C_LED_PIN, HIGH); //Turn LED C on when gps has valid fix. + break; + + case(1): + if (GPS.valid_read == true){ + GPS_light = !GPS_light; // Toggle light on and off to indicate gps messages being received, but no GPS fix lock + if (GPS_light){ + digitalWrite(C_LED_PIN, LOW); + } else { + digitalWrite(C_LED_PIN, HIGH); + } + GPS.valid_read = false; + } + break; + + default: + digitalWrite(C_LED_PIN, LOW); + break; + } +} + + + +void resetPerfData(void) { + mainLoop_count = 0; + G_Dt_max = 0; + gyro_sat_count = 0; + adc_constraints = 0; + renorm_sqrt_count = 0; + renorm_blowup_count = 0; + gps_fix_count = 0; + perf_mon_timer = millis(); +} + + +/* This function gets the current value of the heap and stack pointers. +* The stack pointer starts at the top of RAM and grows downwards. The heap pointer +* starts just above the static variables etc. and grows upwards. SP should always +* be larger than HP or you'll be in big trouble! The smaller the gap, the more +* careful you need to be. Julian Gall 6 - Feb - 2009. +*/ +unsigned long freeRAM() { + uint8_t * heapptr, * stackptr; + stackptr = (uint8_t *)malloc(4); // use stackptr temporarily + heapptr = stackptr; // save value of heap pointer + free(stackptr); // free up the memory again (sets stackptr to 0) + stackptr = (uint8_t *)(SP); // save value of stack pointer + return stackptr - heapptr; +} + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/test.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/test.pde new file mode 100644 index 0000000000..d6791b4291 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/test.pde @@ -0,0 +1,433 @@ +// These are function definitions so the Menu can be constructed before the functions +// are defined below. Order matters to the compiler. +static int8_t test_radio(uint8_t argc, const Menu::arg *argv); +static int8_t test_gps(uint8_t argc, const Menu::arg *argv); +static int8_t test_imu(uint8_t argc, const Menu::arg *argv); +static int8_t test_gyro(uint8_t argc, const Menu::arg *argv); +static int8_t test_battery(uint8_t argc, const Menu::arg *argv); +static int8_t test_relay(uint8_t argc, const Menu::arg *argv); +static int8_t test_wp(uint8_t argc, const Menu::arg *argv); +static int8_t test_airspeed(uint8_t argc, const Menu::arg *argv); +static int8_t test_pressure(uint8_t argc, const Menu::arg *argv); +static int8_t test_mag(uint8_t argc, const Menu::arg *argv); +static int8_t test_xbee(uint8_t argc, const Menu::arg *argv); +static int8_t test_eedump(uint8_t argc, const Menu::arg *argv); +static int8_t test_jeti(uint8_t argc, const Menu::arg *argv); + +// This is the help function +// PSTR is an AVR macro to read strings from flash memory +// printf_P is a version of print_f that reads from flash memory +/*static int8_t help_test(uint8_t argc, const Menu::arg *argv) +{ + Serial.printf_P(PSTR("\n" + "Commands:\n" + " radio\n" + " servos\n" + " gps\n" + " imu\n" + " battery\n" + "\n")); +}*/ + +// Creates a constant array of structs representing menu options +// and stores them in Flash memory, not RAM. +// User enters the string in the console to call the functions on the right. +// See class Menu in AP_Coommon for implementation details +const struct Menu::command test_menu_commands[] PROGMEM = { + {"radio", test_radio}, + {"gps", test_gps}, + {"imu", test_imu}, + {"gyro", test_gyro}, + {"battery", test_battery}, + {"relay", test_relay}, + {"waypoints", test_wp}, + {"airspeed", test_airspeed}, + {"airpressure", test_pressure}, + {"compass", test_mag}, + {"xbee", test_xbee}, + {"eedump", test_eedump}, + {"jeti", test_jeti}, +}; + +// A Macro to create the Menu +MENU(test_menu, "test", test_menu_commands); + +int8_t +test_mode(uint8_t argc, const Menu::arg *argv) +{ + Serial.printf_P(PSTR("Test Mode\n\n")); + test_menu.run(); +} + +static int8_t +test_eedump(uint8_t argc, const Menu::arg *argv) +{ + int i, j; + + // hexdump the EEPROM + for (i = 0; i < EEPROM_MAX_ADDR; i += 16) { + Serial.printf_P(PSTR("%04x:"), i); + for (j = 0; j < 16; j++) + Serial.printf_P(PSTR(" %02x"), eeprom_read_byte((const uint8_t *)(i + j))); + Serial.println(); + } + return(0); +} + +static int8_t +test_radio(uint8_t argc, const Menu::arg *argv) +{ + print_hit_enter(); + delay(1000); + + #if THROTTLE_REVERSE == 1 + Serial.println("Throttle is reversed in config: "); + delay(1000); + #endif + + // read the radio to set trims + // --------------------------- + trim_radio(); + + while(1){ + delay(20); + // Filters radio input - adjust filters in the radio.pde file + // ---------------------------------------------------------- + read_radio(); + update_servo_switches(); + + servo_out[CH_ROLL] = reverse_roll * (radio_in[CH_ROLL] - radio_trim[CH_ROLL]) * 9; + servo_out[CH_PITCH] = reverse_pitch * (radio_in[CH_PITCH] - radio_trim[CH_PITCH]) * 9; + servo_out[CH_RUDDER] = reverse_rudder * (radio_in[CH_RUDDER] - radio_trim[CH_RUDDER]) * 9; + + // write out the servo PWM values + // ------------------------------ + set_servos_4(); + + + for(int y = 4; y < 8; y++) { + radio_out[y] = constrain(radio_in[y], radio_min[y], radio_max[y]); + APM_RC.OutputCh(y, radio_out[y]); // send to Servos + } + Serial.printf_P(PSTR("IN: 1: %d\t2: %d\t3: %d\t4: %d\t5: %d\t6: %d\t7: %d\t8: %d\t"), radio_in[CH_1], radio_in[CH_2], radio_in[CH_3], radio_in[CH_4], radio_in[CH_5], radio_in[CH_6], radio_in[CH_7], radio_in[CH_8]); + Serial.printf_P(PSTR("OUT 1: %d\t2: %d\t3: %d\t4: %d\n"), (servo_out[CH_ROLL]/100), (servo_out[CH_PITCH]/100), servo_out[CH_THROTTLE], (servo_out[CH_RUDDER]/100)); + + if(Serial.available() > 0){ + return (0); + } + } +} + + +static int8_t +test_gps(uint8_t argc, const Menu::arg *argv) +{ + print_hit_enter(); + delay(1000); + + while(1){ + delay(333); + + // Blink GPS LED if we don't have a fix + // ------------------------------------ + update_GPS_light(); + + GPS.update(); + + if (GPS.new_data){ + Serial.print("Lat:"); + Serial.print((float)GPS.latitude/10000000, 10); + Serial.print(" Lon:"); + Serial.print((float)GPS.longitude/10000000, 10); + Serial.printf_P(PSTR("alt %dm, #sats: %d\n"), GPS.altitude/100, GPS.num_sats); + }else{ + Serial.print("."); + } + if(Serial.available() > 0){ + return (0); + } + } +} + +static int8_t +test_imu(uint8_t argc, const Menu::arg *argv) +{ + Serial.printf_P(PSTR("Calibrating.")); + startup_IMU_ground(); + print_hit_enter(); + delay(1000); + + while(1){ + delay(20); + read_AHRS(); + + // We are using the IMU + // --------------------- + Serial.printf_P(PSTR("r: %d\tp: %d\t y: %d\n"), ((int)roll_sensor/100), ((int)pitch_sensor/100), ((uint16_t)yaw_sensor/100)); + + if(Serial.available() > 0){ + return (0); + } + } +} + +static int8_t +test_battery(uint8_t argc, const Menu::arg *argv) +{ +#if BATTERY_EVENT == 1 + for (int i = 0; i < 20; i++){ + delay(20); + read_battery(); + } + Serial.printf_P(PSTR("Volts: 1:")); + Serial.print(battery_voltage1, 4); + Serial.print(" 2:"); + Serial.print(battery_voltage2, 4); + Serial.print(" 3:"); + Serial.print(battery_voltage3, 4); + Serial.print(" 4:"); + Serial.println(battery_voltage4, 4); +#else + Serial.printf_P(PSTR("Not enabled\n")); + +#endif + return (0); +} + + +static int8_t +test_relay(uint8_t argc, const Menu::arg *argv) +{ + print_hit_enter(); + delay(1000); + //DDRL |= B00000100; + + while(1){ + Serial.println(int DDRL); + Serial.println(int PORTL); + Serial.println("Relay A"); + relay_A(); + delay(500); + if(Serial.available() > 0){ + return (0); + } + + Serial.println("Relay B"); + relay_B(); + delay(500); + if(Serial.available() > 0){ + return (0); + } + } +} + + +static int8_t +test_gyro(uint8_t argc, const Menu::arg *argv) +{ + print_hit_enter(); + delay(1000); + Serial.printf_P(PSTR("Gyro | Accel\n")); + delay(200); + + while(1){ + for (int i = 0; i < 6; i++) { + AN[i] = APM_ADC.Ch(sensors[i]); + } + Serial.printf_P(PSTR("%d\t%d\t%d\t|\t%d\t%d\t%d\n"), (int)AN[0], (int)AN[1], (int)AN[2], (int)AN[3], (int)AN[4], (int)AN[5]); + delay(100); + + if(Serial.available() > 0){ + return (0); + } + } +} + +static int8_t +test_wp(uint8_t argc, const Menu::arg *argv) +{ + delay(1000); + ground_alt = 0; + read_EEPROM_waypoint_info(); + + uint8_t options = eeprom_read_byte((const uint8_t *) EE_CONFIG); + int32_t hold = eeprom_read_dword((const uint32_t *) EE_ALT_HOLD_HOME); + + // save the alitude above home option + if(options & HOLD_ALT_ABOVE_HOME){ + Serial.printf_P(PSTR("Hold altitude of %dm\n"), hold/100); + }else{ + Serial.printf_P(PSTR("Hold current altitude\n")); + } + + Serial.printf_P(PSTR("%d waypoints\n"), wp_total); + Serial.printf_P(PSTR("Hit radius: %d\n"), wp_radius); + Serial.printf_P(PSTR("Loiter radius: %d\n\n"), loiter_radius); + + for(byte i = 0; i <= wp_total; i++){ + struct Location temp = get_wp_with_index(i); + print_waypoint(&temp, i); + } + + return (0); +} + + +static int8_t +test_airspeed(uint8_t argc, const Menu::arg *argv) +{ +#if AIRSPEED_SENSOR == DISABLED + Serial.printf_P(PSTR("airspeed disabled\n")); + return (0); +#else + print_hit_enter(); + zero_airspeed(); + + while(1){ + delay(20); + read_airspeed(); + Serial.printf_P(PSTR("%dm/s\n"),airspeed/100); + + if(Serial.available() > 0){ + return (0); + } + } +#endif +} + +static int8_t +test_xbee(uint8_t argc, const Menu::arg *argv) +{ + print_hit_enter(); + delay(1000); + Serial.printf_P(PSTR("Begin XBee X-CTU Range and RSSI Test:\n")); + while(1){ + delay(250); + // Timeout set high enough for X-CTU RSSI Calc over XBee @ 115200 + //Serial3.printf_P(PSTR("0123456789:;<=>?@ABCDEFGHIJKLMNO\n")); + //Serial.print("X"); + // Default 32bit data from X-CTU Range Test + if(Serial.available() > 0){ + return (0); + } + } +} + +static int8_t +test_pressure(uint8_t argc, const Menu::arg *argv) +{ + uint32_t sum = 0; + Serial.printf_P(PSTR("Uncalibrated Abs Airpressure\n")); + Serial.printf_P(PSTR("Note - the altitude displayed is relative to the start of this test\n")); + print_hit_enter(); + Serial.printf_P(PSTR("\nCalibrating....\n")); + for (int i=1;i<301;i++) { + read_airpressure(); + if(i>200)sum += abs_press_filt; + delay(10); + } + abs_press_gnd = (double)sum/100.0; + + ground_alt = 0; + while(1){ + delay(100); + read_airpressure(); + //Serial.printf_P(PSTR("Alt: %dm, Raw: %d\n"), press_alt / 100, abs_press_filt); // Someone needs to fix the formatting here for long integers +Serial.print("Altitude: "); +Serial.print(press_alt/100.0,2); +Serial.print(" Raw pressure value: "); +Serial.println(abs_press_filt); + if(Serial.available() > 0){ + return (0); + } + } +} + +static int8_t +test_mag(uint8_t argc, const Menu::arg *argv) +{ +#if MAGNETOMETER == DISABLED + Serial.printf_P(PSTR("Compass disabled\n")); + return (0); +#else + print_hit_enter(); + + while(1){ + delay(250); + APM_Compass.Read(); + APM_Compass.Calculate(0,0); + Serial.printf_P(PSTR("Heading: (")); + Serial.print(ToDeg(APM_Compass.Heading)); + Serial.printf_P(PSTR(") XYZ: (")); + Serial.print(APM_Compass.Mag_X); + Serial.print(comma); + Serial.print(APM_Compass.Mag_Y); + Serial.print(comma); + Serial.print(APM_Compass.Mag_Z); + Serial.println(")"); + if(Serial.available() > 0){ + return (0); + } + } +#endif +} + +static int8_t +test_jeti(uint8_t argc, const Menu::arg *argv) +{ + uint8_t switchPosition, m; + print_hit_enter(); + + JB.begin(); + //JB.print(" X-DIY"); + //JB.print(" Test mode"); + //JB.checkvalue(20000); + Serial.print("Jeti Box test: press any buttons\n\n"); + while(1){ + delay(200); + //Serial.println(JB.checkvalue(0)); + read_radio(); + switchPosition = readSwitch(); + m = flight_modes[switchPosition]; + JB.clear(1); + JB.print("Mode: "); + JB.print(flight_mode_strings[m]); + JB.clear(2); + switch (JB.readbuttons()) + { + case JB_key_right: + JB.print("rechts"); + Serial.print("rechts\n"); + break; + + case JB_key_left: + JB.print("links"); + Serial.print("links\n"); + break; + + case JB_key_up: + JB.print("hoch"); + Serial.print("hoch\n"); + break; + + case JB_key_down: + JB.print("runter"); + Serial.print("runter\n"); + break; + + case JB_key_left | JB_key_right: + JB.print("links-rechts"); + Serial.print("links-rechts\n"); + break; + } + + if(Serial.available() > 0){ + return (0); + } + } +} + +void print_hit_enter() +{ + Serial.printf_P(PSTR("Hit Enter to exit.\n\n")); +} diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_ADC/APM_ADC.cpp b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_ADC/APM_ADC.cpp new file mode 100644 index 0000000000..2543002d76 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_ADC/APM_ADC.cpp @@ -0,0 +1,149 @@ +/* + APM_ADC.cpp - ADC ADS7844 Library for Ardupilot Mega + Code by Jordi Muoz and Jose Julio. DIYDrones.com + + Modified by John Ihlein 6/19/2010 to: + 1)Prevent overflow of adc_counter when more than 8 samples collected between reads. Probably + only an issue on initial read of ADC at program start. + 2)Reorder analog read order as follows: + p, q, r, ax, ay, az + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + External ADC ADS7844 is connected via Serial port 2 (in SPI mode) + TXD2 = MOSI = pin PH1 + RXD2 = MISO = pin PH0 + XCK2 = SCK = pin PH2 + Chip Select pin is PC4 (33) [PH6 (9)] + We are using the 16 clocks per conversion timming to increase efficiency (fast) + The sampling frequency is 400Hz (Timer2 overflow interrupt) + So if our loop is at 50Hz, our needed sampling freq should be 100Hz, so + we have an 4x oversampling and averaging. + + Methods: + Init() : Initialization of interrupts an Timers (Timer2 overflow interrupt) + Ch(ch_num) : Return the ADC channel value + + // HJI - Input definitions. USB connector assumed to be on the left, Rx and servo + // connector pins to the rear. IMU shield components facing up. These are board + // referenced sensor inputs, not device referenced. + On Ardupilot Mega Hardware, oriented as described above: + Channel 0 : yaw rate, r + Channel 1 : roll rate, p + Channel 2 : pitch rate, q + Channel 3 : x/y gyro temperature + Channel 4 : x acceleration, aX + Channel 5 : y acceleration, aY + Channel 6 : z acceleration, aZ + Channel 7 : Differential pressure sensor port + +*/ +extern "C" { + // AVR LibC Includes + #include + #include + #include "WConstants.h" +} + +#include "APM_ADC.h" + + +// Commands for reading ADC channels on ADS7844 +const unsigned char adc_cmd[9]= { 0x87, 0xC7, 0x97, 0xD7, 0xA7, 0xE7, 0xB7, 0xF7, 0x00 }; +volatile long adc_value[8] = { 0, 0, 0, 0, 0, 0, 0, 0 }; +volatile unsigned char adc_counter[8] = { 0, 0, 0, 0, 0, 0, 0, 0 }; + +unsigned char ADC_SPI_transfer(unsigned char data) +{ + /* Wait for empty transmit buffer */ + while ( !( UCSR2A & (1<= 17) // HJI - Added this to prevent + { // overflow of adc_value + adc_value[ch] = 0; + adc_counter[ch] = 0; + } + adc_tmp = ADC_SPI_transfer(0)<<8; // Read first byte + adc_tmp |= ADC_SPI_transfer(adc_cmd[ch+1]); // Read second byte and send next command + adc_value[ch] += adc_tmp>>3; // Shift to 12 bits + adc_counter[ch]++; // Number of samples + } + bit_set(PORTC,4); // Disable Chip Select (PIN PC4) + //bit_clear(PORTL,6); // To test performance + TCNT2 = 104; // 400 Hz +} + + +// Constructors //////////////////////////////////////////////////////////////// +APM_ADC_Class::APM_ADC_Class() +{ +} + +// Public Methods ////////////////////////////////////////////////////////////// +void APM_ADC_Class::Init(void) +{ + unsigned char tmp; + + pinMode(ADC_CHIP_SELECT,OUTPUT); + + digitalWrite(ADC_CHIP_SELECT,HIGH); // Disable device (Chip select is active low) + + // Setup Serial Port2 in SPI mode + UBRR2 = 0; + DDRH |= (1<0) + result = adc_value[ch_num]/adc_counter[ch_num]; + else + result = 0; + adc_value[ch_num] = 0; // Initialize for next reading + adc_counter[ch_num] = 0; + sei(); + return(result); +} + +// make one instance for the user to use +APM_ADC_Class APM_ADC; \ No newline at end of file diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_ADC/APM_ADC.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_ADC/APM_ADC.h new file mode 100644 index 0000000000..cea6102eb2 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_ADC/APM_ADC.h @@ -0,0 +1,24 @@ +#ifndef APM_ADC_h +#define APM_ADC_h + +#define bit_set(p,m) ((p) |= ( 1< // ArduPilot Mega ADC Library + +unsigned long timer; + +void setup() +{ + APM_ADC.Init(); // APM ADC initialization + Serial.begin(57600); + Serial.println("ArduPilot Mega ADC library test"); + delay(1000); + timer = millis(); +} + +void loop() +{ + int ch; + + if((millis()- timer) > 20) + { + timer = millis(); + for (ch=0;ch<7;ch++) + { + Serial.print(APM_ADC.Ch(ch)); + Serial.print(","); + } + Serial.println(); + } +} \ No newline at end of file diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_ADC/keywords.txt b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_ADC/keywords.txt new file mode 100644 index 0000000000..c82cb5d786 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_ADC/keywords.txt @@ -0,0 +1,3 @@ +APM_ADC KEYWORD1 +Init KEYWORD2 +Ch KEYWORD2 diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BMP085/APM_BMP085.cpp b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BMP085/APM_BMP085.cpp new file mode 100644 index 0000000000..72f84b7161 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BMP085/APM_BMP085.cpp @@ -0,0 +1,243 @@ +/* + APM_BMP085.cpp - Arduino Library for BMP085 absolute pressure sensor + Code by Jordi Muoz and Jose Julio. DIYDrones.com + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + Sensor is conected to I2C port + Sensor End of Conversion (EOC) pin is PC7 (30) + + Variables: + RawTemp : Raw temperature data + RawPress : Raw pressure data + + Temp : Calculated temperature (in 0.1C units) + Press : Calculated pressure (in Pa units) + + Methods: + Init() : Initialization of I2C and read sensor calibration data + Read() : Read sensor data and calculate Temperature and Pressure + This function is optimized so the main host dont need to wait + You can call this function in your main loop + It returns a 1 if there are new data. + + Internal functions: + Command_ReadTemp(): Send commando to read temperature + Command_ReadPress(): Send commando to read Pressure + ReadTemp() : Read temp register + ReadPress() : Read press register + Calculate() : Calculate Temperature and Pressure in real units + + +*/ +extern "C" { + // AVR LibC Includes + #include + #include + #include "WConstants.h" +} + +#include +#include "APM_BMP085.h" + +#define BMP085_ADDRESS 0x77 //(0xEE >> 1) +#define BMP085_EOC 30 // End of conversion pin PC7 + +// Constructors //////////////////////////////////////////////////////////////// +APM_BMP085_Class::APM_BMP085_Class() +{ +} + +// Public Methods ////////////////////////////////////////////////////////////// +void APM_BMP085_Class::Init(void) +{ + unsigned char tmp; + byte buff[22]; + int i=0; + + pinMode(BMP085_EOC,INPUT); // End Of Conversion (PC7) input + Wire.begin(); + oss = 3; // Over Sampling setting 3 = High resolution + BMP085_State = 0; // Initial state + + // We read the calibration data registers + Wire.beginTransmission(BMP085_ADDRESS); + Wire.send(0xAA); + Wire.endTransmission(); + + Wire.requestFrom(BMP085_ADDRESS, 22); + //Wire.endTransmission(); + while(Wire.available()) + { + buff[i] = Wire.receive(); // receive one byte + i++; + } + ac1 = ((int)buff[0] << 8) | buff[1]; + ac2 = ((int)buff[2] << 8) | buff[3]; + ac3 = ((int)buff[4] << 8) | buff[5]; + ac4 = ((int)buff[6] << 8) | buff[7]; + ac5 = ((int)buff[8] << 8) | buff[9]; + ac6 = ((int)buff[10] << 8) | buff[11]; + b1 = ((int)buff[12] << 8) | buff[13]; + b2 = ((int)buff[14] << 8) | buff[15]; + mb = ((int)buff[16] << 8) | buff[17]; + mc = ((int)buff[18] << 8) | buff[19]; + md = ((int)buff[20] << 8) | buff[21]; + + //Send a command to read Temp + Command_ReadTemp(); + BMP085_State=1; +} + + +// Read the sensor. This is a state machine +// We read one time Temperature (state=1) and then 4 times Pressure (states 2-5) +uint8_t APM_BMP085_Class::Read() +{ +uint8_t result=0; + + if (BMP085_State==1) + { + if (digitalRead(BMP085_EOC)) + { + ReadTemp(); // On state 1 we read temp + BMP085_State++; + Command_ReadPress(); + } + } + else + { + if (BMP085_State==5) + { + if (digitalRead(BMP085_EOC)) + { + ReadPress(); + Calculate(); + BMP085_State = 1; // Start again from state=1 + Command_ReadTemp(); // Read Temp + result=1; // New pressure reading + } + } + else + { + if (digitalRead(BMP085_EOC)) + { + ReadPress(); + Calculate(); + BMP085_State++; + Command_ReadPress(); + result=1; // New pressure reading + } + } + } + return(result); +} + + +// Send command to Read Pressure +void APM_BMP085_Class::Command_ReadPress() +{ + Wire.beginTransmission(BMP085_ADDRESS); + Wire.send(0xF4); + Wire.send(0x34+(oss<<6)); //write_register(0xF4,0x34+(oversampling_setting<<6)); + Wire.endTransmission(); +} + +// Read Raw Pressure values +void APM_BMP085_Class::ReadPress() +{ + byte msb; + byte lsb; + byte xlsb; + + Wire.beginTransmission(BMP085_ADDRESS); + Wire.send(0xF6); + Wire.endTransmission(); + + Wire.requestFrom(BMP085_ADDRESS, 3); // read a byte + while(!Wire.available()) { + // waiting + } + msb = Wire.receive(); + while(!Wire.available()) { + // waiting + } + lsb = Wire.receive(); + while(!Wire.available()) { + // waiting + } + xlsb = Wire.receive(); + RawPress = (((long)msb<<16) | ((long)lsb<<8) | ((long)xlsb)) >> (8-oss); +} + +// Send Command to Read Temperature +void APM_BMP085_Class::Command_ReadTemp() +{ + Wire.beginTransmission(BMP085_ADDRESS); + Wire.send(0xF4); + Wire.send(0x2E); + Wire.endTransmission(); +} + +// Read Raw Temperature values +void APM_BMP085_Class::ReadTemp() +{ + byte tmp; + + Wire.beginTransmission(BMP085_ADDRESS); + Wire.send(0xF6); + Wire.endTransmission(); + + Wire.beginTransmission(BMP085_ADDRESS); + Wire.requestFrom(BMP085_ADDRESS,2); + while(!Wire.available()); // wait + RawTemp = Wire.receive(); + while(!Wire.available()); // wait + tmp = Wire.receive(); + RawTemp = RawTemp<<8 | tmp; +} + +// Calculate Temperature and Pressure in real units. +void APM_BMP085_Class::Calculate() +{ + long x1, x2, x3, b3, b5, b6, p; + unsigned long b4, b7; + int32_t tmp; + + // See Datasheet page 13 for this formulas + // Based also on Jee Labs BMP085 example code. Thanks for share. + // Temperature calculations + x1 = ((long)RawTemp - ac6) * ac5 >> 15; + x2 = ((long) mc << 11) / (x1 + md); + b5 = x1 + x2; + Temp = (b5 + 8) >> 4; + + // Pressure calculations + b6 = b5 - 4000; + x1 = (b2 * (b6 * b6 >> 12)) >> 11; + x2 = ac2 * b6 >> 11; + x3 = x1 + x2; + //b3 = (((int32_t) ac1 * 4 + x3)<> 2; // BAD + //b3 = ((int32_t) ac1 * 4 + x3 + 2) >> 2; //OK for oss=0 + tmp = ac1; + tmp = (tmp*4 + x3)<> 13; + x2 = (b1 * (b6 * b6 >> 12)) >> 16; + x3 = ((x1 + x2) + 2) >> 2; + b4 = (ac4 * (uint32_t) (x3 + 32768)) >> 15; + b7 = ((uint32_t) RawPress - b3) * (50000 >> oss); + p = b7 < 0x80000000 ? (b7 * 2) / b4 : (b7 / b4) * 2; + + x1 = (p >> 8) * (p >> 8); + x1 = (x1 * 3038) >> 16; + x2 = (-7357 * p) >> 16; + Press = p + ((x1 + x2 + 3791) >> 4); +} + + +// make one instance for the user to use +APM_BMP085_Class APM_BMP085; \ No newline at end of file diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BMP085/APM_BMP085.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BMP085/APM_BMP085.h new file mode 100644 index 0000000000..d5ad04932c --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BMP085/APM_BMP085.h @@ -0,0 +1,34 @@ +#ifndef APM_BMP085_h +#define APM_BMP085_h + + +class APM_BMP085_Class +{ + private: + // State machine + uint8_t BMP085_State; + // Internal calibration registers + int16_t ac1, ac2, ac3, b1, b2, mb, mc, md; + uint16_t ac4, ac5, ac6; + void Command_ReadPress(); + void Command_ReadTemp(); + void ReadPress(); + void ReadTemp(); + void Calculate(); + public: + int32_t RawPress; + int32_t RawTemp; + int16_t Temp; + int32_t Press; + //int Altitude; + uint8_t oss; + //int32_t Press0; // Pressure at sea level + + APM_BMP085_Class(); // Constructor + void Init(); + uint8_t Read(); +}; + +extern APM_BMP085_Class APM_BMP085; + +#endif \ No newline at end of file diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BMP085/examples/APM_BMP085_test/APM_BMP085_test.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BMP085/examples/APM_BMP085_test/APM_BMP085_test.pde new file mode 100644 index 0000000000..1ed59977b8 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BMP085/examples/APM_BMP085_test/APM_BMP085_test.pde @@ -0,0 +1,41 @@ +/* + Example of APM_BMP085 (absolute pressure sensor) library. + Code by Jordi Muoz and Jose Julio. DIYDrones.com +*/ + +#include +#include // ArduPilot Mega BMP085 Library + +unsigned long timer; + +void setup() +{ + APM_BMP085.Init(); // APM ADC initialization + Serial.begin(57600); + Serial.println("ArduPilot Mega BMP085 library test"); + delay(1000); + timer = millis(); +} + +void loop() +{ + int ch; + float tmp_float; + float Altitude; + + if((millis()- timer) > 50) + { + timer=millis(); + APM_BMP085.Read(); + Serial.print("Pressure:"); + Serial.print(APM_BMP085.Press); + Serial.print(" Temperature:"); + Serial.print(APM_BMP085.Temp/10.0); + Serial.print(" Altitude:"); + tmp_float = (APM_BMP085.Press/101325.0); + tmp_float = pow(tmp_float,0.190295); + Altitude = 44330*(1.0-tmp_float); + Serial.print(Altitude); + Serial.println(); + } +} \ No newline at end of file diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BMP085/keywords.txt b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BMP085/keywords.txt new file mode 100644 index 0000000000..0d26768c39 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BMP085/keywords.txt @@ -0,0 +1,5 @@ +APM_BMP085 KEYWORD1 +Init KEYWORD2 +Read KEYWORD2 +Press KEYWORD2 +Temp KEYWORD2 diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/APM_BinComm.cpp b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/APM_BinComm.cpp new file mode 100644 index 0000000000..8d5107a5fc --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/APM_BinComm.cpp @@ -0,0 +1,206 @@ +// -*- Mode: C++; c-basic-offset: 8; indent-tabs-mode: nil -*- +// +// Copyright (c) 2010 Michael Smith. All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// 1. Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// 2. Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE AUTHOR AND CONTRIBUTORS ``AS IS'' AND +// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE +// FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +// DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS +// OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) +// HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY +// OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF +// SUCH DAMAGE. + +/// @file BinComm.cpp +/// @brief Implementation of the ArduPilot Mega binary communications +/// library. + +#include "APM_BinComm.h" +#include "WProgram.h" + +/// @name decoder state machine phases +//@{ +#define DEC_WAIT_P1 0 +#define DEC_WAIT_P2 1 +#define DEC_WAIT_HEADER 2 +#define DEC_WAIT_MESSAGE 3 +#define DEC_WAIT_SUM_A 4 +#define DEC_WAIT_SUM_B 5 +//@} + + +/// inter-byte timeout for decode (ms) +#define DEC_MESSAGE_TIMEOUT 100 + +BinComm::BinComm(const BinComm::MessageHandler *handlerTable, + Stream *interface) : + _handlerTable(handlerTable), + _interface(interface) +{ +}; + +void +BinComm::_sendMessage(void) +{ + uint8_t bytesToSend; + uint8_t sumA, sumB; + const uint8_t *p; + + // send the preamble first + _interface->write((uint8_t)MSG_PREAMBLE_1); + _interface->write((uint8_t)MSG_PREAMBLE_2); + + // set up to send the payload + bytesToSend = _encodeBuf.header.length + sizeof(_encodeBuf.header); + sumA = sumB = 0; + p = (const uint8_t *)&_encodeBuf; + + // send message bytes and compute checksum on the fly + while (bytesToSend--) { + sumA += *p; + sumB += sumA; + _interface->write(*p++); + } + + // send the checksum + _interface->write(sumA); + _interface->write(sumB); +} + +void +BinComm::update(void) +{ + uint8_t count; + + // Ensure that we don't spend too long here by only processing + // the bytes that were available when we started. + // + // XXX we might want to further constrain this count + count = _interface->available(); + while (count--) + _decode(_interface->read()); +} + +void +BinComm::_decode(uint8_t inByte) +{ + uint8_t tableIndex; + + // handle inter-byte timeouts (resync after link loss, etc.) + // + if ((millis() - _lastReceived) > DEC_MESSAGE_TIMEOUT) + _decodePhase = DEC_WAIT_P1; + + // run the decode state machine + // + switch (_decodePhase) { + + // Preamble detection + // + // Note the fallthrough from P2 to P1 deals with the case where + // we see 0x34, 0x34, 0x44 where the first 0x34 is garbage or + // a SUM_B byte we never looked at. + // + case DEC_WAIT_P2: + if (MSG_PREAMBLE_2 == inByte) { + _decodePhase++; + + // prepare for the header + _bytesIn = 0; + _bytesExpected = sizeof(MessageHeader); + + // intialise the checksum accumulators + _sumA = _sumB = 0; + + break; + } + _decodePhase = DEC_WAIT_P1; + // FALLTHROUGH + case DEC_WAIT_P1: + if (MSG_PREAMBLE_1 == inByte) { + _decodePhase++; + } + break; + + // receiving the header + // + case DEC_WAIT_HEADER: + // do checksum accumulation + _sumA += inByte; + _sumB += _sumA; + + // store the byte + _decodeBuf.bytes[_bytesIn++] = inByte; + + // check for complete header received + if (_bytesIn == _bytesExpected) { + _decodePhase++; + + // prepare for the payload + // variable-length data? + _bytesIn = 0; + _bytesExpected = _decodeBuf.header.length; + _messageID = _decodeBuf.header.messageID; + _messageVersion = _decodeBuf.header.messageVersion; + + // sanity check to avoid buffer overflow - revert back to waiting + if (_bytesExpected > sizeof(_decodeBuf)) + _decodePhase = DEC_WAIT_P1; + } + break; + + // receiving payload data + // + case DEC_WAIT_MESSAGE: + // do checksum accumulation + _sumA += inByte; + _sumB += _sumA; + + // store the byte + _decodeBuf.bytes[_bytesIn++] = inByte; + + // check for complete payload received + if (_bytesIn == _bytesExpected) { + _decodePhase++; + } + break; + + // waiting for the checksum bytes + // + case DEC_WAIT_SUM_A: + if (inByte != _sumA) { + badMessagesReceived++; + _decodePhase = DEC_WAIT_P1; + } else { + _decodePhase++; + } + break; + case DEC_WAIT_SUM_B: + if (inByte == _sumB) { + // if we got this far, we have a message + messagesReceived++; + + // call any handler interested in this message + for (tableIndex = 0; MSG_NULL != _handlerTable[tableIndex].messageID; tableIndex++) + if ((_handlerTable[tableIndex].messageID == _messageID) || + (_handlerTable[tableIndex].messageID == MSG_ANY)) + _handlerTable[tableIndex].handler(_handlerTable[tableIndex].arg, _messageID, _messageVersion, &_decodeBuf); + } else { + badMessagesReceived++; + } + _decodePhase = DEC_WAIT_P1; + break; + } +} diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/APM_BinComm.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/APM_BinComm.h new file mode 100644 index 0000000000..22708f2dd7 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/APM_BinComm.h @@ -0,0 +1,267 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- +// +// Copyright (c) 2010 Michael Smith. All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// 1. Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// 2. Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE AUTHOR AND CONTRIBUTORS ``AS IS'' AND +// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE +// FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +// DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS +// OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) +// HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY +// OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF +// SUCH DAMAGE. + +/// @file BinComm.h +/// @brief Definitions for the ArduPilot Mega binary communications +/// library. + +#ifndef APM_BinComm_h +#define APM_BinComm_h + +#include +#include +#include "WProgram.h" + +/// +/// @class BinComm +/// @brief Class providing protocol en/decoding services for the ArduPilot +/// Mega binary telemetry protocol. +/// +class BinComm { +public: + struct MessageHandler; + + ////////////////////////////////////////////////////////////////////// + /// Constructor. + /// + /// @param handlerTable Array of callout functions to which + /// received messages will be sent. More than + /// one handler for a given messageID may be + /// registered; handlers are called in the order + /// they appear in the table. + /// + /// @param interface The stream that will be used + /// for telemetry communications. + /// + BinComm(const MessageHandler *handlerTable, + Stream *interface); + +private: + /// OTA message header + struct MessageHeader { + uint8_t length; + uint8_t messageID; + uint8_t messageVersion; + }; + + /// Incoming header/packet buffer + /// XXX we could make this smaller + union { + uint8_t bytes[0]; + MessageHeader header; + uint8_t payload[256]; + } _decodeBuf; + + /// Outgoing header/packet buffer + /// XXX we could make this smaller + struct { + MessageHeader header; + uint8_t payload[256 - sizeof(MessageHeader)]; + } _encodeBuf; + + + ////////////////////////////////////////////////////////////////////// + /// @name Message pack/unpack utility functions + /// + //@{ + inline void _pack(uint8_t *&ptr, const uint8_t x) { *(uint8_t *)ptr = x; ptr += sizeof(x); } + inline void _pack(uint8_t *&ptr, const uint16_t x) { *(uint16_t *)ptr = x; ptr += sizeof(x); } + inline void _pack(uint8_t *&ptr, const int16_t x) { *(int16_t *)ptr = x; ptr += sizeof(x); } + inline void _pack(uint8_t *&ptr, const uint32_t x) { *(uint32_t *)ptr = x; ptr += sizeof(x); } + inline void _pack(uint8_t *&ptr, const int32_t x) { *(int32_t *)ptr = x; ptr += sizeof(x); } + + inline void _pack(uint8_t *&ptr, const char *msg, uint8_t size) { strlcpy((char *)ptr, msg, size); ptr += size; } + inline void _pack(uint8_t *&ptr, const uint8_t *values, uint8_t count) { memcpy(ptr, values, count); ptr += count; } + inline void _pack(uint8_t *&ptr, const uint16_t *values, uint8_t count) { memcpy(ptr, values, count * 2); ptr += count * 2; } + + inline void _unpack(uint8_t *&ptr, uint8_t &x) { x = *(uint8_t *)ptr; ptr += sizeof(x); } + inline void _unpack(uint8_t *&ptr, uint16_t &x) { x = *(uint16_t *)ptr; ptr += sizeof(x); } + inline void _unpack(uint8_t *&ptr, int16_t &x) { x = *(int16_t *)ptr; ptr += sizeof(x); } + inline void _unpack(uint8_t *&ptr, uint32_t &x) { x = *(uint32_t *)ptr; ptr += sizeof(x); } + inline void _unpack(uint8_t *&ptr, int32_t &x) { x = *(int32_t *)ptr; ptr += sizeof(x); } + + inline void _unpack(uint8_t *&ptr, char *msg, uint8_t size) { strlcpy(msg, (char *)ptr, size); ptr += size; } + inline void _unpack(uint8_t *&ptr, uint8_t *values, uint8_t count) { memcpy(values, ptr, count); ptr += count; } + inline void _unpack(uint8_t *&ptr, uint16_t *values, uint8_t count) { memcpy(values, ptr, count * 2); ptr += count * 2; } + //@} + +public: + ////////////////////////////////////////////////////////////////////// + /// @name Protocol definition + /// + /// The protocol definition, including structures describing messages, + /// MessageID values and helper functions for packing messages are + /// automatically generated. + //@{ +#include "protocol/protocol.h" + //@} + + ////////////////////////////////////////////////////////////////////// + /// @name Protocol magic numbers + /// + /// @note The MessageID enum is automatically generated and thus not described here. + /// + //@{ + + /// Variables defined + /// XXX these should probably be handled by the database/MIB? + enum variableID { + MSG_VAR_ROLL_MODE = 0x00, + MSG_VAR_PITCH_MODE = 0x01, + MSG_VAR_THROTTLE_MODE = 0x02, + MSG_VAR_YAW_MODE = 0x03, + MSG_VAR_ELEVON_TRIM_1 = 0x04, + MSG_VAR_ELEVON_TRIM_2 = 0x05, + + MSG_VAR_INTEGRATOR_0 = 0x10, + MSG_VAR_INTEGRATOR_1 = 0x11, + MSG_VAR_INTEGRATOR_2 = 0x12, + MSG_VAR_INTEGRATOR_3 = 0x13, + MSG_VAR_INTEGRATOR_4 = 0x14, + MSG_VAR_INTEGRATOR_5 = 0x15, + MSG_VAR_INTEGRATOR_6 = 0x16, + MSG_VAR_INTEGRATOR_7 = 0x17, + + MSG_VAR_KFF_0 = 0x1a, + MSG_VAR_KFF_1 = 0x1b, + MSG_VAR_KFF_2 = 0x1c, + + MSG_VAR_TARGET_BEARING = 0x20, + MSG_VAR_NAV_BEARING = 0x21, + MSG_VAR_BEARING_ERROR = 0x22, + MSG_VAR_CROSSTRACK_BEARING = 0x23, + MSG_VAR_CROSSTRACK_ERROR = 0x24, + MSG_VAR_ALTITUDE_ERROR = 0x25, + MSG_VAR_WP_RADIUS = 0x26, + MSG_VAR_LOITER_RADIUS = 0x27, + MSG_VAR_WP_MODE = 0x28, + MSG_VAR_LOOP_COMMANDS = 0x29, + MSG_VAR_NAV_GAIN_SCALER = 0x2a, + }; + + /// PID sets defined + enum PIDSet { + MSG_SERVO_ROLL = 0, + MSG_SERVO_PITCH = 1, + MSG_SERVO_RUDDER = 2, + MSG_SERVO_NAV_ROLL = 3, + MSG_SERVO_NAV_PITCH_ASP = 4, + MSG_SERVO_NAV_PITCH_ALT = 5, + MSG_SERVO_TE_THROTTLE = 6, + MSG_SERVO_ALT_THROTTLE = 7, + MSG_SERVO_ELEVATOR = 8 // Added by Randy + }; + + //@} + + ////////////////////////////////////////////////////////////////////// + /// Message reception callout descriptor + /// + /// An array of these handlers is passed to the constructor to delegate + /// processing for received messages. + /// + struct MessageHandler { + MessageID messageID; ///< messageID for which the handler will be called + void (* handler)(void *arg, + uint8_t messageId, + uint8_t messageVersion, + void *messageData); ///< function to be called + void *arg; ///< argument passed to function + }; + + ////////////////////////////////////////////////////////////////////// + /// @name Decoder interface + //@{ + + /// Consume bytes from the interface and feed them to the decoder. + /// + /// If a packet is completed, then any callbacks associated + /// with the packet's messageID will be called. + /// + /// If no bytes are passed to the decoder for a period determined + /// by DEC_MESSAGE_TIMEOUT, the decode state machine will reset + /// before processing the next byte. This can help re-synchronise + /// after a link loss or in-flight failure. + /// + + void update(void); + + uint32_t messagesReceived; ///< statistics + uint32_t badMessagesReceived; ///< statistics + + //@} + + ////////////////////////////////////////////////////////////////////// + /// @name Encoder interface + /// + /// Messages are normally encoded and sent using the + /// send_msg_* functions defined in protocol/protocol.h. + /// For each message type MSG_* there is a corresponding send_msg_* + /// function which will construct and transmit the message. + /// + //@{ + uint32_t messagesSent; ///< statistics + //@} + + +private: + const MessageHandler *_handlerTable; ///< callout table + Stream *_interface; ///< Serial port we send/receive using. + + /// Various magic numbers + enum MagicNumbers { + MSG_PREAMBLE_1 = 0x34, + MSG_PREAMBLE_2 = 0x44, + MSG_VERSION_1 = 1, + MSG_VARIABLE_LENGTH = 0xff + }; + + ////////////////////////////////////////////////////////////////////// + /// @name Decoder state + //@{ + uint8_t _decodePhase; ///< decoder state machine phase + uint8_t _bytesIn; ///< bytes received in the current phase + uint8_t _bytesExpected; ///< bytes expected in the current phase + uint8_t _sumA; ///< sum of incoming bytes + uint8_t _sumB; ///< sum of _sumA values + + uint8_t _messageID; ///< messageID from the packet being received + uint8_t _messageVersion;///< messageVersion from the packet being received + + unsigned long _lastReceived; ///< timestamp of last byte reception + //@} + + /// Decoder state machine. + /// + /// @param inByte The byte to process. + /// + void _decode(uint8_t inByte); + + /// Send the packet in the encode buffer. + /// + void _sendMessage(void); +}; + +#endif // BinComm_h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/keywords.txt b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/keywords.txt new file mode 100644 index 0000000000..3d75c5372d --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/keywords.txt @@ -0,0 +1,6 @@ +APM_BinComm KEYWORD1 +update KEYWORD2 +messagesReceived KEYWORD2 +badMessagesReceived KEYWORD2 +messagesSent KEYWORD2 + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/protocol/protocol.def b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/protocol/protocol.def new file mode 100644 index 0000000000..d1e465cc6f --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/protocol/protocol.def @@ -0,0 +1,224 @@ +# +# Message definitions for the ArduPilot Mega binary communications protocol. +# +# Process this file using: +# +# awk -f protogen.awk protocol.def > protocol.h +# +# Messages are declared with +# +# message +# +# is a valid member of BinComm::MessageID. +# is the message ID byte +# +# Following a message declaration the fields of the message are +# defined in the format: +# +# [] +# +# is a C type corresponding to the field. The type must be a single +# word, either an integer from or "char". +# is the name of the field; it should be unique within the message +# is an optional array count for fields that are arrays +# + +# +# Acknowledge message +# +message 0x00 MSG_ACKNOWLEDGE + uint8_t msgID + uint16_t msgSum + +# +# System heartbeat +# +message 0x01 MSG_HEARTBEAT + uint8_t flightMode + uint16_t timeStamp + uint16_t batteryVoltage + uint16_t commandIndex + +# +# Attitude report +# +message 0x02 MSG_ATTITUDE + int16_t roll + int16_t pitch + int16_t yaw + +# +# Location report +# +message 0x03 MSG_LOCATION + int32_t latitude + int32_t longitude + int16_t altitude + int16_t groundSpeed + int16_t groundCourse + uint16_t timeOfWeek + +# +# Optional pressure-based location report +# +message 0x04 MSG_PRESSURE + uint16_t pressureAltitude + uint16_t airSpeed + +# +# Text status message +# +message 0x05 MSG_STATUS_TEXT + uint8_t severity + char text 50 + +# +# Algorithm performance report +# +message 0x06 MSG_PERF_REPORT + uint32_t interval + uint16_t mainLoopCycles + uint8_t mainLoopTime + uint8_t gyroSaturationCount + uint8_t adcConstraintCount + uint16_t imuHealth + uint16_t gcsMessageCount + +# +# System version messages +# +message 0x07 MSG_VERSION_REQUEST + uint8_t systemType + uint8_t systemID + +message 0x08 MSG_VERSION + uint8_t systemType + uint8_t systemID + uint8_t firmwareVersion 3 + +# +# Flight command operations +# +message 0x20 MSG_COMMAND_REQUEST + uint16_t UNSPECIFIED + +message 0x21 MSG_COMMAND_UPLOAD + uint8_t action + uint16_t itemNumber + int listLength + uint8_t commandID + uint8_t p1 + uint16_t p2 + uint32_t p3 + uint32_t p4 + +message 0x22 MSG_COMMAND_LIST + int itemNumber + int listLength + uint8_t commandID + uint8_t p1 + uint16_t p2 + uint32_t p3 + uint32_t p4 + +message 0x23 MSG_COMMAND_MODE_CHANGE + uint16_t UNSPECIFIED + +# +# Parameter operations +# +message 0x30 MSG_VALUE_REQUEST + uint8_t valueID + uint8_t broadcast + + +message 0x31 MSG_VALUE_SET + uint8_t valueID + uint32_t value + +message 0x32 MSG_VALUE + uint8_t valueID + uint32_t value + +# +# PID adjustments +# +message 0x40 MSG_PID_REQUEST + uint8_t pidSet + +message 0x41 MSG_PID_SET + uint8_t pidSet + int32_t p + int32_t i + int32_t d + int16_t integratorMax + +message 0x42 MSG_PID + uint8_t pidSet + int32_t p + int32_t i + int32_t d + int16_t integratorMax + + +# +# Radio settings and values +# +message 0x50 MSG_TRIM_STARTUP + uint16_t value 8 + +message 0x51 MSG_TRIM_MIN + uint16_t value 8 + +message 0x52 MSG_TRIM_MAX + uint16_t value 8 + +message 0x53 MSG_SERVOS + int16_t ch1 + int16_t ch2 + int16_t ch3 + int16_t ch4 + int16_t ch5 + int16_t ch6 + int16_t ch7 + int16_t ch8 + +# +# Direct sensor access +# +message 0x60 MSG_SENSOR + uint16_t UNSPECIFIED + +# +# Simulation-related messages +# +message 0x70 MSG_SIM + uint16_t UNSPECIFIED + +# +# Direct I/O pin control +# +message 0x80 MSG_PIN_REQUEST + uint16_t UNSPECIFIED + +message 0x81 MSG_PIN_SET + uint16_t UNSPECIFIED + +# +# Dataflash operations +# +message 0x90 MSG_DATAFLASH_REQUEST + uint16_t UNSPECIFIED + +message 0x91 MSG_DATAFLASH_SET + uint16_t UNSPECIFIED + +# +# EEPROM operations +# +message 0xa0 MSG_EEPROM_REQUEST + uint16_t UNSPECIFIED + +message 0xa1 MSG_EEPROM_SET + uint16_t UNSPECIFIED + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/protocol/protocol.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/protocol/protocol.h new file mode 100644 index 0000000000..2da8e0f7c3 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/protocol/protocol.h @@ -0,0 +1,1301 @@ +// +// THIS FILE WAS AUTOMATICALLY GENERATED - DO NOT EDIT +// +/// @file protocol.h +#pragma pack(1) + +////////////////////////////////////////////////////////////////////// +/// @name MSG_ACKNOWLEDGE +//@{ + +/// Structure describing the payload section of the MSG_ACKNOWLEDGE message +struct msg_acknowledge { + uint8_t msgID; + uint16_t msgSum; +}; + +/// Send a MSG_ACKNOWLEDGE message +inline void +send_msg_acknowledge( + const uint8_t msgID, + const uint16_t msgSum) +{ + uint8_t *__p = &_encodeBuf.payload[0]; + _pack(__p, msgID); + _pack(__p, msgSum); + _encodeBuf.header.length = 3; + _encodeBuf.header.messageID = MSG_ACKNOWLEDGE; + _encodeBuf.header.messageVersion = MSG_VERSION_1; + _sendMessage(); +}; + +/// Unpack a MSG_ACKNOWLEDGE message +inline void +unpack_msg_acknowledge( + uint8_t &msgID, + uint16_t &msgSum) +{ + uint8_t *__p = &_decodeBuf.payload[0]; + _unpack(__p, msgID); + _unpack(__p, msgSum); +}; +//@} + +////////////////////////////////////////////////////////////////////// +/// @name MSG_HEARTBEAT +//@{ + +/// Structure describing the payload section of the MSG_HEARTBEAT message +struct msg_heartbeat { + uint8_t flightMode; + uint16_t timeStamp; + uint16_t batteryVoltage; + uint16_t commandIndex; +}; + +/// Send a MSG_HEARTBEAT message +inline void +send_msg_heartbeat( + const uint8_t flightMode, + const uint16_t timeStamp, + const uint16_t batteryVoltage, + const uint16_t commandIndex) +{ + uint8_t *__p = &_encodeBuf.payload[0]; + _pack(__p, flightMode); + _pack(__p, timeStamp); + _pack(__p, batteryVoltage); + _pack(__p, commandIndex); + _encodeBuf.header.length = 7; + _encodeBuf.header.messageID = MSG_HEARTBEAT; + _encodeBuf.header.messageVersion = MSG_VERSION_1; + _sendMessage(); +}; + +/// Unpack a MSG_HEARTBEAT message +inline void +unpack_msg_heartbeat( + uint8_t &flightMode, + uint16_t &timeStamp, + uint16_t &batteryVoltage, + uint16_t &commandIndex) +{ + uint8_t *__p = &_decodeBuf.payload[0]; + _unpack(__p, flightMode); + _unpack(__p, timeStamp); + _unpack(__p, batteryVoltage); + _unpack(__p, commandIndex); +}; +//@} + +////////////////////////////////////////////////////////////////////// +/// @name MSG_ATTITUDE +//@{ + +/// Structure describing the payload section of the MSG_ATTITUDE message +struct msg_attitude { + int16_t roll; + int16_t pitch; + int16_t yaw; +}; + +/// Send a MSG_ATTITUDE message +inline void +send_msg_attitude( + const int16_t roll, + const int16_t pitch, + const int16_t yaw) +{ + uint8_t *__p = &_encodeBuf.payload[0]; + _pack(__p, roll); + _pack(__p, pitch); + _pack(__p, yaw); + _encodeBuf.header.length = 6; + _encodeBuf.header.messageID = MSG_ATTITUDE; + _encodeBuf.header.messageVersion = MSG_VERSION_1; + _sendMessage(); +}; + +/// Unpack a MSG_ATTITUDE message +inline void +unpack_msg_attitude( + int16_t &roll, + int16_t &pitch, + int16_t &yaw) +{ + uint8_t *__p = &_decodeBuf.payload[0]; + _unpack(__p, roll); + _unpack(__p, pitch); + _unpack(__p, yaw); +}; +//@} + +////////////////////////////////////////////////////////////////////// +/// @name MSG_LOCATION +//@{ + +/// Structure describing the payload section of the MSG_LOCATION message +struct msg_location { + int32_t latitude; + int32_t longitude; + int16_t altitude; + int16_t groundSpeed; + int16_t groundCourse; + uint16_t timeOfWeek; +}; + +/// Send a MSG_LOCATION message +inline void +send_msg_location( + const int32_t latitude, + const int32_t longitude, + const int16_t altitude, + const int16_t groundSpeed, + const int16_t groundCourse, + const uint16_t timeOfWeek) +{ + uint8_t *__p = &_encodeBuf.payload[0]; + _pack(__p, latitude); + _pack(__p, longitude); + _pack(__p, altitude); + _pack(__p, groundSpeed); + _pack(__p, groundCourse); + _pack(__p, timeOfWeek); + _encodeBuf.header.length = 16; + _encodeBuf.header.messageID = MSG_LOCATION; + _encodeBuf.header.messageVersion = MSG_VERSION_1; + _sendMessage(); +}; + +/// Unpack a MSG_LOCATION message +inline void +unpack_msg_location( + int32_t &latitude, + int32_t &longitude, + int16_t &altitude, + int16_t &groundSpeed, + int16_t &groundCourse, + uint16_t &timeOfWeek) +{ + uint8_t *__p = &_decodeBuf.payload[0]; + _unpack(__p, latitude); + _unpack(__p, longitude); + _unpack(__p, altitude); + _unpack(__p, groundSpeed); + _unpack(__p, groundCourse); + _unpack(__p, timeOfWeek); +}; +//@} + +////////////////////////////////////////////////////////////////////// +/// @name MSG_PRESSURE +//@{ + +/// Structure describing the payload section of the MSG_PRESSURE message +struct msg_pressure { + uint16_t pressureAltitude; + uint16_t airSpeed; +}; + +/// Send a MSG_PRESSURE message +inline void +send_msg_pressure( + const uint16_t pressureAltitude, + const uint16_t airSpeed) +{ + uint8_t *__p = &_encodeBuf.payload[0]; + _pack(__p, pressureAltitude); + _pack(__p, airSpeed); + _encodeBuf.header.length = 4; + _encodeBuf.header.messageID = MSG_PRESSURE; + _encodeBuf.header.messageVersion = MSG_VERSION_1; + _sendMessage(); +}; + +/// Unpack a MSG_PRESSURE message +inline void +unpack_msg_pressure( + uint16_t &pressureAltitude, + uint16_t &airSpeed) +{ + uint8_t *__p = &_decodeBuf.payload[0]; + _unpack(__p, pressureAltitude); + _unpack(__p, airSpeed); +}; +//@} + +////////////////////////////////////////////////////////////////////// +/// @name MSG_STATUS_TEXT +//@{ + +/// Structure describing the payload section of the MSG_STATUS_TEXT message +struct msg_status_text { + uint8_t severity; + char text[50]; +}; + +/// Send a MSG_STATUS_TEXT message +inline void +send_msg_status_text( + const uint8_t severity, + const char (&text)[50]) +{ + uint8_t *__p = &_encodeBuf.payload[0]; + _pack(__p, severity); + _pack(__p, text, 50); + _encodeBuf.header.length = 51; + _encodeBuf.header.messageID = MSG_STATUS_TEXT; + _encodeBuf.header.messageVersion = MSG_VERSION_1; + _sendMessage(); +}; + +/// Unpack a MSG_STATUS_TEXT message +inline void +unpack_msg_status_text( + uint8_t &severity, + char (&text)[50]) +{ + uint8_t *__p = &_decodeBuf.payload[0]; + _unpack(__p, severity); + _unpack(__p, text, 50); +}; +//@} + +////////////////////////////////////////////////////////////////////// +/// @name MSG_PERF_REPORT +//@{ + +/// Structure describing the payload section of the MSG_PERF_REPORT message +struct msg_perf_report { + uint32_t interval; + uint16_t mainLoopCycles; + uint8_t mainLoopTime; + uint8_t gyroSaturationCount; + uint8_t adcConstraintCount; + uint16_t imuHealth; + uint16_t gcsMessageCount; +}; + +/// Send a MSG_PERF_REPORT message +inline void +send_msg_perf_report( + const uint32_t interval, + const uint16_t mainLoopCycles, + const uint8_t mainLoopTime, + const uint8_t gyroSaturationCount, + const uint8_t adcConstraintCount, + const uint16_t imuHealth, + const uint16_t gcsMessageCount) +{ + uint8_t *__p = &_encodeBuf.payload[0]; + _pack(__p, interval); + _pack(__p, mainLoopCycles); + _pack(__p, mainLoopTime); + _pack(__p, gyroSaturationCount); + _pack(__p, adcConstraintCount); + _pack(__p, imuHealth); + _pack(__p, gcsMessageCount); + _encodeBuf.header.length = 13; + _encodeBuf.header.messageID = MSG_PERF_REPORT; + _encodeBuf.header.messageVersion = MSG_VERSION_1; + _sendMessage(); +}; + +/// Unpack a MSG_PERF_REPORT message +inline void +unpack_msg_perf_report( + uint32_t &interval, + uint16_t &mainLoopCycles, + uint8_t &mainLoopTime, + uint8_t &gyroSaturationCount, + uint8_t &adcConstraintCount, + uint16_t &imuHealth, + uint16_t &gcsMessageCount) +{ + uint8_t *__p = &_decodeBuf.payload[0]; + _unpack(__p, interval); + _unpack(__p, mainLoopCycles); + _unpack(__p, mainLoopTime); + _unpack(__p, gyroSaturationCount); + _unpack(__p, adcConstraintCount); + _unpack(__p, imuHealth); + _unpack(__p, gcsMessageCount); +}; +//@} + +////////////////////////////////////////////////////////////////////// +/// @name MSG_VERSION_REQUEST +//@{ + +/// Structure describing the payload section of the MSG_VERSION_REQUEST message +struct msg_version_request { + uint8_t systemType; + uint8_t systemID; +}; + +/// Send a MSG_VERSION_REQUEST message +inline void +send_msg_version_request( + const uint8_t systemType, + const uint8_t systemID) +{ + uint8_t *__p = &_encodeBuf.payload[0]; + _pack(__p, systemType); + _pack(__p, systemID); + _encodeBuf.header.length = 2; + _encodeBuf.header.messageID = MSG_VERSION_REQUEST; + _encodeBuf.header.messageVersion = MSG_VERSION_1; + _sendMessage(); +}; + +/// Unpack a MSG_VERSION_REQUEST message +inline void +unpack_msg_version_request( + uint8_t &systemType, + uint8_t &systemID) +{ + uint8_t *__p = &_decodeBuf.payload[0]; + _unpack(__p, systemType); + _unpack(__p, systemID); +}; +//@} + +////////////////////////////////////////////////////////////////////// +/// @name MSG_VERSION +//@{ + +/// Structure describing the payload section of the MSG_VERSION message +struct msg_version { + uint8_t systemType; + uint8_t systemID; + uint8_t firmwareVersion[3]; +}; + +/// Send a MSG_VERSION message +inline void +send_msg_version( + const uint8_t systemType, + const uint8_t systemID, + const uint8_t (&firmwareVersion)[3]) +{ + uint8_t *__p = &_encodeBuf.payload[0]; + _pack(__p, systemType); + _pack(__p, systemID); + _pack(__p, firmwareVersion, 3); + _encodeBuf.header.length = 5; + _encodeBuf.header.messageID = MSG_VERSION; + _encodeBuf.header.messageVersion = MSG_VERSION_1; + _sendMessage(); +}; + +/// Unpack a MSG_VERSION message +inline void +unpack_msg_version( + uint8_t &systemType, + uint8_t &systemID, + uint8_t (&firmwareVersion)[3]) +{ + uint8_t *__p = &_decodeBuf.payload[0]; + _unpack(__p, systemType); + _unpack(__p, systemID); + _unpack(__p, firmwareVersion, 3); +}; +//@} + +////////////////////////////////////////////////////////////////////// +/// @name MSG_COMMAND_REQUEST +//@{ + +/// Structure describing the payload section of the MSG_COMMAND_REQUEST message +struct msg_command_request { + uint16_t UNSPECIFIED; +}; + +/// Send a MSG_COMMAND_REQUEST message +inline void +send_msg_command_request( + const uint16_t UNSPECIFIED) +{ + uint8_t *__p = &_encodeBuf.payload[0]; + _pack(__p, UNSPECIFIED); + _encodeBuf.header.length = 2; + _encodeBuf.header.messageID = MSG_COMMAND_REQUEST; + _encodeBuf.header.messageVersion = MSG_VERSION_1; + _sendMessage(); +}; + +/// Unpack a MSG_COMMAND_REQUEST message +inline void +unpack_msg_command_request( + uint16_t &UNSPECIFIED) +{ + uint8_t *__p = &_decodeBuf.payload[0]; + _unpack(__p, UNSPECIFIED); +}; +//@} + +////////////////////////////////////////////////////////////////////// +/// @name MSG_COMMAND_UPLOAD +//@{ + +/// Structure describing the payload section of the MSG_COMMAND_UPLOAD message +struct msg_command_upload { + uint8_t action; + uint16_t itemNumber; + int listLength; + uint8_t commandID; + uint8_t p1; + uint16_t p2; + uint32_t p3; + uint32_t p4; +}; + +/// Send a MSG_COMMAND_UPLOAD message +inline void +send_msg_command_upload( + const uint8_t action, + const uint16_t itemNumber, + const int listLength, + const uint8_t commandID, + const uint8_t p1, + const uint16_t p2, + const uint32_t p3, + const uint32_t p4) +{ + uint8_t *__p = &_encodeBuf.payload[0]; + _pack(__p, action); + _pack(__p, itemNumber); + _pack(__p, listLength); + _pack(__p, commandID); + _pack(__p, p1); + _pack(__p, p2); + _pack(__p, p3); + _pack(__p, p4); + _encodeBuf.header.length = 16; + _encodeBuf.header.messageID = MSG_COMMAND_UPLOAD; + _encodeBuf.header.messageVersion = MSG_VERSION_1; + _sendMessage(); +}; + +/// Unpack a MSG_COMMAND_UPLOAD message +inline void +unpack_msg_command_upload( + uint8_t &action, + uint16_t &itemNumber, + int &listLength, + uint8_t &commandID, + uint8_t &p1, + uint16_t &p2, + uint32_t &p3, + uint32_t &p4) +{ + uint8_t *__p = &_decodeBuf.payload[0]; + _unpack(__p, action); + _unpack(__p, itemNumber); + _unpack(__p, listLength); + _unpack(__p, commandID); + _unpack(__p, p1); + _unpack(__p, p2); + _unpack(__p, p3); + _unpack(__p, p4); +}; +//@} + +////////////////////////////////////////////////////////////////////// +/// @name MSG_COMMAND_LIST +//@{ + +/// Structure describing the payload section of the MSG_COMMAND_LIST message +struct msg_command_list { + int itemNumber; + int listLength; + uint8_t commandID; + uint8_t p1; + uint16_t p2; + uint32_t p3; + uint32_t p4; +}; + +/// Send a MSG_COMMAND_LIST message +inline void +send_msg_command_list( + const int itemNumber, + const int listLength, + const uint8_t commandID, + const uint8_t p1, + const uint16_t p2, + const uint32_t p3, + const uint32_t p4) +{ + uint8_t *__p = &_encodeBuf.payload[0]; + _pack(__p, itemNumber); + _pack(__p, listLength); + _pack(__p, commandID); + _pack(__p, p1); + _pack(__p, p2); + _pack(__p, p3); + _pack(__p, p4); + _encodeBuf.header.length = 14; + _encodeBuf.header.messageID = MSG_COMMAND_LIST; + _encodeBuf.header.messageVersion = MSG_VERSION_1; + _sendMessage(); +}; + +/// Unpack a MSG_COMMAND_LIST message +inline void +unpack_msg_command_list( + int &itemNumber, + int &listLength, + uint8_t &commandID, + uint8_t &p1, + uint16_t &p2, + uint32_t &p3, + uint32_t &p4) +{ + uint8_t *__p = &_decodeBuf.payload[0]; + _unpack(__p, itemNumber); + _unpack(__p, listLength); + _unpack(__p, commandID); + _unpack(__p, p1); + _unpack(__p, p2); + _unpack(__p, p3); + _unpack(__p, p4); +}; +//@} + +////////////////////////////////////////////////////////////////////// +/// @name MSG_COMMAND_MODE_CHANGE +//@{ + +/// Structure describing the payload section of the MSG_COMMAND_MODE_CHANGE message +struct msg_command_mode_change { + uint16_t UNSPECIFIED; +}; + +/// Send a MSG_COMMAND_MODE_CHANGE message +inline void +send_msg_command_mode_change( + const uint16_t UNSPECIFIED) +{ + uint8_t *__p = &_encodeBuf.payload[0]; + _pack(__p, UNSPECIFIED); + _encodeBuf.header.length = 2; + _encodeBuf.header.messageID = MSG_COMMAND_MODE_CHANGE; + _encodeBuf.header.messageVersion = MSG_VERSION_1; + _sendMessage(); +}; + +/// Unpack a MSG_COMMAND_MODE_CHANGE message +inline void +unpack_msg_command_mode_change( + uint16_t &UNSPECIFIED) +{ + uint8_t *__p = &_decodeBuf.payload[0]; + _unpack(__p, UNSPECIFIED); +}; +//@} + +////////////////////////////////////////////////////////////////////// +/// @name MSG_VALUE_REQUEST +//@{ + +/// Structure describing the payload section of the MSG_VALUE_REQUEST message +struct msg_value_request { + uint8_t valueID; + uint8_t broadcast; +}; + +/// Send a MSG_VALUE_REQUEST message +inline void +send_msg_value_request( + const uint8_t valueID, + const uint8_t broadcast) +{ + uint8_t *__p = &_encodeBuf.payload[0]; + _pack(__p, valueID); + _pack(__p, broadcast); + _encodeBuf.header.length = 2; + _encodeBuf.header.messageID = MSG_VALUE_REQUEST; + _encodeBuf.header.messageVersion = MSG_VERSION_1; + _sendMessage(); +}; + +/// Unpack a MSG_VALUE_REQUEST message +inline void +unpack_msg_value_request( + uint8_t &valueID, + uint8_t &broadcast) +{ + uint8_t *__p = &_decodeBuf.payload[0]; + _unpack(__p, valueID); + _unpack(__p, broadcast); +}; +//@} + +////////////////////////////////////////////////////////////////////// +/// @name MSG_VALUE_SET +//@{ + +/// Structure describing the payload section of the MSG_VALUE_SET message +struct msg_value_set { + uint8_t valueID; + uint32_t value; +}; + +/// Send a MSG_VALUE_SET message +inline void +send_msg_value_set( + const uint8_t valueID, + const uint32_t value) +{ + uint8_t *__p = &_encodeBuf.payload[0]; + _pack(__p, valueID); + _pack(__p, value); + _encodeBuf.header.length = 5; + _encodeBuf.header.messageID = MSG_VALUE_SET; + _encodeBuf.header.messageVersion = MSG_VERSION_1; + _sendMessage(); +}; + +/// Unpack a MSG_VALUE_SET message +inline void +unpack_msg_value_set( + uint8_t &valueID, + uint32_t &value) +{ + uint8_t *__p = &_decodeBuf.payload[0]; + _unpack(__p, valueID); + _unpack(__p, value); +}; +//@} + +////////////////////////////////////////////////////////////////////// +/// @name MSG_VALUE +//@{ + +/// Structure describing the payload section of the MSG_VALUE message +struct msg_value { + uint8_t valueID; + uint32_t value; +}; + +/// Send a MSG_VALUE message +inline void +send_msg_value( + const uint8_t valueID, + const uint32_t value) +{ + uint8_t *__p = &_encodeBuf.payload[0]; + _pack(__p, valueID); + _pack(__p, value); + _encodeBuf.header.length = 5; + _encodeBuf.header.messageID = MSG_VALUE; + _encodeBuf.header.messageVersion = MSG_VERSION_1; + _sendMessage(); +}; + +/// Unpack a MSG_VALUE message +inline void +unpack_msg_value( + uint8_t &valueID, + uint32_t &value) +{ + uint8_t *__p = &_decodeBuf.payload[0]; + _unpack(__p, valueID); + _unpack(__p, value); +}; +//@} + +////////////////////////////////////////////////////////////////////// +/// @name MSG_PID_REQUEST +//@{ + +/// Structure describing the payload section of the MSG_PID_REQUEST message +struct msg_pid_request { + uint8_t pidSet; +}; + +/// Send a MSG_PID_REQUEST message +inline void +send_msg_pid_request( + const uint8_t pidSet) +{ + uint8_t *__p = &_encodeBuf.payload[0]; + _pack(__p, pidSet); + _encodeBuf.header.length = 1; + _encodeBuf.header.messageID = MSG_PID_REQUEST; + _encodeBuf.header.messageVersion = MSG_VERSION_1; + _sendMessage(); +}; + +/// Unpack a MSG_PID_REQUEST message +inline void +unpack_msg_pid_request( + uint8_t &pidSet) +{ + uint8_t *__p = &_decodeBuf.payload[0]; + _unpack(__p, pidSet); +}; +//@} + +////////////////////////////////////////////////////////////////////// +/// @name MSG_PID_SET +//@{ + +/// Structure describing the payload section of the MSG_PID_SET message +struct msg_pid_set { + uint8_t pidSet; + int32_t p; + int32_t i; + int32_t d; + int16_t integratorMax; +}; + +/// Send a MSG_PID_SET message +inline void +send_msg_pid_set( + const uint8_t pidSet, + const int32_t p, + const int32_t i, + const int32_t d, + const int16_t integratorMax) +{ + uint8_t *__p = &_encodeBuf.payload[0]; + _pack(__p, pidSet); + _pack(__p, p); + _pack(__p, i); + _pack(__p, d); + _pack(__p, integratorMax); + _encodeBuf.header.length = 15; + _encodeBuf.header.messageID = MSG_PID_SET; + _encodeBuf.header.messageVersion = MSG_VERSION_1; + _sendMessage(); +}; + +/// Unpack a MSG_PID_SET message +inline void +unpack_msg_pid_set( + uint8_t &pidSet, + int32_t &p, + int32_t &i, + int32_t &d, + int16_t &integratorMax) +{ + uint8_t *__p = &_decodeBuf.payload[0]; + _unpack(__p, pidSet); + _unpack(__p, p); + _unpack(__p, i); + _unpack(__p, d); + _unpack(__p, integratorMax); +}; +//@} + +////////////////////////////////////////////////////////////////////// +/// @name MSG_PID +//@{ + +/// Structure describing the payload section of the MSG_PID message +struct msg_pid { + uint8_t pidSet; + int32_t p; + int32_t i; + int32_t d; + int16_t integratorMax; +}; + +/// Send a MSG_PID message +inline void +send_msg_pid( + const uint8_t pidSet, + const int32_t p, + const int32_t i, + const int32_t d, + const int16_t integratorMax) +{ + uint8_t *__p = &_encodeBuf.payload[0]; + _pack(__p, pidSet); + _pack(__p, p); + _pack(__p, i); + _pack(__p, d); + _pack(__p, integratorMax); + _encodeBuf.header.length = 15; + _encodeBuf.header.messageID = MSG_PID; + _encodeBuf.header.messageVersion = MSG_VERSION_1; + _sendMessage(); +}; + +/// Unpack a MSG_PID message +inline void +unpack_msg_pid( + uint8_t &pidSet, + int32_t &p, + int32_t &i, + int32_t &d, + int16_t &integratorMax) +{ + uint8_t *__p = &_decodeBuf.payload[0]; + _unpack(__p, pidSet); + _unpack(__p, p); + _unpack(__p, i); + _unpack(__p, d); + _unpack(__p, integratorMax); +}; +//@} + +////////////////////////////////////////////////////////////////////// +/// @name MSG_TRIM_STARTUP +//@{ + +/// Structure describing the payload section of the MSG_TRIM_STARTUP message +struct msg_trim_startup { + uint16_t value[8]; +}; + +/// Send a MSG_TRIM_STARTUP message +inline void +send_msg_trim_startup( + const uint16_t (&value)[8]) +{ + uint8_t *__p = &_encodeBuf.payload[0]; + _pack(__p, value, 8); + _encodeBuf.header.length = 16; + _encodeBuf.header.messageID = MSG_TRIM_STARTUP; + _encodeBuf.header.messageVersion = MSG_VERSION_1; + _sendMessage(); +}; + +/// Unpack a MSG_TRIM_STARTUP message +inline void +unpack_msg_trim_startup( + uint16_t (&value)[8]) +{ + uint8_t *__p = &_decodeBuf.payload[0]; + _unpack(__p, value, 8); +}; +//@} + +////////////////////////////////////////////////////////////////////// +/// @name MSG_TRIM_MIN +//@{ + +/// Structure describing the payload section of the MSG_TRIM_MIN message +struct msg_trim_min { + uint16_t value[8]; +}; + +/// Send a MSG_TRIM_MIN message +inline void +send_msg_trim_min( + const uint16_t (&value)[8]) +{ + uint8_t *__p = &_encodeBuf.payload[0]; + _pack(__p, value, 8); + _encodeBuf.header.length = 16; + _encodeBuf.header.messageID = MSG_TRIM_MIN; + _encodeBuf.header.messageVersion = MSG_VERSION_1; + _sendMessage(); +}; + +/// Unpack a MSG_TRIM_MIN message +inline void +unpack_msg_trim_min( + uint16_t (&value)[8]) +{ + uint8_t *__p = &_decodeBuf.payload[0]; + _unpack(__p, value, 8); +}; +//@} + +////////////////////////////////////////////////////////////////////// +/// @name MSG_TRIM_MAX +//@{ + +/// Structure describing the payload section of the MSG_TRIM_MAX message +struct msg_trim_max { + uint16_t value[8]; +}; + +/// Send a MSG_TRIM_MAX message +inline void +send_msg_trim_max( + const uint16_t (&value)[8]) +{ + uint8_t *__p = &_encodeBuf.payload[0]; + _pack(__p, value, 8); + _encodeBuf.header.length = 16; + _encodeBuf.header.messageID = MSG_TRIM_MAX; + _encodeBuf.header.messageVersion = MSG_VERSION_1; + _sendMessage(); +}; + +/// Unpack a MSG_TRIM_MAX message +inline void +unpack_msg_trim_max( + uint16_t (&value)[8]) +{ + uint8_t *__p = &_decodeBuf.payload[0]; + _unpack(__p, value, 8); +}; +//@} + +////////////////////////////////////////////////////////////////////// +/// @name MSG_SERVOS +//@{ + +/// Structure describing the payload section of the MSG_SERVOS message +struct msg_servos { + int16_t ch1; + int16_t ch2; + int16_t ch3; + int16_t ch4; + int16_t ch5; + int16_t ch6; + int16_t ch7; + int16_t ch8; +}; + +/// Send a MSG_SERVOS message +inline void +send_msg_servos( + const int16_t ch1, + const int16_t ch2, + const int16_t ch3, + const int16_t ch4, + const int16_t ch5, + const int16_t ch6, + const int16_t ch7, + const int16_t ch8) +{ + uint8_t *__p = &_encodeBuf.payload[0]; + _pack(__p, ch1); + _pack(__p, ch2); + _pack(__p, ch3); + _pack(__p, ch4); + _pack(__p, ch5); + _pack(__p, ch6); + _pack(__p, ch7); + _pack(__p, ch8); + _encodeBuf.header.length = 16; + _encodeBuf.header.messageID = MSG_SERVOS; + _encodeBuf.header.messageVersion = MSG_VERSION_1; + _sendMessage(); +}; + +/// Unpack a MSG_SERVOS message +inline void +unpack_msg_servos( + int16_t &ch1, + int16_t &ch2, + int16_t &ch3, + int16_t &ch4, + int16_t &ch5, + int16_t &ch6, + int16_t &ch7, + int16_t &ch8) +{ + uint8_t *__p = &_decodeBuf.payload[0]; + _unpack(__p, ch1); + _unpack(__p, ch2); + _unpack(__p, ch3); + _unpack(__p, ch4); + _unpack(__p, ch5); + _unpack(__p, ch6); + _unpack(__p, ch7); + _unpack(__p, ch8); +}; +//@} + +////////////////////////////////////////////////////////////////////// +/// @name MSG_SENSOR +//@{ + +/// Structure describing the payload section of the MSG_SENSOR message +struct msg_sensor { + uint16_t UNSPECIFIED; +}; + +/// Send a MSG_SENSOR message +inline void +send_msg_sensor( + const uint16_t UNSPECIFIED) +{ + uint8_t *__p = &_encodeBuf.payload[0]; + _pack(__p, UNSPECIFIED); + _encodeBuf.header.length = 2; + _encodeBuf.header.messageID = MSG_SENSOR; + _encodeBuf.header.messageVersion = MSG_VERSION_1; + _sendMessage(); +}; + +/// Unpack a MSG_SENSOR message +inline void +unpack_msg_sensor( + uint16_t &UNSPECIFIED) +{ + uint8_t *__p = &_decodeBuf.payload[0]; + _unpack(__p, UNSPECIFIED); +}; +//@} + +////////////////////////////////////////////////////////////////////// +/// @name MSG_SIM +//@{ + +/// Structure describing the payload section of the MSG_SIM message +struct msg_sim { + uint16_t UNSPECIFIED; +}; + +/// Send a MSG_SIM message +inline void +send_msg_sim( + const uint16_t UNSPECIFIED) +{ + uint8_t *__p = &_encodeBuf.payload[0]; + _pack(__p, UNSPECIFIED); + _encodeBuf.header.length = 2; + _encodeBuf.header.messageID = MSG_SIM; + _encodeBuf.header.messageVersion = MSG_VERSION_1; + _sendMessage(); +}; + +/// Unpack a MSG_SIM message +inline void +unpack_msg_sim( + uint16_t &UNSPECIFIED) +{ + uint8_t *__p = &_decodeBuf.payload[0]; + _unpack(__p, UNSPECIFIED); +}; +//@} + +////////////////////////////////////////////////////////////////////// +/// @name MSG_PIN_REQUEST +//@{ + +/// Structure describing the payload section of the MSG_PIN_REQUEST message +struct msg_pin_request { + uint16_t UNSPECIFIED; +}; + +/// Send a MSG_PIN_REQUEST message +inline void +send_msg_pin_request( + const uint16_t UNSPECIFIED) +{ + uint8_t *__p = &_encodeBuf.payload[0]; + _pack(__p, UNSPECIFIED); + _encodeBuf.header.length = 2; + _encodeBuf.header.messageID = MSG_PIN_REQUEST; + _encodeBuf.header.messageVersion = MSG_VERSION_1; + _sendMessage(); +}; + +/// Unpack a MSG_PIN_REQUEST message +inline void +unpack_msg_pin_request( + uint16_t &UNSPECIFIED) +{ + uint8_t *__p = &_decodeBuf.payload[0]; + _unpack(__p, UNSPECIFIED); +}; +//@} + +////////////////////////////////////////////////////////////////////// +/// @name MSG_PIN_SET +//@{ + +/// Structure describing the payload section of the MSG_PIN_SET message +struct msg_pin_set { + uint16_t UNSPECIFIED; +}; + +/// Send a MSG_PIN_SET message +inline void +send_msg_pin_set( + const uint16_t UNSPECIFIED) +{ + uint8_t *__p = &_encodeBuf.payload[0]; + _pack(__p, UNSPECIFIED); + _encodeBuf.header.length = 2; + _encodeBuf.header.messageID = MSG_PIN_SET; + _encodeBuf.header.messageVersion = MSG_VERSION_1; + _sendMessage(); +}; + +/// Unpack a MSG_PIN_SET message +inline void +unpack_msg_pin_set( + uint16_t &UNSPECIFIED) +{ + uint8_t *__p = &_decodeBuf.payload[0]; + _unpack(__p, UNSPECIFIED); +}; +//@} + +////////////////////////////////////////////////////////////////////// +/// @name MSG_DATAFLASH_REQUEST +//@{ + +/// Structure describing the payload section of the MSG_DATAFLASH_REQUEST message +struct msg_dataflash_request { + uint16_t UNSPECIFIED; +}; + +/// Send a MSG_DATAFLASH_REQUEST message +inline void +send_msg_dataflash_request( + const uint16_t UNSPECIFIED) +{ + uint8_t *__p = &_encodeBuf.payload[0]; + _pack(__p, UNSPECIFIED); + _encodeBuf.header.length = 2; + _encodeBuf.header.messageID = MSG_DATAFLASH_REQUEST; + _encodeBuf.header.messageVersion = MSG_VERSION_1; + _sendMessage(); +}; + +/// Unpack a MSG_DATAFLASH_REQUEST message +inline void +unpack_msg_dataflash_request( + uint16_t &UNSPECIFIED) +{ + uint8_t *__p = &_decodeBuf.payload[0]; + _unpack(__p, UNSPECIFIED); +}; +//@} + +////////////////////////////////////////////////////////////////////// +/// @name MSG_DATAFLASH_SET +//@{ + +/// Structure describing the payload section of the MSG_DATAFLASH_SET message +struct msg_dataflash_set { + uint16_t UNSPECIFIED; +}; + +/// Send a MSG_DATAFLASH_SET message +inline void +send_msg_dataflash_set( + const uint16_t UNSPECIFIED) +{ + uint8_t *__p = &_encodeBuf.payload[0]; + _pack(__p, UNSPECIFIED); + _encodeBuf.header.length = 2; + _encodeBuf.header.messageID = MSG_DATAFLASH_SET; + _encodeBuf.header.messageVersion = MSG_VERSION_1; + _sendMessage(); +}; + +/// Unpack a MSG_DATAFLASH_SET message +inline void +unpack_msg_dataflash_set( + uint16_t &UNSPECIFIED) +{ + uint8_t *__p = &_decodeBuf.payload[0]; + _unpack(__p, UNSPECIFIED); +}; +//@} + +////////////////////////////////////////////////////////////////////// +/// @name MSG_EEPROM_REQUEST +//@{ + +/// Structure describing the payload section of the MSG_EEPROM_REQUEST message +struct msg_eeprom_request { + uint16_t UNSPECIFIED; +}; + +/// Send a MSG_EEPROM_REQUEST message +inline void +send_msg_eeprom_request( + const uint16_t UNSPECIFIED) +{ + uint8_t *__p = &_encodeBuf.payload[0]; + _pack(__p, UNSPECIFIED); + _encodeBuf.header.length = 2; + _encodeBuf.header.messageID = MSG_EEPROM_REQUEST; + _encodeBuf.header.messageVersion = MSG_VERSION_1; + _sendMessage(); +}; + +/// Unpack a MSG_EEPROM_REQUEST message +inline void +unpack_msg_eeprom_request( + uint16_t &UNSPECIFIED) +{ + uint8_t *__p = &_decodeBuf.payload[0]; + _unpack(__p, UNSPECIFIED); +}; +//@} + +////////////////////////////////////////////////////////////////////// +/// @name MSG_EEPROM_SET +//@{ + +/// Structure describing the payload section of the MSG_EEPROM_SET message +struct msg_eeprom_set { + uint16_t UNSPECIFIED; +}; + +/// Send a MSG_EEPROM_SET message +inline void +send_msg_eeprom_set( + const uint16_t UNSPECIFIED) +{ + uint8_t *__p = &_encodeBuf.payload[0]; + _pack(__p, UNSPECIFIED); + _encodeBuf.header.length = 2; + _encodeBuf.header.messageID = MSG_EEPROM_SET; + _encodeBuf.header.messageVersion = MSG_VERSION_1; + _sendMessage(); +}; + +/// Unpack a MSG_EEPROM_SET message +inline void +unpack_msg_eeprom_set( + uint16_t &UNSPECIFIED) +{ + uint8_t *__p = &_decodeBuf.payload[0]; + _unpack(__p, UNSPECIFIED); +}; +//@} + +////////////////////////////////////////////////////////////////////// +/// Message ID values +enum MessageID { + MSG_PID = 0x42, + MSG_DATAFLASH_REQUEST = 0x90, + MSG_DATAFLASH_SET = 0x91, + MSG_SENSOR = 0x60, + MSG_VALUE_REQUEST = 0x30, + MSG_VALUE_SET = 0x31, + MSG_VALUE = 0x32, + MSG_PIN_REQUEST = 0x80, + MSG_PIN_SET = 0x81, + MSG_ACKNOWLEDGE = 0x0, + MSG_HEARTBEAT = 0x1, + MSG_ATTITUDE = 0x2, + MSG_LOCATION = 0x3, + MSG_PRESSURE = 0x4, + MSG_TRIM_STARTUP = 0x50, + MSG_STATUS_TEXT = 0x5, + MSG_TRIM_MIN = 0x51, + MSG_PERF_REPORT = 0x6, + MSG_TRIM_MAX = 0x52, + MSG_VERSION_REQUEST = 0x7, + MSG_SERVOS = 0x53, + MSG_VERSION = 0x8, + MSG_COMMAND_REQUEST = 0x20, + MSG_COMMAND_UPLOAD = 0x21, + MSG_COMMAND_LIST = 0x22, + MSG_COMMAND_MODE_CHANGE = 0x23, + MSG_SIM = 0x70, + MSG_EEPROM_REQUEST = 0xa0, + MSG_EEPROM_SET = 0xa1, + MSG_PID_REQUEST = 0x40, + MSG_PID_SET = 0x41, + MSG_ANY = 0xfe, + MSG_NULL = 0xff +}; +#pragma pack(pop) diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/protocol/protogen.awk b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/protocol/protogen.awk new file mode 100644 index 0000000000..3b5e0b65e4 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/protocol/protogen.awk @@ -0,0 +1,174 @@ +# +# Process the protocol specification and emit functions to pack and unpack buffers. +# +# See protocol.def for a description of the definition format. +# + +BEGIN { + printf("//\n// THIS FILE WAS AUTOMATICALLY GENERATED - DO NOT EDIT\n//\n") + printf("/// @file protocol.h\n") + printf("#pragma pack(1)\n"); + + currentMessage = "" +} + +END { + # finalise the last message definition + EMIT_MESSAGE() + + # + # emit the MessageID enum + # + # XXX it would be elegant to sort the array here, but not + # everyone has GNU awk. + # + printf("\n//////////////////////////////////////////////////////////////////////\n") + printf("/// Message ID values\n") + printf("enum MessageID {\n") + for (opcode in opcodes) { + printf("\t%s = 0x%x,\n", opcodes[opcode], opcode) + } + printf("\tMSG_ANY = 0xfe,\n") + printf("\tMSG_NULL = 0xff\n") + printf("};\n") + + printf("#pragma pack(pop)\n") +} + +# +# Emit definitions for one message +# +function EMIT_MESSAGE(payloadSize) +{ + if (currentMessage != "") { + printf("\n//////////////////////////////////////////////////////////////////////\n") + printf("/// @name %s \n//@{\n\n", currentMessage) + + # + # emit a structure defining the message payload + # + printf("/// Structure describing the payload section of the %s message\n", currentMessage) + printf("struct %s {\n", tolower(currentMessage)) + for (i = 0; i < fieldCount; i++) { + printf("\t%s %s", types[i], names[i]) + if (counts[i]) + printf("[%s]", counts[i]) + printf(";\n") + } + printf("};\n\n") + + # + # emit a routine to pack the message payload from a set of variables and send it + # + printf("/// Send a %s message\n", currentMessage) + printf("inline void\nsend_%s(\n", tolower(currentMessage)) + for (i = 0; i < fieldCount; i++) { + if (counts[i]) { + printf("\tconst %s (&%s)[%d]", types[i], names[i], counts[i]) + } else { + printf("\tconst %s %s", types[i], names[i]) + } + if (i < (fieldCount -1)) + printf(",\n"); + } + printf(")\n{\n") + printf("\tuint8_t *__p = &_encodeBuf.payload[0];\n") + payloadSize = 0; + for (i = 0; i < fieldCount; i++) { + if (counts[i]) { + printf("\t_pack(__p, %s, %s);\n", names[i], counts[i]) + payloadSize += sizes[i] * counts[i] + } else { + printf("\t_pack(__p, %s);\n", names[i]) + payloadSize += sizes[i] + } + } + printf("\t_encodeBuf.header.length = %s;\n", payloadSize) + printf("\t_encodeBuf.header.messageID = %s;\n", currentMessage) + printf("\t_encodeBuf.header.messageVersion = MSG_VERSION_1;\n") + printf("\t_sendMessage();\n") + printf("};\n\n") + + # + # emit a routine to unpack the current message into a set of variables + # + printf("/// Unpack a %s message\n", currentMessage) + printf("inline void\nunpack_%s(\n", tolower(currentMessage)) + for (i = 0; i < fieldCount; i++) { + if (counts[i]) { + printf("\t%s (&%s)[%d]", types[i], names[i], counts[i]) + } else { + printf("\t%s &%s", types[i], names[i]) + } + if (i < (fieldCount -1)) + printf(",\n"); + } + printf(")\n{\n") + printf("\tuint8_t *__p = &_decodeBuf.payload[0];\n") + for (i = 0; i < fieldCount; i++) { + if (counts[i]) { + printf("\t_unpack(__p, %s, %s);\n", names[i], counts[i]) + payloadSize += sizes[i] * counts[i] + } else { + printf("\t_unpack(__p, %s);\n", names[i]) + payloadSize += sizes[i] + } + } + printf("};\n") + + # close the Doxygen group + printf("//@}\n") + } +} + +# skip lines containing comments +$1=="#" { + next +} + +# +# process a new message declaration +# +$1=="message" { + + # emit any previous message + EMIT_MESSAGE() + + # save the current opcode and message name + currentOpcode = $2 + currentMessage = $3 + opcodes[$2] = $3 + + # set up for the coming fields + fieldCount = 0 + delete types + delete names + delete sizes + delete counts + + next +} + +# +# process a field inside a message definition +# +NF >= 2 { + + # save the field definition + types[fieldCount] = $1 + names[fieldCount] = $2 + + # guess the field size, note that we only support and "char" + sizes[fieldCount] = 1 + if ($1 ~ ".*16.*") + sizes[fieldCount] = 2 + if ($1 ~ ".*32.*") + sizes[fieldCount] = 4 + + # if an array size was supplied, save it + if (NF >= 3) { + counts[fieldCount] = $3 + } + + fieldCount++ +} diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/test/Makefile b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/test/Makefile new file mode 100644 index 0000000000..a484d5a004 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/test/Makefile @@ -0,0 +1,14 @@ + +PROG := BinCommTest +SRCS := test.cpp ../APM_BinComm.cpp +OBJS := $(SRCS:.cpp=.o) + +BinCommTest: $(OBJS) + c++ -g -o $@ $(OBJS) + +.cpp.o: + @echo C++ $< -> $@ + c++ -g -c -I. -o $@ $< + +clean: + rm $(PROG) $(OBJS) diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/test/WProgram.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/test/WProgram.h new file mode 100644 index 0000000000..539db09c5d --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/test/WProgram.h @@ -0,0 +1,15 @@ + +#ifndef WPROGRAM_H +#define WPROGRAM_H + +class Stream { +public: + void write(uint8_t val); + int available(void); + int read(void); +}; + + +extern unsigned int millis(void); + +#endif diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/test/test.cpp b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/test/test.cpp new file mode 100644 index 0000000000..e15f1827f0 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/test/test.cpp @@ -0,0 +1,110 @@ +// -*- Mode: C++; c-basic-offset: 8; indent-tabs-mode: nil -*- + +// test harness for the APM_BinComm bits + +#include +#include +#include +#include +#include +#include + +#include "WProgram.h" + +#include "../APM_BinComm.h" + +static void handler(void *arg, uint8_t messageId, uint8_t messageVersion, void *messageData); + +BinComm::MessageHandler handlers[] = { + {BinComm::MSG_ANY, handler, NULL}, + {BinComm::MSG_NULL, 0, 0} +}; + +Stream port; +BinComm comm(handlers, &port); + +int port_fd; + +unsigned int +millis(void) +{ + return 0; +} + +void +Stream::write(uint8_t val) +{ + ::write(port_fd, &val, 1); +} + +int +Stream::available(void) +{ + return(1); +} + +int +Stream::read(void) +{ + int ret; + uint8_t c; + + switch(::read(port_fd, &c, 1)) { + case 1: + return c; + case 0: + errx(1, "device disappeared"); + + default: + // almost certainly EWOULDBLOCK + return -1; + } +} + +void +handler(void *arg, uint8_t messageId, uint8_t messageVersion, void *messageData) +{ + + if (messageId == BinComm::MSG_HEARTBEAT) { + struct BinComm::msg_heartbeat *m = (struct BinComm::msg_heartbeat *)messageData; + printf("Heartbeat: mode %u time %u voltage %u command %u\n", + m->flightMode, m->timeStamp, m->batteryVoltage, m->commandIndex); + } else + if (messageId == BinComm::MSG_ATTITUDE) { + struct BinComm::msg_attitude *m = (struct BinComm::msg_attitude *)messageData; + printf("Attitude: pitch %d roll %d yaw %d\n", + m->pitch, m->roll, m->yaw); + } else + if (messageId == BinComm::MSG_LOCATION) { + struct BinComm::msg_location *m = (struct BinComm::msg_location *)messageData; + printf("Location: lat %d long %d altitude %d groundspeed %d groundcourse %d time %u\n", + m->latitude, m->longitude, m->altitude, m->groundSpeed, m->groundCourse, m->timeOfWeek); + } else + if (messageId == BinComm::MSG_STATUS_TEXT) { + struct BinComm::msg_status_text *m = (struct BinComm::msg_status_text *)messageData; + printf("Message %d: %-50s\n", m->severity, m->text); + } else { + warnx("received message %d,%d", messageId, messageVersion); + } +} + +int +main(int argc, char *argv[]) +{ + struct termios t; + + if (2 > argc) + errx(1, "BinCommTest "); + if (0 >= (port_fd = open(argv[1], O_RDWR | O_NONBLOCK))) + err(1, "could not open port %s", argv[1]); + if (tcgetattr(port_fd, &t)) + err(1, "tcgetattr"); + cfsetspeed(&t, 115200); + if (tcsetattr(port_fd, TCSANOW, &t)) + err(1, "tcsetattr"); + + // spin listening + for (;;) { + comm.update(); + } +} diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_Compass/APM_Compass.cpp b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_Compass/APM_Compass.cpp new file mode 100644 index 0000000000..4b83191ef9 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_Compass/APM_Compass.cpp @@ -0,0 +1,235 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 3; indent-tabs-mode: t -*- +/* + APM_Compass.cpp - Arduino Library for HMC5843 I2C Magnetometer + Code by Jordi Muoz and Jose Julio. DIYDrones.com + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + Sensor is conected to I2C port + Sensor is initialized in Continuos mode (10Hz) + + Variables: + Heading : Magnetic heading + Heading_X : Magnetic heading X component + Heading_Y : Magnetic heading Y component + Mag_X : Raw X axis magnetometer data + Mag_Y : Raw Y axis magnetometer data + Mag_Z : Raw Z axis magnetometer data + lastUpdate : the time of the last successful reading + + Methods: + Init() : Initialization of I2C and sensor + Read() : Read Sensor data + Calculate(float roll, float pitch) : Calculate tilt adjusted heading + SetOrientation(const Matrix3f &rotationMatrix) : Set orientation of compass + SetOffsets(int x, int y, int z) : Set adjustments for HardIron disturbances + SetDeclination(float radians) : Set heading adjustment between true north and magnetic north + + To do : code optimization + Mount position : UPDATED + Big capacitor pointing backward, connector forward + +*/ +extern "C" { + // AVR LibC Includes + #include + #include "WConstants.h" +} + +#include +#include "APM_Compass.h" + +#define CompassAddress 0x1E +#define ConfigRegA 0x00 +#define ConfigRegB 0x01 +#define MagGain 0x20 +#define PositiveBiasConfig 0x11 +#define NegativeBiasConfig 0x12 +#define NormalOperation 0x10 +#define ModeRegister 0x02 +#define ContinuousConversion 0x00 +#define SingleConversion 0x01 + +// Constructors //////////////////////////////////////////////////////////////// +APM_Compass_Class::APM_Compass_Class() : orientation(0), declination(0.0) +{ + // mag x y z offset initialisation + offset[0] = 0; + offset[1] = 0; + offset[2] = 0; + + // initialise orientation matrix + orientationMatrix = ROTATION_NONE; +} + +// Public Methods ////////////////////////////////////////////////////////////// +bool APM_Compass_Class::Init(void) +{ + unsigned long currentTime = millis(); // record current time + int numAttempts = 0; + int success = 0; + + Wire.begin(); + + delay(10); + + // calibration initialisation + calibration[0] = 1.0; + calibration[1] = 1.0; + calibration[2] = 1.0; + + while( success == 0 && numAttempts < 5 ) + { + // record number of attempts at initialisation + numAttempts++; + + // force positiveBias (compass should return 715 for all channels) + Wire.beginTransmission(CompassAddress); + Wire.send(ConfigRegA); + Wire.send(PositiveBiasConfig); + if (0 != Wire.endTransmission()) + continue; // compass not responding on the bus + delay(50); + + // set gains + Wire.beginTransmission(CompassAddress); + Wire.send(ConfigRegB); + Wire.send(MagGain); + Wire.endTransmission(); + delay(10); + + Wire.beginTransmission(CompassAddress); + Wire.send(ModeRegister); + Wire.send(SingleConversion); + Wire.endTransmission(); + delay(10); + + // read values from the compass + Read(); + delay(10); + + // calibrate + if( abs(Mag_X) > 500 && abs(Mag_X) < 1000 && abs(Mag_Y) > 500 && abs(Mag_Y) < 1000 && abs(Mag_Z) > 500 && abs(Mag_Z) < 1000) + { + calibration[0] = abs(715.0 / Mag_X); + calibration[1] = abs(715.0 / Mag_Y); + calibration[2] = abs(715.0 / Mag_Z); + + // mark success + success = 1; + } + + // leave test mode + Wire.beginTransmission(CompassAddress); + Wire.send(ConfigRegA); + Wire.send(NormalOperation); + Wire.endTransmission(); + delay(50); + + Wire.beginTransmission(CompassAddress); + Wire.send(ModeRegister); + Wire.send(ContinuousConversion); // Set continuous mode (default to 10Hz) + Wire.endTransmission(); // End transmission + delay(50); + } + return(success); +} + +// Read Sensor data +void APM_Compass_Class::Read() +{ + int i = 0; + byte buff[6]; + + Wire.beginTransmission(CompassAddress); + Wire.send(0x03); //sends address to read from + Wire.endTransmission(); //end transmission + + //Wire.beginTransmission(CompassAddress); + Wire.requestFrom(CompassAddress, 6); // request 6 bytes from device + while(Wire.available()) + { + buff[i] = Wire.receive(); // receive one byte + i++; + } + Wire.endTransmission(); //end transmission + + if (i==6) // All bytes received? + { + // MSB byte first, then LSB, X,Y,Z + Mag_X = -((((int)buff[0]) << 8) | buff[1]) * calibration[0]; // X axis + Mag_Y = ((((int)buff[2]) << 8) | buff[3]) * calibration[1]; // Y axis + Mag_Z = -((((int)buff[4]) << 8) | buff[5]) * calibration[2]; // Z axis + lastUpdate = millis(); // record time of update + } +} + +void APM_Compass_Class::Calculate(float roll, float pitch) +{ + float Head_X; + float Head_Y; + float cos_roll; + float sin_roll; + float cos_pitch; + float sin_pitch; + Vector3f rotMagVec; + + cos_roll = cos(roll); // Optimizacion, se puede sacar esto de la matriz DCM? + sin_roll = sin(roll); + cos_pitch = cos(pitch); + sin_pitch = sin(pitch); + + // rotate the magnetometer values depending upon orientation + if( orientation == 0 ) + rotMagVec = Vector3f(Mag_X+offset[0],Mag_Y+offset[1],Mag_Z+offset[2]); + else + rotMagVec = orientationMatrix*Vector3f(Mag_X+offset[0],Mag_Y+offset[1],Mag_Z+offset[2]); + + // Tilt compensated Magnetic field X component: + Head_X = rotMagVec.x*cos_pitch+rotMagVec.y*sin_roll*sin_pitch+rotMagVec.z*cos_roll*sin_pitch; + // Tilt compensated Magnetic field Y component: + Head_Y = rotMagVec.y*cos_roll-rotMagVec.z*sin_roll; + // Magnetic Heading + Heading = atan2(-Head_Y,Head_X); + + // Declination correction (if supplied) + if( declination != 0.0 ) + { + Heading = Heading + declination; + if (Heading > M_PI) // Angle normalization (-180 deg, 180 deg) + Heading -= (2.0 * M_PI); + else if (Heading < -M_PI) + Heading += (2.0 * M_PI); + } + + // Optimization for external DCM use. Calculate normalized components + Heading_X = cos(Heading); + Heading_Y = sin(Heading); +} + +void APM_Compass_Class::SetOrientation(const Matrix3f &rotationMatrix) +{ + orientationMatrix = rotationMatrix; + if( orientationMatrix == ROTATION_NONE ) + orientation = 0; + else + orientation = 1; +} + +void APM_Compass_Class::SetOffsets(int x, int y, int z) +{ + offset[0] = x; + offset[1] = y; + offset[2] = z; +} + +void APM_Compass_Class::SetDeclination(float radians) +{ + declination = radians; +} + +// make one instance for the user to use +APM_Compass_Class APM_Compass; diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_Compass/APM_Compass.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_Compass/APM_Compass.h new file mode 100644 index 0000000000..a8d0282a85 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_Compass/APM_Compass.h @@ -0,0 +1,69 @@ +#ifndef APM_Compass_h +#define APM_Compass_h + +#include "../AP_Math/AP_Math.h" + +// Rotation matrices +#define ROTATION_NONE Matrix3f(1, 0, 0, 0, 1, 0, 0 ,0, 1) +#define ROTATION_YAW_45 Matrix3f(0.70710678, -0.70710678, 0, 0.70710678, 0.70710678, 0, 0, 0, 1) +#define ROTATION_YAW_90 Matrix3f(0, -1, 0, 1, 0, 0, 0, 0, 1) +#define ROTATION_YAW_135 Matrix3f(-0.70710678, -0.70710678, 0, 0.70710678, -0.70710678, 0, 0, 0, 1) +#define ROTATION_YAW_180 Matrix3f(-1, 0, 0, 0, -1, 0, 0, 0, 1) +#define ROTATION_YAW_225 Matrix3f(-0.70710678, 0.70710678, 0, -0.70710678, -0.70710678, 0, 0, 0, 1) +#define ROTATION_YAW_270 Matrix3f(0, 1, 0, -1, 0, 0, 0, 0, 1) +#define ROTATION_YAW_315 Matrix3f(0.70710678, 0.70710678, 0, -0.70710678, 0.70710678, 0, 0, 0, 1) +#define ROTATION_ROLL_180 Matrix3f(1, 0, 0, 0, -1, 0, 0, 0, -1) +#define ROTATION_ROLL_180_YAW_45 Matrix3f(0.70710678, 0.70710678, 0, 0.70710678, -0.70710678, 0, 0, 0, -1) +#define ROTATION_ROLL_180_YAW_90 Matrix3f(0, 1, 0, 1, 0, 0, 0, 0, -1) +#define ROTATION_ROLL_180_YAW_135 Matrix3f(-0.70710678, 0.70710678, 0, 0.70710678, 0.70710678, 0, 0, 0, -1) +#define ROTATION_PITCH_180 Matrix3f(-1, 0, 0, 0, 1, 0, 0, 0, -1) +#define ROTATION_ROLL_180_YAW_225 Matrix3f(-0.70710678, -0.70710678, 0, -0.70710678, 0.70710678, 0, 0, 0, -1) +#define ROTATION_ROLL_180_YAW_270 Matrix3f(0, -1, 0, -1, 0, 0, 0, 0, -1) +#define ROTATION_ROLL_180_YAW_315 Matrix3f(0.70710678, -0.70710678, 0, -0.70710678, -0.70710678, 0, 0, 0, -1) + +#define APM_COMPASS_COMPONENTS_UP_PINS_FORWARD ROTATION_NONE +#define APM_COMPONENTS_UP_PINS_FORWARD_RIGHT ROTATION_YAW_45 +#define APM_COMPASS_COMPONENTS_UP_PINS_RIGHT ROTATION_YAW_90 +#define APM_COMPONENTS_UP_PINS_BACK_RIGHT ROTATION_YAW_135 +#define APM_COMPASS_COMPONENTS_UP_PINS_BACK ROTATION_YAW_180 +#define APM_COMPONENTS_UP_PINS_BACK_LEFT ROTATION_YAW_225 +#define APM_COMPASS_COMPONENTS_UP_PINS_LEFT ROTATION_YAW_270 +#define APM_COMPONENTS_UP_PINS_FORWARD_LEFT ROTATION_YAW_315 +#define APM_COMPASS_COMPONENTS_DOWN_PINS_FORWARD ROTATION_ROLL_180 +#define APM_COMPONENTS_DOWN_PINS_FORWARD_RIGHT ROTATION_ROLL_180_YAW_45 +#define APM_COMPASS_COMPONENTS_DOWN_PINS_RIGHT ROTATION_ROLL_180_YAW_90 +#define APM_COMPONENTS_DOWN_PINS_BACK_RIGHT ROTATION_ROLL_180_YAW_135 +#define APM_COMPASS_COMPONENTS_DOWN_PINS_BACK ROTATION_PITCH_180 +#define APM_COMPONENTS_DOWN_PINS_BACK_LEFT ROTATION_ROLL_180_YAW_225 +#define APM_COMPASS_COMPONENTS_DOWN_PINS_LEFT ROTATION_ROLL_180_YAW_270 +#define APM_COMPONENTS_DOWN_PINS_FORWARD_LEFT ROTATION_ROLL_180_YAW_315 + +class APM_Compass_Class +{ + private: + int orientation; + Matrix3f orientationMatrix; + float calibration[3]; + int offset[3]; + float declination; + public: + int Mag_X; + int Mag_Y; + int Mag_Z; + float Heading; + float Heading_X; + float Heading_Y; + unsigned long lastUpdate; + + APM_Compass_Class(); // Constructor + bool Init(); + void Read(); + void Calculate(float roll, float pitch); + void SetOrientation(const Matrix3f &rotationMatrix); + void SetOffsets(int x, int y, int z); + void SetDeclination(float radians); +}; + +extern APM_Compass_Class APM_Compass; + +#endif diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_Compass/examples/APM_Compass_test/APM_Compass_test.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_Compass/examples/APM_Compass_test/APM_Compass_test.pde new file mode 100644 index 0000000000..3216f89f55 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_Compass/examples/APM_Compass_test/APM_Compass_test.pde @@ -0,0 +1,87 @@ +/* + Example of APM_Compass library (HMC5843 sensor). + Code by Jordi MuÒoz and Jose Julio. DIYDrones.com + + offsets displayed are calculated from the min/max values from each axis. + rotate the compass so as to produce the maximum and minimum values + after the offsets stop changing, edit the code to pass these offsets into + APM_Compass.SetOffsets. +*/ + +#include +#include // Compass Library +#include // Math library + +#define ToRad(x) (x*0.01745329252) // *pi/180 +#define ToDeg(x) (x*57.2957795131) // *180/pi + +unsigned long timer; + +void setup() +{ + Serial.begin(38400); + Serial.println("Compass library test (HMC5843)"); + + APM_Compass.Init(); // Initialization + APM_Compass.SetOrientation(APM_COMPASS_COMPONENTS_UP_PINS_FORWARD); // set compass's orientation on aircraft + APM_Compass.SetOffsets(0,0,0); // set offsets to account for surrounding interference + APM_Compass.SetDeclination(ToRad(0.0)); // set local difference between magnetic north and true north + + delay(1000); + timer = millis(); +} + +void loop() +{ + static float min[3], max[3], offset[3]; + + if((millis()- timer) > 100) + { + timer = millis(); + APM_Compass.Read(); + APM_Compass.Calculate(0,0); // roll = 0, pitch = 0 for this example + + // capture min + if( APM_Compass.Mag_X < min[0] ) + min[0] = APM_Compass.Mag_X; + if( APM_Compass.Mag_Y < min[1] ) + min[1] = APM_Compass.Mag_Y; + if( APM_Compass.Mag_Z < min[2] ) + min[2] = APM_Compass.Mag_Z; + + // capture max + if( APM_Compass.Mag_X > max[0] ) + max[0] = APM_Compass.Mag_X; + if( APM_Compass.Mag_Y > max[1] ) + max[1] = APM_Compass.Mag_Y; + if( APM_Compass.Mag_Z > max[2] ) + max[2] = APM_Compass.Mag_Z; + + // calculate offsets + offset[0] = -(max[0]+min[0])/2; + offset[1] = -(max[1]+min[1])/2; + offset[2] = -(max[2]+min[2])/2; + + // display all to user + Serial.print("Heading:"); + Serial.print(ToDeg(APM_Compass.Heading)); + Serial.print(" ("); + Serial.print(APM_Compass.Mag_X); + Serial.print(","); + Serial.print(APM_Compass.Mag_Y); + Serial.print(","); + Serial.print(APM_Compass.Mag_Z); + Serial.print(")"); + + // display offsets + Serial.print("\t offsets("); + Serial.print(offset[0]); + Serial.print(","); + Serial.print(offset[1]); + Serial.print(","); + Serial.print(offset[2]); + Serial.print(")"); + + Serial.println(); + } +} diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_Compass/keywords.txt b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_Compass/keywords.txt new file mode 100644 index 0000000000..617c9aa805 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_Compass/keywords.txt @@ -0,0 +1,19 @@ +Compass KEYWORD1 +AP_Compass KEYWORD1 +APM_Compass KEYWORD1 +Init KEYWORD2 +Read KEYWORD2 +Calculate KEYWORD2 +SetOrientation KEYWORD2 +SetOffsets KEYWORDS2 +SetDeclination KEYWORDS2 +Heading KEYWORD2 +Heading_X KEYWORD2 +Heading_Y KEYWORD2 +Mag_X KEYWORD2 +Mag_Y KEYWORD2 +Mag_Z KEYWORD2 +lastUpdate KEYWORD2 + + + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_FastSerial/APM_FastSerial.cpp b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_FastSerial/APM_FastSerial.cpp new file mode 100644 index 0000000000..6b811caa5b --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_FastSerial/APM_FastSerial.cpp @@ -0,0 +1,150 @@ +/* + APM_FastSerial.cpp - Fast Serial Output for Ardupilot Mega Hardware (atmega1280) + Its also compatible with standard Arduino boards (atmega 168 and 328) + Interrupt driven Serial output with intermediate buffer + Code Jose Julio and Jordi Muoz. DIYDrones.com + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library works as a complement of the standard Arduino Serial + library. So user must initialize Standard Serial Arduino library first. + This library works in Serial port 0 and Serial port3(telemetry port)[APM] + Methods: (the same as standard arduino library, inherits from Print) + write() for bytes or array of bytes (binary output) + print() for chars, strings, numbers and floats + println() +*/ + +//#include "WProgram.h" +#include "APM_FastSerial.h" +extern "C" { + // AVR LibC Includes + #include + #include + #include + #include "WConstants.h" +} +#define TX_BUFFER_SIZE 80 // Serial output buffer size + +// Serial0 buffer +uint8_t tx_buffer0[TX_BUFFER_SIZE]; +volatile int tx_buffer0_head=0; +volatile int tx_buffer0_tail=0; + +#if defined(__AVR_ATmega1280__) +// Serial3 buffer +uint8_t tx_buffer3[TX_BUFFER_SIZE]; +volatile int tx_buffer3_head=0; +volatile int tx_buffer3_tail=0; +#endif + +#if defined(__AVR_ATmega1280__) // For atmega1280 we use Serial port 0 and 3 +// Serial0 interrupt +ISR(SIG_USART0_DATA) +{ + uint8_t data; + + if (tx_buffer0_tail == tx_buffer0_head) + UCSR0B &= ~(_BV(UDRIE0)); // Disable interrupt + else { + data = tx_buffer0[tx_buffer0_tail]; + tx_buffer0_tail = (tx_buffer0_tail + 1) % TX_BUFFER_SIZE; + UDR0 = data; + } +} + +// Serial3 interrupt +ISR(SIG_USART3_DATA) +{ + uint8_t data; + + if (tx_buffer3_tail == tx_buffer3_head) + UCSR3B &= ~(_BV(UDRIE3)); // Disable interrupt + else { + data = tx_buffer3[tx_buffer3_tail]; + tx_buffer3_tail = (tx_buffer3_tail + 1) % TX_BUFFER_SIZE; + UDR3 = data; + } +} +#else + +// Serial interrupt +ISR(USART_UDRE_vect) +{ + uint8_t data; + + if (tx_buffer0_tail == tx_buffer0_head) + UCSR0B &= ~(_BV(UDRIE0)); // Disable interrupt + else { + data = tx_buffer0[tx_buffer0_tail]; + tx_buffer0_tail = (tx_buffer0_tail + 1) % TX_BUFFER_SIZE; + UDR0 = data; + } +} +#endif + +// Constructors //////////////////////////////////////////////////////////////// +APM_FastSerial_Class::APM_FastSerial_Class(uint8_t SerialPort) +{ + SerialPortNumber=SerialPort; // This could be serial port 0 or 3 +} + +// Public Methods ////////////////////////////////////////////////////////////// + +// This is the important function (basic funtion: send a byte) +void APM_FastSerial_Class::write(uint8_t b) +{ + uint8_t Enable_tx_int=0; + uint8_t new_head; + + if (SerialPortNumber==0) // Serial Port 0 + { + // if buffer was empty then we enable Serial TX interrupt + if (tx_buffer0_tail == tx_buffer0_head) + Enable_tx_int=1; + + new_head = (tx_buffer0_head + 1) % TX_BUFFER_SIZE; // Move to next position in the ring buffer + if (new_head==tx_buffer0_tail) + return; // This is an Error : BUFFER OVERFLOW. We lost this character!! + + tx_buffer0[tx_buffer0_head] = b; // Add data to the tx buffer + tx_buffer0_head = new_head; // Update head pointer + + if (Enable_tx_int) + UCSR0B |= _BV(UDRIE0); // Enable Serial TX interrupt + } +#if defined(__AVR_ATmega1280__) + else // Serial Port 3 + { + // if buffer was empty then we enable Serial TX interrupt + if (tx_buffer3_tail == tx_buffer3_head) + Enable_tx_int=1; + + new_head = (tx_buffer3_head + 1) % TX_BUFFER_SIZE; // Move to next position in the ring buffer + if (new_head==tx_buffer3_tail) + return; // This is an Error : BUFFER OVERFLOW. We lost this character!! + + tx_buffer3[tx_buffer3_head] = b; // Add data to the tx buffer + tx_buffer3_head = new_head; // Update head pointer + + if (Enable_tx_int) + UCSR3B |= _BV(UDRIE3); // Enable Serial TX interrupt + } +#endif +} + +// Send a buffer of bytes (this is util for binary protocols) +void APM_FastSerial_Class::write(const uint8_t *buffer, int size) +{ + while (size--) + write(*buffer++); +} + +// We create this two instances +APM_FastSerial_Class APM_FastSerial(0); // For Serial port 0 +#if defined(__AVR_ATmega1280__) + APM_FastSerial_Class APM_FastSerial3(3); // For Serial port 3 (only Atmega1280) +#endif \ No newline at end of file diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_FastSerial/APM_FastSerial.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_FastSerial/APM_FastSerial.h new file mode 100644 index 0000000000..319ec523dd --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_FastSerial/APM_FastSerial.h @@ -0,0 +1,25 @@ +#ifndef APM_FastSerial_h +#define APM_FastSerial_h + +#include + +#include "Print.h" + +class APM_FastSerial_Class : public Print // Inherit from Print +{ + private: + uint8_t SerialPortNumber; + + public: + APM_FastSerial_Class(uint8_t SerialPort); // Constructor + // we overwrite the write methods + void write(uint8_t b); // basic funtion : send a byte + void write(const uint8_t *buffer, int size); +}; + +extern APM_FastSerial_Class APM_FastSerial; +#if defined(__AVR_ATmega1280__) + extern APM_FastSerial_Class APM_FastSerial3; +#endif +#endif + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_FastSerial/examples/APM_FastSerial/APM_FastSerial.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_FastSerial/examples/APM_FastSerial/APM_FastSerial.pde new file mode 100644 index 0000000000..97616237ed --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_FastSerial/examples/APM_FastSerial/APM_FastSerial.pde @@ -0,0 +1,91 @@ +/* + Example of APM_FastSerial library. + Code by Jose Julio and Jordi Muoz. DIYDrones.com +*/ + +// FastSerial is implemented for Serial port 0 (connection to PC) and 3 (telemetry) +#include // ArduPilot Mega Fast Serial Output Library + +#if defined(__AVR_ATmega1280__) + #define LED 35 +#else + #define LED 13 +#endif + +unsigned long timer; +unsigned long counter; + +void setup() +{ + int myint=14235; // Examples of data tytpes + long mylong=-23456432; + float myfloat=-26.669; + byte mybyte=0xD1; + byte bc_bufIn[50]; + + for (int i=0;i<10;i++) + bc_bufIn[i]=i*10+30; // we fill the byte array + + pinMode(LED,OUTPUT); + + // We use the standard serial port initialization + Serial.begin(57600); + //Serial3.begin(57600); // if we want to use port3 also (Mega boards)... + delay(100); + // We can use both methods to write to serial port: + Serial.println("ArduPilot Mega FastSerial library test"); // Standard serial output + APM_FastSerial.println("FAST_SERIAL : ArduPilot Mega FastSerial library test"); // Fast serial output + // We can use the same on serial port3 (telemetry) + // APM_FastSerial3.println("Serial Port3 : ArduPilot Mega FastSerial library test"); + delay(1000); + // Examples of data types (same result as standard arduino library) + APM_FastSerial.println("Numbers:"); + APM_FastSerial.println(myint); + APM_FastSerial.println(mylong); + APM_FastSerial.println(myfloat); + APM_FastSerial.println("Byte:"); + APM_FastSerial.write(mybyte); + APM_FastSerial.println(); + APM_FastSerial.println("Bytes:"); + APM_FastSerial.write(bc_bufIn,10); + APM_FastSerial.println(); + delay(4000); +} + +void loop() +{ + if((millis()- timer) > 20) // 50Hz loop + { + timer = millis(); + if (counter < 250) // we use the Normal Serial output for 5 seconds + { + // Example of typical telemetry output + digitalWrite(LED,HIGH); + Serial.println("!ATT:14.2;-5.5;-26.8"); // 20 bytes + digitalWrite(LED,LOW); + if ((counter%5)==0) // GPS INFO at 5Hz + { + digitalWrite(LED,HIGH); + Serial.println("!LAT:26.345324;LON:-57.372638;ALT:46.7;GC:121.3;GS:23.1"); // 54 bytes + digitalWrite(LED,LOW); + } + } + else // and Fast Serial Output for other 5 seconds + { + // The same info... + digitalWrite(LED,HIGH); + APM_FastSerial.println("#ATT:14.2;-5.5;-26.8"); // 20 bytes + digitalWrite(LED,LOW); + if ((counter%5)==0) // GPS INFO at 5Hz + { + digitalWrite(LED,HIGH); + + APM_FastSerial.println("#LAT:26.345324;LON:-57.372638;ALT:46.7;GC:121.3;GS:23.1"); // 54 bytes + digitalWrite(LED,LOW); + } + if (counter>500) // Counter reset + counter=0; + } + counter++; + } +} \ No newline at end of file diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_FastSerial/keywords.txt b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_FastSerial/keywords.txt new file mode 100644 index 0000000000..91cfc02dea --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_FastSerial/keywords.txt @@ -0,0 +1,2 @@ +APM_FastSerial KEYWORD1 +APM_FastSerial3 KEYWORD1 diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC/APM_RC.cpp b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC/APM_RC.cpp new file mode 100644 index 0000000000..7099b44e26 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC/APM_RC.cpp @@ -0,0 +1,193 @@ +/* + APM_RC.cpp - Radio Control Library for Ardupilot Mega. Arduino + Code by Jordi Muoz and Jose Julio. DIYDrones.com + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + RC Input : PPM signal on IC4 pin + RC Output : 11 Servo outputs (standard 20ms frame) + + Methods: + Init() : Initialization of interrupts an Timers + OutpuCh(ch,pwm) : Output value to servos (range : 900-2100us) ch=0..10 + InputCh(ch) : Read a channel input value. ch=0..7 + GetState() : Returns the state of the input. 1 => New radio frame to process + Automatically resets when we call InputCh to read channels + +*/ +#include "APM_RC.h" + +#include +#include "WProgram.h" + +#if !defined(__AVR_ATmega1280__) +# error Please check the Tools/Board menu to ensure you have selected Arduino Mega as your target. +#else + +// Variable definition for Input Capture interrupt +volatile unsigned int ICR4_old; +volatile unsigned char PPM_Counter=0; +volatile unsigned int PWM_RAW[8] = {2400,2400,2400,2400,2400,2400,2400,2400}; +volatile unsigned char radio_status=0; + +/**************************************************** + Input Capture Interrupt ICP4 => PPM signal read + ****************************************************/ +ISR(TIMER4_CAPT_vect) +{ + unsigned int Pulse; + unsigned int Pulse_Width; + + Pulse=ICR4; + if (Pulse8000) // SYNC pulse? + PPM_Counter=0; + else + { + PPM_Counter &= 0x07; // For safety only (limit PPM_Counter to 7) + PWM_RAW[PPM_Counter++]=Pulse_Width; //Saving pulse. + if (PPM_Counter >= NUM_CHANNELS) + radio_status = 1; + } + ICR4_old = Pulse; +} + + +// Constructors //////////////////////////////////////////////////////////////// + +APM_RC_Class::APM_RC_Class() +{ +} + +// Public Methods ////////////////////////////////////////////////////////////// +void APM_RC_Class::Init(void) +{ + // Init PWM Timer 1 + pinMode(11,OUTPUT); // (PB5/OC1A) + pinMode(12,OUTPUT); //OUT2 (PB6/OC1B) + pinMode(13,OUTPUT); //OUT3 (PB7/OC1C) + + //Remember the registers not declared here remains zero by default... + TCCR1A =((1<>1; // Because timer runs at 0.5us we need to do value/2 + result2 = PWM_RAW[ch]>>1; + if (result != result2) + result = PWM_RAW[ch]>>1; // if the results are different we make a third reading (this should be fine) + + // Limit values to a valid range + result = constrain(result,MIN_PULSEWIDTH,MAX_PULSEWIDTH); + radio_status=0; // Radio channel read + return(result); +} + +unsigned char APM_RC_Class::GetState(void) +{ + return(radio_status); +} + +// InstantPWM implementation +// This function forces the PWM output (reset PWM) on Out0 and Out1 (Timer5). For quadcopters use +void APM_RC_Class::Force_Out0_Out1(void) +{ + if (TCNT5>5000) // We take care that there are not a pulse in the output + TCNT5=39990; // This forces the PWM output to reset in 5us (10 counts of 0.5us). The counter resets at 40000 +} +// This function forces the PWM output (reset PWM) on Out2 and Out3 (Timer1). For quadcopters use +void APM_RC_Class::Force_Out2_Out3(void) +{ + if (TCNT1>5000) + TCNT1=39990; +} +// This function forces the PWM output (reset PWM) on Out6 and Out7 (Timer3). For quadcopters use +void APM_RC_Class::Force_Out6_Out7(void) +{ + if (TCNT3>5000) + TCNT3=39990; +} + +// make one instance for the user to use +APM_RC_Class APM_RC; + +#endif // defined(ATMega1280) diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC/APM_RC.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC/APM_RC.h new file mode 100644 index 0000000000..3874e0a319 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC/APM_RC.h @@ -0,0 +1,24 @@ +#ifndef APM_RC_h +#define APM_RC_h + +#define NUM_CHANNELS 8 +#define MIN_PULSEWIDTH 900 +#define MAX_PULSEWIDTH 2100 + +class APM_RC_Class +{ + private: + public: + APM_RC_Class(); + void Init(); + void OutputCh(unsigned char ch, int pwm); + int InputCh(unsigned char ch); + unsigned char GetState(); + void Force_Out0_Out1(void); + void Force_Out2_Out3(void); + void Force_Out6_Out7(void); +}; + +extern APM_RC_Class APM_RC; + +#endif \ No newline at end of file diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC/examples/APM_radio/APM_radio.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC/examples/APM_radio/APM_radio.pde new file mode 100644 index 0000000000..3edc3d223a --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC/examples/APM_radio/APM_radio.pde @@ -0,0 +1,31 @@ +/* + Example of APM_RC library. + Code by Jordi Muoz and Jose Julio. DIYDrones.com + + Print Input values and send Output to the servos + (Works with last PPM_encoder firmware) +*/ + +#include // ArduPilot Mega RC Library + +void setup() +{ + APM_RC.Init(); // APM Radio initialization + Serial.begin(57600); + Serial.println("ArduPilot Mega RC library test"); + delay(1000); +} +void loop() +{ + if (APM_RC.GetState()==1) // New radio frame? (we could use also if((millis()- timer) > 20) + { + Serial.print("CH:"); + for(int i=0;i<8;i++) + { + Serial.print(APM_RC.InputCh(i)); // Print channel values + Serial.print(","); + APM_RC.OutputCh(i,APM_RC.InputCh(i)); // Copy input to Servos + } + Serial.println(); + } +} \ No newline at end of file diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC/keywords.txt b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC/keywords.txt new file mode 100644 index 0000000000..0fba1dd8a0 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC/keywords.txt @@ -0,0 +1,8 @@ +APM_RC KEYWORD1 +begin KEYWORD2 +InputCh KEYWORD2 +OutputCh KEYWORD2 +GetState KEYWORD2 +Force_Out0_Out1 KEYWORD2 +Force_Out2_Out3 KEYWORD2 +Force_Out6_Out7 KEYWORD2 diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC_QUAD/APM_RC_QUAD.cpp b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC_QUAD/APM_RC_QUAD.cpp new file mode 100644 index 0000000000..da5f4dd4a9 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC_QUAD/APM_RC_QUAD.cpp @@ -0,0 +1,169 @@ +/* + APM_RC_QUAD.cpp - Radio Control Library for Ardupilot Mega. Arduino + Code by Jordi Muoz and Jose Julio. DIYDrones.com + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This is a special version of the library for use in Quadcopters + Because we have modified servo outputs 0..3 to have a higher rate (300Hz) + + RC Input : PPM signal on IC4 pin + RC Output : 8 servo Outputs, + OUT0..OUT3 : 300Hz Servo output (for Quad ESCs) + OUT4..OUT7 : standard 50Hz servo outputs + + Methods: + Init() : Initialization of interrupts an Timers + OutpuCh(ch,pwm) : Output value to servos (range : 900-2100us) ch=0..10 + InputCh(ch) : Read a channel input value. ch=0..7 + GetState() : Returns the state of the input. 1 => New radio frame to process + Automatically resets when we call InputCh to read channels + +*/ +#include "APM_RC_QUAD.h" + +#include +#include "WProgram.h" + +// Variable definition for Input Capture interrupt +volatile unsigned int ICR4_old; +volatile unsigned char PPM_Counter=0; +volatile unsigned int PWM_RAW[8] = {2400,2400,2400,2400,2400,2400,2400,2400}; +volatile unsigned char radio_status=0; + +/**************************************************** + Input Capture Interrupt ICP4 => PPM signal read + ****************************************************/ +ISR(TIMER4_CAPT_vect) +{ + unsigned int Pulse; + unsigned int Pulse_Width; + + Pulse=ICR4; + if (Pulse8000) // SYNC pulse? + PPM_Counter=0; + else + { + PPM_Counter &= 0x07; // For safety only (limit PPM_Counter to 7) + PWM_RAW[PPM_Counter++]=Pulse_Width; //Saving pulse. + if (PPM_Counter >= NUM_CHANNELS) + radio_status = 1; + } + ICR4_old = Pulse; +} + + +// Constructors //////////////////////////////////////////////////////////////// + +APM_RC_QUAD_Class::APM_RC_QUAD_Class() +{ +} + +// Public Methods ////////////////////////////////////////////////////////////// +void APM_RC_QUAD_Class::Init(void) +{ + // Init PWM Timer 1 + //pinMode(11,OUTPUT); // (PB5/OC1A) + pinMode(12,OUTPUT); //OUT2 (PB6/OC1B) + pinMode(13,OUTPUT); //OUT3 (PB7/OC1C) + + //Remember the registers not declared here remains zero by default... + TCCR1A =((1<>1; // Because timer runs at 0.5us we need to do value/2 + result2 = PWM_RAW[ch]>>1; + if (result != result2) + result = PWM_RAW[ch]>>1; // if the results are different we make a third reading (this should be fine) + + // Limit values to a valid range + result = constrain(result,MIN_PULSEWIDTH,MAX_PULSEWIDTH); + radio_status=0; // Radio channel read + return(result); +} + +unsigned char APM_RC_QUAD_Class::GetState(void) +{ + return(radio_status); +} + +// make one instance for the user to use +APM_RC_QUAD_Class APM_RC_QUAD; \ No newline at end of file diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC_QUAD/APM_RC_QUAD.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC_QUAD/APM_RC_QUAD.h new file mode 100644 index 0000000000..421089d7af --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC_QUAD/APM_RC_QUAD.h @@ -0,0 +1,21 @@ +#ifndef APM_RC_QUAD_h +#define APM_RC_QUAD_h + +#define NUM_CHANNELS 8 +#define MIN_PULSEWIDTH 900 +#define MAX_PULSEWIDTH 2100 + +class APM_RC_QUAD_Class +{ + private: + public: + APM_RC_QUAD_Class(); + void Init(); + void OutputCh(unsigned char ch, int pwm); + int InputCh(unsigned char ch); + unsigned char GetState(); +}; + +extern APM_RC_QUAD_Class APM_RC_QUAD; + +#endif \ No newline at end of file diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC_QUAD/examples/APM_radio_quad/APM_radio_quad.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC_QUAD/examples/APM_radio_quad/APM_radio_quad.pde new file mode 100644 index 0000000000..3edc3d223a --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC_QUAD/examples/APM_radio_quad/APM_radio_quad.pde @@ -0,0 +1,31 @@ +/* + Example of APM_RC library. + Code by Jordi Muoz and Jose Julio. DIYDrones.com + + Print Input values and send Output to the servos + (Works with last PPM_encoder firmware) +*/ + +#include // ArduPilot Mega RC Library + +void setup() +{ + APM_RC.Init(); // APM Radio initialization + Serial.begin(57600); + Serial.println("ArduPilot Mega RC library test"); + delay(1000); +} +void loop() +{ + if (APM_RC.GetState()==1) // New radio frame? (we could use also if((millis()- timer) > 20) + { + Serial.print("CH:"); + for(int i=0;i<8;i++) + { + Serial.print(APM_RC.InputCh(i)); // Print channel values + Serial.print(","); + APM_RC.OutputCh(i,APM_RC.InputCh(i)); // Copy input to Servos + } + Serial.println(); + } +} \ No newline at end of file diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC_QUAD/keywords.txt b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC_QUAD/keywords.txt new file mode 100644 index 0000000000..762966e545 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC_QUAD/keywords.txt @@ -0,0 +1,5 @@ +APM_RC_QUAD KEYWORD1 +begin KEYWORD2 +InputCh KEYWORD2 +OutputCh KEYWORD2 +GetState KEYWORD2 diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Common/AP_Common.cpp b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Common/AP_Common.cpp new file mode 100644 index 0000000000..5b476c4f09 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Common/AP_Common.cpp @@ -0,0 +1,17 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- +// +// This is free software; you can redistribute it and/or modify it under +// the terms of the GNU Lesser General Public License as published by the +// Free Software Foundation; either version 2.1 of the License, or (at +// your option) any later version. +// + +/// @file AP_Common.cpp +/// @brief Common utility routines for the ArduPilot libraries. +/// +/// @note Exercise restraint adding code here; everything in this +/// library will be linked with any sketch using it. +/// + +#include "AP_Common.h" + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Common/AP_Common.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Common/AP_Common.h new file mode 100644 index 0000000000..8ad2f0fbf5 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Common/AP_Common.h @@ -0,0 +1,53 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- +// +// This is free software; you can redistribute it and/or modify it under +// the terms of the GNU Lesser General Public License as published by the +// Free Software Foundation; either version 2.1 of the License, or (at +// your option) any later version. +// + +/// +/// @file AP_Common.h +/// @brief Common definitions and utility routines for the ArduPilot +/// libraries. +/// + +#ifndef _AP_COMMON_H +#define _AP_COMMON_H + +#include + +#include "include/menu.h" /// simple menu subsystem + +//////////////////////////////////////////////////////////////////////////////// +/// @name Types +/// +/// Data structures and types used throughout the libraries and applications. +/// +//@{ + +struct Location { + uint8_t id; ///< command id + uint8_t p1; ///< param 1 + int32_t alt; ///< param 2 - Altitude in centimeters (meters * 100) + int32_t lat; ///< param 3 - Lattitude * 10**7 + int32_t lng; ///< param 4 - Longitude * 10**7 +}; + +//@} + +//////////////////////////////////////////////////////////////////////////////// +/// @name Conversions +/// +/// Conversion macros and factors. +/// +//@{ + +/// XXX this should probably be replaced with radians()/degrees(), but their +/// inclusion in wiring.h makes doing that here difficult. +#define ToDeg(x) (x*57.2957795131) // *180/pi + +//@} + + +#endif // _AP_COMMON_H diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Common/c++.cpp b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Common/c++.cpp new file mode 100644 index 0000000000..107d7fb045 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Common/c++.cpp @@ -0,0 +1,21 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- + +// +// C++ runtime support not provided by Arduino +// +// Note: use new/delete with caution. The heap is small and +// easily fragmented. +// + +#include + +void * operator new(size_t size) +{ + return(calloc(size, 1)); +} + +void operator delete(void *p) +{ + if (p) + free(p); +} diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Common/examples/menu/menu.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Common/examples/menu/menu.pde new file mode 100644 index 0000000000..fea9efa188 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Common/examples/menu/menu.pde @@ -0,0 +1,45 @@ + +#include +#include + +#include + +FastSerialPort0(Serial); + +int +menu_test(uint8_t argc, const Menu::arg *argv) +{ + int i; + + Serial.printf("This is a test with %d arguments\n", argc); + for (i = 1; i < argc; i++) { + Serial.printf("%d: int %ld float ", i, argv[i].i); + Serial.println(argv[i].f, 6); // gross + } +} + +int +menu_auto(uint8_t argc, const Menu::arg *argv) +{ + Serial.println("auto text"); +} + +const struct Menu::command top_menu_commands[] PROGMEM = { + {"*", menu_auto}, + {"test", menu_test}, +}; + +MENU(top, "menu", top_menu_commands); + +void +setup(void) +{ + Serial.begin(38400); + top.run(); +} + +void +loop(void) +{ +} + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Common/include/menu.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Common/include/menu.h new file mode 100644 index 0000000000..96b863c05b --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Common/include/menu.h @@ -0,0 +1,138 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- + +/// @file menu.h +/// @brief Simple commandline menu subsystem. +/// @discussion +/// The Menu class implements a simple CLI that accepts commands typed by +/// the user, and passes the arguments to those commands to a function +/// defined as handing the command. +/// +/// Commands are defined in an array of Menu::command structures passed +/// to the constructor. Each entry in the array defines one command. +/// +/// Arguments passed to the handler function are pre-converted to both +/// long and float for convenience. +/// + +#define MENU_COMMANDLINE_MAX 32 ///< maximum input line length +#define MENU_ARGS_MAX 4 ///< maximum number of arguments +#define MENU_COMMAND_MAX 14 ///< maximum size of a command name + +/// Class defining and handling one menu tree +class Menu { +public: + /// argument passed to a menu function + /// + /// Space-delimited arguments are parsed from the commandline and + /// separated into these structures. + /// + /// If the argument cannot be parsed as a float or a long, the value + /// of f or i respectively is undefined. You should range-check + /// the inputs to your function. + /// + struct arg { + const char *str; ///< string form of the argument + long i; ///< integer form of the argument (if a number) + float f; ///< floating point form of the argument (if a number) + }; + + /// menu command function + /// + /// Functions called by menu array entries are expected to be of this + /// type. + /// + /// @param argc The number of valid arguments, including the + /// name of the command in argv[0]. Will never be + /// more than MENU_ARGS_MAX. + /// @param argv Pointer to an array of Menu::arg structures + /// detailing any optional arguments given to the + /// command. argv[0] is always the name of the + /// command, so that the same function can be used + /// to handle more than one command. + /// + typedef int8_t (*func)(uint8_t argc, const struct arg *argv); + + /// menu pre-prompt function + /// + /// Called immediately before waiting for the user to type a command; can be + /// used to display help text or status, for example. + /// + /// If this function returns false, the menu exits. + /// + typedef bool (*preprompt)(void); + + /// menu command description + /// + struct command { + /// Name of the command, as typed or received. + /// Command names are limited in size to keep this structure compact. + /// + const char command[MENU_COMMAND_MAX]; + + /// The function to call when the command is received. + /// + /// The argc argument will be at least 1, and no more than + /// MENU_ARGS_MAX. The argv array will be populated with + /// arguments typed/received up to MENU_ARGS_MAX. The command + /// name will always be in argv[0]. + /// + /// Commands may return -2 to cause the menu itself to exit. + /// The "?", "help" and "exit" commands are always defined, but + /// can be overridden by explicit entries in the command array. + /// + int8_t (*func)(uint8_t argc, const struct arg *argv); ///< callback function + }; + + /// constructor + /// + /// Note that you should normally not call the constructor directly. Use + /// the MENU and MENU2 macros defined below. + /// + /// @param prompt The prompt to be displayed with this menu. + /// @param commands An array of ::command structures in program memory (PROGMEM). + /// @param entries The number of entries in the menu. + /// + Menu(const char *prompt, const struct command *commands, uint8_t entries, preprompt ppfunc = 0); + + /// menu runner + void run(void); + +private: + /// Implements the default 'help' command. + /// + void _help(void); ///< implements the 'help' command + + /// calls the function for the n'th menu item + /// + /// @param n Index for the menu item to call + /// @param argc Number of arguments prepared for the menu item + /// + int8_t _call(uint8_t n, uint8_t argc); + + const char *_prompt; ///< prompt to display + const command *_commands; ///< array of commands + const uint8_t _entries; ///< size of the menu + const preprompt _ppfunc; ///< optional pre-prompt action + + static char _inbuf[MENU_COMMANDLINE_MAX]; ///< input buffer + static arg _argv[MENU_ARGS_MAX + 1]; ///< arguments +}; + +/// Macros used to define a menu. +/// +/// The commands argument should be an arary of Menu::command structures, one +/// per command name. The array does not need to be terminated with any special +/// record. +/// +/// Use name.run() to run the menu. +/// +/// The MENU2 macro supports the optional pre-prompt printing function. +/// +#define MENU(name, prompt, commands) \ + static const char __menu_name__ ##name[] PROGMEM = prompt; \ + static Menu name(__menu_name__ ##name, commands, sizeof(commands) / sizeof(commands[0])) + +#define MENU2(name, prompt, commands, preprompt) \ + static const char __menu_name__ ##name[] PROGMEM = prompt; \ + static Menu name(__menu_name__ ##name, commands, sizeof(commands) / sizeof(commands[0]), preprompt) + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Common/keywords.txt b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Common/keywords.txt new file mode 100644 index 0000000000..470e71f7a8 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Common/keywords.txt @@ -0,0 +1,4 @@ +Menu KEYWORD1 +run KEYWORD2 +Location KEYWORD2 + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Common/menu.cpp b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Common/menu.cpp new file mode 100644 index 0000000000..58e129d03e --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Common/menu.cpp @@ -0,0 +1,129 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- + +// +// Simple commandline menu system. +// + +#include + +#include +#include +#include + +#include "include/menu.h" + +// statics +char Menu::_inbuf[MENU_COMMANDLINE_MAX]; +Menu::arg Menu::_argv[MENU_ARGS_MAX + 1]; + +// constructor +Menu::Menu(const prog_char *prompt, const Menu::command *commands, uint8_t entries, preprompt ppfunc) : + _prompt(prompt), + _commands(commands), + _entries(entries), + _ppfunc(ppfunc) +{ +} + +// run the menu +void +Menu::run(void) +{ + uint8_t len, i, ret; + uint8_t argc; + int c; + char *s; + + // loop performing commands + for (;;) { + + // run the pre-prompt function, if one is defined + if ((NULL != _ppfunc) && !_ppfunc()) + return; + + // loop reading characters from the input + len = 0; + Serial.printf("%S] ", _prompt); + for (;;) { + c = Serial.read(); + if (-1 == c) + continue; + // carriage return -> process command + if ('\r' == c) { + _inbuf[len] = '\0'; + Serial.write('\r'); + Serial.write('\n'); + break; + } + // backspace + if ('\b' == c) { + if (len > 0) { + len--; + Serial.write('\b'); + Serial.write(' '); + Serial.write('\b'); + continue; + } + } + // printable character + if (isprint(c) && (len < (MENU_COMMANDLINE_MAX - 1))) { + _inbuf[len++] = c; + Serial.write((char)c); + continue; + } + } + + // split the input line into tokens + argc = 0; + _argv[argc++].str = strtok_r(_inbuf, " ", &s); + // XXX should an empty line by itself back out of the current menu? + while (argc <= MENU_ARGS_MAX) { + _argv[argc].str = strtok_r(NULL, " ", &s); + if ('\0' == _argv[argc].str) + break; + _argv[argc].i = atol(_argv[argc].str); + _argv[argc].f = atof(_argv[argc].str); // calls strtod, > 700B ! + argc++; + } + + // look for a command matching the first word (note that it may be empty) + for (i = 0; i < _entries; i++) { + if (!strcasecmp_P(_argv[0].str, _commands[i].command)) { + ret = _call(i, argc); + if (-2 == ret) + return; + break; + } + } + + // implicit commands + if (i == _entries) { + if (!strcmp(_argv[0].str, "?") || (!strcasecmp_P(_argv[0].str, PSTR("help")))) { + _help(); + } else if (!strcasecmp_P(_argv[0].str, PSTR("exit"))) { + return; + } + } + } +} + +// display the list of commands in response to the 'help' command +void +Menu::_help(void) +{ + int i; + + Serial.println("Commands:"); + for (i = 0; i < _entries; i++) + Serial.printf(" %S\n", _commands[i].command); +} + +// run the n'th command in the menu +int8_t +Menu::_call(uint8_t n, uint8_t argc) +{ + func fn; + + fn = (func)pgm_read_word(&_commands[n].func); + return(fn(argc, &_argv[0])); +} diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Compass/AP_Compass.cpp b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Compass/AP_Compass.cpp new file mode 100644 index 0000000000..a92cfa7acc --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Compass/AP_Compass.cpp @@ -0,0 +1,115 @@ +/* + AP_Compass.cpp - Arduino Library for HMC5843 I2C Magnetometer + Code by Jordi Muoz and Jose Julio. DIYDrones.com + + This library is free software; you can redistribute it and / or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + Sensor is conected to I2C port + Sensor is initialized in Continuos mode (10Hz) + + Variables: + heading : Magnetic heading + heading_X : Magnetic heading X component + heading_Y : Magnetic heading Y component + mag_X : Raw X axis magnetometer data + mag_Y : Raw Y axis magnetometer data + mag_Z : Raw Z axis magnetometer data + + Methods: + init() : initialization of I2C and sensor + update() : update Sensor data + + To do : Calibration of the sensor, code optimization + Mount position : UPDATED + Big capacitor pointing backward, connector forward + +*/ + + +extern "C" { + // AVR LibC Includes + #include + #include "WConstants.h" +} + +#include +#include "AP_Compass.h" + +#define COMPASS_ADDRESS 0x1E + +// Constructors //////////////////////////////////////////////////////////////// +AP_Compass::AP_Compass() +{ +} + +// Public Methods ////////////////////////////////////////////////////////////// +void +AP_Compass::init(void) +{ + Wire.begin(); + Wire.beginTransmission(COMPASS_ADDRESS); + Wire.send(0x02); + Wire.send(0x00); // Set continouos mode (default to 10Hz) + Wire.endTransmission(); // end transmission +} + +// update Sensor data +void +AP_Compass::update() +{ + int i = 0; + byte buff[6]; + + Wire.beginTransmission(COMPASS_ADDRESS); + Wire.send(0x03); // sends address to read from + Wire.endTransmission(); // end transmission + + //Wire.beginTransmission(COMPASS_ADDRESS); + Wire.requestFrom(COMPASS_ADDRESS, 6); // request 6 bytes from device + while(Wire.available()){ + buff[i] = Wire.receive(); // receive one byte + i++; + } + Wire.endTransmission(); // end transmission + + // All bytes received? + if (i == 6) { + // MSB byte first, then LSB, X,Y,Z + mag_X = -((((int)buff[0]) << 8) | buff[1]); // X axis + mag_Y = ((((int)buff[2]) << 8) | buff[3]); // Y axis + mag_Z = -((((int)buff[4]) << 8) | buff[5]); // Z axis + } +} + +void +AP_Compass::calculate(float roll, float pitch) +{ + float head_X; + float head_Y; + float cos_roll; + float sin_roll; + float cos_pitch; + float sin_pitch; + + cos_roll = cos(roll); // Optimization, you can get this out of the matrix DCM? + sin_roll = sin(roll); + cos_pitch = cos(pitch); + sin_pitch = sin(pitch); + + // Tilt compensated Magnetic field X component: + head_X = mag_X * cos_pitch + mag_Y * sin_roll * sin_pitch + mag_Z * cos_roll * sin_pitch; + + // Tilt compensated Magnetic field Y component: + head_Y = mag_Y * cos_roll - mag_Z * sin_roll; + + // Magnetic heading + heading = atan2(-head_Y, head_X); + ground_course = (degrees(heading) + 180) * 100; + + // Optimization for external DCM use. calculate normalized components + heading_X = cos(heading); + heading_Y = sin(heading); +} diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Compass/AP_Compass.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Compass/AP_Compass.h new file mode 100644 index 0000000000..cbafb19e18 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Compass/AP_Compass.h @@ -0,0 +1,17 @@ +#ifndef AP_Compass_h +#define AP_Compass_h + +#include + +class AP_Compass : public Compass +{ + public: + AP_Compass(); // Constructor + void init(); + void update(); + void calculate(float roll, float pitch); + + private: +}; + +#endif \ No newline at end of file diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Compass/Compass.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Compass/Compass.h new file mode 100644 index 0000000000..0852cdd52a --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Compass/Compass.h @@ -0,0 +1,23 @@ +#ifndef Compass_h +#define Compass_h + +#include + +class Compass +{ + public: + virtual void init(); + virtual void update(); + virtual void calculate(float roll, float pitch); + + int16_t mag_X; + int16_t mag_Y; + int16_t mag_Z; + int32_t ground_course; + float heading; + float heading_X; + float heading_Y; + +}; + +#endif \ No newline at end of file diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.pde new file mode 100644 index 0000000000..1a69883789 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.pde @@ -0,0 +1,40 @@ +/* + Example of APM_Compass library (HMC5843 sensor). + Code by Jordi MuÒoz and Jose Julio. DIYDrones.com +*/ + +#include +#include // Compass Library + +AP_Compass compass; + +unsigned long timer; + +void setup() +{ + compass.init(); // Initialization + Serial.begin(38400); + Serial.println("AP Compass library test (HMC5843)"); + delay(1000); + timer = millis(); +} + +void loop() +{ + float tmp; + + if((millis()- timer) > 100){ + timer = millis(); + compass.update(); + compass.calculate(0, 0); // roll = 0, pitch = 0 for this example + Serial.print("Heading:"); + Serial.print(compass.ground_course,DEC); + Serial.print(" ("); + Serial.print(compass.mag_X); + Serial.print(","); + Serial.print(compass.mag_Y); + Serial.print(","); + Serial.print(compass.mag_Z); + Serial.println(" )"); + } +} \ No newline at end of file diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Compass/keywords.txt b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Compass/keywords.txt new file mode 100644 index 0000000000..91affe3e73 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Compass/keywords.txt @@ -0,0 +1,15 @@ +Compass KEYWORD1 +AP_Compass KEYWORD1 +APM_Compass KEYWORD1 +init KEYWORD2 +update KEYWORD2 +calculate KEYWORD2 +heading KEYWORD2 +heading_X KEYWORD2 +heading_Y KEYWORD2 +mag_X KEYWORD2 +mag_Y KEYWORD2 +mag_Z KEYWORD2 + + + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS.h new file mode 100644 index 0000000000..384d7daccc --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS.h @@ -0,0 +1,13 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- + +/// @file AP_GPS.h +/// @brief Catch-all header that defines all supported GPS classes. + +#include "AP_GPS_NMEA.h" +#include "AP_GPS_SIRF.h" +#include "AP_GPS_406.h" +#include "AP_GPS_UBLOX.h" +#include "AP_GPS_MTK.h" +#include "AP_GPS_IMU.h" +#include "AP_GPS_None.h" +#include "AP_GPS_Auto.h" diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_406.cpp b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_406.cpp new file mode 100644 index 0000000000..379d096cdd --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_406.cpp @@ -0,0 +1,81 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- +// +// GPS_406.cpp - 406 GPS library for Arduino +// Code by Michael Smith, Jason Short, Jordi Muoz and Jose Julio. DIYDrones.com +// This code works with boards based on ATMega168/328 ATMega1280 (Serial port 1) +// +// This library is free software; you can redistribute it and / or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 2.1 of the License, or (at your option) any later version. + +#include "../FastSerial/FastSerial.h" // because we need to change baud rates... ugh. +#include "AP_GPS_406.h" +#include "WProgram.h" + +static const char init_str[] = "$PSRF100,0,57600,8,1,0*37"; + +// Constructors //////////////////////////////////////////////////////////////// +AP_GPS_406::AP_GPS_406(Stream *s) : AP_GPS_SIRF(s) +{ +} + +// Public Methods //////////////////////////////////////////////////////////////////// +void AP_GPS_406::init(void) +{ + _change_to_sirf_protocol(); // Changes to SIRF protocol and sets baud rate + _configure_gps(); // Function to configure GPS, to output only the desired msg's + + AP_GPS_SIRF::init(); // let the superclass do anything it might need here +} + +// Private Methods ////////////////////////////////////////////////////////////// + +void +AP_GPS_406::_configure_gps(void) +{ + const uint8_t gps_header[] = {0xA0, 0xA2, 0x00, 0x08, 0xA6, 0x00}; + const uint8_t gps_payload[] = {0x02, 0x04, 0x07, 0x09, 0x1B}; + const uint8_t gps_checksum[] = {0xA8, 0xAA, 0xAD, 0xAF, 0xC1}; + const uint8_t gps_ender[] = {0xB0, 0xB3}; + + for(int z = 0; z < 2; z++){ + for(int x = 0; x < 5; x++){ + _port->write(gps_header, sizeof(gps_header)); // Prints the msg header, is the same header for all msg.. + _port->write(gps_payload[x]); // Prints the payload, is not the same for every msg + for(int y = 0; y < 6; y++) // Prints 6 zeros + _port->write((uint8_t)0); + _port->write(gps_checksum[x]); // Print the Checksum + _port->write(gps_ender[0]); // Print the Ender of the string, is same on all msg's. + _port->write(gps_ender[1]); // ender + } + } +} + +// The EM406 defalts to NMEA at 4800bps. We want to switch it to SiRF binary +// mode at a higher rate. +// +// The change is sticky, but only for as long as the internal supercap holds +// settings (usually less than a week). +// +void +AP_GPS_406::_change_to_sirf_protocol(void) +{ + FastSerial *fs = (FastSerial *)_port; // this is a bit grody... + + fs->begin(4800); + delay(300); + _port->print(init_str); + delay(300); + + fs->begin(9600); + delay(300); + _port->print(init_str); + delay(300); + + fs->begin(GPS_406_BITRATE); + delay(300); + _port->print(init_str); + delay(300); +} + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_406.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_406.h new file mode 100644 index 0000000000..39b6e55164 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_406.h @@ -0,0 +1,32 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- +// +// EM406 GPS driver for ArduPilot and ArduPilotMega. +// Code by Michael Smith, Jason Short, Jordi Muoz and Jose Julio. DIYDrones.com +// +// This library is free software; you can redistribute it and / or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 2.1 of the License, or (at your option) any later version. +// + +#ifndef AP_GPS_406_h +#define AP_GPS_406_h + +#include "AP_GPS_SIRF.h" + +#define GPS_406_BITRATE 57600 + +class AP_GPS_406 : public AP_GPS_SIRF +{ +public: + // Methods + AP_GPS_406(Stream *port); + void init(void); + +private: + void _change_to_sirf_protocol(void); + void _configure_gps(void); +}; + +#endif + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_Auto.cpp b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_Auto.cpp new file mode 100644 index 0000000000..727b1eac74 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_Auto.cpp @@ -0,0 +1,162 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- +// +// Auto-detecting pseudo-GPS driver +// + +#include "AP_GPS.h" +#include +#include +#include + +static unsigned int baudrates[] = {38400U, 57600U, 9600U, 4800U}; + +void +AP_GPS_Auto::init(void) +{ +} + +// +// Called the first time that a client tries to kick the GPS to update. +// +// We detect the real GPS, then update the pointer we have been called through +// and return. +void +AP_GPS_Auto::update(void) +{ + GPS *gps; + int i; + + // loop trying to find a GPS + for (;;) { + // loop through possible baudrates + for (i = 0; i < (sizeof(baudrates) / sizeof(baudrates[0])); i++) { + printf("GPS autodetect at %d:%u\n", i, baudrates[i]); + _port->begin(baudrates[i]); + if (NULL != (gps = _detect())) { + // make the detected GPS the default + *_gps = gps; + + // configure the detected GPS and run one update + gps->print_errors = true; // XXX + gps->init(); + gps->update(); + + // drop back to our caller - subsequent calls through + // the global will not come here + return; + } + } + } +} + +// +// Perform one iteration of the auto-detection process. +// +GPS * +AP_GPS_Auto::_detect(void) +{ + unsigned long then; + int fingerprint[4]; + int tries; + GPS *gps; + + // + // Loop attempting to detect a recognised GPS + // + gps = NULL; + for (tries = 0; tries < 2; tries++) { + + // + // Empty the serial buffer and wait for 50ms of quiet. + // + // XXX We can detect babble by counting incoming characters, but + // what would we do about it? + // + _port->flush(); + then = millis(); + do { + if (_port->available()) { + then = millis(); + _port->read(); + } + } while ((millis() - then) < 50); + + // + // Collect four characters to fingerprint a device + // + fingerprint[0] = _getc(); + fingerprint[1] = _getc(); + fingerprint[2] = _getc(); + fingerprint[3] = _getc(); + printf("fingerprints 0x%02x 0x%02x 0x%02x 0x%02x\n", + fingerprint[0], + fingerprint[1], + fingerprint[2], + fingerprint[3]); + + // + // u-blox or MTK in DIYD binary mode (whose smart idea was + // it to make the MTK look sort-of like it was talking UBX?) + // + if ((0xb5 == fingerprint[0]) && + (0x62 == fingerprint[1]) && + (0x01 == fingerprint[2])) { + + // message 5 is MTK pretending to talk UBX + if (0x05 == fingerprint[3]) { + printf("detected MTK in binary mode\n"); + gps = new AP_GPS_MTK(_port); + break; + } + + // any other message is u-blox + printf("detected u-blox in binary mode\n"); + gps = new AP_GPS_UBLOX(_port); + break; + } + + // + // SIRF in binary mode + // + if ((0xa0 == fingerprint[0]) && + (0xa2 == fingerprint[1])) { + printf("detected SIRF in binary mode\n"); + gps = new AP_GPS_SIRF(_port); + break; + } + + // + // If we haven't spammed the various init strings, send them now + // and retry to avoid a false-positive on the NMEA detector. + // + if (0 == tries) { + printf("sending setup strings and trying again\n"); + _port->println(MTK_SET_BINARY); + _port->println(UBLOX_SET_BINARY); + _port->println(SIRF_SET_BINARY); + continue; + } + + // + // Something talking NMEA + // + if (('$' == fingerprint[0]) && + (('G' == fingerprint[1]) || ('P' == fingerprint[1]))) { + + // XXX this may be a bit presumptive, might want to give the GPS a couple of + // iterations around the loop to react to init strings? + printf("detected NMEA\n"); + gps = new AP_GPS_NMEA(_port); + break; + } + } + return(gps); +} + +int +AP_GPS_Auto::_getc(void) +{ + while (0 == _port->available()) + ; + return(_port->read()); +} diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_Auto.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_Auto.h new file mode 100644 index 0000000000..a259add7c0 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_Auto.h @@ -0,0 +1,52 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- +// +// Auto-detecting pseudo-GPS driver +// + +#ifndef AP_GPS_Auto_h +#define AP_GPS_Auto_h + +#include +#include + +class AP_GPS_Auto : public GPS +{ +public: + /// Constructor + /// + /// @note The stream is expected to be set up and configured for the + /// correct bitrate before ::init is called. + /// + /// @param port Stream connected to the GPS module. + /// @param ptr Pointer to a GPS * that will be fixed up by ::init + /// when the GPS type has been detected. + /// + AP_GPS_Auto(FastSerial *port, GPS **gps) : + _port(port), + _gps(gps) + {}; + + void init(void); + + /// Detect and initialise the attached GPS unit. Returns a + /// pointer to the allocated & initialised GPS driver. + /// + void update(void); + +private: + /// Serial port connected to the GPS. + FastSerial *_port; + + /// global GPS driver pointer, updated by auto-detection + /// + GPS **_gps; + + /// low-level auto-detect routine + /// + GPS *_detect(void); + + /// fetch a character from the port + /// + int _getc(void); +}; +#endif diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_IMU.cpp b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_IMU.cpp new file mode 100644 index 0000000000..53195ef75f --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_IMU.cpp @@ -0,0 +1,224 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- +/* + GPS_MTK.cpp - Ublox GPS library for Arduino + Code by Jordi Muoz and Jose Julio. DIYDrones.com + This code works with boards based on ATMega168/328 and ATMega1280 (Serial port 1) + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + GPS configuration : Costum protocol + Baud rate : 38400 + + Methods: + init() : GPS initialization + update() : Call this funcion as often as you want to ensure you read the incomming gps data + + Properties: + lattitude : lattitude * 10000000 (long value) + longitude : longitude * 10000000 (long value) + altitude : altitude * 100 (meters) (long value) + ground_speed : Speed (m/s) * 100 (long value) + ground_course : Course (degrees) * 100 (long value) + new_data : 1 when a new data is received. + You need to write a 0 to new_data when you read the data + fix : 1: GPS NO fix, 2: 2D fix, 3: 3D fix. + +*/ +#include "AP_GPS_IMU.h" +#include "WProgram.h" + + +// Constructors //////////////////////////////////////////////////////////////// +AP_GPS_IMU::AP_GPS_IMU(Stream *s) : GPS(s) +{ +} + + +// Public Methods ////////////////////////////////////////////////////////////// +void AP_GPS_IMU::init(void) +{ + // we expect the stream to already be open at the corret bitrate +} + +// optimization : This code doesn't wait for data. It only proccess the data available. +// We can call this function on the main loop (50Hz loop) +// If we get a complete packet this function calls parse_IMU_gps() to parse and update the GPS info. +void AP_GPS_IMU::update(void) +{ + byte data; + int numc = 0; + static byte message_num = 0; + + numc = _port->available(); + + if (numc > 0){ + for (int i=0;iread(); + + switch(step){ //Normally we start from zero. This is a state machine + case 0: + if(data == 0x44) // IMU sync char 1 + step++; //OH first data packet is correct, so jump to the next step + break; + + case 1: + if(data == 0x49) // IMU sync char 2 + step++; //ooh! The second data packet is correct, jump to the step 2 + else + step=0; //Nop, is not correct so restart to step zero and try again. + break; + + case 2: + if(data == 0x59) // IMU sync char 3 + step++; //ooh! The second data packet is correct, jump to the step 2 + else + step=0; //Nop, is not correct so restart to step zero and try again. + break; + + case 3: + if(data == 0x64) // IMU sync char 4 + step++; //ooh! The second data packet is correct, jump to the step 2 + else + step=0; //Nop, is not correct so restart to step zero and try again. + break; + + case 4: + payload_length = data; + checksum(payload_length); + step++; + if (payload_length > 28){ + step = 0; //Bad data, so restart to step zero and try again. + payload_counter = 0; + ck_a = 0; + ck_b = 0; + //payload_error_count++; + } + break; + + case 5: + message_num = data; + checksum(data); + step++; + break; + + case 6: // Payload data read... + // We stay in this state until we reach the payload_length + buffer[payload_counter] = data; + checksum(data); + payload_counter++; + if (payload_counter >= payload_length) { + step++; + } + break; + + case 7: + GPS_ck_a = data; // First checksum byte + step++; + break; + + case 8: + GPS_ck_b = data; // Second checksum byte + + // We end the IMU/GPS read... + // Verify the received checksum with the generated checksum.. + if((ck_a == GPS_ck_a) && (ck_b == GPS_ck_b)) { + if (message_num == 0x02) { + join_data(); + } else if (message_num == 0x03) { + GPS_join_data(); + } else if (message_num == 0x04) { + join_data_xplane(); + } else if (message_num == 0x0a) { + //PERF_join_data(); + } else { + _error("Invalid message number = %d\n", (int)message_num); + } + } else { + _error("XXX Checksum error\n"); //bad checksum + //imu_checksum_error_count++; + } + // Variable initialization + step = 0; + payload_counter = 0; + ck_a = 0; + ck_b = 0; + break; + } + }// End for... + } +} + +/**************************************************************** + * + ****************************************************************/ + +void AP_GPS_IMU::join_data(void) +{ + //Verifing if we are in class 1, you can change this "IF" for a "Switch" in case you want to use other IMU classes.. + //In this case all the message im using are in class 1, to know more about classes check PAGE 60 of DataSheet. + + //Storing IMU roll + roll_sensor = *(int *)&buffer[0]; + + //Storing IMU pitch + pitch_sensor = *(int *)&buffer[2]; + + //Storing IMU heading (yaw) + ground_course = *(int *)&buffer[4]; + imu_ok = true; +} + +void AP_GPS_IMU::join_data_xplane() +{ + //Storing IMU roll + roll_sensor = *(int *)&buffer[0]; + + + //Storing IMU pitch + pitch_sensor = *(int *)&buffer[2]; + + //Storing IMU heading (yaw) + ground_course = *(unsigned int *)&buffer[4]; + + //Storing airspeed + airspeed = *(int *)&buffer[6]; + + imu_ok = true; + +} + +void AP_GPS_IMU::GPS_join_data(void) +{ + longitude = *(long *)&buffer[0]; // degrees * 10e7 + latitude = *(long *)&buffer[4]; + + //Storing GPS Height above the sea level + altitude = (long)*(int *)&buffer[8] * 10; + + //Storing Speed + speed_3d = ground_speed = (float)*(int *)&buffer[10]; + + //We skip the gps ground course because we use yaw value from the IMU for ground course + time = *(long *)&buffer[14]; + + imu_health = buffer[15]; + + new_data = true; + fix = true; +} + + + +/**************************************************************** + * + ****************************************************************/ +// checksum algorithm +void AP_GPS_IMU::checksum(byte data) +{ + ck_a += data; + ck_b += ck_a; +} diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_IMU.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_IMU.h new file mode 100644 index 0000000000..0e3f1d294f --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_IMU.h @@ -0,0 +1,44 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- +#ifndef AP_GPS_IMU_h +#define AP_GPS_IMU_h + +#include +#define MAXPAYLOAD 32 + +class AP_GPS_IMU : public GPS +{ + public: + + // Methods + AP_GPS_IMU(Stream *s); + void init(); + void update(); + + // Properties + long roll_sensor; // how much we're turning in deg * 100 + long pitch_sensor; // our angle of attack in deg * 100 + int airspeed; + float imu_health; + uint8_t imu_ok; + + private: + // Packet checksums + uint8_t ck_a; + uint8_t ck_b; + uint8_t GPS_ck_a; + uint8_t GPS_ck_b; + + uint8_t step; + uint8_t msg_class; + uint8_t message_num; + uint8_t payload_length; + uint8_t payload_counter; + uint8_t buffer[MAXPAYLOAD]; + + void join_data(); + void join_data_xplane(); + void GPS_join_data(); + void checksum(unsigned char data); +}; + +#endif diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_MTK.cpp b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_MTK.cpp new file mode 100644 index 0000000000..db281390c0 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_MTK.cpp @@ -0,0 +1,146 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- +// +// DIYDrones Custom Mediatek GPS driver for ArduPilot and ArduPilotMega. +// Code by Michael Smith, Jordi Munoz and Jose Julio, DIYDrones.com +// +// This library is free software; you can redistribute it and / or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 2.1 of the License, or (at your option) any later version. +// +// GPS configuration : Custom protocol per "DIYDrones Custom Binary Sentence Specification V1.1" +// + +#include "AP_GPS_MTK.h" +#include "WProgram.h" + +// Constructors //////////////////////////////////////////////////////////////// +AP_GPS_MTK::AP_GPS_MTK(Stream *s) : GPS(s) +{ +} + +// Public Methods ////////////////////////////////////////////////////////////// +void AP_GPS_MTK::init(void) +{ + _port->flush(); + // initialize serial port for binary protocol use + // XXX should assume binary, let GPS_AUTO handle dynamic config? + _port->print(MTK_SET_BINARY); + + // set 4Hz update rate + _port->print(MTK_OUTPUT_4HZ); +} + +// Process bytes available from the stream +// +// The stream is assumed to contain only our custom message. If it +// contains other messages, and those messages contain the preamble bytes, +// it is possible for this code to become de-synchronised. Without +// buffering the entire message and re-processing it from the top, +// this is unavoidable. +// +// The lack of a standard header length field makes it impossible to skip +// unrecognised messages. +// +void AP_GPS_MTK::update(void) +{ + byte data; + int numc; + + numc = _port->available(); + for (int i = 0; i < numc; i++){ // Process bytes received + + // read the next byte + data = _port->read(); + +restart: + switch(_step){ + + // Message preamble, class, ID detection + // + // If we fail to match any of the expected bytes, we + // reset the state machine and re-consider the failed + // byte as the first byte of the preamble. This + // improves our chances of recovering from a mismatch + // and makes it less likely that we will be fooled by + // the preamble appearing as data in some other message. + // + case 0: + if(PREAMBLE1 == data) + _step++; + break; + case 1: + if (PREAMBLE2 == data) { + _step++; + break; + } + _step = 0; + goto restart; + case 2: + if (MESSAGE_CLASS == data) { + _step++; + _ck_b = _ck_a = data; // reset the checksum accumulators + } else { + _step = 0; // reset and wait for a message of the right class + goto restart; + } + break; + case 3: + if (MESSAGE_ID == data) { + _step++; + _ck_b += (_ck_a += data); + _payload_length = sizeof(diyd_mtk_msg); // prepare to receive our message + _payload_counter = 0; + } else { + _step = 0; + goto restart; + } + break; + + // Receive message data + // + case 4: + _buffer.bytes[_payload_counter++] = data; + _ck_b += (_ck_a += data); + if (_payload_counter == _payload_length) + _step++; + break; + + // Checksum and message processing + // + case 5: + _step++; + if (_ck_a != data) { + _error("GPS_MTK: checksum error\n"); + _step = 0; + } + break; + case 6: + _step = 0; + if (_ck_b != data) { + _error("GPS_MTK: checksum error\n"); + break; + } + _parse_gps(); // Parse the new GPS packet + } + } +} + +// Private Methods +void +AP_GPS_MTK::_parse_gps(void) +{ + fix = (_buffer.msg.fix_type == FIX_3D); + latitude = _swapl(&_buffer.msg.latitude) * 10; + longitude = _swapl(&_buffer.msg.longitude) * 10; + altitude = _swapl(&_buffer.msg.altitude); + ground_speed = _swapl(&_buffer.msg.ground_speed); + ground_course = _swapl(&_buffer.msg.ground_course) / 10000; + num_sats = _buffer.msg.satellites; + + // XXX docs say this is UTC, but our clients expect msToW + time = _swapl(&_buffer.msg.utc_time); + _setTime(); + valid_read = true; + new_data = true; +} diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_MTK.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_MTK.h new file mode 100644 index 0000000000..a69dca60df --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_MTK.h @@ -0,0 +1,87 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- +// +// DIYDrones Custom Mediatek GPS driver for ArduPilot and ArduPilotMega. +// Code by Michael Smith, Jordi Munoz and Jose Julio, DIYDrones.com +// +// This library is free software; you can redistribute it and / or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 2.1 of the License, or (at your option) any later version. +// +// GPS configuration : Custom protocol per "DIYDrones Custom Binary Sentence Specification V1.1" +// +#ifndef AP_GPS_MTK_h +#define AP_GPS_MTK_h + +#include +#define MAXPAYLOAD 32 + +#define MTK_SET_BINARY "$PGCMD,16,0,0,0,0,0*6A\r\n" +#define MTK_SET_NMEA "$PGCMD,16,1,1,1,1,1*6B\r\n" + +#define MTK_OUTPUT_1HZ "$PMTK220,1000*1F\r\n" +#define MTK_OUTPUT_2HZ "$PMTK220,500*2B\r\n" +#define MTK_OUTPUT_4HZ "$PMTK220,250*29\r\n" +#define MTK_OTUPUT_5HZ "$PMTK220,200*2C\r\n" +#define MTK_OUTPUT_10HZ "$PMTK220,100*2F\r\n" + +#define MTK_BAUD_RATE_38400 "$PMTK251,38400*27\r\n" + +#define SBAS_ON "$PMTK313,1*2E\r\n" +#define SBAS_OFF "$PMTK313,0*2F\r\n" + +#define WAAS_ON "$PSRF151,1*3F\r\n" +#define WAAS_OFF "$PSRF151,0*3E\r\n" + +class AP_GPS_MTK : public GPS { +public: + AP_GPS_MTK(Stream *s); + virtual void init(void); + virtual void update(void); + +private: +#pragma pack(1) + struct diyd_mtk_msg { + int32_t latitude; + int32_t longitude; + int32_t altitude; + int32_t ground_speed; + int32_t ground_course; + uint8_t satellites; + uint8_t fix_type; + uint32_t utc_time; + }; +#pragma pack(pop) + enum diyd_mtk_fix_type { + FIX_NONE = 1, + FIX_2D = 2, + FIX_3D = 3 + }; + + enum diyd_mtk_protocol_bytes { + PREAMBLE1 = 0xb5, + PREAMBLE2 = 0x62, + MESSAGE_CLASS = 1, + MESSAGE_ID = 5 + }; + + // Packet checksum accumulators + uint8_t _ck_a; + uint8_t _ck_b; + + // State machine state + uint8_t _step; + uint8_t _payload_length; + uint8_t _payload_counter; + + // Receive buffer + union { + diyd_mtk_msg msg; + uint8_t bytes[]; + } _buffer; + + // Buffer parse & GPS state update + void _parse_gps(); +}; + +#endif // AP_GPS_MTK_H diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_NMEA.cpp b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_NMEA.cpp new file mode 100644 index 0000000000..4f9bf6f6c0 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_NMEA.cpp @@ -0,0 +1,246 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- +/* + GPS_NMEA.cpp - Generic NMEA GPS library for Arduino + Code by Jordi Muoz and Jose Julio. DIYDrones.com + Edits by HappyKillmore + This code works with boards based on ATMega168 / 328 and ATMega1280 (Serial port 1) + + This library is free software; you can redistribute it and / or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + GPS configuration : NMEA protocol + Baud rate : 38400 + NMEA Sentences : + $GPGGA : Global Positioning System fix Data + $GPVTG : Ttack and Ground Speed + + Methods: + init() : GPS Initialization + update() : Call this funcion as often as you want to ensure you read the incomming gps data + + Properties: + latitude : latitude * 10000000 (long value) + longitude : longitude * 10000000 (long value) + altitude : altitude * 1000 (milimeters) (long value) + ground_speed : Speed (m / s) * 100 (long value) + ground_course : Course (degrees) * 100 (long value) + Type : 2 (This indicate that we are using the Generic NMEA library) + new_data : 1 when a new data is received. + You need to write a 0 to new_data when you read the data + fix : > = 1: GPS FIX, 0: No fix (normal logic) + quality : 0 = No fix + 1 = Bad (Num sats < 5) + 2 = Poor + 3 = Medium + 4 = Good + + NOTE : This code has been tested on a Locosys 20031 GPS receiver (MTK chipset) +*/ +#include "AP_GPS_NMEA.h" +#include "WProgram.h" + +// Constructors //////////////////////////////////////////////////////////////// +AP_GPS_NMEA::AP_GPS_NMEA(Stream *s) : GPS(s) +{ +} + +// Public Methods ////////////////////////////////////////////////////////////// +void +AP_GPS_NMEA::init(void) +{ + //Type = 2; + // initialize serial port for binary protocol use + _port->print(NMEA_OUTPUT_SENTENCES); + _port->print(NMEA_OUTPUT_4HZ); + _port->print(SBAS_ON); + _port->print(DGPS_SBAS); + _port->print(DATUM_GOOGLE); +} + +// This code dont wait for data, only proccess the data available on serial port +// We can call this function on the main loop (50Hz loop) +// If we get a complete packet this function call parse_nmea_gps() to parse and update the GPS info. +void +AP_GPS_NMEA::update(void) +{ + char c; + int numc; + int i; + + numc = _port->available(); + + if (numc > 0){ + for (i = 0; i < numc; i++){ + c = _port->read(); + if (c == '$'){ // NMEA Start + bufferidx = 0; + buffer[bufferidx++] = c; + GPS_checksum = 0; + GPS_checksum_calc = true; + continue; + } + if (c == '\r'){ // NMEA End + buffer[bufferidx++] = 0; + parse_nmea_gps(); + } else { + if (bufferidx < (GPS_BUFFERSIZE - 1)){ + if (c == '*') + GPS_checksum_calc = false; // Checksum calculation end + buffer[bufferidx++] = c; + if (GPS_checksum_calc){ + GPS_checksum ^= c; // XOR + } + } else { + bufferidx = 0; // Buffer overflow : restart + } + } + } + } +} + +/**************************************************************** + * + * * ** * ** * ** * ** * ** * ** * ** * ** * ** * ** * ** * ** * ** * ** * ** * ** * ** * ** * ** * ** * **/ +// Private Methods ////////////////////////////////////////////////////////////// +void +AP_GPS_NMEA::parse_nmea_gps(void) +{ + uint8_t NMEA_check; + long aux_deg; + long aux_min; + char *parseptr; + + if (strncmp(buffer,"$GPGGA",6)==0){ // Check if sentence begins with $GPGGA + if (buffer[bufferidx-4]=='*'){ // Check for the "*" character + NMEA_check = parseHex(buffer[bufferidx - 3]) * 16 + parseHex(buffer[bufferidx - 2]); // Read the checksums characters + if (GPS_checksum == NMEA_check){ // Checksum validation + //Serial.println("buffer"); + _setTime(); + valid_read = true; + new_data = true; // New GPS Data + parseptr = strchr(buffer, ',')+1; + //parseptr = strchr(parseptr, ',')+1; + time = parsenumber(parseptr, 2); // GPS UTC time hhmmss.ss + parseptr = strchr(parseptr, ',')+1; + aux_deg = parsedecimal(parseptr, 2); // degrees + aux_min = parsenumber(parseptr + 2, 4); // minutes (sexagesimal) => Convert to decimal + latitude = aux_deg * 10000000 + (aux_min * 50) / 3; // degrees + minutes / 0.6 ( * 10000000) (0.6 = 3 / 5) + parseptr = strchr(parseptr, ',')+1; + if ( * parseptr == 'S') + latitude = -1 * latitude; // South latitudes are negative + parseptr = strchr(parseptr, ',')+1; + // W longitudes are Negative + aux_deg = parsedecimal(parseptr, 3); // degrees + aux_min = parsenumber(parseptr + 3, 4); // minutes (sexagesimal) + longitude = aux_deg * 10000000 + (aux_min * 50) / 3; // degrees + minutes / 0.6 ( * 10000000) + //longitude = -1*longitude; // This Assumes that we are in W longitudes... + parseptr = strchr(parseptr, ',')+1; + if ( * parseptr == 'W') + longitude = -1 * longitude; // West longitudes are negative + parseptr = strchr(parseptr, ',')+1; + fix = parsedecimal(parseptr, 1); + parseptr = strchr(parseptr, ',')+1; + num_sats = parsedecimal(parseptr, 2); + parseptr = strchr(parseptr, ',')+1; + HDOP = parsenumber(parseptr, 1); // HDOP * 10 + parseptr = strchr(parseptr, ',')+1; + altitude = parsenumber(parseptr, 1) * 100; // altitude in decimeters * 100 = milimeters + if (fix < 1) + quality = 0; // No FIX + else if(num_sats < 5) + quality = 1; // Bad (Num sats < 5) + else if(HDOP > 30) + quality = 2; // Poor (HDOP > 30) + else if(HDOP > 25) + quality = 3; // Medium (HDOP > 25) + else + quality = 4; // Good (HDOP < 25) + } else { + _error("GPSERR: Checksum error!!\n"); + } + } + } else if (strncmp(buffer,"$GPVTG",6)==0){ // Check if sentence begins with $GPVTG + //Serial.println(buffer); + if (buffer[bufferidx-4]=='*'){ // Check for the "*" character + NMEA_check = parseHex(buffer[bufferidx - 3]) * 16 + parseHex(buffer[bufferidx - 2]); // Read the checksums characters + if (GPS_checksum == NMEA_check){ // Checksum validation + _setTime(); + valid_read = true; + new_data = true; // New GPS Data + parseptr = strchr(buffer, ',')+1; + ground_course = parsenumber(parseptr, 2); // Ground course in degrees * 100 + parseptr = strchr(parseptr, ',')+1; + parseptr = strchr(parseptr, ',')+1; + parseptr = strchr(parseptr, ',')+1; + parseptr = strchr(parseptr, ',')+1; + parseptr = strchr(parseptr, ',')+1; + parseptr = strchr(parseptr, ',')+1; + ground_speed = parsenumber(parseptr, 2) * 10 / 36; // Convert Km / h to m / s ( * 100) + //GPS_line = true; + } else { + _error("GPSERR: Checksum error!!\n"); + } + } + } else { + bufferidx = 0; + _error("GPSERR: Bad sentence!!\n"); + } +} + + + // Parse hexadecimal numbers +uint8_t +AP_GPS_NMEA::parseHex(char c) { + if (c < '0') + return (0); + if (c <= '9') + return (c - '0'); + if (c < 'A') + return (0); + if (c <= 'F') + return ((c - 'A')+10); +} + +// Decimal number parser +long +AP_GPS_NMEA::parsedecimal(char *str, uint8_t num_car) { + long d = 0; + uint8_t i; + + i = num_car; + while ((str[0] != 0) && (i > 0)) { + if ((str[0] > '9') || (str[0] < '0')) + return d; + d *= 10; + d += str[0] - '0'; + str++; + i--; + } + return d; +} + +// Function to parse fixed point numbers (numdec=number of decimals) +long +AP_GPS_NMEA::parsenumber(char *str, uint8_t numdec) { + long d = 0; + uint8_t ndec = 0; + + while (str[0] != 0) { + if (str[0] == '.'){ + ndec = 1; + } else { + if ((str[0] > '9') || (str[0] < '0')) + return d; + d *= 10; + d += str[0] - '0'; + if (ndec > 0) + ndec++; + if (ndec > numdec) // we reach the number of decimals... + return d; + } + str++; + } + return d; +} diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_NMEA.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_NMEA.h new file mode 100644 index 0000000000..b7b46bee15 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_NMEA.h @@ -0,0 +1,60 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- +#ifndef AP_GPS_NMEA_h +#define AP_GPS_NMEA_h + +#include +#define GPS_BUFFERSIZE 120 + +#define NMEA_OUTPUT_SENTENCES "$PMTK314,0,0,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0*28\r\n" //Set GPGGA and GPVTG + +#define NMEA_BAUD_RATE_4800 "$PSRF100,1,4800,8,1,0*0E\r\n" +#define NMEA_BAUD_RATE_9600 "$PSRF100,1,9600,8,1,0*0D\r\n" +#define NMEA_BAUD_RATE_19200 "$PSRF100,1,19200,8,1,0*38\r\n" +#define NMEA_BAUD_RATE_38400 "$PSRF100,1,38400,8,1,0*3D\r\n" +#define NMEA_BAUD_RATE_57600 "$PSRF100,1,57600,8,1,0*36\r\n" + +#define NMEA_OUTPUT_1HZ "$PMTK220,1000*1F\r\n" +#define NMEA_OUTPUT_2HZ "$PMTK220,500*2B\r\n" +#define NMEA_OUTPUT_4HZ "$PMTK220,250*29\r\n" +#define NMEA_OTUPUT_5HZ "$PMTK220,200*2C\r\n" +#define NMEA_OUTPUT_10HZ "$PMTK220,100*2F\r\n" + +#define SBAS_ON "$PMTK313,1*2E\r\n" +#define SBAS_OFF "$PMTK313,0*2F\r\n" + +#define WAAS_ON "$PSRF151,1*3F\r\n" +#define WAAS_OFF "$PSRF151,0*3E\r\n" + +#define DGPS_OFF "$PMTK301,0*2C\r\n" +#define DGPS_RTCM "$PMTK301,1*2D\r\n" +#define DGPS_SBAS "$PMTK301,2*2E\r\n" + +#define DATUM_GOOGLE "$PMTK330,0*2E\r\n" + +class AP_GPS_NMEA : public GPS +{ + public: + // Methods + AP_GPS_NMEA(Stream *s); + void init(); + void update(); + + // Properties + uint8_t quality; // GPS Signal quality + int HDOP; // HDOP + + private: + // Internal variables + uint8_t GPS_checksum; + uint8_t GPS_checksum_calc; + char buffer[GPS_BUFFERSIZE]; + int bufferidx; + + void parse_nmea_gps(void); + uint8_t parseHex(char c); + long parsedecimal(char *str,uint8_t num_car); + long parsenumber(char *str,uint8_t numdec); + +}; + +#endif diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_None.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_None.h new file mode 100644 index 0000000000..23f242b59c --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_None.h @@ -0,0 +1,13 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- + +#ifndef AP_GPS_None_h +#define AP_GPS_None_h + +#include + +class AP_GPS_None : public GPS +{ + virtual void init(void) {}; + virtual void update(void) {}; +}; +#endif diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_SIRF.cpp b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_SIRF.cpp new file mode 100644 index 0000000000..f1fe5e9f5c --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_SIRF.cpp @@ -0,0 +1,193 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- +// +// SiRF Binary GPS driver for ArduPilot and ArduPilotMega. +// Code by Michael Smith. +// +// This library is free software; you can redistribute it and / or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 2.1 of the License, or (at your option) any later version. +// + +#include "AP_GPS_SIRF.h" +#include "WProgram.h" + +// Initialisation messages +// +// Turn off all messages except for 0x29. +// +// XXX the bytes show up on the wire, but at least my test unit (EM-411) seems to ignore them. +// +static uint8_t init_messages[] = { + 0xa0, 0xa2, 0x00, 0x08, 0xa6, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xa8, 0xb0, 0xb3, + 0xa0, 0xa2, 0x00, 0x08, 0xa6, 0x00, 0x29, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0xd0, 0xb0, 0xb3 +}; + +// Constructors //////////////////////////////////////////////////////////////// +AP_GPS_SIRF::AP_GPS_SIRF(Stream *s) : GPS(s) +{ +} + +// Public Methods ////////////////////////////////////////////////////////////// +void AP_GPS_SIRF::init(void) +{ + _port->flush(); + + // For modules that default to something other than SiRF binary, + // the module-specific subclass should take care of switching to binary mode + // before calling us. + + // send SiRF binary setup messages + _port->write(init_messages, sizeof(init_messages)); +} + +// Process bytes available from the stream +// +// The stream is assumed to contain only messages we recognise. If it +// contains other messages, and those messages contain the preamble +// bytes, it is possible for this code to fail to synchronise to the +// stream immediately. Without buffering the entire message and +// re-processing it from the top, this is unavoidable. The parser +// attempts to avoid this when possible. +// +void AP_GPS_SIRF::update(void) +{ + byte data; + int numc; + + numc = _port->available(); + while(numc--) { + + // read the next byte + data = _port->read(); + + switch(_step){ + + // Message preamble detection + // + // If we fail to match any of the expected bytes, we reset + // the state machine and re-consider the failed byte as + // the first byte of the preamble. This improves our + // chances of recovering from a mismatch and makes it less + // likely that we will be fooled by the preamble appearing + // as data in some other message. + // + case 1: + if (PREAMBLE2 == data) { + _step++; + break; + } + _step = 0; + // FALLTHROUGH + case 0: + if(PREAMBLE1 == data) + _step++; + break; + + // Message length + // + // We always collect the length so that we can avoid being + // fooled by preamble bytes in messages. + // + case 2: + _step++; + _payload_length = (uint16_t)data << 8; + break; + case 3: + _step++; + _payload_length |= data; + _payload_counter = 0; + _checksum = 0; + break; + + // Message header processing + // + // We sniff the message ID to determine whether we are going + // to gather the message bytes or just discard them. + // + case 4: + _step++; + _accumulate(data); + _payload_length--; + _gather = false; + switch(data) { + case MSG_GEONAV: + if (_payload_length == sizeof(sirf_geonav)) { + _gather = true; + _msg_id = data; + } + break; + } + break; + + // Receive message data + // + // Note that we are effectively guaranteed by the protocol + // that the checksum and postamble cannot be mistaken for + // the preamble, so if we are discarding bytes in this + // message when the payload is done we return directly + // to the preamble detector rather than bothering with + // the checksum logic. + // + case 5: + if (_gather) { // gather data if requested + _accumulate(data); + _buffer.bytes[_payload_counter] = data; + if (++_payload_counter == _payload_length) + _step++; + } else { + if (++_payload_counter == _payload_length) + _step = 0; + } + break; + + // Checksum and message processing + // + case 6: + _step++; + if ((_checksum >> 8) != data) { + _error("GPS_SIRF: checksum error\n"); + _step = 0; + } + break; + case 7: + _step = 0; + if ((_checksum & 0xff) != data) { + _error("GPS_SIRF: checksum error\n"); + break; + } + if (_gather) { + _parse_gps(); // Parse the new GPS packet + } + } + } +} + +void +AP_GPS_SIRF::_parse_gps(void) +{ + switch(_msg_id) { + case MSG_GEONAV: + time = _swapl(&_buffer.nav.time); + //fix = (0 == _buffer.nav.fix_invalid) && (FIX_3D == (_buffer.nav.fix_type & FIX_MASK)); + fix = (0 == _buffer.nav.fix_invalid); + latitude = _swapl(&_buffer.nav.latitude); + longitude = _swapl(&_buffer.nav.longitude); + altitude = _swapl(&_buffer.nav.altitude_msl); + ground_speed = _swapi(&_buffer.nav.ground_speed); + // at low speeds, ground course wanders wildly; suppress changes if we are not moving + if (ground_speed > 50) + ground_course = _swapi(&_buffer.nav.ground_course); + num_sats = _buffer.nav.satellites; + _setTime(); + valid_read = 1; + break; + } + new_data = true; +} + +void +AP_GPS_SIRF::_accumulate(uint8_t val) +{ + _checksum = (_checksum + val) & 0x7fff; +} diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_SIRF.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_SIRF.h new file mode 100644 index 0000000000..ce3ff454be --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_SIRF.h @@ -0,0 +1,96 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- +// +// SiRF Binary GPS driver for ArduPilot and ArduPilotMega. +// Code by Michael Smith. +// +// This library is free software; you can redistribute it and / or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 2.1 of the License, or (at your option) any later version. +// +#ifndef AP_GPS_SIRF_h +#define AP_GPS_SIRF_h + +#include + +#define SIRF_SET_BINARY "$PSRF100,0,38400,8,1,0*3C" + +class AP_GPS_SIRF : public GPS { +public: + AP_GPS_SIRF(Stream *s); + + virtual void init(); + virtual void update(); + +private: +#pragma pack(1) + struct sirf_geonav { + uint16_t fix_invalid; + uint16_t fix_type; + uint16_t week; + uint32_t time; + uint16_t year; + uint8_t month; + uint8_t day; + uint8_t hour; + uint8_t minute; + uint16_t second; + uint32_t satellites_used; + int32_t latitude; + int32_t longitude; + int32_t altitude_ellipsoid; + int32_t altitude_msl; + int8_t map_datum; + int16_t ground_speed; + int16_t ground_course; + int16_t res1; + int16_t climb_rate; + uint16_t heading_rate; + uint32_t horizontal_position_error; + uint32_t vertical_position_error; + uint32_t time_error; + int16_t horizontal_velocity_error; + int32_t clock_bias; + uint32_t clock_bias_error; + int32_t clock_drift; + uint32_t clock_drift_error; + uint32_t distance; + uint16_t distance_error; + uint16_t heading_error; + uint8_t satellites; + uint8_t hdop; + uint8_t mode_info; + }; +#pragma pack(pop) + enum sirf_protocol_bytes { + PREAMBLE1 = 0xa0, + PREAMBLE2 = 0xa2, + POSTAMBLE1 = 0xb0, + POSTAMBLE2 = 0xb3, + MSG_GEONAV = 0x29 + }; + enum sirf_fix_type { + FIX_3D = 0x6, + FIX_MASK = 0x7 + }; + + + // State machine state + uint8_t _step; + uint16_t _checksum; + bool _gather; + uint16_t _payload_length; + uint16_t _payload_counter; + uint8_t _msg_id; + + // Message buffer + union { + sirf_geonav nav; + uint8_t bytes[]; + } _buffer; + + void _parse_gps(void); + void _accumulate(uint8_t val); +}; + +#endif // AP_GPS_SIRF_h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_UBLOX.cpp b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_UBLOX.cpp new file mode 100644 index 0000000000..cd2541d118 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_UBLOX.cpp @@ -0,0 +1,192 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- +// +// u-blox UBX GPS driver for ArduPilot and ArduPilotMega. +// Code by Michael Smith, Jordi Munoz and Jose Julio, DIYDrones.com +// +// This library is free software; you can redistribute it and / or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 2.1 of the License, or (at your option) any later version. +// + +#include "AP_GPS_UBLOX.h" +#include "WProgram.h" + +// Constructors //////////////////////////////////////////////////////////////// + +AP_GPS_UBLOX::AP_GPS_UBLOX(Stream *s) : GPS(s) +{ +} + +// Public Methods ////////////////////////////////////////////////////////////// + +void AP_GPS_UBLOX::init(void) +{ + // XXX it might make sense to send some CFG_MSG,CFG_NMEA messages to get the + // right reporting configuration. + + _port->flush(); +} + +// Process bytes available from the stream +// +// The stream is assumed to contain only messages we recognise. If it +// contains other messages, and those messages contain the preamble +// bytes, it is possible for this code to fail to synchronise to the +// stream immediately. Without buffering the entire message and +// re-processing it from the top, this is unavoidable. The parser +// attempts to avoid this when possible. +// +void AP_GPS_UBLOX::update(void) +{ + byte data; + int numc; + + numc = _port->available(); + for (int i = 0; i < numc; i++){ // Process bytes received + + // read the next byte + data = _port->read(); + + switch(_step){ + + // Message preamble detection + // + // If we fail to match any of the expected bytes, we reset + // the state machine and re-consider the failed byte as + // the first byte of the preamble. This improves our + // chances of recovering from a mismatch and makes it less + // likely that we will be fooled by the preamble appearing + // as data in some other message. + // + case 1: + if (PREAMBLE2 == data) { + _step++; + break; + } + _step = 0; + // FALLTHROUGH + case 0: + if(PREAMBLE1 == data) + _step++; + break; + + // Message header processing + // + // We sniff the class and message ID to decide whether we + // are going to gather the message bytes or just discard + // them. + // + // We always collect the length so that we can avoid being + // fooled by preamble bytes in messages. + // + case 2: + _step++; + if (CLASS_NAV == data) { + _gather = true; // class is interesting, maybe gather + _ck_b = _ck_a = data; // reset the checksum accumulators + } else { + _error("ignoring class 0x%x\n", (int)data); + _gather = false; // class is not interesting, discard + } + break; + case 3: + _step++; + _ck_b += (_ck_a += data); // checksum byte + _msg_id = data; + if (_gather) { // if class was interesting + switch(data) { + case MSG_POSLLH: // message is interesting + _expect = sizeof(ubx_nav_posllh); + break; + case MSG_STATUS: + _expect = sizeof(ubx_nav_status); + break; + case MSG_SOL: + _expect = sizeof(ubx_nav_solution); + break; + case MSG_VELNED: + _expect = sizeof(ubx_nav_velned); + break; + default: + _error("ignoring message 0x%x\n", (int)data); + _gather = false; // message is not interesting + } + } + break; + case 4: + _step++; + _ck_b += (_ck_a += data); // checksum byte + _payload_length = data; // payload length low byte + break; + case 5: + _step++; + _ck_b += (_ck_a += data); // checksum byte + _payload_length += (uint16_t)data; // payload length high byte + _payload_counter = 0; // prepare to receive payload + if (_payload_length != _expect) { + _error("payload %d expected %d\n", _payload_length, _expect); + _gather = false; + } + break; + + // Receive message data + // + case 6: + _ck_b += (_ck_a += data); // checksum byte + if (_gather) // gather data if requested + _buffer.bytes[_payload_counter] = data; + if (++_payload_counter == _payload_length) + _step++; + break; + + // Checksum and message processing + // + case 7: + _step++; + if (_ck_a != data) { + _error("GPS_UBLOX: checksum error\n"); + _step = 0; + } + break; + case 8: + _step = 0; + if (_ck_b != data) { + _error("GPS_UBLOX: checksum error\n"); + break; + } + if (_gather) + _parse_gps(); // Parse the new GPS packet + } + } +} + +// Private Methods ///////////////////////////////////////////////////////////// + +void +AP_GPS_UBLOX::_parse_gps(void) +{ + switch (_msg_id) { + case MSG_POSLLH: + time = _buffer.posllh.time; + longitude = _buffer.posllh.longitude; + latitude = _buffer.posllh.latitude; + altitude = _buffer.posllh.altitude_msl / 10; + break; + case MSG_STATUS: + fix = (_buffer.status.fix_status & NAV_STATUS_FIX_VALID) && (_buffer.status.fix_type == FIX_3D); + break; + case MSG_SOL: + fix = (_buffer.solution.fix_status & NAV_STATUS_FIX_VALID) && (_buffer.solution.fix_type == FIX_3D); + num_sats = _buffer.solution.satellites; + break; + case MSG_VELNED: + speed_3d = _buffer.velned.speed_3d; // cm/s + ground_speed = _buffer.velned.speed_2d; // cm/s + ground_course = _buffer.velned.heading_2d / 1000; // Heading 2D deg * 100000 rescaled to deg * 100 + break; + } + _setTime(); + valid_read = 1; + new_data = 1; +} diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_UBLOX.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_UBLOX.h new file mode 100644 index 0000000000..ce905a85e8 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_UBLOX.h @@ -0,0 +1,124 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- +// +// u-blox UBX GPS driver for ArduPilot and ArduPilotMega. +// Code by Michael Smith, Jordi Munoz and Jose Julio, DIYDrones.com +// +// This library is free software; you can redistribute it and / or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 2.1 of the License, or (at your option) any later version. +// +#ifndef AP_GPS_UBLOX_h +#define AP_GPS_UBLOX_h + +#include + +#define UBLOX_SET_BINARY "$PUBX,41,1,0003,0001,38400,0*26" + +class AP_GPS_UBLOX : public GPS +{ +public: + // Methods + AP_GPS_UBLOX(Stream *s = NULL); + void init(void); + void update(); + +private: + // u-blox UBX protocol essentials +#pragma pack(1) + struct ubx_nav_posllh { + uint32_t time; // GPS msToW + int32_t longitude; + int32_t latitude; + int32_t altitude_ellipsoid; + int32_t altitude_msl; + uint32_t horizontal_accuracy; + uint32_t vertical_accuracy; + }; + struct ubx_nav_status { + uint32_t time; // GPS msToW + uint8_t fix_type; + uint8_t fix_status; + uint8_t differential_status; + uint8_t res; + uint32_t time_to_first_fix; + uint32_t uptime; // milliseconds + }; + struct ubx_nav_solution { + uint32_t time; + int32_t time_nsec; + int16_t week; + uint8_t fix_type; + uint8_t fix_status; + int32_t ecef_x; + int32_t ecef_y; + int32_t ecef_z; + uint32_t position_accuracy_3d; + int32_t ecef_x_velocity; + int32_t ecef_y_velocity; + int32_t ecef_z_velocity; + uint32_t speed_accuracy; + uint16_t position_DOP; + uint8_t res; + uint8_t satellites; + uint32_t res2; + }; + struct ubx_nav_velned { + uint32_t time; // GPS msToW + int32_t ned_north; + int32_t ned_east; + int32_t ned_down; + uint32_t speed_3d; + uint32_t speed_2d; + int32_t heading_2d; + uint32_t speed_accuracy; + uint32_t heading_accuracy; + }; +#pragma pack(pop) + enum ubs_protocol_bytes { + PREAMBLE1 = 0xb5, + PREAMBLE2 = 0x62, + CLASS_NAV = 0x1, + MSG_POSLLH = 0x2, + MSG_STATUS = 0x3, + MSG_SOL = 0x6, + MSG_VELNED = 0x12 + }; + enum ubs_nav_fix_type { + FIX_NONE = 0, + FIX_DEAD_RECKONING = 1, + FIX_2D = 2, + FIX_3D = 3, + FIX_GPS_DEAD_RECKONING = 4, + FIX_TIME = 5 + }; + enum ubx_nav_status_bits { + NAV_STATUS_FIX_VALID = 1 + }; + + // Packet checksum accumulators + uint8_t _ck_a; + uint8_t _ck_b; + + // State machine state + uint8_t _step; + uint8_t _msg_id; + bool _gather; + uint16_t _expect; + uint16_t _payload_length; + uint16_t _payload_counter; + + // Receive buffer + union { + ubx_nav_posllh posllh; + ubx_nav_status status; + ubx_nav_solution solution; + ubx_nav_velned velned; + uint8_t bytes[]; + } _buffer; + + // Buffer parse & GPS state update + void _parse_gps(); +}; + +#endif diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/GPS.cpp b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/GPS.cpp new file mode 100644 index 0000000000..89bfefa1a0 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/GPS.cpp @@ -0,0 +1,35 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- + +#include "GPS.h" +#include "WProgram.h" +#include + +int +GPS::status(void) +{ + if (millis() - _lastTime >= 500){ + return 0; + } else if (fix == 0) { + return 1; + } else { + return 2; + } +} + +void +GPS::_setTime(void) +{ + _lastTime = millis(); +} + +void +GPS::_error(const char *fmt, ...) +{ + va_list ap; + + if (print_errors && stderr) { + va_start(ap, fmt); + vfprintf(stderr, fmt, ap); + va_end(ap); + } +} diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/GPS.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/GPS.h new file mode 100644 index 0000000000..219254ba41 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/GPS.h @@ -0,0 +1,150 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- + +/// @file GPS.h +/// @brief Interface definition for the various GPS drivers. + +#ifndef GPS_h +#define GPS_h + +#include +#include + +/// @class GPS +/// @brief Abstract base class for GPS receiver drivers. +class GPS +{ +public: + + /// Constructor + /// + /// @note The stream is expected to be set up and configured for the + /// correct bitrate before ::init is called. + /// + /// @param s Stream connected to the GPS module. If NULL, assumed + /// to be set up at ::init time. Support for setting + /// the port in the ctor for backwards compatibility. + /// + GPS(Stream *s = NULL) : _port(s) {}; + + /// Startup initialisation. + /// + /// This routine performs any one-off initialisation required to set the + /// GPS up for use. + /// + /// Must be implemented by the GPS driver. + /// + /// @param s Stream connected to the GPS module. If NULL, assumed to + /// have been set up at constructor time. + /// + virtual void init(void) = 0; + + /// Update GPS state based on possible bytes received from the module. + /// + /// This routine must be called periodically to process incoming data. + /// + /// Must be implemented by the GPS driver. + /// + virtual void update(void) = 0; + + /// Query GPS status + /// + /// The 'valid message' status indicates that a recognised message was + /// received from the GPS within the last 500ms. + /// + /// @todo should probably return an enumeration here. + /// + /// @return 0 No GPS connected/detected + /// @return 1 Receiving valid GPS messages but no lock + /// @return 2 Receiving valid messages and locked + /// + int status(void); + + // Properties + long time; ///< GPS time in milliseconds from the start of the week + long latitude; ///< latitude in degrees * 10,000,000 + long longitude; ///< longitude in degrees * 10,000,000 + long altitude; ///< altitude in cm + long ground_speed; ///< ground speed in cm/sec + long ground_course; ///< ground course in 100ths of a degree + long speed_3d; ///< 3D speed in cm/sec (not always available) + uint8_t num_sats; ///< Number of visible satelites + + /// Set to true when new data arrives. A client may set this + /// to false in order to avoid processing data they have + /// already seen. + bool new_data; + + // Deprecated properties + bool fix; ///< true if we have a position fix (use ::status instead) + bool valid_read; ///< true if we have seen data from the GPS (use ::status instead) + + // Debug support + bool print_errors; ///< if true, errors will be printed to stderr + +protected: + Stream *_port; ///< stream port the GPS is attached to + unsigned long _lastTime; ///< Timer for lost connection + + /// reset the last-message-received timer used by ::status + /// + void _setTime(void); + + /// perform an endian swap on a long + /// + /// @param bytes pointer to a buffer containing bytes representing a + /// long in the wrong byte order + /// @returns endian-swapped value + /// + long _swapl(const void *bytes); + + /// perform an endian swap on an int + /// + /// @param bytes pointer to a buffer containing bytes representing an + /// int in the wrong byte order + /// @returns endian-swapped value + int _swapi(const void *bytes); + + /// emit an error message + /// + /// based on the value of print_errors, emits the printf-formatted message + /// in msg,... to stderr + /// + /// @param fmt printf-like format string + /// + void _error(const char *msg, ...); + +}; + +inline long +GPS::_swapl(const void *bytes) +{ + const uint8_t *b = (const uint8_t *)bytes; + union { + long v; + uint8_t b[4]; + } u; + + u.b[0] = b[3]; + u.b[1] = b[2]; + u.b[2] = b[1]; + u.b[3] = b[0]; + + return(u.v); +} + +inline int16_t +GPS::_swapi(const void *bytes) +{ + const uint8_t *b = (const uint8_t *)bytes; + union { + int16_t v; + uint8_t b[2]; + } u; + + u.b[0] = b[1]; + u.b[1] = b[0]; + + return(u.v); +} + +#endif diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/examples/GPS_406_test/GPS_406_test.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/examples/GPS_406_test/GPS_406_test.pde new file mode 100644 index 0000000000..8ffadd5680 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/examples/GPS_406_test/GPS_406_test.pde @@ -0,0 +1,58 @@ +/* + Example of GPS 406 library. + Code by Jordi Munoz and Jose Julio. DIYDrones.com + + Works with Ardupilot Mega Hardware (GPS on Serial Port1) +*/ + +#include +#include +#include + +FastSerialPort0(Serial); +FastSerialPort1(Serial1); + +AP_GPS_406 gps(&Serial1); +#define T6 1000000 +#define T7 10000000 + +void setup() +{ + tone(A6, 1000, 200); + + Serial.begin(38400, 16, 128); + Serial1.begin(57600, 128, 16); + stderr = stdout; + gps.print_errors = true; + + Serial.println("GPS 406 library test"); + gps.init(); // GPS Initialization + delay(1000); +} +void loop() +{ + delay(20); + gps.update(); + if (gps.new_data){ + Serial.print("gps:"); + Serial.print(" Lat:"); + Serial.print((float)gps.latitude / T7, DEC); + Serial.print(" Lon:"); + Serial.print((float)gps.longitude / T7, DEC); + Serial.print(" Alt:"); + Serial.print((float)gps.altitude / 100.0, DEC); + Serial.print(" GSP:"); + Serial.print(gps.ground_speed / 100.0); + Serial.print(" COG:"); + Serial.print(gps.ground_course / 100, DEC); + Serial.print(" SAT:"); + Serial.print(gps.num_sats, DEC); + Serial.print(" FIX:"); + Serial.print(gps.fix, DEC); + Serial.print(" TIM:"); + Serial.print(gps.time, DEC); + Serial.println(); + gps.new_data = 0; // We have readed the data + } +} + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.pde new file mode 100644 index 0000000000..d60057e532 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.pde @@ -0,0 +1,59 @@ +// +// Test for AP_GPS_AUTO +// + +#include +#include +#include + +FastSerialPort0(Serial); +FastSerialPort1(Serial1); + +GPS *gps; +AP_GPS_Auto GPS(&Serial1, &gps); + +#define T6 1000000 +#define T7 10000000 + +void * operator new(size_t size) +{ + return(calloc(size, 1)); +} + +void setup() +{ + Serial.begin(38400); + Serial1.begin(38400); + + Serial.println("GPS AUTO library test"); + gps = &GPS; + gps->init(); + delay(1000); +} +void loop() +{ + delay(20); + gps->update(); + if (gps->new_data){ + Serial.print("gps:"); + Serial.print(" Lat:"); + Serial.print((float)gps->latitude / T7, DEC); + Serial.print(" Lon:"); + Serial.print((float)gps->longitude / T7, DEC); + Serial.print(" Alt:"); + Serial.print((float)gps->altitude / 100.0, DEC); + Serial.print(" GSP:"); + Serial.print(gps->ground_speed / 100.0); + Serial.print(" COG:"); + Serial.print(gps->ground_course / 100.0, DEC); + Serial.print(" SAT:"); + Serial.print(gps->num_sats, DEC); + Serial.print(" FIX:"); + Serial.print(gps->fix, DEC); + Serial.print(" TIM:"); + Serial.print(gps->time, DEC); + Serial.println(); + gps->new_data = 0; + } +} + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/examples/GPS_MTK_test/GPS_MTK_test.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/examples/GPS_MTK_test/GPS_MTK_test.pde new file mode 100644 index 0000000000..bda3b85229 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/examples/GPS_MTK_test/GPS_MTK_test.pde @@ -0,0 +1,56 @@ +/* + Example of GPS MTK library. + Code by Jordi Munoz and Jose Julio. DIYDrones.com + + Works with Ardupilot Mega Hardware (GPS on Serial Port1) +*/ + +#include +#include +#include + +FastSerialPort0(Serial); +FastSerialPort1(Serial1); + +AP_GPS_MTK gps(&Serial1); +#define T6 1000000 +#define T7 10000000 + +void setup() +{ + Serial.begin(38400); + Serial1.begin(38400); + stderr = stdout; + gps.print_errors = true; + + Serial.println("GPS MTK library test"); + gps.init(); // GPS Initialization + delay(1000); +} +void loop() +{ + delay(20); + gps.update(); + if (gps.new_data){ + Serial.print("gps:"); + Serial.print(" Lat:"); + Serial.print((float)gps.latitude / T7, DEC); + Serial.print(" Lon:"); + Serial.print((float)gps.longitude / T7, DEC); + Serial.print(" Alt:"); + Serial.print((float)gps.altitude / 100.0, DEC); + Serial.print(" GSP:"); + Serial.print(gps.ground_speed / 100.0); + Serial.print(" COG:"); + Serial.print(gps.ground_course / 100.0, DEC); + Serial.print(" SAT:"); + Serial.print(gps.num_sats, DEC); + Serial.print(" FIX:"); + Serial.print(gps.fix, DEC); + Serial.print(" TIM:"); + Serial.print(gps.time, DEC); + Serial.println(); + gps.new_data = 0; // We have readed the data + } +} + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/examples/GPS_NMEA_test/GPS_NMEA_test.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/examples/GPS_NMEA_test/GPS_NMEA_test.pde new file mode 100644 index 0000000000..fd071541a4 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/examples/GPS_NMEA_test/GPS_NMEA_test.pde @@ -0,0 +1,57 @@ +/* + Example of GPS NMEA library. + Code by Jordi Munoz and Jose Julio. DIYDrones.com + + Works with Ardupilot Mega Hardware (GPS on Serial Port1) +*/ + +#include +#include +#include + +FastSerialPort0(Serial); +FastSerialPort1(Serial1); + +AP_GPS_NMEA gps(&Serial1); +#define T6 1000000 +#define T7 10000000 + +void setup() +{ + Serial.begin(38400); + Serial1.begin(38400); + stderr = stdout; + gps.print_errors = true; + + Serial.println("GPS NMEA library test"); + gps.init(); // GPS Initialization + delay(1000); +} + +void loop() +{ + delay(20); + gps.update(); + if (gps.new_data){ + Serial.print("gps:"); + Serial.print(" Lat:"); + Serial.print((float)gps.latitude / T7, DEC); + Serial.print(" Lon:"); + Serial.print((float)gps.longitude / T7, DEC); + Serial.print(" Alt:"); + Serial.print((float)gps.altitude / 100.0, DEC); + Serial.print(" GSP:"); + Serial.print(gps.ground_speed / 100.0); + Serial.print(" COG:"); + Serial.print(gps.ground_course / 100, DEC); + Serial.print(" SAT:"); + Serial.print(gps.num_sats, DEC); + Serial.print(" FIX:"); + Serial.print(gps.fix, DEC); + Serial.print(" TIM:"); + Serial.print(gps.time, DEC); + Serial.println(); + gps.new_data = 0; // We have read the data + } +} + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/examples/GPS_UBLOX_test/GPS_UBLOX_test.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/examples/GPS_UBLOX_test/GPS_UBLOX_test.pde new file mode 100644 index 0000000000..43eb239495 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/examples/GPS_UBLOX_test/GPS_UBLOX_test.pde @@ -0,0 +1,56 @@ +/* + Example of GPS UBlox library. + Code by Jordi Munoz and Jose Julio. DIYDrones.com + + Works with Ardupilot Mega Hardware (GPS on Serial Port1) +*/ + +#include +#include +#include + +FastSerialPort0(Serial); +FastSerialPort1(Serial1); + +AP_GPS_UBLOX gps(&Serial1); +#define T6 1000000 +#define T7 10000000 + +void setup() +{ + Serial.begin(38400); + Serial1.begin(38400); + stderr = stdout; + gps.print_errors = true; + + Serial.println("GPS UBLOX library test"); + gps.init(); // GPS Initialization + delay(1000); +} +void loop() +{ + delay(20); + gps.update(); + if (gps.new_data){ + Serial.print("gps:"); + Serial.print(" Lat:"); + Serial.print((float)gps.latitude / T7, DEC); + Serial.print(" Lon:"); + Serial.print((float)gps.longitude / T7, DEC); + Serial.print(" Alt:"); + Serial.print((float)gps.altitude / 100.0, DEC); + Serial.print(" GSP:"); + Serial.print(gps.ground_speed / 100.0); + Serial.print(" COG:"); + Serial.print(gps.ground_course / 100.0, DEC); + Serial.print(" SAT:"); + Serial.print(gps.num_sats, DEC); + Serial.print(" FIX:"); + Serial.print(gps.fix, DEC); + Serial.print(" TIM:"); + Serial.print(gps.time, DEC); + Serial.println(); + gps.new_data = 0; // We have readed the data + } +} + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Math/AP_Math.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Math/AP_Math.h new file mode 100644 index 0000000000..b94ed1c696 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Math/AP_Math.h @@ -0,0 +1,7 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- + +// Assorted useful math operations for ArduPilot(Mega) + +#include "vector2.h" +#include "vector3.h" +#include "matrix3.h" diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Math/keywords.txt b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Math/keywords.txt new file mode 100644 index 0000000000..a5b7938f47 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Math/keywords.txt @@ -0,0 +1,29 @@ +Vector2 KEYWORD1 +Vector2i KEYWORD1 +Vector2ui KEYWORD1 +Vector2l KEYWORD1 +Vector2ul KEYWORD1 +Vector2f KEYWORD1 +Vector3 KEYWORD1 +Vector3i KEYWORD1 +Vector3ui KEYWORD1 +Vector3l KEYWORD1 +Vector3ul KEYWORD1 +Vector3f KEYWORD1 +Matrix3 KEYWORD1 +Matrix3i KEYWORD1 +Matrix3ui KEYWORD1 +Matrix3l KEYWORD1 +Matrix3ul KEYWORD1 +Matrix3f KEYWORD1 +length_squared KEYWORD2 +length KEYWORD2 +normalize KEYWORD2 +normalized KEYWORD2 +reflect KEYWORD2 +project KEYWORD2 +projected KEYWORD2 +angle KEYWORD2 +angle_normalized KEYWORD2 +rotate KEYWORD2 +rotated KEYWORD2 diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Math/matrix3.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Math/matrix3.h new file mode 100644 index 0000000000..51fd144c75 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Math/matrix3.h @@ -0,0 +1,134 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- + +// Copyright 2010 Michael Smith, all rights reserved. + +// This library is free software; you can redistribute it and / or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 2.1 of the License, or (at your option) any later version. + +// Inspired by: +/**************************************** + * 3D Vector Classes + * By Bill Perone (billperone@yahoo.com) + */ + +// +// 3x3 matrix implementation. +// +// Note that the matrix is organised in row-normal form (the same as +// applies to array indexing). +// +// In addition to the template, this header defines the following types: +// +// Matrix3i 3x3 matrix of signed integers +// Matrix3ui 3x3 matrix of unsigned integers +// Matrix3l 3x3 matrix of signed longs +// Matrix3ul 3x3 matrix of unsigned longs +// Matrix3f 3x3 matrix of signed floats +// + +#ifndef MATRIX3_H +#define MATRIX3_H + +#include "vector3.h" + +// 3x3 matrix with elements of type T +template +class Matrix3 { +public: + + // Vectors comprising the rows of the matrix + Vector3 a, b, c; + + // trivial ctor + Matrix3() {} + + // setting ctor + Matrix3(const Vector3 a0, const Vector3 b0, const Vector3 c0): a(a0), b(b0), c(c0) {} + + // setting ctor + Matrix3(const T ax, const T ay, const T az, const T bx, const T by, const T bz, const T cx, const T cy, const T cz): a(ax,ay,az), b(bx,by,bz), c(cx,cy,cz) {} + + // function call operator + void operator () (const Vector3 a0, const Vector3 b0, const Vector3 c0) + { a = a0; b = b0; c = c0; } + + // test for equality + bool operator == (const Matrix3 &m) + { return (a==m.a && b==m.b && c==m.c); } + + // test for inequality + bool operator != (const Matrix3 &m) + { return (a!=m.a || b!=m.b || c!=m.c); } + + // negation + Matrix3 operator - (void) const + { return Matrix3(-a,-b,-c); } + + // addition + Matrix3 operator + (const Matrix3 &m) const + { return Matrix3(a+m.a, b+m.b, c+m.c); } + Matrix3 &operator += (const Matrix3 &m) + { return *this = *this + m; } + + // subtraction + Matrix3 operator - (const Matrix3 &m) const + { return Matrix3(a-m.a, b-m.b, c-m.c); } + Matrix3 &operator -= (const Matrix3 &m) + { return *this = *this - m; } + + // uniform scaling + Matrix3 operator * (const T num) const + { return Matrix3(a*num, b*num, c*num); } + Matrix3 &operator *= (const T num) + { return *this = *this * num; } + Matrix3 operator / (const T num) const + { return Matrix3(a/num, b/num, c/num); } + Matrix3 &operator /= (const T num) + { return *this = *this / num; } + + // multiplication by a vector + Vector3 operator *(const Vector3 &v) const + { + return Vector3(a.x * v.x + a.y * v.y + a.z * v.z, + b.x * v.x + b.y * v.y + b.z * v.z, + c.x * v.x + c.y * v.y + c.z * v.z); + } + + // multiplication by another Matrix3 + Matrix3 operator *(const Matrix3 &m) const + { + Matrix3 temp (Vector3(a.x * m.a.x + a.y * m.b.x + a.z * m.c.x, + a.x * m.a.y + a.y * m.b.y + a.z * m.c.y, + a.x * m.a.z + a.y * m.b.z + a.z * m.c.z), + Vector3(b.x * m.a.x + b.y * m.b.x + b.z * m.c.x, + b.x * m.a.y + b.y * m.b.y + b.z * m.c.y, + b.x * m.a.z + b.y * m.b.z + b.z * m.c.z), + Vector3(c.x * m.a.x + c.y * m.b.x + c.z * m.c.x, + c.x * m.a.y + c.y * m.b.y + c.z * m.c.y, + c.x * m.a.z + c.y * m.b.z + c.z * m.c.z)); + return temp; + } + Matrix3 &operator *=(const Matrix3 &m) + { return *this = *this * m; } + + // transpose the matrix + Matrix3 transposed(void) + { + return Matrix3(Vector3(a.x, b.x, c.x), + Vector3(a.y, b.y, c.y), + Vector3(a.z, b.z, c.z)); + } + Matrix3 transpose(void) + { return *this = transposed(); } + +}; + +typedef Matrix3 Matrix3i; +typedef Matrix3 Matrix3ui; +typedef Matrix3 Matrix3l; +typedef Matrix3 Matrix3ul; +typedef Matrix3 Matrix3f; + +#endif // MATRIX3_H diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Math/vector2.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Math/vector2.h new file mode 100644 index 0000000000..bbe380aeb6 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Math/vector2.h @@ -0,0 +1,158 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- + +// Copyright 2010 Michael Smith, all rights reserved. + +// This library is free software; you can redistribute it and / or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 2.1 of the License, or (at your option) any later version. + +// Derived closely from: +/**************************************** + * 2D Vector Classes + * By Bill Perone (billperone@yahoo.com) + * Original: 9-16-2002 + * Revised: 19-11-2003 + * 18-12-2003 + * 06-06-2004 + * + * 2003, This code is provided "as is" and you can use it freely as long as + * credit is given to Bill Perone in the application it is used in + ****************************************/ + +#ifndef VECTOR2_H +#define VECTOR2_H + +#include + +template +struct Vector2 +{ + T x, y; + + + // trivial ctor + Vector2() {} + + // setting ctor + Vector2(const T x0, const T y0): x(x0), y(y0) {} + + // function call operator + void operator ()(const T x0, const T y0) + { x= x0; y= y0; } + + // test for equality + bool operator==(const Vector2 &v) + { return (x==v.x && y==v.y); } + + // test for inequality + bool operator!=(const Vector2 &v) + { return (x!=v.x || y!=v.y); } + + // negation + Vector2 operator -(void) const + { return Vector2(-x, -y); } + + // addition + Vector2 operator +(const Vector2 &v) const + { return Vector2(x+v.x, y+v.y); } + + // subtraction + Vector2 operator -(const Vector2 &v) const + { return Vector2(x-v.x, y-v.y); } + + // uniform scaling + Vector2 operator *(const T num) const + { + Vector2 temp(*this); + return temp*=num; + } + + // uniform scaling + Vector2 operator /(const T num) const + { + Vector2 temp(*this); + return temp/=num; + } + + // addition + Vector2 &operator +=(const Vector2 &v) + { + x+=v.x; y+=v.y; + return *this; + } + + // subtraction + Vector2 &operator -=(const Vector2 &v) + { + x-=v.x; y-=v.y; + return *this; + } + + // uniform scaling + Vector2 &operator *=(const T num) + { + x*=num; y*=num; + return *this; + } + + // uniform scaling + Vector2 &operator /=(const T num) + { + x/=num; y/=num; + return *this; + } + + // dot product + T operator *(const Vector2 &v) const + { return x*v.x + y*v.y; } + + // gets the length of this vector squared + T length_squared() const + { return (T)(*this * *this); } + + // gets the length of this vector + T length() const + { return (T)sqrt(*this * *this); } + + // normalizes this vector + void normalize() + { *this/=length(); } + + // returns the normalized vector + Vector2 normalized() const + { return *this/length(); } + + // reflects this vector about n + void reflect(const Vector2 &n) + { + Vector2 orig(*this); + project(n); + *this= *this*2 - orig; + } + + // projects this vector onto v + void project(const Vector2 &v) + { *this= v * (*this * v)/(v*v); } + + // returns this vector projected onto v + Vector2 projected(const Vector2 &v) + { return v * (*this * v)/(v*v); } + + // computes the angle between 2 arbitrary vectors + static inline T angle(const Vector2 &v1, const Vector2 &v2) + { return (T)acosf((v1*v2) / (v1.length()*v2.length())); } + + // computes the angle between 2 normalized arbitrary vectors + static inline T angle_normalized(const Vector2 &v1, const Vector2 &v2) + { return (T)acosf(v1*v2); } + +}; + +typedef Vector2 Vector2i; +typedef Vector2 Vector2ui; +typedef Vector2 Vector2l; +typedef Vector2 Vector2ul; +typedef Vector2 Vector2f; + +#endif // VECTOR2_H diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Math/vector3.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Math/vector3.h new file mode 100644 index 0000000000..7c23a5fc63 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Math/vector3.h @@ -0,0 +1,183 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- + +// Copyright 2010 Michael Smith, all rights reserved. + +// This library is free software; you can redistribute it and / or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 2.1 of the License, or (at your option) any later version. + +// Derived closely from: +/**************************************** + * 3D Vector Classes + * By Bill Perone (billperone@yahoo.com) + * Original: 9-16-2002 + * Revised: 19-11-2003 + * 11-12-2003 + * 18-12-2003 + * 06-06-2004 + * + * 2003, This code is provided "as is" and you can use it freely as long as + * credit is given to Bill Perone in the application it is used in + * + * Notes: + * if a*b = 0 then a & b are orthogonal + * a%b = -b%a + * a*(b%c) = (a%b)*c + * a%b = a(cast to matrix)*b + * (a%b).length() = area of parallelogram formed by a & b + * (a%b).length() = a.length()*b.length() * sin(angle between a & b) + * (a%b).length() = 0 if angle between a & b = 0 or a.length() = 0 or b.length() = 0 + * a * (b%c) = volume of parallelpiped formed by a, b, c + * vector triple product: a%(b%c) = b*(a*c) - c*(a*b) + * scalar triple product: a*(b%c) = c*(a%b) = b*(c%a) + * vector quadruple product: (a%b)*(c%d) = (a*c)*(b*d) - (a*d)*(b*c) + * if a is unit vector along b then a%b = -b%a = -b(cast to matrix)*a = 0 + * vectors a1...an are linearly dependant if there exists a vector of scalars (b) where a1*b1 + ... + an*bn = 0 + * or if the matrix (A) * b = 0 + * + ****************************************/ + +#ifndef VECTOR3_H +#define VECTOR3_H + +#include + +template +class Vector3 +{ +public: + T x, y, z; + + // trivial ctor + Vector3() {} + + // setting ctor + Vector3(const T x0, const T y0, const T z0): x(x0), y(y0), z(z0) {} + + // function call operator + void operator ()(const T x0, const T y0, const T z0) + { x= x0; y= y0; z= z0; } + + // test for equality + bool operator==(const Vector3 &v) + { return (x==v.x && y==v.y && z==v.z); } + + // test for inequality + bool operator!=(const Vector3 &v) + { return (x!=v.x || y!=v.y || z!=v.z); } + + // negation + Vector3 operator -(void) const + { return Vector3(-x,-y,-z); } + + // addition + Vector3 operator +(const Vector3 &v) const + { return Vector3(x+v.x, y+v.y, z+v.z); } + + // subtraction + Vector3 operator -(const Vector3 &v) const + { return Vector3(x-v.x, y-v.y, z-v.z); } + + // uniform scaling + Vector3 operator *(const T num) const + { + Vector3 temp(*this); + return temp*=num; + } + + // uniform scaling + Vector3 operator /(const T num) const + { + Vector3 temp(*this); + return temp/=num; + } + + // addition + Vector3 &operator +=(const Vector3 &v) + { + x+=v.x; y+=v.y; z+=v.z; + return *this; + } + + // subtraction + Vector3 &operator -=(const Vector3 &v) + { + x-=v.x; y-=v.y; z-=v.z; + return *this; + } + + // uniform scaling + Vector3 &operator *=(const T num) + { + x*=num; y*=num; z*=num; + return *this; + } + + // uniform scaling + Vector3 &operator /=(const T num) + { + x/=num; y/=num; z/=num; + return *this; + } + + // dot product + T operator *(const Vector3 &v) const + { return x*v.x + y*v.y + z*v.z; } + + // cross product + Vector3 operator %(const Vector3 &v) const + { + Vector3 temp(y*v.z - z*v.y, z*v.x - x*v.z, x*v.y - y*v.x); + return temp; + } + + // gets the length of this vector squared + T length_squared() const + { return (T)(*this * *this); } + + // gets the length of this vector + float length() const + { return (T)sqrt(*this * *this); } + + // normalizes this vector + void normalize() + { *this/=length(); } + + // returns the normalized version of this vector + Vector3 normalized() const + { return *this/length(); } + + // reflects this vector about n + void reflect(const Vector3 &n) + { + Vector3 orig(*this); + project(n); + *this= *this*2 - orig; + } + + // projects this vector onto v + void project(const Vector3 &v) + { *this= v * (*this * v)/(v*v); } + + // returns this vector projected onto v + Vector3 projected(const Vector3 &v) + { return v * (*this * v)/(v*v); } + + // computes the angle between 2 arbitrary vectors + static inline T angle(const Vector3 &v1, const Vector3 &v2) + { return (T)acosf((v1*v2) / (v1.length()*v2.length())); } + + // computes the angle between 2 arbitrary normalized vectors + static inline T angle_normalized(const Vector3 &v1, const Vector3 &v2) + { return (T)acosf(v1*v2); } + +}; + +typedef Vector3 Vector3i; +typedef Vector3 Vector3ui; +typedef Vector3 Vector3l; +typedef Vector3 Vector3ul; +typedef Vector3 Vector3f; + +#endif // VECTOR3_H diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Navigation/Navigation.cpp b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Navigation/Navigation.cpp new file mode 100644 index 0000000000..9802257a89 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Navigation/Navigation.cpp @@ -0,0 +1,249 @@ +#include "Navigation.h" + +Navigation::Navigation(GPS *withGPS, Waypoints *withWP) : + _gps(withGPS), + _wp(withWP), + _hold_course(-1) +{ +} + +void +Navigation::update_gps() +{ + location.alt = _gps->altitude; + location.lng = _gps->longitude; + location.lat = _gps->latitude; + + // target_bearing is where we should be heading + bearing = get_bearing(&location, &next_wp); + + // waypoint distance from plane + distance = get_distance(&location, &next_wp); + + calc_bearing_error(); + calc_altitude_error(); + altitude_above_home = location.alt - home.alt; + + // check if we have missed the WP + _loiter_delta = (bearing - _old_bearing) / 100; + + // reset the old value + _old_bearing = bearing; + + // wrap values + if (_loiter_delta > 170) _loiter_delta -= 360; + if (_loiter_delta < -170) _loiter_delta += 360; + loiter_sum += abs(_loiter_delta); + + if (distance <= 0){ + distance = -1; + Serial.print("MSG wp error "); + Serial.println(distance, DEC); + } +} + +void +Navigation::load_first_wp(void) +{ + set_next_wp(_wp->get_waypoint_with_index(1)); +} + +void +Navigation::load_home(void) +{ + home = _wp->get_waypoint_with_index(0); +} + +void +Navigation::return_to_home_with_alt(uint32_t alt) +{ + Waypoints::WP loc = _wp->get_waypoint_with_index(0); + loc.alt += alt; + set_next_wp(loc); +} + +void +Navigation::reload_wp(void) +{ + set_next_wp(_wp->get_current_waypoint()); +} + +void +Navigation::load_wp_index(uint8_t i) +{ + _wp->set_index(i); + set_next_wp(_wp->get_current_waypoint()); +} + +void +Navigation::hold_location() +{ + // set_next_wp() XXX needs to be implemented +} + +void +Navigation::set_home(Waypoints::WP loc) +{ + _wp->set_waypoint_with_index(loc, 0); + home = loc; + //location = home; +} + +void +Navigation::set_next_wp(Waypoints::WP loc) +{ + prev_wp = next_wp; + next_wp = loc; + + if(_scaleLongDown == 0) + calc_long_scaling(loc.lat); + + total_distance = get_distance(&location, &next_wp); + distance = total_distance; + + bearing = get_bearing(&location, &next_wp); + _old_bearing = bearing; + + // clear loitering code + _loiter_delta = 0; + loiter_sum = 0; + + // set a new crosstrack bearing + // ---------------------------- + reset_crosstrack(); +} + +void +Navigation::calc_long_scaling(int32_t lat) +{ + // this is used to offset the shrinking longitude as we go towards the poles + float rads = (abs(lat) / T7) * 0.0174532925; + _scaleLongDown = cos(rads); + _scaleLongUp = 1.0f / cos(rads); +} + +void +Navigation::set_hold_course(int16_t b) +{ + if(b) + _hold_course = bearing; + else + _hold_course = -1; +} + +int16_t +Navigation::get_hold_course(void) +{ + return _hold_course; +} + +void +Navigation::calc_distance_error() +{ + //distance_estimate += (float)_gps->ground_speed * .0002 * cos(radians(bearing_error * .01)); + //distance_estimate -= DST_EST_GAIN * (float)(distance_estimate - GPS_distance); + //distance = max(distance_estimate,10); +} + +void +Navigation::calc_bearing_error(void) +{ + if(_hold_course == -1){ + bearing_error = wrap_180(bearing - _gps->ground_course); + }else{ + bearing_error = _hold_course; + } +} + +int32_t +Navigation::wrap_180(int32_t error) +{ + if (error > 18000) error -= 36000; + if (error < -18000) error += 36000; + return error; +} + +int32_t +Navigation::wrap_360(int32_t angle) +{ + if (angle > 36000) angle -= 36000; + if (angle < 0) angle += 36000; + return angle; +} + +void +Navigation::set_bearing_error(int32_t error) +{ + bearing_error = wrap_180(error); +} + + +/***************************************** + * Altitude error with Airspeed correction + *****************************************/ +void +Navigation::calc_altitude_error(void) +{ + // limit climb rates + _target_altitude = next_wp.alt - ((float)((distance -20) * _offset_altitude) / (float)(total_distance - 20)); + 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 - location.alt; +} + +void +Navigation::set_loiter_vector(int16_t v) +{ + // _vector = constrain(v, -18000, 18000); XXX needs to be implemented +} + +void +Navigation::update_crosstrack(void) +{ + // Crosstrack Error + // ---------------- + if (abs(bearing - _crosstrack_bearing) < 4500) { // If we are too far off or too close we don't do track following + _crosstrack_error = sin(radians((bearing - _crosstrack_bearing) / 100)) * distance; // Meters we are off track line + bearing += constrain(_crosstrack_error * XTRACK_GAIN, -XTRACK_ENTRY_ANGLE, XTRACK_ENTRY_ANGLE); + } +} + +void +Navigation::reset_crosstrack(void) +{ + _crosstrack_bearing = get_bearing(&location, &next_wp); // Used for track following +} + +long +Navigation::get_distance(Waypoints::WP *loc1, Waypoints::WP *loc2) +{ + if(loc1->lat == 0 || loc1->lng == 0) + return -1; + if(loc2->lat == 0 || loc2->lng == 0) + return -1; + if(_scaleLongDown == 0) + calc_long_scaling(loc2->lat); + float dlat = (float)(loc2->lat - loc1->lat); + float dlong = ((float)(loc2->lng - loc1->lng)) * _scaleLongDown; + return sqrt(sq(dlat) + sq(dlong)) * .01113195; +} + +long +Navigation::get_bearing(Waypoints::WP *loc1, Waypoints::WP *loc2) +{ + if(loc1->lat == 0 || loc1->lng == 0) + return -1; + if(loc2->lat == 0 || loc2->lng == 0) + return -1; + if(_scaleLongDown == 0) + calc_long_scaling(loc2->lat); + long off_x = loc2->lng - loc1->lng; + long off_y = (loc2->lat - loc1->lat) * _scaleLongUp; + long bearing = 9000 + atan2(-off_y, off_x) * 5729.57795; + if (bearing < 0) + bearing += 36000; + return bearing; +} diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Navigation/Navigation.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Navigation/Navigation.h new file mode 100644 index 0000000000..4fce19da63 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Navigation/Navigation.h @@ -0,0 +1,76 @@ + +#ifndef AP_NAVIGATION_h +#define AP_NAVIGATION_h + +#define XTRACK_GAIN 10 // Amount to compensate for crosstrack (degrees/100 per meter) +#define XTRACK_ENTRY_ANGLE 3000 // Max angle used to correct for track following degrees*100 +#include // ArduPilot GPS Library +#include "Waypoints.h" // ArduPilot Waypoints Library +#include "WProgram.h" + +#define T7 10000000 + +class Navigation { +public: + Navigation(GPS *withGPS, Waypoints *withWP); + + void update_gps(void); // called 50 Hz + void set_home(Waypoints::WP loc); + void set_next_wp(Waypoints::WP loc); + void load_first_wp(void); + void load_wp_with_index(uint8_t i); + void load_home(void); + void return_to_home_with_alt(uint32_t alt); + + void reload_wp(void); + void load_wp_index(uint8_t i); + void hold_location(); + void set_wp(Waypoints::WP loc); + + void set_hold_course(int16_t b); // -1 deisables, 0-36000 enables + int16_t get_hold_course(void); + + int32_t get_distance(Waypoints::WP *loc1, Waypoints::WP *loc2); + int32_t get_bearing(Waypoints::WP *loc1, Waypoints::WP *loc2); + void set_bearing_error(int32_t error); + + void set_loiter_vector(int16_t v); + void update_crosstrack(void); + + int32_t wrap_180(int32_t error); // utility + int32_t wrap_360(int32_t angle); // utility + + int32_t bearing; // deg * 100 : 0 to 360 current desired bearing to navigate + int32_t distance; // meters : distance plane to next waypoint + int32_t altitude_above_home; // meters * 100 relative to home position + int32_t total_distance; // meters : distance between waypoints + int32_t bearing_error; // deg * 100 : 18000 to -18000 + int32_t altitude_error; // deg * 100 : 18000 to -18000 + + int16_t loiter_sum; + Waypoints::WP home, location, prev_wp, next_wp; + +private: + void calc_int32_t_scaling(int32_t lat); + void calc_bearing_error(void); + void calc_altitude_error(void); + void calc_distance_error(void); + void calc_long_scaling(int32_t lat); + void reset_crosstrack(void); + + int16_t _old_bearing; // used to track delta on the bearing + GPS *_gps; + Waypoints *_wp; + int32_t _crosstrack_bearing; // deg * 100 : 0 to 360 desired angle of plane to target + float _crosstrack_error; // deg * 100 : 18000 to -18000 meters we are off trackline + int16_t _hold_course; // deg * 100 dir of plane + int32_t _target_altitude; // used for + int32_t _offset_altitude; // used for + float _altitude_estimate; + float _scaleLongUp; // used to reverse int32_ttitude scaling + float _scaleLongDown; // used to reverse int32_ttitude scaling + int16_t _loiter_delta; +}; + + +#endif // AP_NAVIGATION_h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Navigation/examples/Navigation/Navigation.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Navigation/examples/Navigation/Navigation.pde new file mode 100644 index 0000000000..19b0b54483 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Navigation/examples/Navigation/Navigation.pde @@ -0,0 +1,152 @@ +/* + +This test assumes you are at the LOWl demo Airport + +*/ + +#include "Waypoints.h" +#include "Navigation.h" +#include "AP_GPS_IMU.h" +#include "AP_RC.h" + + +AP_GPS_IMU gps; +Navigation nav((GPS *) &gps); +AP_RC rc; + +#define CH_ROLL 0 +#define CH_PITCH 1 +#define CH_THROTTLE 2 +#define CH_RUDDER 3 + +#define CH3_MIN 1100 +#define CH3_MAX 1900 + +#define REVERSE_RUDDER 1 +#define REVERSE_ROLL 1 +#define REVERSE_PITCH 1 + +int8_t did_init_home; +int16_t servo_out[4]; +int16_t radio_trim[4] = {1500,1500,1100,1500}; +int16_t radio_in[4]; + +void setup() +{ + Serial.begin(38400); + Serial.println("Navigation test"); + Waypoints::WP location_B = {0, 0, 74260, 472586364, 113366012}; + nav.set_next_wp(location_B); + rc.init(radio_trim); +} + +void loop() +{ + delay(20); + gps.update(); + rc.read_pwm(); + for(int y=0; y<4; y++) { + //rc.set_ch_pwm(y, rc.input[y]); // send to Servos + radio_in[y] = rc.input[y]; + } + + servo_out[CH_ROLL] = ((radio_in[CH_ROLL] - radio_trim[CH_ROLL]) * 45 * REVERSE_ROLL) / 500; + servo_out[CH_PITCH] = ((radio_in[CH_PITCH] - radio_trim[CH_PITCH]) * 45 * REVERSE_PITCH) / 500; + servo_out[CH_RUDDER] = ((radio_in[CH_RUDDER] - radio_trim[CH_RUDDER]) * 45 * REVERSE_RUDDER) / 500; + servo_out[CH_THROTTLE] = (float)(radio_in[CH_THROTTLE] - CH3_MIN) / (float)(CH3_MAX - CH3_MIN) *100; + servo_out[CH_THROTTLE] = constrain(servo_out[CH_THROTTLE], 0, 100); + + output_Xplane(); + if(gps.new_data /* && gps.fix */ ){ + if(did_init_home == 0){ + did_init_home = 1; + Waypoints::WP wp = {0, 0, gps.altitude, gps.lattitude, gps.longitude}; + nav.set_home(wp); + Serial.println("MSG init home"); + }else{ + nav.update_gps(); + } + //print_loc(); + } +} + +void print_loc() +{ + Serial.print("MSG GPS: "); + Serial.print(nav.location.lat, DEC); + Serial.print(", "); + Serial.print(nav.location.lng, DEC); + Serial.print(", "); + Serial.print(nav.location.alt, DEC); + Serial.print("\tDistance = "); + Serial.print(nav.distance, DEC); + Serial.print(" Bearing = "); + Serial.print(nav.bearing/100, DEC); + Serial.print(" Bearing err = "); + Serial.print(nav.bearing_error/100, DEC); + Serial.print(" alt err = "); + Serial.print(nav.altitude_error/100, DEC); + Serial.print(" Alt above home = "); + Serial.println(nav.altitude_above_home/100, DEC); +} + +void print_pwm() +{ + Serial.print("ch1 "); + Serial.print(rc.input[CH_ROLL],DEC); + Serial.print("\tch2: "); + Serial.print(rc.input[CH_PITCH],DEC); + Serial.print("\tch3 :"); + Serial.print(rc.input[CH_THROTTLE],DEC); + Serial.print("\tch4 :"); + Serial.println(rc.input[CH_RUDDER],DEC); +} + + + + +byte buf_len = 0; +byte out_buffer[32]; + +void output_Xplane(void) +{ + // output real-time sensor data + Serial.print("AAA"); // Message preamble + output_int((int)(servo_out[CH_ROLL]*100)); // 0 bytes 0,1 + output_int((int)(servo_out[CH_PITCH]*100)); // 1 bytes 2,3 + output_int((int)(servo_out[CH_THROTTLE])); // 2 bytes 4,5 + output_int((int)(servo_out[CH_RUDDER]*100)); // 3 bytes 6,7 + output_int((int)nav.distance); // 4 bytes 8,9 + output_int((int)nav.bearing_error); // 5 bytes 10,11 + output_int((int)nav.altitude_error); // 6 bytes 12,13 + output_int(0); // 7 bytes 14,15 + output_byte(1); // 8 bytes 16 + output_byte(1); // 9 bytes 17 + + // print out the buffer and checksum + // --------------------------------- + print_buffer(); +} + +void output_int(int value) +{ + //buf_len += 2; + out_buffer[buf_len++] = value & 0xff; + out_buffer[buf_len++] = (value >> 8) & 0xff; +} +void output_byte(byte value) +{ + out_buffer[buf_len++] = value; +} + +void print_buffer() +{ + byte ck_a = 0; + byte ck_b = 0; + for (byte i = 0;i < buf_len; i++){ + Serial.print (out_buffer[i]); + } + Serial.print('\r'); + Serial.print('\n'); + buf_len = 0; +} diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Navigation/examples/Navigation_simple/Navigation_simple.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Navigation/examples/Navigation_simple/Navigation_simple.pde new file mode 100644 index 0000000000..5c0f21739c --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Navigation/examples/Navigation_simple/Navigation_simple.pde @@ -0,0 +1,28 @@ +#include +#include +#include + + +AP_GPS_IMU gps; +Navigation nav((GPS *) & gps); + +void setup() +{ + Serial.begin(38400); + Serial.println("Navigation test"); + + Waypoints::WP location_A = {0, 0, 38.579633 * T7, -122.566265 * T7, 10000}; + Waypoints::WP location_B = {0, 0, 38.578743 * T7, -122.572782 * T7, 5000}; + + long distance = nav.get_distance(&location_A, &location_B); + long bearing = nav.get_bearing(&location_A, &location_B); + + Serial.print("\tDistance = "); + Serial.print(distance, DEC); + Serial.print(" Bearing = "); + Serial.println(bearing, DEC); +} + +void loop() +{ +} diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/DCM/DCM.cpp b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/DCM/DCM.cpp new file mode 100644 index 0000000000..90655df9f8 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/DCM/DCM.cpp @@ -0,0 +1,472 @@ +#include "DCM.h" + +// XXX HACKS +APM_ADC adc; + +// XXX END HACKS + + +#define GRAVITY 418 //this equivalent to 1G in the raw data coming from the accelerometer +#define ADC_CONSTRAINT 900 + +#define Kp_ROLLPITCH 0.0014 //0.015 // Pitch&Roll Proportional Gain +#define Ki_ROLLPITCH 0.0000003 // 0.00001 Pitch&Roll Integrator Gain +#define Kp_YAW 1.2 // 1.2 Yaw Porportional Gain +#define Ki_YAW 0.00005 // 0.00005 Yaw Integrator Gain + +// Sensor: GYROX, GYROY, GYROZ, ACCELX, ACCELY, ACCELZ +const uint8_t AP_DCM::_sensors[6] = {1,2,0,4,5,6}; // For ArduPilot Mega Sensor Shield Hardware +const int AP_DCM::_sensor_signs[] = {1,-1,-1,-1,1,1,-1,-1,-1}; //{-1,1,-1,1,-1,1,-1,-1,-1} !!!! These are probably not right + +// Temp compensation curve constants +// These must be produced by measuring data and curve fitting +// [X/Y/Z gyro][A/B/C or 0 order/1st order/2nd order constants] +const float AP_DCM::_gyro_temp_curve[3][3] = { + {1665,0,0}, + {1665,0,0}, + {1665,0,0} +}; // values may migrate to a Config file + + + +// Constructors //////////////////////////////////////////////////////////////// +AP_DCM::AP_DCM(APM_Compass *withCompass) : + _compass(withCompass), + _dcm_matrix(1, 0, 0, + 0, 1, 0, + 0, 0, 1), + _G_Dt(0.02), + _course_over_ground_x(0), + _course_over_ground_y(1) +{ +} + +void +AP_DCM::update_DCM(void) +{ + read_adc_raw(); // Get current values for IMU sensors + matrix_update(); // Integrate the DCM matrix + normalize(); // Normalize the DCM matrix + drift_correction(); // Perform drift correction + euler_angles(); // Calculate pitch, roll, yaw for stabilization and navigation +} + + +// Read the 6 ADC channels needed for the IMU +// ------------------------------------------ +void +AP_DCM::read_adc_raw(void) +{ + int tc_temp = adc.Ch(_gyro_temp_ch); + for (int i = 0; i < 6; i++) { + _adc_in[i] = adc.Ch(_sensors[i]); + if (i < 3) { // XXX magic numbers! + _adc_in[i] -= _gyro_temp_comp(i, tc_temp); // Subtract temp compensated typical gyro bias + } else { + _adc_in[i] -= 2025; // Subtract typical accel bias + } + } +} + +// Returns the temperature compensated raw gyro value +//--------------------------------------------------- +float +AP_DCM::_gyro_temp_comp(int i, int temp) const +{ + // We use a 2nd order curve of the form Gtc = A + B * Graw + C * (Graw)**2 + //------------------------------------------------------------------------ + return _gyro_temp_curve[i][0] + _gyro_temp_curve[i][1] * temp + _gyro_temp_curve[i][2] * temp * temp; +} + +// Returns an analog value with the offset removed +// ----------------- +float +AP_DCM::read_adc(int select) +{ + float temp; + if (_sensor_signs[select] < 0) + temp = (_adc_offset[select] - _adc_in[select]); + else + temp = (_adc_in[select] - _adc_offset[select]); + + if (abs(temp) > ADC_CONSTRAINT) + adc_constraints++; // We keep track of the number of times we constrain the ADC output for performance reporting + +/* +// For checking the pitch/roll drift correction gain time constants +switch (select) { + case 3: + return 0; + break; + case 4: + return 0; + break; + case 5: + return 400; + break; +} +*/ + + +//End of drift correction gain test code + + return constrain(temp, -ADC_CONSTRAINT, ADC_CONSTRAINT); // Throw out nonsensical values +} + +/**************************************************/ +void +AP_DCM::normalize(void) +{ + float error = 0; + DCM_Vector temporary[3]; + + uint8_t problem = 0; + + error = -_dcm_matrix(0).dot_product(_dcm_matrix(1)) * 0.5; // eq.19 + + temporary[0] = _dcm_matrix(1) * error + _dcm_matrix(0); // eq.19 + temporary[1] = _dcm_matrix(0) * error + _dcm_matrix(1); // eq.19 + + temporary[2] = temporary[0] ^ temporary[1]; // c= a x b // eq.20 + + _dcm_matrix(0) = _renorm(temporary[0], problem); + _dcm_matrix(1) = _renorm(temporary[1], problem); + _dcm_matrix(2) = _renorm(temporary[2], problem); + + if (problem == 1) { // Our solution is blowing up and we will force back to initial condition. Hope we are not upside down! + _dcm_matrix(0, 0)= 1.0f; + _dcm_matrix(0, 1)= 0.0f; + _dcm_matrix(0, 2)= 0.0f; + _dcm_matrix(1, 0)= 0.0f; + _dcm_matrix(1, 1)= 1.0f; + _dcm_matrix(1, 2)= 0.0f; + _dcm_matrix(2, 0)= 0.0f; + _dcm_matrix(2, 1)= 0.0f; + _dcm_matrix(2, 2)= 1.0f; + } +} + +DCM_Vector +AP_DCM::_renorm(DCM_Vector const &a, uint8_t &problem) +{ + float renorm; + + renorm = a.dot_product(a); + + if (renorm < 1.5625f && renorm > 0.64f) { // Check if we are OK with Taylor expansion + renorm = 0.5 * (3 - renorm); // eq.21 + } else if (renorm < 100.0f && renorm > 0.01f) { + renorm = 1.0 / sqrt(renorm); + renorm_sqrt_count++; + } else { + problem = 1; + renorm_blowup_count++; + } + + return(a * renorm); +} + +/**************************************************/ +void +AP_DCM::drift_correction(void) +{ + //Compensation the Roll, Pitch and Yaw drift. + float mag_heading_x; + float mag_heading_y; + float error_course = 0; + static float scaled_omega_P[3]; + static float scaled_omega_I[3]; + float accel_magnitude; + float accel_weight; + float integrator_magnitude; + + //*****Roll and Pitch*************** + + // Calculate the magnitude of the accelerometer vector + accel_magnitude = _accel_vector.magnitude() / GRAVITY; // Scale to gravity. + + // Dynamic weighting of accelerometer info (reliability filter) + // Weight for accelerometer info (<0.5G = 0.0, 1G = 1.0 , >1.5G = 0.0) + accel_weight = constrain(1 - 2 * abs(1 - accel_magnitude), 0, 1); // + + // We monitor the amount that the accelerometer based drift correction is deweighted for performanc reporting + imu_health = imu_health + 0.02 * (accel_weight-.5); + imu_health = constrain(imu_health, 0, 1); + + // adjust the ground of reference + _error_roll_pitch = _accel_vector ^ _dcm_matrix(2); + + // error_roll_pitch are in Accel ADC units + // Limit max error_roll_pitch to limit max omega_P and omega_I + _error_roll_pitch(0) = constrain(_error_roll_pitch(0), -50, 50); + _error_roll_pitch(1) = constrain(_error_roll_pitch(1), -50, 50); + _error_roll_pitch(2) = constrain(_error_roll_pitch(2), -50, 50); + + _omega_P = _error_roll_pitch * (Kp_ROLLPITCH * accel_weight); + _omega_I += _error_roll_pitch * (Ki_ROLLPITCH * accel_weight); + + //*****YAW*************** + + if (_compass) { + // We make the gyro YAW drift correction based on compass magnetic heading + error_course= (_dcm_matrix(0, 0) * _compass->Heading_Y) - (_dcm_matrix(1, 0) * _compass->Heading_X); // Calculating YAW error + } else { + // Use GPS Ground course to correct yaw gyro drift + if (ground_speed >= SPEEDFILT) { + // Optimization: We have precalculated course_over_ground_x and course_over_ground_y (Course over Ground X and Y) from GPS info + error_course = (_dcm_matrix(0, 0) * _course_over_ground_y) - (_dcm_matrix(1, 0) * _course_over_ground_x); // Calculating YAW error + } + } + _error_yaw = _dcm_matrix(2) * error_course; // Applys the yaw correction to the XYZ rotation of the aircraft, depeding the position. + + _omega_P += _error_yaw * Kp_YAW; // Adding Proportional. + _omega_I += _error_yaw * Ki_YAW; // adding integrator to the omega_I + + // Here we will place a limit on the integrator so that the integrator cannot ever exceed half the saturation limit of the gyros + integrator_magnitude = sqrt(_omega_I.dot_product(_omega_I)); + if (integrator_magnitude > radians(300)) { + _omega_I *= (0.5f * radians(300) / integrator_magnitude); + } + +} + +/**************************************************/ +void +AP_DCM::_accel_adjust(void) +{ + _accel_vector(1) += accel_scale((ground_speed / 100) * _omega(2)); // Centrifugal force on Acc_y = GPS_speed * GyroZ + _accel_vector(2) -= accel_scale((ground_speed / 100) * _omega(1)); // Centrifugal force on Acc_z = GPS_speed * GyroY +} + + +/**************************************************/ +void +AP_DCM::matrix_update(void) +{ + DCM_Matrix update_matrix; + + _gyro_vector(0) = gyro_scaled_X(read_adc(0)); // gyro x roll + _gyro_vector(1) = gyro_scaled_Y(read_adc(1)); // gyro y pitch + _gyro_vector(2) = gyro_scaled_Z(read_adc(2)); // gyro Z yaw + + //Record when you saturate any of the gyros. + if((abs(_gyro_vector(0)) >= radians(300)) || + (abs(_gyro_vector(1)) >= radians(300)) || + (abs(_gyro_vector(2)) >= radians(300))) + gyro_sat_count++; + +/* +Serial.print (__adc_in[0]); +Serial.print (" "); +Serial.print (_adc_offset[0]); +Serial.print (" "); +Serial.print (_gyro_vector(0)); +Serial.print (" "); +Serial.print (__adc_in[1]); +Serial.print (" "); +Serial.print (_adc_offset[1]); +Serial.print (" "); +Serial.print (_gyro_vector(1)); +Serial.print (" "); +Serial.print (__adc_in[2]); +Serial.print (" "); +Serial.print (_adc_offset[2]); +Serial.print (" "); +Serial.println (_gyro_vector(2)); +*/ + +// _accel_vector(0) = read_adc(3); // acc x +// _accel_vector(1) = read_adc(4); // acc y +// _accel_vector(2) = read_adc(5); // acc z + // Low pass filter on accelerometer data (to filter vibrations) + _accel_vector(0) = _accel_vector(0) * 0.6 + (float)read_adc(3) * 0.4; // acc x + _accel_vector(1) = _accel_vector(1) * 0.6 + (float)read_adc(4) * 0.4; // acc y + _accel_vector(2) = _accel_vector(2) * 0.6 + (float)read_adc(5) * 0.4; // acc z + + _omega = _gyro_vector + _omega_I; // adding proportional term + _omega_vector = _omega + _omega_P; // adding Integrator term + + _accel_adjust(); // Remove centrifugal acceleration. + + #if OUTPUTMODE == 1 + update_matrix(0, 0) = 0; + update_matrix(0, 1) = -_G_Dt * _omega_vector(2); // -z + update_matrix(0, 2) = _G_Dt * _omega_vector(1); // y + update_matrix(1, 0) = _G_Dt * _omega_vector(2); // z + update_matrix(1, 1) = 0; + update_matrix(1, 2) = -_G_Dt * _omega_vector(0); // -x + update_matrix(2, 0) = -_G_Dt * _omega_vector(1); // -y + update_matrix(2, 1) = _G_Dt * _omega_vector(0); // x + update_matrix(2, 2) = 0; + #else // Uncorrected data (no drift correction) + update_matrix(0, 0) = 0; + update_matrix(0, 1) = -_G_Dt * _gyro_vector(2); // -z + update_matrix(0, 2) = _G_Dt * _gyro_vector(1); // y + update_matrix(1, 0) = _G_Dt * _gyro_vector(2); // z + update_matrix(1, 1) = 0; + update_matrix(1, 2) = -_G_Dt * _gyro_vector(0); + update_matrix(2, 0) = -_G_Dt * _gyro_vector(1); + update_matrix(2, 1) = _G_Dt * _gyro_vector(0); + update_matrix(2, 2) = 0; + #endif + + // update + _dcm_matrix += _dcm_matrix * update_matrix; + +/* +Serial.print (_G_Dt * 1000); +Serial.print (" "); +Serial.print (dcm_matrix(0, 0)); +Serial.print (" "); +Serial.print (dcm_matrix(0, 1)); +Serial.print (" "); +Serial.print (dcm_matrix(0, 2)); +Serial.print (" "); +Serial.print (dcm_matrix(1, 0)); +Serial.print (" "); +Serial.print (dcm_matrix(1, 1)); +Serial.print (" "); +Serial.print (dcm_matrix(1, 2)); +Serial.print (" "); +Serial.print (dcm_matrix(2, 0)); +Serial.print (" "); +Serial.print (dcm_matrix(2, 1)); +Serial.print (" "); +Serial.println (dcm_matrix(2, 2)); +*/ +} + +/**************************************************/ +void +AP_DCM::euler_angles(void) +{ + #if (OUTPUTMODE == 2) // Only accelerometer info (debugging purposes) + roll = atan2(_accel_vector(1), _accel_vector(2)); // atan2(acc_y, acc_z) + roll_sensor = degrees(roll) * 100; + pitch = -asin((_accel_vector(0)) / (double)GRAVITY); // asin(acc_x) + pitch_sensor = degrees(pitch) * 100; + yaw = 0; + #else + pitch = -asin(_dcm_matrix(2, 0)); + pitch_sensor = degrees(pitch) * 100; + roll = atan2(_dcm_matrix(2, 1), _dcm_matrix(2, 2)); + roll_sensor = degrees(roll) * 100; + yaw = atan2(_dcm_matrix(1, 0), _dcm_matrix(0, 0)); + yaw_sensor = degrees(yaw) * 100; + #endif + + /* + Serial.print ("Roll "); + Serial.print (roll_sensor / 100); + Serial.print (", Pitch "); + Serial.print (pitch_sensor / 100); + Serial.print (", Yaw "); + Serial.println (yaw_sensor / 100); + */ +} + +/**************************************************/ +//Computes the dot product of two vectors +float +DCM_Vector::dot_product(DCM_Vector const &vector2) const +{ + float op = 0; + + for(int c = 0; c < 3; c++) + op += _v[c] * vector2(c); + + return op; +} + +// cross-product +DCM_Vector +DCM_Vector::operator^(DCM_Vector const &a) const +{ + DCM_Vector result; + + result(0) = (_v[1] * a(2)) - (_v[2] * a(1)); + result(1) = (_v[2] * a(0)) - (_v[0] * a(2)); + result(2) = (_v[0] * a(1)) - (_v[1] * a(0)); + + return(result); +} + +// scale +DCM_Vector +DCM_Vector::operator*(float scale) const +{ + DCM_Vector result; + + result(0) = _v[0] * scale; + result(1) = _v[1] * scale; + result(2) = _v[2] * scale; + + return(result); +} + +// scale +void +DCM_Vector::operator*=(float scale) +{ + _v[0] *= scale; + _v[1] *= scale; + _v[2] *= scale; +} + +// add +DCM_Vector +DCM_Vector::operator+(DCM_Vector const &a) const +{ + DCM_Vector result; + + result(0) = _v[0] + a(0); + result(1) = _v[1] + a(1); + result(2) = _v[2] + a(2); + + return(result); +} + +// add +void +DCM_Vector::operator+=(DCM_Vector const &a) +{ + _v[0] += a(0); + _v[1] += a(1); + _v[2] += a(2); +} + +// magnitude +float +DCM_Vector::magnitude(void) const +{ + return(sqrt((_v[0] * _v[0]) + + (_v[1] * _v[1]) + + (_v[2] * _v[2]))); +} + +// 3x3 matrix multiply +DCM_Matrix +DCM_Matrix::operator*(DCM_Matrix const &a) const +{ + DCM_Matrix result; + + for (int x = 0; x < 3; x++) { + for (int y = 0; y < 3; y++) { + result(x, y) = + _m[x](0) * a(0, y) + + _m[x](1) * a(1, y) + + _m[x](2) * a(2, y); + } + } + return(result); +} + +// 3x3 matrix add +void +DCM_Matrix::operator+=(DCM_Matrix const &a) +{ + for (int x = 0; x < 3; x++) + for (int y = 0; y < 3; y++) + _m[x](y) += a(x,y); +} + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/DCM/DCM.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/DCM/DCM.h new file mode 100644 index 0000000000..76dbb71381 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/DCM/DCM.h @@ -0,0 +1,147 @@ +#ifndef AP_DCM_h +#define AP_DCM_h + +#include +//#include "WProgram.h" + +//////////////////////////////////////////////////////////////////////////////// +// XXX HACKS +class APM_Compass { +public: + int Heading_X; + int Heading_Y; +}; + +typedef uint8_t byte; + +class APM_ADC { +public: + int Ch(int c) {return ~c;}; +}; + +extern int ground_speed; +extern int pitch; +extern int yaw; +extern int roll; +extern int roll_sensor; +extern int pitch_sensor; +extern int yaw_sensor; +#define SPEEDFILT 100 + +// XXX warning, many of these are nonsense just to make the compiler think +#define abs(_x) (((_x) < 0) ? -(_x) : (_x)) +#define constrain(_x, _min, _max) (((_x) < (_min)) ? (_min) : (((_x) > (_max)) ? (_max) : (_x))) +#define sqrt(_x) ((_x) / 2) // !!! +#define radians(_x) ((_x) / (180 * 3.14)) // !!! shoot me... +#define degrees(_x) ((_x) * (180 / 3.14)) +#define accel_scale(_x) ((_x) * 3) // !!! +#define gyro_scaled_X(_x) ((_x) / 3) +#define gyro_scaled_Y(_x) ((_x) / 3) +#define gyro_scaled_Z(_x) ((_x) / 3) +#define asin(_x) ((_x) * 5) +#define atan2(_x, _y) (((_x) + (_y)) / 5) + +// XXX END HACKS +//////////////////////////////////////////////////////////////////////////////// + +class DCM_Vector { +public: + DCM_Vector(float v0 = 0, float v1 = 0, float v2 = 0); + + // access vector elements with obj(element) + float& operator() (int x) {return _v[x];}; + float operator() (int x) const {return _v[x];}; + + DCM_Vector operator+ (DCM_Vector const &a) const; // add + void operator+= (DCM_Vector const &a); // add + DCM_Vector operator^ (DCM_Vector const &a) const; // cross-product + DCM_Vector operator* (float scale) const; // scale + void operator*= (float scale); // scale + + float dot_product(DCM_Vector const &v2) const; + float magnitude(void) const; + +private: + float _v[3]; +}; + +class DCM_Matrix { +public: + DCM_Matrix(float m00 = 0, float m01 = 0, float m02 = 0, + float m10 = 0, float m11 = 0, float m12 = 0, + float m20 = 0, float m21 = 0, float m22 = 0); + + // access matrix elements with obj(x,y) + float& operator() (int x, int y) {return _m[x](y);}; + float operator() (int x, int y) const {return _m[x](y);}; + + // access matrix columns with obj(x) + DCM_Vector& operator() (int x) {return _m[x];}; + DCM_Vector operator() (int x) const {return _m[x];}; + + // matrix multiply + DCM_Matrix operator* (DCM_Matrix const &a) const; + + // matrix add + void operator+= (DCM_Matrix const &a); + +private: + DCM_Vector _m[3]; +}; + + +class AP_DCM +{ +public: + // Methods + AP_DCM(APM_Compass *withCompass); + void update_DCM(void); //G_Dt + + // XXX these are all private (called by update_DCM only?) + void read_adc_raw(void); + void euler_angles(void); + void matrix_update(void); + void drift_correction(void); + void normalize(void); + float read_adc(int select); + + float imu_health; //Metric based on accel gain deweighting + byte gyro_sat_count; + byte adc_constraints; + byte renorm_sqrt_count; + byte renorm_blowup_count; + +private: + // Methods + void _accel_adjust(void); + float _gyro_temp_comp(int i, int temp) const; + DCM_Vector _renorm(DCM_Vector const &a, uint8_t &problem); + + // members + APM_Compass *_compass; + + DCM_Matrix _dcm_matrix; + + float _adc_in[6]; // array that store the 6 ADC channels used by IMU + float _adc_offset[6]; // Array that store the Offset of the gyros and accelerometers + float _G_Dt; // Integration time for the gyros (DCM algorithm) + DCM_Vector _accel_vector; // Store the acceleration in a vector + DCM_Vector _gyro_vector; //Store the gyros turn rate in a vector + DCM_Vector _omega_vector; //Corrected Gyro_Vector data + DCM_Vector _omega_P; //Omega Proportional correction + DCM_Vector _omega_I; //Omega Integrator + DCM_Vector _omega; + DCM_Vector _error_roll_pitch; + DCM_Vector _error_yaw; + float _errorCourse; + float _course_over_ground_x; //Course overground X axis + float _course_over_ground_y; //Course overground Y axis + + // constants + static const uint8_t _sensors[6]; + static const int _sensor_signs[9]; + static const uint8_t _gyro_temp_ch = 3; // The ADC channel reading the gyro temperature + static const float _gyro_temp_curve[3][3]; +}; + +#endif diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/DCM/examples/DCM_test/DCM_test.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/DCM/examples/DCM_test/DCM_test.pde new file mode 100644 index 0000000000..c7225d44ae --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/DCM/examples/DCM_test/DCM_test.pde @@ -0,0 +1,38 @@ +/* + Example of APM_Compass library (HMC5843 sensor). + Code by Jordi MuÒoz and Jose Julio. DIYDrones.com +*/ + +//#include +#include // Compass Library + +unsigned long timer; + +void setup() +{ + DCM.init(); // Initialization + Serial.begin(38400); + Serial.println("Compass library test (HMC5843)"); + delay(1000); + timer = millis(); +} + +void loop() +{ + float tmp; + + if((millis()- timer) > 100){ + timer = millis(); + APM_Compass.Read(); + APM_Compass.Calculate(0, 0); // roll = 0, pitch = 0 for this example + Serial.print("Heading:"); + Serial.print(ToDeg(APM_Compass.Heading)); + Serial.print(" ("); + Serial.print(APM_Compass.Mag_X); + Serial.print(","); + Serial.print(APM_Compass.Mag_Y); + Serial.print(","); + Serial.print(APM_Compass.Mag_Z); + Serial.println(" )"); + } +} \ No newline at end of file diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/DataFlash/DataFlash.cpp b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/DataFlash/DataFlash.cpp new file mode 100644 index 0000000000..d7c4bba837 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/DataFlash/DataFlash.cpp @@ -0,0 +1,342 @@ +/* + DataFlash.cpp - DataFlash log library for AT45DB161 + Code by Jordi Muñoz and Jose Julio. DIYDrones.com + This code works with boards based on ATMega168/328 and ATMega1280 using SPI port + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + Dataflash library for AT45DB161D flash memory + Memory organization : 4096 pages of 512 bytes + + Maximun write bandwidth : 512 bytes in 14ms + This code is written so the master never has to wait to write the data on the eeprom + + Methods: + Init() : Library initialization (SPI initialization) + StartWrite(page) : Start a write session. page=start page. + WriteByte(data) : Write a byte + WriteInt(data) : Write an integer (2 bytes) + WriteLong(data) : Write a long (4 bytes) + StartRead(page) : Start a read on (page) + GetWritePage() : Returns the last page written to + GetPage() : Returns the last page read + ReadByte() + ReadInt() + ReadLong() + + Properties: + +*/ + +extern "C" { + // AVR LibC Includes + #include + #include + #include "WConstants.h" +} + +#include "DataFlash.h" + +#define OVERWRITE_DATA 0 // 0: When reach the end page stop, 1: Start overwritten from page 1 + +// *** INTERNAL FUNCTIONS *** +unsigned char dataflash_SPI_transfer(unsigned char output) +{ + SPDR = output; // Start the transmission + while (!(SPSR & (1<> 6)); + dataflash_SPI_transfer((unsigned char)(PageAdr << 2)); + dataflash_SPI_transfer(0x00); // don´t care bytes + + dataflash_CS_inactive(); //initiate the transfer + dataflash_CS_active(); + + while(!ReadStatus()); //monitor the status register, wait until busy-flag is high +} + +void DataFlash_Class::BufferToPage (unsigned char BufferNum, unsigned int PageAdr, unsigned char wait) +{ + dataflash_CS_inactive(); // Reset dataflash command decoder + dataflash_CS_active(); + + if (BufferNum==1) + dataflash_SPI_transfer(DF_BUFFER_1_TO_PAGE_WITH_ERASE); + else + dataflash_SPI_transfer(DF_BUFFER_2_TO_PAGE_WITH_ERASE); + dataflash_SPI_transfer((unsigned char)(PageAdr >> 6)); + dataflash_SPI_transfer((unsigned char)(PageAdr << 2)); + dataflash_SPI_transfer(0x00); // don´t care bytes + + dataflash_CS_inactive(); //initiate the transfer + dataflash_CS_active(); + + // Check if we need to wait to write the buffer to memory or we can continue... + if (wait) + while(!ReadStatus()); //monitor the status register, wait until busy-flag is high +} + +void DataFlash_Class::BufferWrite (unsigned char BufferNum, unsigned int IntPageAdr, unsigned char Data) +{ + dataflash_CS_inactive(); // Reset dataflash command decoder + dataflash_CS_active(); + + if (BufferNum==1) + dataflash_SPI_transfer(DF_BUFFER_1_WRITE); + else + dataflash_SPI_transfer(DF_BUFFER_2_WRITE); + dataflash_SPI_transfer(0x00); //don't cares + dataflash_SPI_transfer((unsigned char)(IntPageAdr>>8)); //upper part of internal buffer address + dataflash_SPI_transfer((unsigned char)(IntPageAdr)); //lower part of internal buffer address + dataflash_SPI_transfer(Data); //write data byte +} + +unsigned char DataFlash_Class::BufferRead (unsigned char BufferNum, unsigned int IntPageAdr) +{ + byte tmp; + + dataflash_CS_inactive(); // Reset dataflash command decoder + dataflash_CS_active(); + + if (BufferNum==1) + dataflash_SPI_transfer(DF_BUFFER_1_READ); + else + dataflash_SPI_transfer(DF_BUFFER_2_READ); + dataflash_SPI_transfer(0x00); //don't cares + dataflash_SPI_transfer((unsigned char)(IntPageAdr>>8)); //upper part of internal buffer address + dataflash_SPI_transfer((unsigned char)(IntPageAdr)); //lower part of internal buffer address + dataflash_SPI_transfer(0x00); //don't cares + tmp = dataflash_SPI_transfer(0x00); //read data byte + + return (tmp); +} +// *** END OF INTERNAL FUNCTIONS *** + +void DataFlash_Class::PageErase (unsigned int PageAdr) +{ + dataflash_CS_inactive(); //make sure to toggle CS signal in order + dataflash_CS_active(); //to reset Dataflash command decoder + dataflash_SPI_transfer(DF_PAGE_ERASE); // Command + dataflash_SPI_transfer((unsigned char)(PageAdr >> 6)); //upper part of page address + dataflash_SPI_transfer((unsigned char)(PageAdr << 2)); //lower part of page address and MSB of int.page adr. + dataflash_SPI_transfer(0x00); // "dont cares" + dataflash_CS_inactive(); //initiate flash page erase + dataflash_CS_active(); + while(!ReadStatus()); +} + +// *** DATAFLASH PUBLIC FUNCTIONS *** +void DataFlash_Class::StartWrite(int PageAdr) +{ + df_BufferNum=1; + df_BufferIdx=0; + df_PageAdr=PageAdr; + df_Stop_Write=0; + WaitReady(); +} + +void DataFlash_Class::WriteByte(byte data) +{ + if (!df_Stop_Write) + { + BufferWrite(df_BufferNum,df_BufferIdx,data); + df_BufferIdx++; + if (df_BufferIdx >= 512) // End of buffer? + { + df_BufferIdx=0; + BufferToPage(df_BufferNum,df_PageAdr,0); // Write Buffer to memory, NO WAIT + df_PageAdr++; + if (OVERWRITE_DATA==1) + { + if (df_PageAdr>=4096) // If we reach the end of the memory, start from the begining + df_PageAdr = 1; + } + else + { + if (df_PageAdr>=4096) // If we reach the end of the memory, stop here + df_Stop_Write=1; + } + + if (df_BufferNum==1) // Change buffer to continue writing... + df_BufferNum=2; + else + df_BufferNum=1; + } + } +} + +void DataFlash_Class::WriteInt(int data) +{ + WriteByte(data>>8); // High byte + WriteByte(data&0xFF); // Low byte +} + +void DataFlash_Class::WriteLong(long data) +{ + WriteByte(data>>24); // First byte + WriteByte(data>>16); + WriteByte(data>>8); + WriteByte(data&0xFF); // Last byte +} + +// Get the last page written to +int DataFlash_Class::GetWritePage() +{ + return(df_PageAdr); +} + +// Get the last page read +int DataFlash_Class::GetPage() +{ + return(df_Read_PageAdr-1); +} + +void DataFlash_Class::StartRead(int PageAdr) +{ + df_Read_BufferNum=1; + df_Read_BufferIdx=0; + df_Read_PageAdr=PageAdr; + WaitReady(); + PageToBuffer(df_Read_BufferNum,df_Read_PageAdr); // Write Memory page to buffer + df_Read_PageAdr++; +} + +byte DataFlash_Class::ReadByte() +{ + byte result; + + WaitReady(); + result = BufferRead(df_Read_BufferNum,df_Read_BufferIdx); + df_Read_BufferIdx++; + if (df_Read_BufferIdx >= 512) // End of buffer? + { + df_Read_BufferIdx=0; + PageToBuffer(df_Read_BufferNum,df_Read_PageAdr); // Write memory page to Buffer + df_Read_PageAdr++; + if (df_Read_PageAdr>=4096) // If we reach the end of the memory, start from the begining + { + df_Read_PageAdr = 0; + df_Read_END = true; + } + } + return result; +} + +int DataFlash_Class::ReadInt() +{ + int result; + + result = ReadByte(); // High byte + result = (result<<8) | ReadByte(); // Low byte + return result; +} + +long DataFlash_Class::ReadLong() +{ + long result; + + result = ReadByte(); // First byte + result = (result<<8) | ReadByte(); + result = (result<<8) | ReadByte(); + result = (result<<8) | ReadByte(); // Last byte + return result; +} + +// make one instance for the user to use +DataFlash_Class DataFlash; \ No newline at end of file diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/DataFlash/DataFlash.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/DataFlash/DataFlash.h new file mode 100644 index 0000000000..037421c989 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/DataFlash/DataFlash.h @@ -0,0 +1,86 @@ +/* ************************************************************ */ +/* Test for DataFlash Log library */ +/* ************************************************************ */ +#ifndef DataFlash_h +#define DataFlash_h + +// arduino mega SPI pins +#if defined(__AVR_ATmega1280__) + #define DF_DATAOUT 51 // MOSI + #define DF_DATAIN 50 // MISO + #define DF_SPICLOCK 52 // SCK + #define DF_SLAVESELECT 53 // SS (PB0) + #define DF_RESET 31 // RESET (PC6) +#else // normal arduino SPI pins... + #define DF_DATAOUT 11 //MOSI + #define DF_DATAIN 12 //MISO + #define DF_SPICLOCK 13 //SCK + #define DF_SLAVESELECT 10 //SS +#endif + +// AT45DB161D Commands (from Datasheet) +#define DF_TRANSFER_PAGE_TO_BUFFER_1 0x53 +#define DF_TRANSFER_PAGE_TO_BUFFER_2 0x55 +#define DF_STATUS_REGISTER_READ 0xD7 +#define DF_READ_MANUFACTURER_AND_DEVICE_ID 0x9F +#define DF_PAGE_READ 0xD2 +#define DF_BUFFER_1_READ 0xD4 +#define DF_BUFFER_2_READ 0xD6 +#define DF_BUFFER_1_WRITE 0x84 +#define DF_BUFFER_2_WRITE 0x87 +#define DF_BUFFER_1_TO_PAGE_WITH_ERASE 0x83 +#define DF_BUFFER_2_TO_PAGE_WITH_ERASE 0x86 +#define DF_PAGE_ERASE 0x81 +#define DF_BLOCK_ERASE 0x50 +#define DF_SECTOR_ERASE 0x7C +#define DF_CHIP_ERASE_0 0xC7 +#define DF_CHIP_ERASE_1 0x94 +#define DF_CHIP_ERASE_2 0x80 +#define DF_CHIP_ERASE_3 0x9A + +class DataFlash_Class +{ + private: + // DataFlash Log variables... + unsigned char df_BufferNum; + unsigned char df_Read_BufferNum; + unsigned int df_BufferIdx; + unsigned int df_Read_BufferIdx; + unsigned int df_PageAdr; + unsigned int df_Read_PageAdr; + unsigned char df_Read_END; + unsigned char df_Stop_Write; + //Methods + unsigned char BufferRead (unsigned char BufferNum, unsigned int IntPageAdr); + void BufferWrite (unsigned char BufferNum, unsigned int IntPageAdr, unsigned char Data); + void BufferToPage (unsigned char BufferNum, unsigned int PageAdr, unsigned char wait); + void PageToBuffer(unsigned char BufferNum, unsigned int PageAdr); + void WaitReady(); + unsigned char ReadStatus(); + + public: + unsigned char df_manufacturer; + unsigned char df_device_0; + unsigned char df_device_1; + + DataFlash_Class(); // Constructor + void Init(); + void ReadManufacturerID(); + int GetPage(); + int GetWritePage(); + void PageErase (unsigned int PageAdr); + // Write methods + void StartWrite(int PageAdr); + void WriteByte(unsigned char data); + void WriteInt(int data); + void WriteLong(long data); + // Read methods + void StartRead(int PageAdr); + unsigned char ReadByte(); + int ReadInt(); + long ReadLong(); +}; + +extern DataFlash_Class DataFlash; + +#endif \ No newline at end of file diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/DataFlash/examples/DataFlash_test/DataFlash_test.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/DataFlash/examples/DataFlash_test/DataFlash_test.pde new file mode 100644 index 0000000000..8ffc712d72 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/DataFlash/examples/DataFlash_test/DataFlash_test.pde @@ -0,0 +1,99 @@ +/* + Example of DataFlash library. + Code by Jordi Muoz and Jose Julio. DIYDrones.com +*/ + +#include + +#define HEAD_BYTE1 0xA3 +#define HEAD_BYTE2 0x95 + +void setup() +{ + Serial.begin(57600); + DataFlash.Init(); // DataFlash initialization + + Serial.println("Dataflash Log Test 1.0"); + + // Test + delay(20); + DataFlash.ReadManufacturerID(); + delay(10); + Serial.print("Manufacturer:"); + Serial.print(int(DataFlash.df_manufacturer)); + Serial.print(","); + Serial.print(int(DataFlash.df_device_0)); + Serial.print(","); + Serial.print(int(DataFlash.df_device_1)); + Serial.println(); + + // We start to write some info (sequentialy) starting from page 1 + // This is similar to what we will do... + DataFlash.StartWrite(1); + Serial.println("Writing to flash... wait..."); + for (int i=0;i<1000;i++) // Write 1000 packets... + { + // We write packets of binary data... (without worry about nothing more) + DataFlash.WriteByte(HEAD_BYTE1); + DataFlash.WriteByte(HEAD_BYTE2); + DataFlash.WriteInt(2000+i); + DataFlash.WriteInt(2001+i); + DataFlash.WriteInt(2002+i); + DataFlash.WriteInt(2003+i); + DataFlash.WriteLong((long)i*5000); + DataFlash.WriteLong((long)i*16268); + DataFlash.WriteByte(0xA2); // 2 bytes of checksum (example) + DataFlash.WriteByte(0x4E); + delay(10); + } + delay(100); +} + +void loop() +{ + int i; + byte tmp_byte1; + byte tmp_byte2; + int tmp_int; + long tmp_long; + + Serial.println("Start reading page 1..."); + DataFlash.StartRead(1); // We start reading from page 1 + for (i=0;i<200;i++) // Read 200 packets... + { + tmp_byte1=DataFlash.ReadByte(); + tmp_byte2=DataFlash.ReadByte(); + Serial.print("PACKET:"); + if ((tmp_byte1==HEAD_BYTE1)&&(tmp_byte1==HEAD_BYTE1)) + { + // Read 4 ints... + tmp_int=DataFlash.ReadInt(); + Serial.print(tmp_int); + Serial.print(","); + tmp_int=DataFlash.ReadInt(); + Serial.print(tmp_int); + Serial.print(","); + tmp_int=DataFlash.ReadInt(); + Serial.print(tmp_int); + Serial.print(","); + tmp_int=DataFlash.ReadInt(); + Serial.print(tmp_int); + Serial.print(","); + + // Read 2 longs... + tmp_long=DataFlash.ReadLong(); + Serial.print(tmp_long); + Serial.print(","); + tmp_long=DataFlash.ReadLong(); + Serial.print(tmp_long); + Serial.print(";"); + + // Read the checksum... + tmp_byte1=DataFlash.ReadByte(); + tmp_byte2=DataFlash.ReadByte(); + } + Serial.println(); + } + + delay(10000); +} \ No newline at end of file diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/DataFlash/keywords.txt b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/DataFlash/keywords.txt new file mode 100644 index 0000000000..eea5025224 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/DataFlash/keywords.txt @@ -0,0 +1,14 @@ +DataFlash KEYWORD1 +Init KEYWORD2 +ReadManufacturerID KEYWORD2 +GetPage KEYWORD2 +PageErase KEYWORD2 +StartWrite KEYWORD2 +StartRead KEYWORD2 +ReadByte KEYWORD2 +ReadInt KEYWORD2 +ReadLong KEYWORD2 +WriteByte KEYWORD2 +WriteInt KEYWORD2 +WriteLong KEYWORD2 + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/FastSerial/FastSerial.cpp b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/FastSerial/FastSerial.cpp new file mode 100644 index 0000000000..88f131bbe4 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/FastSerial/FastSerial.cpp @@ -0,0 +1,348 @@ +// -*- Mode: C++; c-basic-offset: 8; indent-tabs-mode: nil -*- +// +// Interrupt-driven serial transmit/receive library. +// +// Copyright (c) 2010 Michael Smith. All rights reserved. +// +// Receive and baudrate calculations derived from the Arduino +// HardwareSerial driver: +// +// Copyright (c) 2006 Nicholas Zambetti. All right reserved. +// +// Transmit algorithm inspired by work: +// +// Code Jose Julio and Jordi Munoz. DIYDrones.com +// +// This library is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 2.1 of the License, or (at your option) any later version. +// +// This library 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 +// Lesser General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License along with this library; if not, write to the Free Software +// Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +// + + +//#include "../AP_Common/AP_Common.h" +#include "FastSerial.h" +#include "WProgram.h" + +#if defined(__AVR_ATmega1280__) +# define FS_MAX_PORTS 4 +#else +# define FS_MAX_PORTS 1 +#endif + +FastSerial::Buffer __FastSerial__rxBuffer[FS_MAX_PORTS]; +FastSerial::Buffer __FastSerial__txBuffer[FS_MAX_PORTS]; + +// Default buffer sizes +#define RX_BUFFER_SIZE 128 +#define TX_BUFFER_SIZE 64 +#define BUFFER_MAX 512 + +// Interrupt handlers ////////////////////////////////////////////////////////// + +#if 0 +#define HANDLERS(_PORT, _RXVECTOR, _TXVECTOR, _UDR) \ +SIGNAL(_RXVECTOR) \ +{ \ + unsigned char c = _UDR; \ + ports[_PORT]->receive(c); \ +} \ + \ +SIGNAL(_TXVECTOR) \ +{ \ + ports[_PORT]->transmit(); \ +} \ +struct hack + +#if defined(__AVR_ATmega8__) +HANDLERS(0, SIG_UART_RECV, SIG_UART_DATA, UDR); +#else +HANDLERS(0, SIG_USART0_RECV, SIG_USART0_DATA, UDR0); +#if defined(__AVR_ATmega1280__) +HANDLERS(1, SIG_USART1_RECV, SIG_USART1_DATA, UDR1); +HANDLERS(2, SIG_USART2_RECV, SIG_USART2_DATA, UDR2); +//HANDLERS(3, SIG_USART3_RECV, SIG_USART3_DATA, UDR3); +#endif +#endif +#endif + +// Constructor ///////////////////////////////////////////////////////////////// + +FastSerial::FastSerial(const uint8_t portNumber, + volatile uint8_t *ubrrh, + volatile uint8_t *ubrrl, + volatile uint8_t *ucsra, + volatile uint8_t *ucsrb, + volatile uint8_t *udr, + const uint8_t u2x, + const uint8_t portEnableBits, + const uint8_t portTxBits) +{ + _ubrrh = ubrrh; + _ubrrl = ubrrl; + _ucsra = ucsra; + _ucsrb = ucsrb; + _udr = udr; + _u2x = u2x; + _portEnableBits = portEnableBits; + _portTxBits = portTxBits; + + // init buffers + _rxBuffer = &__FastSerial__rxBuffer[portNumber]; + _txBuffer->head = _txBuffer->tail = 0; + _txBuffer = &__FastSerial__txBuffer[portNumber]; + _rxBuffer->head = _rxBuffer->tail = 0; + + // init stdio + fdev_setup_stream(&_fd, &FastSerial::_putchar, &FastSerial::_getchar, _FDEV_SETUP_RW); + fdev_set_udata(&_fd, this); + if (0 == portNumber) { + stdout = &_fd; // serial port 0 is always the default console + stdin = &_fd; + stderr = &_fd; + } +} + +// Public Methods ////////////////////////////////////////////////////////////// + +void FastSerial::begin(long baud) +{ + unsigned int rxb, txb; + + // If we are re-configuring an already-open port, preserve the + // existing buffer sizes. + if (_open) { + rxb = _rxBuffer->mask + 1; + txb = _txBuffer->mask + 1; + } else { + rxb = RX_BUFFER_SIZE; + txb = TX_BUFFER_SIZE; + } + + begin(baud, RX_BUFFER_SIZE, TX_BUFFER_SIZE); +} + +void FastSerial::begin(long baud, unsigned int rxSpace, unsigned int txSpace) +{ + uint16_t ubrr; + bool use_u2x = false; + int ureg, u2; + long breg, b2, dreg, d2; + + // if we are currently open, close and restart + if (_open) + end(); + + // allocate buffers + if (!_allocBuffer(_rxBuffer, rxSpace ? : RX_BUFFER_SIZE) || + !_allocBuffer(_txBuffer, txSpace ? : TX_BUFFER_SIZE)) { + end(); + return; // couldn't allocate buffers - fatal + } + _open = true; + + // U2X mode is needed for bitrates higher than (F_CPU / 16) + if (baud > F_CPU / 16) { + use_u2x = true; + ubrr = F_CPU / (8 * baud) - 1; + } else { + // Determine whether u2x mode would give a closer + // approximation of the desired speed. + + // ubrr for non-2x mode, corresponding baudrate and delta + ureg = F_CPU / 16 / baud - 1; + breg = F_CPU / 16 / (ureg + 1); + dreg = abs(baud - breg); + + // ubrr for 2x mode, corresponding bitrate and delta + u2 = F_CPU / 8 / baud - 1; + b2 = F_CPU / 8 / (u2 + 1); + d2 = abs(baud - b2); + + // Pick the setting that gives the smallest rate + // error, preferring non-u2x mode if the delta is + // identical. + if (dreg <= d2) { + ubrr = ureg; + } else { + ubrr = u2; + use_u2x = true; + } + } + + *_ucsra = use_u2x ? _BV(_u2x) : 0; + *_ubrrh = ubrr >> 8; + *_ubrrl = ubrr; + *_ucsrb |= _portEnableBits; +} + +void FastSerial::end() +{ + *_ucsrb &= ~(_portEnableBits | _portTxBits); + + _freeBuffer(_rxBuffer); + _freeBuffer(_txBuffer); + _open = false; +} + +int +FastSerial::available(void) +{ + if (!_open) + return(-1); + return((_rxBuffer->head - _rxBuffer->tail) & _rxBuffer->mask); +} + +int +FastSerial::read(void) +{ + uint8_t c; + + // if the head and tail are equal, the buffer is empty + if (!_open || (_rxBuffer->head == _rxBuffer->tail)) + return(-1); + + // pull character from tail + c = _rxBuffer->bytes[_rxBuffer->tail]; + _rxBuffer->tail = (_rxBuffer->tail + 1) & _rxBuffer->mask; + + return(c); +} + +void +FastSerial::flush(void) +{ + // don't reverse this or there may be problems if the RX interrupt + // occurs after reading the value of _rxBuffer->head but before writing + // the value to _rxBuffer->tail; the previous value of head + // may be written to tail, making it appear as if the buffer + // don't reverse this or there may be problems if the RX interrupt + // occurs after reading the value of head but before writing + // the value to tail; the previous value of rx_buffer_head + // may be written to tail, making it appear as if the buffer + // were full, not empty. + _rxBuffer->head = _rxBuffer->tail; + + // don't reverse this or there may be problems if the TX interrupt + // occurs after reading the value of _txBuffer->tail but before writing + // the value to _txBuffer->head. + _txBuffer->tail = _rxBuffer->head; +} + +void +FastSerial::write(uint8_t c) +{ + int16_t i; + + if (!_open) // drop bytes if not open + return; + + // wait for room in the tx buffer + i = (_txBuffer->head + 1) & _txBuffer->mask; + while (i == _txBuffer->tail) + ; + + // add byte to the buffer + _txBuffer->bytes[_txBuffer->head] = c; + _txBuffer->head = i; + + // enable the data-ready interrupt, as it may be off if the buffer is empty + *_ucsrb |= _portTxBits; +} + +// STDIO emulation ///////////////////////////////////////////////////////////// + +int +FastSerial::_putchar(char c, FILE *stream) +{ + FastSerial *fs; + + fs = (FastSerial *)fdev_get_udata(stream); + if ('\n' == c) + fs->write('\r'); // ASCII translation on the cheap + fs->write(c); + return(0); +} + +int +FastSerial::_getchar(FILE *stream) +{ + FastSerial *fs; + + fs = (FastSerial *)fdev_get_udata(stream); + + // We return -1 if there is nothing to read, which the library interprets + // as an error, which our clients will need to deal with. + return(fs->read()); +} + +int +FastSerial::printf(const char *fmt, ...) +{ + va_list ap; + int i; + + va_start(ap, fmt); + i = vfprintf(&_fd, fmt, ap); + va_end(ap); + + return(i); +} + +int +FastSerial::printf_P(const char *fmt, ...) +{ + va_list ap; + int i; + + va_start(ap, fmt); + i = vfprintf_P(&_fd, fmt, ap); + va_end(ap); + + return(i); +} + +// Buffer management /////////////////////////////////////////////////////////// + +bool +FastSerial::_allocBuffer(Buffer *buffer, unsigned int size) +{ + uint8_t shift; + + // init buffer state + buffer->head = buffer->tail = 0; + + // Compute the power of 2 greater or equal to the requested buffer size + // and then a mask to simplify wrapping operations. Using __builtin_clz + // would seem to make sense, but it uses a 256(!) byte table. + // Note that we ignore requests for more than BUFFER_MAX space. + for (shift = 1; (1U << shift) < min(BUFFER_MAX, size); shift++) + ; + buffer->mask = (1 << shift) - 1; + + // allocate memory for the buffer - if this fails, we fail + buffer->bytes = (uint8_t *)malloc(buffer->mask + 1); + + return(buffer->bytes != NULL); +} + +void +FastSerial::_freeBuffer(Buffer *buffer) +{ + buffer->head = buffer->tail = 0; + buffer->mask = 0; + if (NULL != buffer->bytes) { + free(buffer->bytes); + buffer->bytes = NULL; + } +} + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/FastSerial/FastSerial.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/FastSerial/FastSerial.h new file mode 100644 index 0000000000..1b83ebcca7 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/FastSerial/FastSerial.h @@ -0,0 +1,261 @@ +// -*- Mode: C++; c-basic-offset: 8; indent-tabs-mode: nil -*- +// +// Interrupt-driven serial transmit/receive library. +// +// Copyright (c) 2010 Michael Smith. All rights reserved. +// +// Receive and baudrate calculations derived from the Arduino +// HardwareSerial driver: +// +// Copyright (c) 2006 Nicholas Zambetti. All right reserved. +// +// Transmit algorithm inspired by work: +// +// Code Jose Julio and Jordi Munoz. DIYDrones.com +// +// This library is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 2.1 of the License, or (at your option) any later +// version. +// +// This library 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 Lesser General Public License for more +// details. +// +// You should have received a copy of the GNU Lesser General +// Public License along with this library; if not, write to the +// Free Software Foundation, Inc., 51 Franklin St, Fifth Floor, +// Boston, MA 02110-1301 USA +// + +// +// Note that this library does not pre-declare drivers for serial +// ports; the user must explicitly create drivers for the ports they +// wish to use. This is less friendly than the stock Arduino driver, +// but it saves ~200 bytes for every unused port. +// + +#ifndef FastSerial_h +#define FastSerial_h + +// disable the stock Arduino serial driver +#ifdef HardwareSerial_h +# error Must include FastSerial.h before the Arduino serial driver is defined. +#endif +#define HardwareSerial_h + +#include +#include +#include +#include +#include + +// +// Because Arduino libraries aren't really libraries, but we want to +// only define interrupt handlers for serial ports that are actually +// used, we have to force our users to define them using a macro. +// +// Due to the way interrupt vectors are specified, we have to have +// a separate macro for every port. Ugh. +// +// The macros are: +// +// FastSerialPort0() creates referencing serial port 0 +// FastSerialPort1() creates referencing serial port 1 +// FastSerialPort2() creates referencing serial port 2 +// FastSerialPort3() creates referencing serial port 3 +// + +// +// Forward declarations for clients that want to assume that the +// default Serial* objects exist. +// +// Note that the application is responsible for ensuring that these +// actually get defined, otherwise Arduino will suck in the +// HardwareSerial library and linking will fail. +// +extern class FastSerial Serial; +extern class FastSerial Serial1; +extern class FastSerial Serial2; +//extern class FastSerial Serial3; + + +class FastSerial : public Stream { +public: + FastSerial(const uint8_t portNumber, + volatile uint8_t *ubrrh, + volatile uint8_t *ubrrl, + volatile uint8_t *ucsra, + volatile uint8_t *ucsrb, + volatile uint8_t *udr, + const uint8_t u2x, + const uint8_t portEnableBits, + const uint8_t portTxBits); + + // Serial API + void begin(long baud); + void begin(long baud, unsigned int rxSpace, unsigned int txSpace); + void end(void); + int available(void); + int read(void); + void flush(void); + void write(uint8_t c); + using Stream::write; + + // stdio extensions + int printf(const char *fmt, ...); + int printf_P(const char *fmt, ...); + FILE *getfd(void) { return &_fd; }; + + // public so the interrupt handlers can see it + struct Buffer { + volatile uint16_t head, tail; + uint16_t mask; + uint8_t *bytes; + }; + +private: + // register accessors + volatile uint8_t *_ubrrh; + volatile uint8_t *_ubrrl; + volatile uint8_t *_ucsra; + volatile uint8_t *_ucsrb; + volatile uint8_t *_udr; + + // register magic numbers + uint8_t _portEnableBits; // rx, tx and rx interrupt enables + uint8_t _portTxBits; // tx data and completion interrupt enables + uint8_t _u2x; + + // ring buffers + Buffer *_rxBuffer; + Buffer *_txBuffer; + bool _open; + + bool _allocBuffer(Buffer *buffer, unsigned int size); + void _freeBuffer(Buffer *buffer); + + // stdio emulation + FILE _fd; + static int _putchar(char c, FILE *stream); + static int _getchar(FILE *stream); +}; + +// Used by the per-port interrupt vectors +extern FastSerial::Buffer __FastSerial__rxBuffer[]; +extern FastSerial::Buffer __FastSerial__txBuffer[]; + +// Generic Rx/Tx vectors for a serial port - needs to know magic numbers +#define FastSerialHandler(_PORT, _RXVECTOR, _TXVECTOR, _UDR, _UCSRB, _TXBITS) \ +ISR(_RXVECTOR, ISR_BLOCK) \ +{ \ + uint8_t c; \ + int16_t i; \ + \ + /* read the byte as quickly as possible */ \ + c = _UDR; \ + /* work out where the head will go next */ \ + i = (__FastSerial__rxBuffer[_PORT].head + 1) & __FastSerial__rxBuffer[_PORT].mask; \ + /* decide whether we have space for another byte */ \ + if (i != __FastSerial__rxBuffer[_PORT].tail) { \ + /* we do, move the head */ \ + __FastSerial__rxBuffer[_PORT].bytes[__FastSerial__rxBuffer[_PORT].head] = c; \ + __FastSerial__rxBuffer[_PORT].head = i; \ + } \ +} \ +ISR(_TXVECTOR, ISR_BLOCK) \ +{ \ + /* if there is another character to send */ \ + if (__FastSerial__txBuffer[_PORT].tail != __FastSerial__txBuffer[_PORT].head) { \ + _UDR = __FastSerial__txBuffer[_PORT].bytes[__FastSerial__txBuffer[_PORT].tail]; \ + /* increment the tail */ \ + __FastSerial__txBuffer[_PORT].tail = \ + (__FastSerial__txBuffer[_PORT].tail + 1) & __FastSerial__txBuffer[_PORT].mask; \ + } else { \ + /* there are no more bytes to send, disable the interrupt */ \ + if (__FastSerial__txBuffer[_PORT].head == __FastSerial__txBuffer[_PORT].tail) \ + _UCSRB &= ~_TXBITS; \ + } \ +} \ +struct hack + +// Macros defining serial ports +#if defined(__AVR_ATmega1280__) +#define FastSerialPort0(_portName) \ + FastSerial _portName(0, \ + &UBRR0H, \ + &UBRR0L, \ + &UCSR0A, \ + &UCSR0B, \ + &UDR0, \ + U2X0, \ + (_BV(RXEN0) | _BV(TXEN0) | _BV(RXCIE0)), \ + (_BV(UDRIE0))); \ + FastSerialHandler(0, SIG_USART0_RECV, SIG_USART0_DATA, UDR0, UCSR0B, _BV(UDRIE0)) +#define FastSerialPort1(_portName) \ + FastSerial _portName(1, \ + &UBRR1H, \ + &UBRR1L, \ + &UCSR1A, \ + &UCSR1B, \ + &UDR1, \ + U2X1, \ + (_BV(RXEN1) | _BV(TXEN1) | _BV(RXCIE1)), \ + (_BV(UDRIE1))); \ + FastSerialHandler(1, SIG_USART1_RECV, SIG_USART1_DATA, UDR1, UCSR1B, _BV(UDRIE1)) +#define FastSerialPort2(_portName) \ + FastSerial _portName(2, \ + &UBRR2H, \ + &UBRR2L, \ + &UCSR2A, \ + &UCSR2B, \ + &UDR2, \ + U2X2, \ + (_BV(RXEN2) | _BV(TXEN2) | _BV(RXCIE2)), \ + (_BV(UDRIE2))); \ + FastSerialHandler(2, SIG_USART2_RECV, SIG_USART2_DATA, UDR2, UCSR2B, _BV(UDRIE2)) +/* + #define FastSerialPort3(_portName) \ + FastSerial _portName(3, \ + &UBRR3H, \ + &UBRR3L, \ + &UCSR3A, \ + &UCSR3B, \ + &UDR3, \ + U2X3, \ + (_BV(RXEN3) | _BV(TXEN3) | _BV(RXCIE3)), \ + (_BV(UDRIE3))); \ + FastSerialHandler(3, SIG_USART3_RECV, SIG_USART3_DATA, UDR3, UCSR3B, _BV(UDRIE3)) +*/ + #else +#if defined(__AVR_ATmega8__) +#define FastSerialPort0(_portName) \ + FastSerial _portName(0, \ + &UBRR0H, \ + &UBRR0L, \ + &UCSR0A, \ + &UCSR0B, \ + &UDR0, \ + U2X0, \ + (_BV(RXEN0) | _BV(TXEN0) | _BV(RXCIE0)), \ + (_BV(UDRIE0))); \ + FastSerialHandler(0, SIG_UART_RECV, SIG_UART_DATA, UDR0, UCSR0B, _BV(UDRIE0)) +#else +// note no SIG_USART_* defines for the 168, 328, etc. +#define FastSerialPort0(_portName) \ + FastSerial _portName(0, \ + &UBRR0H, \ + &UBRR0L, \ + &UCSR0A, \ + &UCSR0B, \ + &UDR0, \ + U2X0, \ + (_BV(RXEN0) | _BV(TXEN0) | _BV(RXCIE0)), \ + (_BV(UDRIE0))); \ + FastSerialHandler(0, USART_RX_vect, USART_UDRE_vect, UDR0, UCSR0B, _BV(UDRIE0)) +#endif +#endif +#endif // FastSerial_h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/FastSerial/examples/FastSerial/FastSerial.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/FastSerial/examples/FastSerial/FastSerial.pde new file mode 100644 index 0000000000..e752e5c099 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/FastSerial/examples/FastSerial/FastSerial.pde @@ -0,0 +1,55 @@ +// -*- Mode: C++; c-basic-offset: 8; indent-tabs-mode: nil -*- + +// +// Example code for the FastSerial driver. +// +// This code is placed into the public domain. +// + +// +// Include the FastSerial library header. +// +// Note that this causes the standard Arduino Serial* driver to be +// disabled. +// +#include + +// +// Create a FastSerial driver that looks just like the stock Arduino +// driver. +// +FastSerialPort0(Serial); + +// +// To create a driver for a different serial port, on a board that +// supports more than one, use the appropriate macro: +// +//FastSerialPort2(Serial2); + + +void setup(void) +{ + // + // Set the speed for our replacement serial port. + // + Serial.begin(38400); + + // + // And send a message. + // + Serial.println("begin"); +} + +void +loop(void) +{ + int c; + + // + // Perform a simple loopback operation. + // + c = Serial.read(); + if (-1 != c) + Serial.write(c); +} + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/FastSerial/keywords.txt b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/FastSerial/keywords.txt new file mode 100644 index 0000000000..5be403f4fa --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/FastSerial/keywords.txt @@ -0,0 +1,7 @@ +FastSerial KEYWORD1 +begin KEYWORD2 +end KEYWORD2 +available KEYWORD2 +read KEYWORD2 +flush KEYWORD2 +write KEYWORD2 diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/.DS_Store b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/.DS_Store new file mode 100644 index 0000000000..944be92a09 Binary files /dev/null and b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/.DS_Store differ diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/GPS_IMU.cpp b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/GPS_IMU.cpp new file mode 100644 index 0000000000..a087ce9516 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/GPS_IMU.cpp @@ -0,0 +1,279 @@ +/* + GPS_IMU.cpp - IMU/X-Plane GPS library for Arduino +*/ + +#include "GPS_IMU.h" +#include +#include "WProgram.h" + + +// Constructors //////////////////////////////////////////////////////////////// +GPS_IMU_Class::GPS_IMU_Class() +{ +} + + +// Public Methods ////////////////////////////////////////////////////////////// +void GPS_IMU_Class::Init(void) +{ + ck_a = 0; + ck_b = 0; + IMU_step = 0; + NewData = 0; + Fix = 0; + PrintErrors = 0; + + IMU_timer = millis(); //Restarting timer... + // Initialize serial port + #if defined(__AVR_ATmega1280__) + Serial1.begin(38400); // Serial port 1 on ATMega1280 + #else + Serial.begin(38400); + #endif +} + +// optimization : This code dont wait for data, only proccess the data available +// We can call this function on the main loop (50Hz loop) +// If we get a complete packet this function calls parse_IMU_gps() to parse and update the GPS info. +void GPS_IMU_Class::Read(void) +{ + static unsigned long GPS_timer = 0; + byte data; + int numc = 0; + static byte message_num = 0; + + #if defined(__AVR_ATmega1280__) // If AtMega1280 then Serial port 1... + numc = Serial.available(); + #else + numc = Serial.available(); + #endif + + if (numc > 0){ + for (int i=0;i 28){ + IMU_step = 0; //Bad data, so restart to IMU_step zero and try again. + payload_counter = 0; + ck_a = 0; + ck_b = 0; + //payload_error_count++; + } + break; + + case 5: + message_num = data; + checksum(data); + IMU_step++; + break; + + case 6: // Payload data read... + // We stay in this state until we reach the payload_length + buffer[payload_counter] = data; + checksum(data); + payload_counter++; + if (payload_counter >= payload_length) { + IMU_step++; + } + break; + + case 7: + IMU_ck_a = data; // First checksum byte + IMU_step++; + break; + + case 8: + IMU_ck_b = data; // Second checksum byte + + // We end the IMU/GPS read... + // Verify the received checksum with the generated checksum.. + if((ck_a == IMU_ck_a) && (ck_b == IMU_ck_b)) { + if (message_num == 0x02) { + IMU_join_data(); + IMU_timer = millis(); + } else if (message_num == 0x03) { + GPS_join_data(); + GPS_timer = millis(); + } else if (message_num == 0x04) { + IMU2_join_data(); + IMU_timer = millis(); + } else if (message_num == 0x0a) { + //PERF_join_data(); + } else { + Serial.print("Invalid message number = "); + Serial.println(message_num,DEC); + } + } else { + Serial.println("XXX Checksum error"); //bad checksum + //imu_checksum_error_count++; + } + // Variable initialization + IMU_step = 0; + payload_counter = 0; + ck_a = 0; + ck_b = 0; + IMU_timer = millis(); //Restarting timer... + break; + } + }// End for... + } + // If we don't receive GPS packets in 2 seconds => Bad FIX state + if ((millis() - GPS_timer) > 3000){ + Fix = 0; + } + if (PrintErrors){ + Serial.println("ERR:GPS_TIMEOUT!!"); + } +} + +/**************************************************************** + * + ****************************************************************/ + +void GPS_IMU_Class::IMU_join_data(void) +{ + int j; + + + //Verifing if we are in class 1, you can change this "IF" for a "Switch" in case you want to use other IMU classes.. + //In this case all the message im using are in class 1, to know more about classes check PAGE 60 of DataSheet. + + //Storing IMU roll + intUnion.byte[0] = buffer[j++]; + intUnion.byte[1] = buffer[j++]; + roll_sensor = intUnion.word; + + //Storing IMU pitch + intUnion.byte[0] = buffer[j++]; + intUnion.byte[1] = buffer[j++]; + pitch_sensor = intUnion.word; + + //Storing IMU heading (yaw) + intUnion.byte[0] = buffer[j++]; + intUnion.byte[1] = buffer[j++]; + Ground_Course = intUnion.word; + imu_ok = true; +} + +void GPS_IMU_Class::IMU2_join_data() +{ + int j=0; + + //Storing IMU roll + intUnion.byte[0] = buffer[j++]; + intUnion.byte[1] = buffer[j++]; + roll_sensor = intUnion.word; + + //Storing IMU pitch + intUnion.byte[0] = buffer[j++]; + intUnion.byte[1] = buffer[j++]; + pitch_sensor = intUnion.word; + + //Storing IMU heading (yaw) + intUnion.byte[0] = buffer[j++]; + intUnion.byte[1] = buffer[j++]; + Ground_Course = (unsigned int)intUnion.word; + + //Storing airspeed + intUnion.byte[0] = buffer[j++]; + intUnion.byte[1] = buffer[j++]; + airspeed = intUnion.word; + + imu_ok = true; + +} + +void GPS_IMU_Class::GPS_join_data(void) +{ + //gps_messages_received++; + int j = 0; + + Longitude = join_4_bytes(&buffer[j]); // Lat and Lon * 10**7 + j += 4; + + Lattitude = join_4_bytes(&buffer[j]); + j += 4; + + //Storing GPS Height above the sea level + intUnion.byte[0] = buffer[j++]; + intUnion.byte[1] = buffer[j++]; + Altitude = (long)intUnion.word * 10; // Altitude in meters * 100 + + //Storing Speed (3-D) + intUnion.byte[0] = buffer[j++]; + intUnion.byte[1] = buffer[j++]; + Speed_3d = Ground_Speed = (float)intUnion.word; // Speed in M/S * 100 + + //We skip the gps ground course because we use yaw value from the IMU for ground course + j += 2; + Time = join_4_bytes(&buffer[j]); // Time of Week in milliseconds + j +=4; + imu_health = buffer[j++]; + + NewData = 1; + Fix = 1; + +} + + +/**************************************************************** + * + ****************************************************************/ + // Join 4 bytes into a long +long GPS_IMU_Class::join_4_bytes(unsigned char Buffer[]) +{ + longUnion.byte[0] = *Buffer; + longUnion.byte[1] = *(Buffer+1); + longUnion.byte[2] = *(Buffer+2); + longUnion.byte[3] = *(Buffer+3); + return(longUnion.dword); +} + + +/**************************************************************** + * + ****************************************************************/ +// checksum algorithm +void GPS_IMU_Class::checksum(byte IMU_data) +{ + ck_a+=IMU_data; + ck_b+=ck_a; +} + +GPS_IMU_Class GPS; diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/GPS_IMU.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/GPS_IMU.h new file mode 100644 index 0000000000..fcf247b911 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/GPS_IMU.h @@ -0,0 +1,69 @@ +#ifndef GPS_IMU_h +#define GPS_IMU_h + +#include + +#define IMU_MAXPAYLOAD 32 + +class GPS_IMU_Class +{ + private: + // Internal variables + union int_union { + int16_t word; + uint8_t byte[2]; + } intUnion; + + union long_union { + int32_t dword; + uint8_t byte[4]; + } longUnion; + + uint8_t ck_a; // Packet checksum + uint8_t ck_b; + uint8_t IMU_ck_a; + uint8_t IMU_ck_b; + uint8_t IMU_step; + uint8_t IMU_class; + uint8_t message_num; + uint8_t payload_length; + uint8_t payload_counter; + uint8_t buffer[IMU_MAXPAYLOAD]; + + long IMU_timer; + long IMU_ecefVZ; + void IMU_join_data(); + void IMU2_join_data(); + void GPS_join_data(); + void checksum(unsigned char IMU_data); + long join_4_bytes(unsigned char Buffer[]); + + public: + // Methods + GPS_IMU_Class(); + void Init(); + void Read(); + + // Properties + long roll_sensor; // how much we're turning in deg * 100 + long pitch_sensor; // our angle of attack in deg * 100 + int airspeed; + float imu_health; + uint8_t imu_ok; + + long Time; //GPS Millisecond Time of Week + long Lattitude; // Geographic coordinates + long Longitude; + long Altitude; + long Ground_Speed; + long Ground_Course; + long Speed_3d; + + uint8_t NumSats; // Number of visible satelites + uint8_t Fix; // 1:GPS FIX 0:No FIX (normal logic) + uint8_t NewData; // 1:New GPS Data + uint8_t PrintErrors; // 1: To Print GPS Errors (for debug) +}; + +extern GPS_IMU_Class GPS; +#endif \ No newline at end of file diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/examples/.DS_Store b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/examples/.DS_Store new file mode 100644 index 0000000000..ccb9677482 Binary files /dev/null and b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/examples/.DS_Store differ diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/examples/GPS_IMU_test/GPS_IMU_test.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/examples/GPS_IMU_test/GPS_IMU_test.pde new file mode 100644 index 0000000000..5ccd3f9dd1 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/examples/GPS_IMU_test/GPS_IMU_test.pde @@ -0,0 +1,44 @@ +/* + Example of GPS IMU library. + Code by Jordi Munoz, Jose Julio and, Jason Short . DIYDrones.com + + Works with Ardupilot Mega Hardware (GPS on Serial Port1) + and with standard ATMega168 and ATMega328 on Serial Port 0 +*/ + +#include // GPS Library + +void setup() +{ + Serial.begin(38400); + Serial.println("GPS IMU library test"); + GPS.Init(); // GPS Initialization + delay(1000); +} +void loop() +{ + GPS.Read(); + if (1){ // New GPS data? + + Serial.print("GPS:"); + Serial.print(" Lat:"); + Serial.print(GPS.Lattitude); + Serial.print(" Lon:"); + Serial.print(GPS.Longitude); + Serial.print(" Alt:"); + Serial.print((float)GPS.Altitude/100.0); + Serial.print(" GSP:"); + Serial.print((float)GPS.Ground_Speed/100.0); + Serial.print(" COG:"); + Serial.print(GPS.Ground_Course/1000000); + Serial.print(" SAT:"); + Serial.print((int)GPS.NumSats); + Serial.print(" FIX:"); + Serial.print((int)GPS.Fix); + Serial.print(" TIM:"); + Serial.print(GPS.Time); + Serial.println(); + GPS.NewData = 0; // We have read the data + } + delay(20); +} diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/keywords.txt b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/keywords.txt new file mode 100644 index 0000000000..9ce6d3ae99 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/keywords.txt @@ -0,0 +1,16 @@ +GPS KEYWORD1 +GPS_IMU KEYWORD1 +Init KEYWORD2 +Read KEYWORD2 +Time KEYWORD2 +Lattitude KEYWORD2 +Longitude KEYWORD2 +Altitude KEYWORD2 +Ground_Speed KETWORD2 +Ground_Course KEYWORD2 +Speed_3d KEYWORD2 +NumSats KEYWORD2 +Fix KEYWORD2 +NewData KEYWORD2 + + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_MTK/GPS_MTK.cpp b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_MTK/GPS_MTK.cpp new file mode 100644 index 0000000000..b5b45b30e6 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_MTK/GPS_MTK.cpp @@ -0,0 +1,225 @@ +/* + GPS_MTK.cpp - Ublox GPS library for Arduino + Code by Jordi Muoz and Jose Julio. DIYDrones.com + This code works with boards based on ATMega168/328 and ATMega1280 (Serial port 1) + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + GPS configuration : Costum protocol + Baud rate : 38400 + + Methods: + Init() : GPS Initialization + Read() : Call this funcion as often as you want to ensure you read the incomming gps data + + Properties: + Lattitude : Lattitude * 10,000,000 (long value) + Longitude : Longitude * 10,000,000 (long value) + Altitude : Altitude * 100 (meters) (long value) + Ground_speed : Speed (m/s) * 100 (long value) + Ground_course : Course (degrees) * 100 (long value) + NewData : 1 when a new data is received. + You need to write a 0 to NewData when you read the data + Fix : 0: GPS NO FIX or 2D FIX, 1: 3D FIX. + +*/ + +#include "GPS_MTK.h" +#include +#include "WProgram.h" + + +// Constructors //////////////////////////////////////////////////////////////// +GPS_MTK_Class::GPS_MTK_Class() +{ +} + + +// Public Methods ////////////////////////////////////////////////////////////// +void GPS_MTK_Class::Init(void) +{ + delay(200); + ck_a=0; + ck_b=0; + UBX_step=0; + NewData=0; + Fix=0; + PrintErrors=0; + GPS_timer=millis(); //Restarting timer... + // Initialize serial port + #if defined(__AVR_ATmega1280__) + Serial1.begin(38400); // Serial port 1 on ATMega1280 + #else + Serial.begin(38400); + #endif + Serial1.print("$PGCMD,16,0,0,0,0,0*6A\r\n"); + //Serial.println("sent config string"); +} + +// optimization : This code dont wait for data, only proccess the data available +// We can call this function on the main loop (50Hz loop) +// If we get a complete packet this function calls parse_ubx_gps() to parse and update the GPS info. +void GPS_MTK_Class::Read(void) +{ + static unsigned long GPS_timer=0; + byte data; + int numc; + + #if defined(__AVR_ATmega1280__) // If AtMega1280 then Serial port 1... + numc = Serial1.available(); + #else + numc = Serial.available(); + #endif + if (numc > 0) + for (int i=0;i Bad FIX state + if ((millis() - GPS_timer)>2000) + { + Fix = 0; + if (PrintErrors) + Serial.println("ERR:GPS_TIMEOUT!!"); + } +} + +/**************************************************************** + * + ****************************************************************/ +// Private Methods ////////////////////////////////////////////////////////////// +void GPS_MTK_Class::parse_ubx_gps(void) +{ + int j; +//Verifing if we are in class 1, you can change this "IF" for a "Switch" in case you want to use other UBX classes.. +//In this case all the message im using are in class 1, to know more about classes check PAGE 60 of DataSheet. + if(UBX_class==0x01) + { + switch(UBX_id)//Checking the UBX ID + { + + + case 0x05: //ID Custom + j=0; + Lattitude= join_4_bytes(&UBX_buffer[j]) * 10; // lon*10,000,000 + j+=4; + Longitude = join_4_bytes(&UBX_buffer[j]) * 10; // lat*10000000 + j+=4; + Altitude = join_4_bytes(&UBX_buffer[j]); // MSL + j+=4; + Ground_Speed = join_4_bytes(&UBX_buffer[j]); + j+=4; + Ground_Course = join_4_bytes(&UBX_buffer[j]) / 10000; // Heading 2D + j+=4; + NumSats=UBX_buffer[j]; + j++; + Fix=UBX_buffer[j]; + if (Fix==3) + Fix = 1; + else + Fix = 0; + j++; + Time = join_4_bytes(&UBX_buffer[j]); + NewData=1; + break; + + } + } +} + + +/**************************************************************** + * + ****************************************************************/ + // Join 4 bytes into a long +long GPS_MTK_Class::join_4_bytes(unsigned char Buffer[]) +{ + union long_union { + int32_t dword; + uint8_t byte[4]; +} longUnion; + + longUnion.byte[3] = *Buffer; + longUnion.byte[2] = *(Buffer+1); + longUnion.byte[1] = *(Buffer+2); + longUnion.byte[0] = *(Buffer+3); + return(longUnion.dword); +} + +/**************************************************************** + * + ****************************************************************/ +// checksum algorithm +void GPS_MTK_Class::ubx_checksum(byte ubx_data) +{ + ck_a+=ubx_data; + ck_b+=ck_a; +} + +GPS_MTK_Class GPS; \ No newline at end of file diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_MTK/GPS_MTK.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_MTK/GPS_MTK.h new file mode 100644 index 0000000000..3023b112ab --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_MTK/GPS_MTK.h @@ -0,0 +1,49 @@ +#ifndef GPS_MTK_h +#define GPS_MTK_h + +#include + +#define UBX_MAXPAYLOAD 60 + +class GPS_MTK_Class +{ + private: + // Internal variables + uint8_t ck_a; // Packet checksum + uint8_t ck_b; + uint8_t UBX_step; + uint8_t UBX_class; + uint8_t UBX_id; + uint8_t UBX_payload_length_hi; + uint8_t UBX_payload_length_lo; + uint8_t UBX_payload_counter; + uint8_t UBX_buffer[UBX_MAXPAYLOAD]; + uint8_t UBX_ck_a; + uint8_t UBX_ck_b; + long GPS_timer; + long UBX_ecefVZ; + void parse_ubx_gps(); + void ubx_checksum(unsigned char ubx_data); + long join_4_bytes(unsigned char Buffer[]); + + public: + // Methods + GPS_MTK_Class(); + void Init(); + void Read(); + // Properties + long Time; //GPS Millisecond Time of Week + long Lattitude; // Geographic coordinates + long Longitude; + long Altitude; + long Ground_Speed; + long Ground_Course; + uint8_t NumSats; // Number of visible satelites + uint8_t Fix; // 1:GPS FIX 0:No FIX (normal logic) + uint8_t NewData; // 1:New GPS Data + uint8_t PrintErrors; // 1: To Print GPS Errors (for debug) +}; + +extern GPS_MTK_Class GPS; + +#endif \ No newline at end of file diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_MTK/examples/GPS_MTK_test/GPS_MTK_test.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_MTK/examples/GPS_MTK_test/GPS_MTK_test.pde new file mode 100644 index 0000000000..6fa5a1cc2f --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_MTK/examples/GPS_MTK_test/GPS_MTK_test.pde @@ -0,0 +1,47 @@ +/* + Example of GPS MTK library. + Code by Jordi Mu�oz and Jose Julio. DIYDrones.com + + Works with Ardupilot Mega Hardware (GPS on Serial Port1) + and with standard ATMega168 and ATMega328 on Serial Port 0 +*/ + +#include // UBLOX GPS Library + +#define T6 1000000 +#define T7 10000000 + +void setup() +{ + Serial.begin(38400); + Serial.println("GPS MTK library test"); + GPS.Init(); // GPS Initialization + delay(1000); +} +void loop() +{ + GPS.Read(); + if (GPS.NewData) // New GPS data? + { + Serial.print("GPS:"); + Serial.print(" Lat:"); + Serial.print((float)GPS.Lattitude/T7, DEC); + Serial.print(" Lon:"); + Serial.print((float)GPS.Longitude/T7, DEC); + Serial.print(" Alt:"); + Serial.print((float)GPS.Altitude/100.0, DEC); + Serial.print(" GSP:"); + Serial.print((float)GPS.Ground_Speed/100.0, DEC); + Serial.print(" COG:"); + Serial.print(GPS.Ground_Course/100.0, DEC); + Serial.print(" SAT:"); + Serial.print((int)GPS.NumSats); + Serial.print(" FIX:"); + Serial.print((int)GPS.Fix); + Serial.print(" TIM:"); + Serial.print(GPS.Time); + Serial.println(); + GPS.NewData = 0; // We have readed the data + } + delay(20); +} diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_MTK/keywords.txt b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_MTK/keywords.txt new file mode 100644 index 0000000000..719ed917a1 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_MTK/keywords.txt @@ -0,0 +1,16 @@ +GPS KEYWORD1 +GPS_MTK KEYWORD1 +Init KEYWORD2 +Read KEYWORD2 +Time KEYWORD2 +Lattitude KEYWORD2 +Longitude KEYWORD2 +Altitude KEYWORD2 +Ground_Speed KEYWORD2 +Ground_Course KEYWORD2 +Speed_3d KEYWORD2 +NumSats KEYWORD2 +Fix KEYWORD2 +NewData KEYWORD2 + + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_NMEA/GPS_NMEA.cpp b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_NMEA/GPS_NMEA.cpp new file mode 100644 index 0000000000..0289b4adc6 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_NMEA/GPS_NMEA.cpp @@ -0,0 +1,272 @@ +/* + GPS_NMEA.cpp - Generic NMEA GPS library for Arduino + Code by Jordi Muoz and Jose Julio. DIYDrones.com + This code works with boards based on ATMega168/328 and ATMega1280 (Serial port 1) + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + GPS configuration : NMEA protocol + Baud rate : 38400 + NMEA Sentences : + $GPGGA : Global Positioning System Fix Data + $GPVTG : Ttack and Ground Speed + + Methods: + Init() : GPS Initialization + Read() : Call this funcion as often as you want to ensure you read the incomming gps data + + Properties: + Lattitude : Lattitude * 10000000 (long value) + Longitude : Longitude * 10000000 (long value) + Altitude : Altitude * 1000 (milimeters) (long value) + Ground_speed : Speed (m/s) * 100 (long value) + Ground_course : Course (degrees) * 100 (long value) + Type : 2 (This indicate that we are using the Generic NMEA library) + NewData : 1 when a new data is received. + You need to write a 0 to NewData when you read the data + Fix : >=1: GPS FIX, 0: No Fix (normal logic) + Quality : 0 = No Fix + 1 = Bad (Num sats < 5) + 2 = Poor + 3 = Medium + 4 = Good + + NOTE : This code has been tested on a Locosys 20031 GPS receiver (MTK chipset) +*/ + +#include "GPS_NMEA.h" + +#include +#include "WProgram.h" + + +// Constructors //////////////////////////////////////////////////////////////// +GPS_NMEA_Class::GPS_NMEA_Class() +{ +} + +// Public Methods ////////////////////////////////////////////////////////////// +void GPS_NMEA_Class::Init(void) +{ + Type = 2; + GPS_checksum_calc = false; + bufferidx = 0; + NewData=0; + Fix=0; + Quality=0; + PrintErrors=0; + // Initialize serial port + #if defined(__AVR_ATmega1280__) + Serial1.begin(38400); // Serial port 1 on ATMega1280 + #else + Serial.begin(38400); + #endif +} + +// This code dont wait for data, only proccess the data available on serial port +// We can call this function on the main loop (50Hz loop) +// If we get a complete packet this function call parse_nmea_gps() to parse and update the GPS info. +void GPS_NMEA_Class::Read(void) +{ + char c; + int numc; + int i; + + + #if defined(__AVR_ATmega1280__) // If AtMega1280 then Serial port 1... + numc = Serial1.available(); + #else + numc = Serial.available(); + #endif + if (numc > 0) + for (i=0;i Convert to decimal + Lattitude = aux_deg*10000000 + (aux_min*50)/3; // degrees + minutes/0.6 (*10000000) (0.6 = 3/5) + parseptr = strchr(parseptr, ',')+1; + // + if (*parseptr=='S') + Lattitude = -1*Lattitude; // South Lattitudes are negative + // + parseptr = strchr(parseptr, ',')+1; + // W Longitudes are Negative + aux_deg = parsedecimal(parseptr,3); // degrees + aux_min = parsenumber(parseptr+3,4); // minutes (sexagesimal) + Longitude = aux_deg*10000000 + (aux_min*50)/3; // degrees + minutes/0.6 (*10000000) + //Longitude = -1*Longitude; // This Assumes that we are in W longitudes... + parseptr = strchr(parseptr, ',')+1; + // + if (*parseptr=='W') + Longitude = -1*Longitude; // West Longitudes are negative + // + parseptr = strchr(parseptr, ',')+1; + Fix = parsedecimal(parseptr,1); + parseptr = strchr(parseptr, ',')+1; + NumSats = parsedecimal(parseptr,2); + parseptr = strchr(parseptr, ',')+1; + HDOP = parsenumber(parseptr,1); // HDOP * 10 + parseptr = strchr(parseptr, ',')+1; + Altitude = parsenumber(parseptr,1)*100; // Altitude in decimeters*100 = milimeters + if (Fix < 1) + Quality = 0; // No FIX + else if(NumSats<5) + Quality = 1; // Bad (Num sats < 5) + else if(HDOP>30) + Quality = 2; // Poor (HDOP > 30) + else if(HDOP>25) + Quality = 3; // Medium (HDOP > 25) + else + Quality = 4; // Good (HDOP < 25) + } + else + { + if (PrintErrors) + Serial.println("GPSERR: Checksum error!!"); + } + } + } + else if (strncmp(buffer,"$GPVTG",6)==0){ // Check if sentence begins with $GPVTG + //Serial.println(buffer); + if (buffer[bufferidx-4]=='*'){ // Check for the "*" character + NMEA_check = parseHex(buffer[bufferidx-3])*16 + parseHex(buffer[bufferidx-2]); // Read the checksums characters + if (GPS_checksum == NMEA_check){ // Checksum validation + parseptr = strchr(buffer, ',')+1; + Ground_Course = parsenumber(parseptr,2); // Ground course in degrees * 100 + parseptr = strchr(parseptr, ',')+1; + parseptr = strchr(parseptr, ',')+1; + parseptr = strchr(parseptr, ',')+1; + parseptr = strchr(parseptr, ',')+1; + parseptr = strchr(parseptr, ',')+1; + parseptr = strchr(parseptr, ',')+1; + Ground_Speed = parsenumber(parseptr,2)*10/36; // Convert Km/h to m/s (*100) + //GPS_line = true; + } + else + { + if (PrintErrors) + Serial.println("GPSERR: Checksum error!!"); + } + } + } + else + { + bufferidx = 0; + if (PrintErrors) + Serial.println("GPSERR: Bad sentence!!"); + } +} + + +/**************************************************************** + * + ****************************************************************/ + // Parse hexadecimal numbers +byte GPS_NMEA_Class::parseHex(char c) { + if (c < '0') + return (0); + if (c <= '9') + return (c - '0'); + if (c < 'A') + return (0); + if (c <= 'F') + return ((c - 'A')+10); +} + +// Decimal number parser +long GPS_NMEA_Class::parsedecimal(char *str,byte num_car) { + long d = 0; + byte i; + + i = num_car; + while ((str[0] != 0)&&(i>0)) { + if ((str[0] > '9') || (str[0] < '0')) + return d; + d *= 10; + d += str[0] - '0'; + str++; + i--; + } + return d; +} + +// Function to parse fixed point numbers (numdec=number of decimals) +long GPS_NMEA_Class::parsenumber(char *str,byte numdec) { + long d = 0; + byte ndec = 0; + + while (str[0] != 0) { + if (str[0] == '.'){ + ndec = 1; + } + else { + if ((str[0] > '9') || (str[0] < '0')) + return d; + d *= 10; + d += str[0] - '0'; + if (ndec > 0) + ndec++; + if (ndec > numdec) // we reach the number of decimals... + return d; + } + str++; + } + return d; +} + +GPS_NMEA_Class GPS; \ No newline at end of file diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_NMEA/GPS_NMEA.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_NMEA/GPS_NMEA.h new file mode 100644 index 0000000000..f144a35e27 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_NMEA/GPS_NMEA.h @@ -0,0 +1,46 @@ +#ifndef GPS_NMEA_h +#define GPS_NMEA_h + +#include + +#define GPS_BUFFERSIZE 120 + +class GPS_NMEA_Class +{ + private: + // Internal variables + uint8_t GPS_checksum; + uint8_t GPS_checksum_calc; + char buffer[GPS_BUFFERSIZE]; + int bufferidx; + + void parse_nmea_gps(void); + uint8_t parseHex(char c); + long parsedecimal(char *str,uint8_t num_car); + long parsenumber(char *str,uint8_t numdec); + + public: + // Methods + GPS_NMEA_Class(); + void Init(); + void Read(); + // Properties + long Time; //GPS Millisecond Time of Week + long Lattitude; // Geographic coordinates + long Longitude; + long Altitude; + long Ground_Speed; + long Speed_3d; //Speed (3-D) + long Ground_Course; + uint8_t Type; // Type of GPS (library used) + uint8_t NumSats; // Number of visible satelites + uint8_t Fix; // >=1:GPS FIX 0:No FIX (normal logic) + uint8_t Quality; // GPS Signal quality + uint8_t NewData; // 1:New GPS Data + uint8_t PrintErrors; // 1: To Print GPS Errors (for debug) + int HDOP; // HDOP +}; + +extern GPS_NMEA_Class GPS; + +#endif \ No newline at end of file diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_NMEA/examples/GPS_NMEA_test/GPS_NMEA_test.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_NMEA/examples/GPS_NMEA_test/GPS_NMEA_test.pde new file mode 100644 index 0000000000..f7a93d0c58 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_NMEA/examples/GPS_NMEA_test/GPS_NMEA_test.pde @@ -0,0 +1,42 @@ +/* + Example of GPS NMEA library. + Code by Jordi Muoz and Jose Julio. DIYDrones.com + + Works with Ardupilot Mega Hardware (GPS on Serial Port1) + and with standard ATMega168 and ATMega328 on Serial Port 0 +*/ + +#include // NMEA GPS Library + +void setup() +{ + Serial.begin(57600); + Serial.println("GPS NMEA library test"); + GPS.Init(); // GPS Initialization + delay(1000); +} +void loop() +{ + GPS.Read(); + if (GPS.NewData) // New GPS data? + { + Serial.print("GPS:"); + Serial.print(" Time:"); + Serial.print(GPS.Time); + Serial.print(" Fix:"); + Serial.print((int)GPS.Fix); + Serial.print(" Lat:"); + Serial.print(GPS.Lattitude); + Serial.print(" Lon:"); + Serial.print(GPS.Longitude); + Serial.print(" Alt:"); + Serial.print(GPS.Altitude/1000.0); + Serial.print(" Speed:"); + Serial.print(GPS.Ground_Speed/100.0); + Serial.print(" Course:"); + Serial.print(GPS.Ground_Course/100.0); + Serial.println(); + GPS.NewData = 0; // We have readed the data + } + delay(20); +} \ No newline at end of file diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_NMEA/keywords.txt b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_NMEA/keywords.txt new file mode 100644 index 0000000000..f2d3a7653d --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_NMEA/keywords.txt @@ -0,0 +1,18 @@ +GPS KEYWORD1 +GPS_NMEA KEYWORD1 +Init KEYWORD2 +Read KEYWORD2 +Type KEYWORD2 +Time KEYWORD2 +Lattitude KEYWORD2 +Longitude KEYWORD2 +Altitude KEYWORD2 +Ground_Speed KETWORD2 +Ground_Course KEYWORD2 +Speed_3d KEYWORD2 +NumSats KEYWORD2 +Fix KEYWORD2 +NewData KEYWORD2 +Quality KEYWORD2 + + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_UBLOX/GPS_UBLOX.cpp b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_UBLOX/GPS_UBLOX.cpp new file mode 100644 index 0000000000..d1f29b336f --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_UBLOX/GPS_UBLOX.cpp @@ -0,0 +1,274 @@ +/* + GPS_UBLOX.cpp - Ublox GPS library for Arduino + Code by Jordi Muoz and Jose Julio. DIYDrones.com + This code works with boards based on ATMega168 / 328 and ATMega1280 (Serial port 1) + + This library is free software; you can redistribute it and / or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + GPS configuration : Ublox protocol + Baud rate : 38400 + Active messages : + NAV - POSLLH Geodetic Position Solution, PAGE 66 of datasheet + NAV - VELNED Velocity Solution in NED, PAGE 71 of datasheet + NAV - STATUS Receiver Navigation Status + or + NAV - SOL Navigation Solution Information + + Methods: + Init() : GPS Initialization + Read() : Call this funcion as often as you want to ensure you read the incomming gps data + + Properties: + Lattitude : Lattitude * 10,000,000 (long value) + Longitude : Longitude * 10,000,000 (long value) + Altitude : Altitude * 100 (meters) (long value) + Ground_speed : Speed (m / s) * 100 (long value) + Ground_course : Course (degrees) * 100 (long value) + NewData : 1 when a new data is received. + You need to write a 0 to NewData when you read the data + Fix : 1: GPS FIX, 0: No Fix (normal logic) + +*/ + +#include "GPS_UBLOX.h" + +#include +#include "WProgram.h" + + +// Constructors //////////////////////////////////////////////////////////////// +GPS_UBLOX_Class::GPS_UBLOX_Class() +{ +} + + +// Public Methods ////////////////////////////////////////////////////////////// +void GPS_UBLOX_Class::Init(void) +{ + ck_a = 0; + ck_b = 0; + UBX_step = 0; + NewData = 0; + Fix = 0; + PrintErrors = 0; + GPS_timer = millis(); // Restarting timer... + // Initialize serial port + #if defined(__AVR_ATmega1280__) + Serial1.begin(38400); // Serial port 1 on ATMega1280 + #else + Serial.begin(38400); + #endif +} + +// optimization : This code dont wait for data, only proccess the data available +// We can call this function on the main loop (50Hz loop) +// If we get a complete packet this function calls parse_ubx_gps() to parse and update the GPS info. +void GPS_UBLOX_Class::Read(void) +{ + static unsigned long GPS_timer = 0; + byte data; + int numc; + + #if defined(__AVR_ATmega1280__) // If AtMega1280 then Serial port 1... + numc = Serial1.available(); + #else + numc = Serial.available(); + #endif + if (numc > 0) + for (int i = 0; i < numc; i++) // Process bytes received + { + #if defined(__AVR_ATmega1280__) + data = Serial1.read(); + #else + data = Serial.read(); + #endif + switch(UBX_step) // Normally we start from zero. This is a state machine + { + case 0: + if(data == 0xB5) // UBX sync char 1 + UBX_step++; // OH first data packet is correct, so jump to the next step + break; + case 1: + if(data == 0x62) // UBX sync char 2 + UBX_step++; // ooh! The second data packet is correct, jump to the step 2 + else + UBX_step = 0; // Nop, is not correct so restart to step zero and try again. + break; + case 2: + UBX_class = data; + ubx_checksum(UBX_class); + UBX_step++; + break; + case 3: + UBX_id = data; + ubx_checksum(UBX_id); + UBX_step++; + break; + case 4: + UBX_payload_length_hi = data; + ubx_checksum(UBX_payload_length_hi); + UBX_step++; + // We check if the payload lenght is valid... + if (UBX_payload_length_hi >= UBX_MAXPAYLOAD) + { + if (PrintErrors) + Serial.println("ERR:GPS_BAD_PAYLOAD_LENGTH!!"); + UBX_step = 0; // Bad data, so restart to step zero and try again. + ck_a = 0; + ck_b = 0; + } + break; + case 5: + UBX_payload_length_lo = data; + ubx_checksum(UBX_payload_length_lo); + UBX_step++; + UBX_payload_counter = 0; + break; + case 6: // Payload data read... + if (UBX_payload_counter < UBX_payload_length_hi) // We stay in this state until we reach the payload_length + { + UBX_buffer[UBX_payload_counter] = data; + ubx_checksum(data); + UBX_payload_counter++; + if (UBX_payload_counter == UBX_payload_length_hi) + UBX_step++; + } + break; + case 7: + UBX_ck_a = data; // First checksum byte + UBX_step++; + break; + case 8: + UBX_ck_b = data; // Second checksum byte + + // We end the GPS read... + if((ck_a == UBX_ck_a) && (ck_b == UBX_ck_b)) // Verify the received checksum with the generated checksum.. + parse_ubx_gps(); // Parse the new GPS packet + else + { + if (PrintErrors) + Serial.println("ERR:GPS_CHK!!"); + } + // Variable initialization + UBX_step = 0; + ck_a = 0; + ck_b = 0; + GPS_timer = millis(); // Restarting timer... + break; + } + } // End for... + // If we dont receive GPS packets in 2 seconds => Bad FIX state + if ((millis() - GPS_timer) > 2000) + { + Fix = 0; + if (PrintErrors) + Serial.println("ERR:GPS_TIMEOUT!!"); + } +} + +/**************************************************************** + * + ****************************************************************/ +// Private Methods ////////////////////////////////////////////////////////////// +void GPS_UBLOX_Class::parse_ubx_gps(void) +{ + int j; +//Verifing if we are in class 1, you can change this "IF" for a "Switch" in case you want to use other UBX classes.. +//In this case all the message im using are in class 1, to know more about classes check PAGE 60 of DataSheet. + if(UBX_class == 0x01) + { + switch(UBX_id) //Checking the UBX ID + { + case 0x02: // ID NAV - POSLLH + j = 0; + Time = join_4_bytes(&UBX_buffer[j]); // ms Time of week + j += 4; + Longitude = join_4_bytes(&UBX_buffer[j]); // lon * 10000000 + j += 4; + Lattitude = join_4_bytes(&UBX_buffer[j]); // lat * 10000000 + j += 4; + //Altitude = join_4_bytes(&UBX_buffer[j]); // elipsoid heigth mm + j += 4; + Altitude = (float)join_4_bytes(&UBX_buffer[j]); // MSL heigth mm + Altitude /= 10.; + + // Rescale altitude to cm + //j+=4; + /* + hacc = (float)join_4_bytes(&UBX_buffer[j]) / (float)1000; + j += 4; + vacc = (float)join_4_bytes(&UBX_buffer[j]) / (float)1000; + j += 4; + */ + NewData = 1; + break; + case 0x03: //ID NAV - STATUS + //if(UBX_buffer[4] >= 0x03) + if((UBX_buffer[4] >= 0x03) && (UBX_buffer[5] & 0x01)) + Fix = 1; // valid position + else + Fix = 0; // invalid position + break; + + case 0x06: //ID NAV - SOL + if((UBX_buffer[10] >= 0x03) && (UBX_buffer[11] & 0x01)) + Fix = 1; // valid position + else + Fix = 0; // invalid position + UBX_ecefVZ = join_4_bytes(&UBX_buffer[36]); // Vertical Speed in cm / s + NumSats = UBX_buffer[47]; // Number of sats... + break; + + case 0x12: // ID NAV - VELNED + j = 16; + Speed_3d = join_4_bytes(&UBX_buffer[j]); // cm / s + j += 4; + Ground_Speed = join_4_bytes(&UBX_buffer[j]); // Ground speed 2D cm / s + j += 4; + Ground_Course = join_4_bytes(&UBX_buffer[j]); // Heading 2D deg * 100000 + Ground_Course /= 1000; // Rescale heading to deg * 100 + j += 4; + /* + sacc = join_4_bytes(&UBX_buffer[j]) // Speed accuracy + j += 4; + headacc = join_4_bytes(&UBX_buffer[j]) // Heading accuracy + j += 4; + */ + break; + } + } +} + + +/**************************************************************** + * + ****************************************************************/ + // Join 4 bytes into a long +long GPS_UBLOX_Class::join_4_bytes(unsigned char Buffer[]) +{ + union long_union { + int32_t dword; + uint8_t byte[4]; +} longUnion; + + longUnion.byte[0] = *Buffer; + longUnion.byte[1] = *(Buffer + 1); + longUnion.byte[2] = *(Buffer + 2); + longUnion.byte[3] = *(Buffer + 3); + return(longUnion.dword); +} + +/**************************************************************** + * + ****************************************************************/ +// Ublox checksum algorithm +void GPS_UBLOX_Class::ubx_checksum(byte ubx_data) +{ + ck_a += ubx_data; + ck_b += ck_a; +} + +GPS_UBLOX_Class GPS; \ No newline at end of file diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_UBLOX/GPS_UBLOX.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_UBLOX/GPS_UBLOX.h new file mode 100644 index 0000000000..8a9e09e611 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_UBLOX/GPS_UBLOX.h @@ -0,0 +1,50 @@ +#ifndef GPS_UBLOX_h +#define GPS_UBLOX_h + +#include + +#define UBX_MAXPAYLOAD 60 + +class GPS_UBLOX_Class +{ + private: + // Internal variables + uint8_t ck_a; // Packet checksum + uint8_t ck_b; + uint8_t UBX_step; + uint8_t UBX_class; + uint8_t UBX_id; + uint8_t UBX_payload_length_hi; + uint8_t UBX_payload_length_lo; + uint8_t UBX_payload_counter; + uint8_t UBX_buffer[UBX_MAXPAYLOAD]; + uint8_t UBX_ck_a; + uint8_t UBX_ck_b; + long GPS_timer; + long UBX_ecefVZ; + void parse_ubx_gps(); + void ubx_checksum(unsigned char ubx_data); + long join_4_bytes(unsigned char Buffer[]); + + public: + // Methods + GPS_UBLOX_Class(); + void Init(); + void Read(); + // Properties + long Time; //GPS Millisecond Time of Week + long Lattitude; // Geographic coordinates + long Longitude; + long Altitude; + long Ground_Speed; + long Speed_3d; //Speed (3-D) + long Ground_Course; + uint8_t NumSats; // Number of visible satelites + uint8_t Fix; // 1:GPS FIX 0:No FIX (normal logic) + uint8_t NewData; // 1:New GPS Data + uint8_t PrintErrors; // 1: To Print GPS Errors (for debug) +}; + +extern GPS_UBLOX_Class GPS; + +#endif \ No newline at end of file diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_UBLOX/examples/GPS_UBLOX_test/GPS_UBLOX_test.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_UBLOX/examples/GPS_UBLOX_test/GPS_UBLOX_test.pde new file mode 100644 index 0000000000..99975c7334 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_UBLOX/examples/GPS_UBLOX_test/GPS_UBLOX_test.pde @@ -0,0 +1,42 @@ +/* + Example of GPS UBLOX library. + Code by Jordi Muoz and Jose Julio. DIYDrones.com + + Works with Ardupilot Mega Hardware (GPS on Serial Port1) + and with standard ATMega168 and ATMega328 on Serial Port 0 +*/ + +#include // UBLOX GPS Library + +void setup() +{ + Serial.begin(57600); + Serial.println("GPS UBLOX library test"); + GPS.Init(); // GPS Initialization + delay(1000); +} +void loop() +{ + GPS.Read(); + if (GPS.NewData) // New GPS data? + { + Serial.print("GPS:"); + Serial.print(" Time:"); + Serial.print(GPS.Time); + Serial.print(" Fix:"); + Serial.print((int)GPS.Fix); + Serial.print(" Lat:"); + Serial.print(GPS.Lattitude); + Serial.print(" Lon:"); + Serial.print(GPS.Longitude); + Serial.print(" Alt:"); + Serial.print(GPS.Altitude/1000.0); + Serial.print(" Speed:"); + Serial.print(GPS.Ground_Speed/100.0); + Serial.print(" Course:"); + Serial.print(GPS.Ground_Course/100000.0); + Serial.println(); + GPS.NewData = 0; // We have readed the data + } + delay(20); +} \ No newline at end of file diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_UBLOX/keywords.txt b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_UBLOX/keywords.txt new file mode 100644 index 0000000000..e211693803 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_UBLOX/keywords.txt @@ -0,0 +1,16 @@ +GPS KEYWORD1 +GPS_UBLOX KEYWORD1 +Init KEYWORD2 +Read KEYWORD2 +Time KEYWORD2 +Lattitude KEYWORD2 +Longitude KEYWORD2 +Altitude KEYWORD2 +Ground_Speed KETWORD2 +Ground_Course KEYWORD2 +Speed_3d KEYWORD2 +NumSats KEYWORD2 +Fix KEYWORD2 +NewData KEYWORD2 + + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/JETI_Box/JETI_Box.cpp b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/JETI_Box/JETI_Box.cpp new file mode 100644 index 0000000000..25d49da553 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/JETI_Box/JETI_Box.cpp @@ -0,0 +1,202 @@ +/* + JETI_Box.cpp, Version 1.0 beta + Oct 2010, by Uwe Gartmann + + + written for Arduino Mega / ArduPilot Mega + +*/ +extern "C" { + #include + #include "Print.h" + #include + #include + #include "wiring.h" +} + +#include +#define LCDMaxPos 32 +#define LCDBufferSize LCDMaxPos + 1 + +volatile uint8_t lcd[LCDBufferSize]; +volatile uint8_t buttons; +volatile uint8_t lastbuttons; +volatile uint8_t cursor; +volatile uint8_t sendpos; +volatile uint8_t dmyError; +volatile uint8_t dmyBit9; +volatile uint8_t dmyData; +volatile uint8_t ledA; +volatile uint8_t t0cntr; +//volatile long valX; + +ISR(USART3_RX_vect) //serial data available +{ + // catch response from Jetibox + dmyError = UCSR3A; + dmyBit9 = UCSR3B; + dmyData = UDR3; + if (!(dmyError & ((1<>4) xor 0x0F; + t0cntr = 10; // set 10ms delay + } + } + } +} + +ISR(USART3_UDRE_vect) //transmit buffer empty +/* + * sendpos = 0 -> start sending data with this interrupt enabled, start byte with 9.bit=0 + * sendpos = 1-32 -> send display data with 9.bit=1 + * sendpos = 33 -> send end byte with 9.bit=0 + * sendpos = 34 -> set sendpos=0 and disable this interrupt + */ +{ + switch (sendpos) + { + case 0: + // send start byte with 9.bit=0 + UCSR3B &= ~(1< 0) --valX; +} + +JETI_Box_class::JETI_Box_class() +{ +// Class constructor +} + +// Public Methods -------------------------------------------------------------------- +void JETI_Box_class::begin(void) +{ +#ifndef F_CPU + #define F_CPU 16000000 +#endif +#define _UBRR3 (F_CPU/8/9600-1) //when U2X0 is not set use divider 16 instead of 8 + + // Set serial interface + // Baudrate + UCSR3A = (1<>8); //high byte + UBRR3L=_UBRR3; //low byte + // Set data format: 9data#1, odd parity, 1stop bit + UCSR3C = (0< + #include "Print.h" + #include + #include + #include "wiring.h" +} + +#include +#define LCDLine1 1 +#define LCDLine2 17 +#define LCDMaxPos 32 +#define LCDBufferSize LCDMaxPos + 1 + +volatile uint8_t lcd[LCDBufferSize]; +volatile uint8_t buttons; +volatile uint8_t lastbuttons; +volatile uint8_t cursor; +volatile uint8_t sendpos; +volatile uint8_t dummy; + +ISR(USART3_RX_vect) //serial data available +{ + // catch response from Jetibox + if (!(UCSR3A & ((1<>4) xor 0x0F; + } + } + } +} + +ISR(USART3_UDRE_vect) //transmit buffer empty +/* + * sendpos = 0 -> start sending data with this interrupt enabled, start byte with 9.bit=0 + * sendpos = 1-32 -> send display data with 9.bit=1 + * sendpos = 33 -> send end byte with 9.bit=0 + * sendpos = 34 -> set sendpos=0 and disable this interrupt + */ +{ + switch (sendpos) + { + case 0: + // send start byte with 9.bit=0 + UCSR3B &= ~(1<>8); //high byte + UBRR3L=_UBRR3; //low byte + + // Set data format: 9data#1, odd parity, 1stop bit + UCSR3C = (0< +//#include "Print.h" + +#define LCDLine1 1 +#define LCDLine2 17 + +#define JB_key_up 0b0010 +#define JB_key_right 0b0001 +#define JB_key_down 0b0100 +#define JB_key_left 0b1000 + +class JETI_Box_class : public Print { +public: + uint8_t readbuttons(void); + //long checkvalue(long v); + virtual void write(uint8_t c); + using Print::write; // pull in write(str) and write(buf, size) from Print + JETI_Box_class(); + void begin(); + void setcursor(uint8_t p); + void clear(); + void clear(uint8_t l); +}; + +extern JETI_Box_class JB; + +#endif diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/JETI_Box/keywords.txt b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/JETI_Box/keywords.txt new file mode 100644 index 0000000000..699b80af69 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/JETI_Box/keywords.txt @@ -0,0 +1,8 @@ +JETI_Box KEYWORD1 +Begin KEYWORD2 +Refresh KEYWORD2 +Write KEYWORD2 +Print KEYWORD2 +Line1 KEYWORD2 +Line2 KEYWORD2 +Keys KEYWORD2 diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/APM2_RC.cpp b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/APM2_RC.cpp new file mode 100644 index 0000000000..d9b4882b21 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/APM2_RC.cpp @@ -0,0 +1,327 @@ +#ifdef __AVR_ATmega1280__ +/* + APM2_RC.cpp - Radio Control Library for Ardupilot Mega. Arduino + Code by Jordi Muoz and Jose Julio. DIYDrones.com + + This library is free software; you can redistribute it and / or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + RC Input : PPM signal on IC4 pin + RC Output : 11 Servo outputs (standard 20ms frame) + + Methods: + Init() : Initialization of interrupts an Timers + OutpuCh(ch, pwm) : Output value to servos (range : 900 - 2100us) ch = 0..10 + InputCh(ch) : Read a channel input value. ch = 0..7 + GetState() : Returns the state of the input. 1 => New radio frame to process + Automatically resets when we call InputCh to read channels + +*/ + +#include "APM2_RC.h" + +#define REVERSE 3050 + +// Variable definition for Input Capture interrupt +volatile uint16_t ICR4_old; +volatile uint8_t PPM_Counter = 0; +volatile uint16_t raw[8] = {1200, 1200, 1200, 1200, 1200, 1200, 1200, 1200}; + +// Constructors //////////////////////////////////////////////////////////////// +APM2_RC::APM2_RC() +{ + _direction_mask = 255; // move to super class + +} + +void +APM2_RC::init() +{ + // Init PWM Timer 1 + pinMode(11, OUTPUT); // (PB5 / OC1A) + pinMode(12, OUTPUT); // OUT2 (PB6 / OC1B) + pinMode(13, OUTPUT); // OUT3 (PB7 / OC1C) + + // Timer 3 + pinMode(2, OUTPUT); // OUT7 (PE4 / OC3B) + pinMode(3, OUTPUT); // OUT6 (PE5 / OC3C) + pinMode(4, OUTPUT); // (PE3 / OC3A) + + // Timer 5 + pinMode(44, OUTPUT); // OUT1 (PL5 / OC5C) + pinMode(45, OUTPUT); // OUT0 (PL4 / OC5B) + pinMode(46, OUTPUT); // (PL3 / OC5A) + + // Init PPM input and PWM Timer 4 + pinMode(49, INPUT); // ICP4 pin (PL0) (PPM input) + pinMode(7, OUTPUT); // OUT5 (PH4 / OC4B) + pinMode(8, OUTPUT); // OUT4 (PH5 / OC4C) + + //Remember the registers not declared here remains zero by default... + TCCR1A =((1 << WGM11) | (1 << COM1A1) | (1 << COM1B1) | (1 << COM1C1)); // Please read page 131 of DataSheet, we are changing the registers settings of WGM11, COM1B1, COM1A1 to 1 thats all... + TCCR1B = (1 << WGM13) | (1 << WGM12) | (1 << CS11); // Prescaler set to 8, that give us a resolution of 0.5us, read page 134 of data sheet + OCR1A = 3000; // PB5, none + //OCR1B = 3000; // PB6, OUT2 + //OCR1C = 3000; // PB7 OUT3 + ICR1 = 40000; // 50hz freq...Datasheet says (system_freq / prescaler) / target frequency. So (16000000hz / 8) / 50hz = 40000, + + // Init PWM Timer 3 + TCCR3A =((1 << WGM31) | (1 << COM3A1) | (1 << COM3B1) | (1 << COM3C1)); + TCCR3B = (1 << WGM33) | (1 << WGM32) | (1 << CS31); + OCR3A = 3000; // PE3, NONE + //OCR3B = 3000; // PE4, OUT7 + //OCR3C = 3000; // PE5, OUT6 + ICR3 = 40000; // 50hz freq + + + // Init PWM Timer 5 + TCCR5A =((1 << WGM51) | (1 << COM5A1) | (1 << COM5B1) | (1 << COM5C1)); + TCCR5B = (1 << WGM53) | (1 << WGM52) | (1 << CS51); + OCR5A = 3000; // PL3, + //OCR5B = 3000; // PL4, OUT0 + //OCR5C = 3000; // PL5, OUT1 + ICR5 = 40000; // 50hz freq + + + // Init PPM input and PWM Timer 4 + TCCR4A = ((1 << WGM40) | (1 << WGM41) | (1 << COM4C1) | (1 << COM4B1) | (1 << COM4A1)); + TCCR4B = ((1 << WGM43) | (1 << WGM42) | (1 << CS41) | (1 << ICES4)); + OCR4A = 40000; // /50hz freq. + //OCR4B = 3000; // PH4, OUT5 + //OCR4C = 3000; // PH5, OUT4 + + //TCCR4B |=(1<= radio_trim[i]) + servo_in[i] = (float)(radio_in[i] - radio_min[i]) / (float)(radio_max[i] - radio_min[i]) * 100.0; + else + servo_in[i] = (float)(radio_in[i] - radio_trim[i]) / (float)(radio_trim[i] - radio_min[i]) * 100.0; + } + servo_in[CH3] = (float)(radio_in[CH3] - radio_min[CH3]) / (float)(radio_max[CH3] - radio_min[CH3]) * 100.0; + servo_in[CH3] = constrain(servo_out[CH3], 0, 100); +} + +void +APM2_RC::output() +{ + uint16_t out; + for (uint8_t i = 0; i < 8; i++){ + if (i == 3) continue; + if(radio_in[i] >= radio_trim[i]) + out = ((servo_in[i] * (radio_max[i] - radio_trim[i])) / 100) + radio_trim[i]; + else + out = ((servo_in[i] * (radio_max[i] - radio_trim[i])) / 100) + radio_trim[i]; + set_ch_pwm(i, out); + } + + out = (servo_out[CH3] * (float)(radio_max[CH3] - radio_min[CH3])) / 100.0; + out += radio_min[CH3]; + set_ch_pwm(CH3, out); +} + +void +APM2_RC::trim() +{ + uint8_t temp = _mix_mode; + _mix_mode = 0; + read(); + _mix_mode = temp; + + // Store the trim values + // --------------------- + for (int y = 0; y < 8; y++) + radio_trim[y] = radio_in[y]; +} +void +APM2_RC::twitch_servos(uint8_t times) +{ + // todo +} +void +APM2_RC::set_ch_pwm(uint8_t ch, uint16_t pwm) +{ + //pwm = constrain(pwm, MIN_PULSEWIDTH, MAX_PULSEWIDTH); + + switch(ch){ + case 0: + //Serial.print("\tpwm out "); + //Serial.print(pwm,DEC); + + if((_direction_mask & 1) == 0 ) + pwm = REVERSE - pwm; + + //Serial.print("\tpwm out "); + //Serial.println(pwm,DEC); + + OCR5B = pwm << 1; + break; // ch0 + + case 1: + if((_direction_mask & 2) == 0 ) + pwm = REVERSE - pwm; + OCR5C = pwm << 1; + break; // ch0 + + case 2: + if((_direction_mask & 4) == 0 ) + pwm = REVERSE - pwm; + OCR1B = pwm << 1; + break; // ch0 + + case 3: + if((_direction_mask & 8) == 0 ) + pwm = REVERSE - pwm; + OCR1C = pwm << 1; + break; // ch0 + + case 4: + if((_direction_mask & 16) == 0 ) + pwm = REVERSE - pwm; + OCR4C = pwm << 1; + break; // ch0 + + case 5: + if((_direction_mask & 32) == 0 ) + pwm = REVERSE - pwm; + OCR4B = pwm << 1; + break; // ch0 + + case 6: + if((_direction_mask & 64) == 0 ) + pwm = REVERSE - pwm; + OCR3C = pwm << 1; + break; // ch0 + + case 7: + if((_direction_mask & 128) == 0 ) + pwm = REVERSE - pwm; + OCR3B = pwm << 1; + break; // ch0 + + case 8: + OCR5A = pwm << 1; + break; // ch0 + + case 9: + OCR1A = pwm << 1; + break; // ch0 + + case 10: + OCR3A = pwm << 1; + break; // ch0 + } +} + +/**************************************************** + Input Capture Interrupt ICP4 => PPM signal read + ****************************************************/ +ISR(TIMER4_CAPT_vect) +{ + uint16_t pulse; + uint16_t pulse_width; + + pulse = ICR4; + if (pulse < ICR4_old){ // Take care of the overflow of Timer4 (TOP = 40000) + pulse_width = (pulse + 40000) - ICR4_old; // Calculating pulse + }else{ + pulse_width = pulse - ICR4_old; // Calculating pulse + } + ICR4_old = pulse; + + + if (pulse_width > 8000){ // SYNC pulse + PPM_Counter = 0; + } else { + //PPM_Counter &= 0x07; // For safety only (limit PPM_Counter to 7) + raw[PPM_Counter++] = pulse_width >> 1; // Saving pulse. + } +} + + + +// InstantPWM implementation +// This function forces the PWM output (reset PWM) on Out0 and Out1 (Timer5). For quadcopters use +void APM2_RC::force_out_0_1(void) +{ + if (TCNT5 > 5000) // We take care that there are not a pulse in the output + TCNT5 = 39990; // This forces the PWM output to reset in 5us (10 counts of 0.5us). The counter resets at 40000 +} +// This function forces the PWM output (reset PWM) on Out2 and Out3 (Timer1). For quadcopters use +void APM2_RC::force_out_2_3(void) +{ + if (TCNT1 > 5000) + TCNT1 = 39990; +} + +// This function forces the PWM output (reset PWM) on Out6 and Out7 (Timer3). For quadcopters use +void APM2_RC::force_out_6_7(void) +{ + if (TCNT3 > 5000) + TCNT3 = 39990; +} +#endif diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/APM2_RC.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/APM2_RC.h new file mode 100644 index 0000000000..5947a91130 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/APM2_RC.h @@ -0,0 +1,38 @@ +#ifndef APM2_RC_h +#define APM2_RC_h + +#include +#include "WProgram.h" +#include "RC.h" + +class APM2_RC : public RC +{ + public: + APM2_RC(); + void init(); + void read(); + void output(); + void set_ch_pwm(uint8_t ch, uint16_t pwm); + void trim(); + void twitch_servos(uint8_t times); + + void force_out_0_1(void); + void force_out_2_3(void); + void force_out_6_7(void); + + int16_t radio_in[8]; + int16_t radio_min[8]; + int16_t radio_trim[8]; + int16_t radio_max[8]; + + int16_t servo_in[8]; + float servo_out[8]; + + private: + uint16_t _timer_out; +}; + +#endif + + +//volatile uint16_t raw[8] = {1200, 1200, 1200, 1200, 1200, 1200, 1200, 1200}; diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/AP_RC.cpp b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/AP_RC.cpp new file mode 100644 index 0000000000..1915285790 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/AP_RC.cpp @@ -0,0 +1,329 @@ +/* + AP_RC.cpp - Radio library for Arduino + Code by Jason Short. DIYDrones.com + + This library is free software; you can redistribute it and / or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + +*/ + +#include "AP_RC.h" +#include +#define REVERSE 3050 + +// Variable definition for interrupt +volatile uint16_t timer1count = 0; +volatile uint16_t timer2count = 0; +volatile uint16_t timer3count = 0; +volatile uint16_t timer4count = 0; + +volatile int16_t timer1diff = 1500 * 2; +volatile int16_t timer2diff = 1500 * 2; +volatile int16_t timer3diff = 1100 * 2; +volatile int16_t timer4diff = 1500 * 2; + +//volatile uint16_t raw[8]; + +#define CH1_READ 1 +#define CH2_READ 2 +#define CH3_READ 4 +#define CH4_READ 8 + +volatile int8_t _rc_ch_read = 0; +volatile uint8_t _timer_ovf_a = 0; +volatile uint8_t _timer_ovf_b = 0; +volatile uint8_t _timer_ovf = 0; + + +AP_RC::AP_RC() +{ + _direction_mask = 255; // move to super class + pinMode(2,INPUT); // PD2 - INT0 - CH 1 in + pinMode(3,INPUT); // PD3 - INT1 - CH 2 in + pinMode(11,INPUT); // PB3 - MOSI/OC2 - CH 3 in + pinMode(13,INPUT); // PB5 - SCK - CH 4 in + + pinMode(10,OUTPUT); // PB2 - OC1B - CH 1 out + pinMode(8, OUTPUT); // PB0 - AIN1 - CH 3 out + pinMode(9, OUTPUT); // PB1 - OC1A - CH 2 out + DDRC |= B00010000; // PC4 - - CH 4 out +} + +void +AP_RC::init() +{ + // enable pin change interrupt 2 - PCINT23..16 + PCICR = _BV(PCIE2); + // enable pin change interrupt 0 - PCINT7..0 + PCICR |= _BV(PCIE0); + // enable in change interrupt on PB5 (digital pin 13) + PCMSK0 = _BV(PCINT3) | _BV(PCINT5); + // enable pin change interrupt on PD2,PD3 (digital pin 2,3) + PCMSK2 = _BV(PCINT18) | _BV(PCINT19); + + // Timer 1 + TCCR1A = ((1 << WGM11) | (1 << COM1B1) | (1 << COM1A1)); + TCCR1B = (1 << WGM13) | (1 << WGM12) | (1 << CS11); + // Loop value + ICR1 = 40000; + + // Throttle; + // Setting up the Timer 2 - 8 bit timer + TCCR2A = 0x0; // Normal Mode + TCCR2B = _BV(CS21) |_BV(CS20); //prescaler 32, at 16mhz (32/16) = 2, the counter will increment 1 every 2us + + // trim out the radio + for(int c = 0; c < 50; c++){ + delay(20); + read(); + } + + trim(); + + for(int y = 0; y < 4; y++) { + set_ch_pwm(y, radio_trim[y]); + } + + // enable throttle and Ch4 output + TIMSK1 |= _BV(ICIE1); // Timer / Counter1, Input Capture Interrupt Enable // PB0 - output throttle + TIMSK2 = _BV(TOIE1) | _BV(OCIE2A) | _BV(OCIE2B); // Timer / Counter2 Compare Match A +} + +void +AP_RC::read() +{ + if((_direction_mask & 1) == 0 ) + timer1diff = REVERSE - timer1diff; + if((_direction_mask & 2) == 0 ) + timer2diff = REVERSE - timer2diff; + if((_direction_mask & 4) == 0 ) + timer3diff = REVERSE - timer3diff; + if((_direction_mask & 8) == 0 ) + timer4diff = REVERSE - timer4diff; + + if(_mix_mode == 1){ + // elevons + int16_t ailerons = (timer1diff - radio_trim[CH1]) * .3; + int16_t elevator = (timer2diff - radio_trim[CH2]) * .7; + + radio_in[CH1] = (elevator - ailerons); // left + radio_in[CH2] = (elevator + ailerons); // right + + radio_in[CH1] += radio_trim[CH1]; + radio_in[CH2] += radio_trim[CH2]; + + //Serial.print("radio_in[CH1] "); + //Serial.print(radio_in[CH1],DEC); + //Serial.print(" \tradio_in[CH2] "); + //Serial.println(radio_in[CH2],DEC); + + }else{ + // normal + radio_in[CH1] = timer1diff; + radio_in[CH2] = timer2diff; + } + + radio_in[CH3] = (float)radio_in[CH3] * .9 + timer3diff * .1; + radio_in[CH4] = timer4diff; + + check_throttle_failsafe(radio_in[CH3]); + + // output servos + for (uint8_t i = 0; i < 4; i++){ + if (i == 3) continue; + if(radio_in[i] >= radio_trim[i]) + servo_in[i] = (float)(radio_in[i] - radio_min[i]) / (float)(radio_max[i] - radio_min[i]) * 100.0; + else + servo_in[i] = (float)(radio_in[i] - radio_trim[i]) / (float)(radio_trim[i] - radio_min[i]) * 100.0; + } + servo_in[CH3] = (float)(radio_in[CH3] - radio_min[CH3]) / (float)(radio_max[CH3] - radio_min[CH3]) * 100.0; + servo_in[CH3] = constrain(servo_out[CH3], 0, 100); +} + +void +AP_RC::output() +{ + uint16_t out; + for (uint8_t i = 0; i < 4; i++){ + if (i == 3) continue; + if(radio_in[i] >= radio_trim[i]) + out = ((servo_in[i] * (radio_max[i] - radio_trim[i])) / 100) + radio_trim[i]; + else + out = ((servo_in[i] * (radio_max[i] - radio_trim[i])) / 100) + radio_trim[i]; + set_ch_pwm(i, out); + } + + out = (servo_out[CH3] * (float)(radio_max[CH3] - radio_min[CH3])) / 100.0; + out += radio_min[CH3]; + set_ch_pwm(CH3, out); +} + +void +AP_RC::trim() +{ + uint8_t temp = _mix_mode; + _mix_mode = 0; + read(); + _mix_mode = temp; + + radio_trim[CH1] = radio_in[CH1]; + radio_trim[CH2] = radio_in[CH2]; + radio_trim[CH3] = radio_in[CH3]; + radio_trim[CH4] = radio_in[CH4]; + + //Serial.print("trim "); + //Serial.println(radio_trim[CH1], DEC); +} + +void +AP_RC::twitch_servos(uint8_t times) +{ + while (times > 0){ + set_ch_pwm(CH1, radio_trim[CH1] + 100); + set_ch_pwm(CH2, radio_trim[CH2] + 100); + delay(400); + set_ch_pwm(CH1, radio_trim[CH1] - 100); + set_ch_pwm(CH2, radio_trim[CH2] - 100); + delay(200); + set_ch_pwm(CH1, radio_trim[CH1]); + set_ch_pwm(CH2, radio_trim[CH2]); + delay(30); + times--; + } +} + +void +AP_RC::set_ch_pwm(uint8_t ch, uint16_t pwm) +{ + switch(ch){ + case CH1: + if((_direction_mask & 1) == 0 ) + pwm = REVERSE - pwm; + pwm <<= 1; + OCR1A = pwm; + break; + + case CH2: + if((_direction_mask & 2) == 0 ) + pwm = REVERSE - pwm; + pwm <<= 1; + OCR1B = pwm; + break; + + case CH3: + if((_direction_mask & 4) == 0 ) + pwm = REVERSE - pwm; + // Jason's fancy 2µs hack + _timer_out = pwm % 512; + _timer_ovf_a = pwm / 512; + _timer_out >>= 1; + OCR2A = _timer_out; + break; + + case CH4: + if((_direction_mask & 8) == 0 ) + pwm = REVERSE - pwm; + _timer_out = pwm % 512; + _timer_ovf_b = pwm / 512; + _timer_out >>= 1; + OCR2B = _timer_out; + break; + } +} + + + +// radio PWM input timers +ISR(PCINT2_vect) { + int cnt = TCNT1; + if(PIND & B00000100){ // ch 1 (pin 2) is high + if ((_rc_ch_read & CH1_READ) != CH1_READ){ + _rc_ch_read |= CH1_READ; + timer1count = cnt; + } + }else if ((_rc_ch_read & CH1_READ) == CH1_READ){ // ch 1 (pin 2) is Low, and we were reading + _rc_ch_read &= B11111110; + if (cnt < timer1count) // Timer1 reset during the read of this pulse + timer1diff = (cnt + 40000 - timer1count) >> 1; // Timer1 TOP = 40000 + else + timer1diff = (cnt - timer1count) >> 1; + } + + if(PIND & B00001000){ // ch 2 (pin 3) is high + if ((_rc_ch_read & CH2_READ) != CH2_READ){ + _rc_ch_read |= CH2_READ; + timer2count = cnt; + } + }else if ((_rc_ch_read & CH2_READ) == CH2_READ){ // ch 1 (pin 2) is Low + _rc_ch_read &= B11111101; + if (cnt < timer2count) // Timer1 reset during the read of this pulse + timer2diff = (cnt + 40000 - timer2count) >> 1; // Timer1 TOP = 40000 + else + timer2diff = (cnt - timer2count) >> 1; + } +} + +ISR(PCINT0_vect) +{ + int cnt = TCNT1; + if(PINB & 8){ // pin 11 + if ((_rc_ch_read & CH3_READ) != CH3_READ){ + _rc_ch_read |= CH3_READ; + timer3count = cnt; + } + }else if ((_rc_ch_read & CH3_READ) == CH3_READ){ // ch 1 (pin 2) is Low + _rc_ch_read &= B11111011; + if (cnt < timer3count) // Timer1 reset during the read of this pulse + timer3diff = (cnt + 40000 - timer3count) >> 1; // Timer1 TOP = 40000 + else + timer3diff = (cnt - timer3count) >> 1; + } + + if(PINB & 32){ // pin 13 + if ((_rc_ch_read & CH4_READ) != CH4_READ){ + _rc_ch_read |= CH4_READ; + timer4count = cnt; + } + }else if ((_rc_ch_read & CH4_READ) == CH4_READ){ // ch 1 (pin 2) is Low + _rc_ch_read &= B11110111; + if (cnt < timer4count) // Timer1 reset during the read of this pulse + timer4diff = (cnt + 40000 - timer4count) >> 1; // Timer1 TOP = 40000 + else + timer4diff = (cnt - timer4count) >> 1; + } +} + + + +// Throttle Timer Interrupt +// ------------------------ +ISR(TIMER1_CAPT_vect) // Timer/Counter1 Capture Event +{ + //This is a timer 1 interrupts, executed every 20us + PORTB |= B00000001; //Putting the pin high! + PORTC |= B00010000; //Putting the pin high! + TCNT2 = 0; //restarting the counter of timer 2 + _timer_ovf = 0; +} + +ISR(TIMER2_OVF_vect) +{ + _timer_ovf++; +} + +ISR(TIMER2_COMPA_vect) // Timer/Counter2 Compare Match A +{ + if(_timer_ovf == _timer_ovf_a){ + PORTB &= B11111110; //Putting the pin low + } +} + +ISR(TIMER2_COMPB_vect) // Timer/Counter2 Compare Match B Rudder Servo +{ + if(_timer_ovf == _timer_ovf_b){ + PORTC &= B11101111; //Putting the pin low! + } +} + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/AP_RC.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/AP_RC.h new file mode 100644 index 0000000000..8118f980fd --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/AP_RC.h @@ -0,0 +1,32 @@ +#ifndef AP_RC_h +#define AP_RC_h + +#include +#include "WProgram.h" +#include "RC.h" + +class AP_RC : public RC +{ + public: + AP_RC(); + void init(); + void read(); + void output(); + void set_ch_pwm(uint8_t ch, uint16_t pwm); + void trim(); + void twitch_servos(uint8_t times); + + int16_t radio_in[4]; + int16_t radio_min[4]; + int16_t radio_trim[4]; + int16_t radio_max[4]; + + int16_t servo_in[4]; + float servo_out[4]; + + private: + uint16_t _timer_out; +}; + +#endif + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/RC.cpp b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/RC.cpp new file mode 100644 index 0000000000..0f92dfd5b7 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/RC.cpp @@ -0,0 +1,84 @@ +/* + AP_RC.cpp - Radio library for Arduino + Code by Jason Short. DIYDrones.com + + This library is free software; you can redistribute it and / or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + +*/ + + + +#include "RC.h" + +/* +RC::RC()// : + _direction_mask(255) +{ +} +*/ + +// direction mask: 0 = normal, 1 = reversed servos +void +RC::set_channel_direction(uint8_t ch, int8_t dir) +{ + uint8_t bitflip = 1 << ch; + + if(dir == 1){ + _direction_mask |= bitflip; + }else{ + _direction_mask &= ~bitflip; + } +} + +void +RC::set_failsafe(uint16_t v) +{ + _fs_value = v; +} + +void +RC::set_mix_mode(uint8_t m) +{ + _mix_mode = m; +} + + +void +RC::check_throttle_failsafe(uint16_t throttle) +{ + //check for failsafe and debounce funky reads + // ------------------------------------------ + if (throttle < _fs_value){ + // we detect a failsafe from radio + // throttle has dropped below the mark + _fs_counter++; + if (_fs_counter == 9){ + + }else if(_fs_counter == 10) { + failsafe = 1; + }else if (_fs_counter > 10){ + _fs_counter = 11; + } + + }else if(_fs_counter > 0){ + // we are no longer in failsafe condition + // but we need to recover quickly + _fs_counter--; + if (_fs_counter > 3){ + _fs_counter = 3; + } + if (_fs_counter == 1){ + + }else if(_fs_counter == 0) { + failsafe = 0; + }else if (_fs_counter <0){ + _fs_counter = -1; + } + } +} + + + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/RC.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/RC.h new file mode 100644 index 0000000000..fdc4505e7d --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/RC.h @@ -0,0 +1,46 @@ +#ifndef RC_h +#define RC_h + +#include +#include "WProgram.h" + +#define CH1 0 +#define CH2 1 +#define CH3 2 +#define CH4 3 +#define CH5 4 +#define CH6 5 +#define CH7 6 +#define CH8 7 + +#define MIN_PULSEWIDTH 900 +#define MAX_PULSEWIDTH 2100 + +#define ELEVONS 1 + +class RC +{ + public: + // RC(); + virtual void init(); + virtual void trim(); + virtual void read(); + virtual void output(); + virtual void set_channel_direction(uint8_t ch, int8_t dir); + virtual void set_ch_pwm(uint8_t ch, uint16_t pwm); + virtual void twitch_servos(void); + + void set_failsafe(uint16_t fs); + void set_mix_mode(uint8_t mode); + + uint8_t failsafe; + + protected: + void check_throttle_failsafe(uint16_t throttle); + uint8_t _fs_counter; + uint8_t _mix_mode; // 0 = normal, 1 = elevons + uint8_t _direction_mask; + uint16_t _fs_value; // PWM value to trigger failsafe flag +}; + +#endif diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/examples/APM_RC_elevons/APM_RC_elevons.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/examples/APM_RC_elevons/APM_RC_elevons.pde new file mode 100644 index 0000000000..196fafc00a --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/examples/APM_RC_elevons/APM_RC_elevons.pde @@ -0,0 +1,59 @@ +/* + Example of APM2_RC library. + Code by Jordi MuÒoz and Jose Julio. DIYDrones.com + + Print Input values and send Output to the servos + (Works with last PPM_encoder firmware) +*/ + +#include // ArduPilot Mega RC Library +APM2_RC rc; + +#define CH_ROLL 0 +#define CH_PITCH 1 +#define CH_THROTTLE 2 +#define CH_RUDDER 3 + +void setup() +{ + Serial.begin(38400); + Serial.println("ArduPilot Mega RC library test"); + + //rc.set_channel_direction(CH_ROLL, -1); + //rc.set_channel_direction(CH_PITCH, -1); + //rc.set_channel_direction(CH_THROTTLE, -1); + //rc.set_channel_direction(CH_RUDDER, -1); + rc.set_mix_mode(1); // 1 = elevons, 0 = normal + rc.init(); + delay(1000); +} + +void loop() +{ + delay(20); + rc.read_pwm(); + for(int y = 0; y < 8; y++) { + rc.set_ch_pwm(y, rc.radio_in[y]); // send to Servos + } + //print_pwm(); +} + +void print_pwm() +{ + Serial.print("ch1 "); + Serial.print(rc.radio_in[CH_ROLL], DEC); + Serial.print("\tch2: "); + Serial.print(rc.radio_in[CH_PITCH], DEC); + Serial.print("\tch3 :"); + Serial.print(rc.radio_in[CH_THROTTLE], DEC); + Serial.print("\tch4 :"); + Serial.print(rc.radio_in[CH_RUDDER], DEC); + Serial.print("\tch5 "); + Serial.print(rc.radio_in[4], DEC); + Serial.print("\tch6: "); + Serial.print(rc.radio_in[5], DEC); + Serial.print("\tch7 :"); + Serial.print(rc.radio_in[6], DEC); + Serial.print("\tch8 :"); + Serial.println(rc.radio_in[7], DEC); +} \ No newline at end of file diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/examples/APM_RC_test/APM_RC_test.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/examples/APM_RC_test/APM_RC_test.pde new file mode 100644 index 0000000000..33c722863b --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/examples/APM_RC_test/APM_RC_test.pde @@ -0,0 +1,59 @@ +/* + Example of APM2_RC library. + Code by Jordi MuÒoz and Jose Julio. DIYDrones.com + + Print Input values and send Output to the servos + (Works with last PPM_encoder firmware) +*/ + +#include // ArduPilot Mega RC Library +APM2_RC rc; + +#define CH_ROLL 0 +#define CH_PITCH 1 +#define CH_THROTTLE 2 +#define CH_RUDDER 3 + +void setup() +{ + Serial.begin(38400); + Serial.println("ArduPilot Mega RC library test"); + + //rc.set_channel_direction(CH_ROLL, -1); + //rc.set_channel_direction(CH_PITCH, -1); + //rc.set_channel_direction(CH_THROTTLE, -1); + //rc.set_channel_direction(CH_RUDDER, -1); + rc.init(); + delay(1000); +} + +void loop() +{ + delay(20); + rc.read_pwm(); + + for(int y = 0; y < 8; y++) { + rc.set_ch_pwm(y, rc.radio_in[y]); // send to Servos + } + //print_pwm(); +} + +void print_pwm() +{ + Serial.print("ch1 "); + Serial.print(rc.radio_in[CH_ROLL], DEC); + Serial.print("\tch2: "); + Serial.print(rc.radio_in[CH_PITCH], DEC); + Serial.print("\tch3 :"); + Serial.print(rc.radio_in[CH_THROTTLE], DEC); + Serial.print("\tch4 :"); + Serial.print(rc.radio_in[CH_RUDDER], DEC); + Serial.print("\tch5 "); + Serial.print(rc.radio_in[4], DEC); + Serial.print("\tch6: "); + Serial.print(rc.radio_in[5], DEC); + Serial.print("\tch7 :"); + Serial.print(rc.radio_in[6], DEC); + Serial.print("\tch8 :"); + Serial.println(rc.radio_in[7], DEC); +} \ No newline at end of file diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/examples/AP_RC_elevons/AP_RC_elevons.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/examples/AP_RC_elevons/AP_RC_elevons.pde new file mode 100644 index 0000000000..810b2df8ac --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/examples/AP_RC_elevons/AP_RC_elevons.pde @@ -0,0 +1,48 @@ +/* + Example of AP_RC library. + Code by Jordi MuÒoz and Jose Julio. DIYDrones.com + + Print Input values and send Output to the servos + (Works with last PPM_encoder firmware) +*/ + +#include // ArduPilot Mega RC Library +AP_RC rc; + +#define CH_ROLL 0 +#define CH_PITCH 1 +#define CH_THROTTLE 2 +#define CH_RUDDER 3 + +void setup() +{ + Serial.begin(38400); + Serial.println("ArduPilot RC Elevon library test"); + + rc.set_mix_mode(1); // 1 = elevons, 0 = normal + rc.init(); + + delay(1000); +} +void loop() +{ + delay(60); + rc.read_pwm(); + for(int y = 0; y < 4; y++) { + rc.set_ch_pwm(y, rc.radio_in[y]); // send to Servos + } + print_pwm(); +} + + +void print_pwm() +{ + Serial.print("ch1 "); + Serial.print(rc.radio_in[CH_ROLL], DEC); + Serial.print("\tch2: "); + Serial.print(rc.radio_in[CH_PITCH], DEC); + Serial.print("\tch3 :"); + Serial.print(rc.radio_in[CH_THROTTLE], DEC); + Serial.print("\tch4 :"); + Serial.println(rc.radio_in[CH_RUDDER], DEC); +} \ No newline at end of file diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/examples/AP_RC_test/AP_RC_test.pde b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/examples/AP_RC_test/AP_RC_test.pde new file mode 100644 index 0000000000..3b2b02c90c --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/examples/AP_RC_test/AP_RC_test.pde @@ -0,0 +1,50 @@ +/* + Example of AP_RC library. + Code by Jordi MuÒoz and Jose Julio. DIYDrones.com + + Print Input values and send Output to the servos + (Works with last PPM_encoder firmware) +*/ + +#include // ArduPilot RC Library +AP_RC rc; + +#define CH_ROLL 0 +#define CH_PITCH 1 +#define CH_THROTTLE 2 +#define CH_RUDDER 3 + +void setup() +{ + Serial.begin(38400); + Serial.println("ArduPilot RC library test"); + + //rc.set_channel_direction(CH_ROLL, -1); + //rc.set_channel_direction(CH_PITCH, -1); + //rc.set_channel_direction(CH_THROTTLE, -1); + //rc.set_channel_direction(CH_RUDDER, -1); + rc.init(); + delay(1000); +} + +void loop() +{ + delay(20); + rc.read_pwm(); + for(int y = 0; y < 4; y++) { + rc.set_ch_pwm(y, rc.radio_in[y]); // send to Servos + } + print_pwm(); +} + +void print_pwm() +{ + Serial.print("ch1 "); + Serial.print(rc.radio_in[CH_ROLL], DEC); + Serial.print("\tch2: "); + Serial.print(rc.radio_in[CH_PITCH], DEC); + Serial.print("\tch3 :"); + Serial.print(rc.radio_in[CH_THROTTLE], DEC); + Serial.print("\tch4 :"); + Serial.println(rc.radio_in[CH_RUDDER], DEC); +} \ No newline at end of file diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/keywords.txt b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/keywords.txt new file mode 100644 index 0000000000..26800b80d5 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/keywords.txt @@ -0,0 +1,4 @@ +AP_RC KEYWORD1 +init KEYWORD2 +set_ch_pwm KEYWORD2 +read_pwm KEYWORD2 diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/Waypoints/Waypoints.cpp b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/Waypoints/Waypoints.cpp new file mode 100644 index 0000000000..a04c6037b4 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/Waypoints/Waypoints.cpp @@ -0,0 +1,120 @@ +/* + AP_Radio.cpp - Radio library for Arduino + Code by Jason Short. DIYDrones.com + + This library is free software; you can redistribute it and / or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + +*/ + +#include "Waypoints.h" + +Waypoints::Waypoints() +{ +} + +void +Waypoints::set_waypoint_with_index(Waypoints::WP wp, uint8_t i) +{ + i = constrain(i, 0, _total); + uint32_t mem = _start_byte + (i * _wp_size); + + eeprom_busy_wait(); + eeprom_write_byte((uint8_t *) mem, wp.id); + + mem++; + eeprom_busy_wait(); + eeprom_write_byte((uint8_t *) mem, wp.p1); + + mem++; + eeprom_busy_wait(); + eeprom_write_dword((uint32_t *) mem, wp.alt); + + mem += 4; + eeprom_busy_wait(); + eeprom_write_dword((uint32_t *) mem, wp.lat); + + mem += 4; + eeprom_busy_wait(); + eeprom_write_dword((uint32_t *) mem, wp.lng); +} + +Waypoints::WP +Waypoints::get_waypoint_with_index(uint8_t i) +{ + Waypoints::WP wp; + + i = constrain(i, 0, _total); + uint32_t mem = _start_byte + (i * _wp_size); + + eeprom_busy_wait(); + wp.id = eeprom_read_byte((uint8_t *)mem); + + mem++; + eeprom_busy_wait(); + wp.p1 = eeprom_read_byte((uint8_t *)mem); + + mem++; + eeprom_busy_wait(); + wp.alt = (long)eeprom_read_dword((uint32_t *)mem); + + mem += 4; + eeprom_busy_wait(); + wp.lat = (long)eeprom_read_dword((uint32_t *)mem); + + mem += 4; + eeprom_busy_wait(); + wp.lng = (long)eeprom_read_dword((uint32_t *)mem); +} + + +Waypoints::WP +Waypoints::get_current_waypoint(void) +{ + return get_waypoint_with_index(_index); +} + +uint8_t +Waypoints::get_index(void) +{ + return _index; +} + +void +Waypoints::next_index(void) +{ + _index++; + if (_index >= _total) + _index == 0; +} + +void +Waypoints::set_index(uint8_t i) +{ + i = constrain(i, 0, _total); +} + +uint8_t +Waypoints::get_total(void) +{ + return _total; +} +void +Waypoints::set_total(uint8_t total) +{ + _total = total; +} + +void +Waypoints::set_start_byte(uint16_t start_byte) +{ + _start_byte = start_byte; +} + +void +Waypoints::set_wp_size(uint8_t wp_size) +{ + _wp_size = wp_size; +} diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/Waypoints/Waypoints.h b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/Waypoints/Waypoints.h new file mode 100644 index 0000000000..ddf03378a4 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/Waypoints/Waypoints.h @@ -0,0 +1,46 @@ +#ifndef Waypoints_h +#define Waypoints_h + +#include +#include "WProgram.h" +#include + +class Waypoints +{ + public: + Waypoints(); + + struct WP { + uint8_t id; // for commands + int8_t p1; // for commands + int32_t alt; // Altitude in centimeters (meters * 100) + int32_t lat; // Lattitude * 10**7 + int32_t lng; // Longitude * 10**7 + }; + + WP get_waypoint_with_index(uint8_t i); + WP get_current_waypoint(void); + + void set_waypoint_with_index(Waypoints::WP wp, uint8_t i); + + void set_start_byte(uint16_t start_byte); + void set_wp_size(uint8_t wp_size); + + void next_index(void); + uint8_t get_index(void); + void set_index(uint8_t i); + + uint8_t get_total(void); + void set_total(uint8_t total); + + + + private: + uint16_t _start_byte; + uint8_t _wp_size; + uint8_t _index; + uint8_t _total; +}; + +#endif + diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/readme.txt b/Tools/ArduPPM/WorkBasket/Jeti Duplex/readme.txt new file mode 100644 index 0000000000..0f37e9394e --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/Jeti Duplex/readme.txt @@ -0,0 +1,29 @@ + +This code is a work from Uwe Gartmann. + + +Could be integrated in the main Ardu code for jeti telemetry support. + + + + + +JetiBox.cpp, Version 1.0 beta + July 2010, by Uwe Gartmann + + Library acts as a Sensor when connected to a Jeti Receiver + written for Arduino Mega / ArduPilot Mega + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library 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 + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA \ No newline at end of file diff --git a/Tools/ArduPPM/WorkBasket/readme.txt b/Tools/ArduPPM/WorkBasket/readme.txt new file mode 100644 index 0000000000..9a03b12c96 --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/readme.txt @@ -0,0 +1,9 @@ + +The ArduPPM "Workbasket" is a source of code or tools usefull for ppm encoder projects. + + +It is recommanded to delete no more needed stuff when integration in the ArduPPM code has been done to keep the repository size smaller. + + + + diff --git a/Tools/ArduPPM/WorkBasket/spektrum_to_ppm_encoder/spektrum_to_ppm_encoder.pde b/Tools/ArduPPM/WorkBasket/spektrum_to_ppm_encoder/spektrum_to_ppm_encoder.pde new file mode 100644 index 0000000000..26ae6eb16a --- /dev/null +++ b/Tools/ArduPPM/WorkBasket/spektrum_to_ppm_encoder/spektrum_to_ppm_encoder.pde @@ -0,0 +1,309 @@ + +/********************************************************************************************************* + Title : C file for the ArduPilotMega PPM encoder + Author: Doug Weibel + Date: 11/11/10 + Comments: This software is FREE. Use it at your own risk. + This software has been tested with limited transmitter types and receiver binding types */ + + #include + #include + + #define TRUE 1 + #define FALSE 0 + + // buffers + struct Buffer { + volatile bool AB; + volatile uint8_t position; + volatile uint8_t bytesA[16]; + volatile uint8_t bytesB[16]; + }; + volatile Buffer buffer; + volatile bool sync = 0; // Are we in sync + volatile unsigned long last_end_time = 4294966895; // time last packet ended (or last char received if not sync'd) + + bool eleven_bit = 0; + uint16_t ch[12]; // PWM values + volatile bool falling_edge; + volatile uint8_t ch_index; + #define CH_MAX 8 // Number of channels to form PWM output + volatile uint16_t offsets[CH_MAX]; + + #define baud_setting 16 // See page 231 of the data sheet + + // Comment - this software rearranges the channel order from the tranmsitter to match APM useage + // Ch1 = Aileron = Spectrum Ch2 + // Ch2 = Elevator = Spectrum Ch3 + // Ch3 = Throttle = Spectrum Ch1 + // Ch8 = Flight mode = Spectrum Ch7 + const uint16_t failsafe_values[8] = {1500,1500,1000,1500,1500,1500,1500,1295}; + const uint16_t startup_values[8] = {1500,1500,1000,1500,1500,1500,1500,1900}; + + extern unsigned long timer0_millis; + + +//******************************************** +void setup() +{ + DDRD &= 0B11111110; // pd0 = RX0 + DDRB |= 0B00000111; // pb0 = PPM LED, pb1 = MUX OUT, pb2 = PPM OUT + PORTB |= 0B00000100; // Set PPM OUT high + + TCCR1A = 0; + TCCR1B = 0B00001001; // This will differ for the 328? + TCCR1C = 0; + OCR1A = 0Xffff; + TCNT1 = 0; + TIMSK1 = 0B00000010; //Output Compare A Match Interrupt Enable + + // init buffers + buffer.position = 0; + buffer.AB = TRUE; + sync = FALSE; + + // assign the baud_setting, a.k.a. ubbr (USART Baud Rate Register) + UCSR0A |= (1<> 8; + UBRR0L = baud_setting; + UCSR0B |= (1<=20) { + ledCount=0; + PORTB ^= 0B00000001; + } + } else if (state == 3) { // LED fast flash means receiving signal + ledCount++; + if(ledCount>=5) { + ledCount=0; + PORTB ^= 0B00000001; + } + } else { // LED off means something is wrong + PORTB &= 0B11111110; + } + + } +} + +// Serial port character received interrupt +//******************************************* +ISR(USART_RX_vect) //, ISR_BLOCK) +{ + unsigned char c = UDR0; + uint8_t i; + unsigned long m; + unsigned long m2; + + // timer0_millis could change inside interrupt and we don't want to disable interrupts + // we can do two readings and compare. + m = timer0_millis; + m2 = timer0_millis; + if (m!=m2) // timer0_millis corrupted? + m = timer0_millis; // this should be fine... + + if (sync) + { + if(buffer.AB) + buffer.bytesA[buffer.position] = c; + else + buffer.bytesB[buffer.position] = c; + + buffer.position++; + if(buffer.position == 16) + { + sync = FALSE; + buffer.AB = !buffer.AB; + last_end_time = m; + } + } + else + { + if ((m - last_end_time) > 7) + { + sync = TRUE; + if (buffer.AB) + { + buffer.bytesA[0] = c; + buffer.position = 1; + } + else + { + buffer.bytesB[0] = c; + buffer.position = 1; + } + } else { + last_end_time = m; + } + } + +/* +if (sync) { + PORTB |= 0B00000001; +} else { + PORTB &= 0B11111110; +} +*/ + +} + + + +// Timer 1 Compare A Match interrupt +//********************************** +ISR(TIMER1_COMPA_vect) { + + if (!falling_edge) { + PORTB |= 0B00000100; // Set PPM OUT high + if(ch_index < CH_MAX ) { + OCR1A = 16 * offsets[ch_index]; + falling_edge = TRUE; + ch_index++; + } else { + // set timer top to max to minimize interupt execution when not sending a frame + OCR1A = 0xffff; + } + } else { + if(ch_index <= CH_MAX ) { + PORTB &= 0B11111011; // Set PPM OUT low + OCR1A = 4800; //16 * 300, 300 usec negative going pulse width; + falling_edge = FALSE; + } else { + // set timer top to max to minimize interupt execution when not sending a frame + OCR1A = 0xffff; + } + } + +//PORTB &= 0B11111110; +} + + +// Get new RC data. Call before calling pwm_output +//************************************************* +uint8_t update(void) { + +// Returns: +// 0 means that we have not yet received packets +// 1 means we are starting up +// 2 means we are in failsafe +// 3 means radio OK + + static bool setup_done = 0; + unsigned long m; + unsigned long m2; + unsigned long time_now; + uint8_t packet1[17], packet2[17]; + uint16_t temp; + bool redo = 0; + + // timer0_millis could change and we don't want to disable interrupts + // we can do two readings and compare. + time_now = timer0_millis; + m2 = timer0_millis; + if (time_now!=m2) // timer0_millis corrupted? + time_now = timer0_millis; // this should be fine... + + m = last_end_time; + m2 = last_end_time; + if (m!=m2) // last_end_time corrupted? + m = last_end_time; // this should be fine... + + if( m > time_now ) { // We have not gotten in sync yet + for(int i=0;i<12;i++) + ch[i] = startup_values[i]; + return 0; + } else if (time_now < m + 500) { // We are receiving packets + + do { + packet1[16] = buffer.AB; + if (buffer.AB) + for (int i=0; i < 16; i++) + packet1[i] = buffer.bytesB[i]; + else + for (int i=0; i < 16; i++) + packet1[i] = buffer.bytesA[i]; + if(packet1[16] != buffer.AB) { // Did buffer.AB didn't change while we were working with it? + redo = 1; + } else { + redo = 0; + } + } while (redo); + + if(!setup_done) { + for (int i=2;i<15;i=i+2) { + if(packet1[i]&0B01000000) eleven_bit = 1; + } + setup_done = 1; + } + + for(int i=2;i<15;i=i+2) { + int ch_num; + temp = packet1[i+1] + (packet1[i]<<8); + if(eleven_bit) { + ch_num = (temp&0B0111100000000000)>>11; + ch[ch_num] = temp&0B0000011111111111; + ch[ch_num] /= 2; + ch[ch_num] += 1000; + } else { + ch_num = (temp&0B0011110000000000)>>10; + ch[ch_num] = temp&0B0000001111111111; + ch[ch_num] += 1000; + } + } + // Rearrange the first three channels from Spektrum order to APM order + temp = ch[0]; + ch[0]=ch[1]; + ch[1]=ch[2]; + ch[2]=temp; + // Rearrange the last two channels from Spektrum order to APM order + temp = ch[6]; + ch[6]=ch[7]; + ch[7]=temp; + return 3; + + } else { // This is the failsafe case + for(int i=0;i<12;i++) + ch[i] = failsafe_values[i]; + return 2; + } +} + +// Send a PWM output frame +// ************************************************ +void ppm_output(void) { + +// Channels 0 to CH_MAX-1 + + // Convert PWM values to offsets + for(int i=0;ifull true bin\Release\ - DEBUG;TRACE + TRACE prompt 4 false @@ -349,6 +349,30 @@ AGauge.cs Designer + + Configuration.cs + + + Firmware.cs + + + FlightData.cs + + + FlightPlanner.cs + + + Help.cs + + + Simulation.cs + + + Terminal.cs + + + JoystickSetup.cs + Log.cs @@ -411,7 +435,6 @@ HUD.cs - Always JoystickSetup.cs @@ -462,6 +485,7 @@ Setup.cs + Always Setup.cs @@ -491,7 +515,9 @@ Always - + + Always + @@ -501,8 +527,12 @@ - - + + Always + + + Always + Always diff --git a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj.user b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj.user new file mode 100644 index 0000000000..0f2d100239 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj.user @@ -0,0 +1,10 @@ + + + + http://www.diydrones.com/ + + + en-US + false + + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/Capture.cs b/Tools/ArdupilotMegaPlanner/Capture.cs index aedd5d50d2..87596b04ba 100644 --- a/Tools/ArdupilotMegaPlanner/Capture.cs +++ b/Tools/ArdupilotMegaPlanner/Capture.cs @@ -61,25 +61,43 @@ namespace WebCamService #endregion - /// Use capture device zero, default frame rate and size public Capture() { - //_Capture(0, 0, 0, 0); } - /// Use specified capture device, default frame rate and size - public Capture(int iDeviceNum) + + /// Use capture with selected media caps + public Capture(int iDeviceNum, AMMediaType media) { - _Capture(iDeviceNum, 0, 0, 0); - } - /// Use specified capture device, specified frame rate and default size - public Capture(int iDeviceNum, int iFrameRate) - { - _Capture(iDeviceNum, iFrameRate, 0, 0); - } - /// Use specified capture device, specified frame rate and size - public Capture(int iDeviceNum, int iFrameRate, int iWidth, int iHeight) - { - _Capture(iDeviceNum, iFrameRate, iWidth, iHeight); + DsDevice[] capDevices; + + // Get the collection of video devices + capDevices = DsDevice.GetDevicesOfCat(FilterCategory.VideoInputDevice); + + if (iDeviceNum + 1 > capDevices.Length) + { + throw new Exception("No video capture devices found at that index!"); + } + + try + { + // Set up the capture graph + SetupGraph(capDevices[iDeviceNum], media); + + // tell the callback to ignore new images + m_PictureReady = new ManualResetEvent(false); + m_bGotOne = true; + m_bRunning = false; + + timer1.Interval = 1000 / 15; // 15 fps + timer1.Tick += new EventHandler(timer1_Tick); + timer1.Start(); + + } + catch + { + Dispose(); + throw; + } } /// release everything. public void Dispose() @@ -195,41 +213,6 @@ namespace WebCamService return list; } - // Internal capture - private void _Capture(int iDeviceNum, int iFrameRate, int iWidth, int iHeight) - { - DsDevice[] capDevices; - - // Get the collection of video devices - capDevices = DsDevice.GetDevicesOfCat( FilterCategory.VideoInputDevice ); - - if (iDeviceNum + 1 > capDevices.Length) - { - throw new Exception("No video capture devices found at that index!"); - } - - try - { - // Set up the capture graph - SetupGraph( capDevices[iDeviceNum], iFrameRate, iWidth, iHeight); - - // tell the callback to ignore new images - m_PictureReady = new ManualResetEvent(false); - m_bGotOne = true; - m_bRunning = false; - - timer1.Interval = 1000 / 15; // 15 fps - timer1.Tick += new EventHandler(timer1_Tick); - timer1.Start(); - - } - catch - { - Dispose(); - throw; - } - } - public bool showhud = true; void timer1_Tick(object sender, EventArgs e) @@ -248,7 +231,7 @@ namespace WebCamService } /// build the capture graph for grabber. - private void SetupGraph(DsDevice dev, int iFrameRate, int iWidth, int iHeight) + private void SetupGraph(DsDevice dev, AMMediaType media) { int hr; @@ -328,11 +311,7 @@ namespace WebCamService hr = m_FilterGraph.AddFilter( baseGrabFlt, "Ds.NET Grabber" ); DsError.ThrowExceptionForHR( hr ); - // If any of the default config items are set - if (iFrameRate + iHeight + iWidth > 0) - { - SetConfigParms(capGraph, capFilter, iFrameRate, iWidth, iHeight); - } + SetConfigParms(capGraph, capFilter, media); hr = capGraph.RenderStream(PinCategory.Capture, MediaType.Video, capFilter, pAVIDecompressor, baseGrabFlt); if (hr < 0) @@ -409,11 +388,10 @@ namespace WebCamService } // Set the Framerate, and video size - private void SetConfigParms(ICaptureGraphBuilder2 capGraph, IBaseFilter capFilter, int iFrameRate, int iWidth, int iHeight) + private void SetConfigParms(ICaptureGraphBuilder2 capGraph, IBaseFilter capFilter, AMMediaType media) { int hr; object o; - AMMediaType media; // Find the stream config interface hr = capGraph.FindInterface( @@ -423,36 +401,7 @@ namespace WebCamService if (videoStreamConfig == null) { throw new Exception("Failed to get IAMStreamConfig"); - } - - // Get the existing format block - hr = videoStreamConfig.GetFormat( out media); - DsError.ThrowExceptionForHR( hr ); - - // copy out the videoinfoheader - VideoInfoHeader v = new VideoInfoHeader(); - Marshal.PtrToStructure( media.formatPtr, v ); - - // if overriding the framerate, set the frame rate - if (iFrameRate > 0) - { - v.AvgTimePerFrame = 10000000 / iFrameRate; - } - - // if overriding the width, set the width - if (iWidth > 0) - { - v.BmiHeader.Width = iWidth; - } - - // if overriding the Height, set the Height - if (iHeight > 0) - { - v.BmiHeader.Height = iHeight; - } - - // Copy the media structure back - Marshal.StructureToPtr( v, media.formatPtr, false ); + } // Set the new format hr = videoStreamConfig.SetFormat( media ); diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.build.log index 51603ba231..4798c845b1 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.build.log @@ -3,19 +3,18 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition -In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:76: +In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77: /root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()': -/root/apm/ardupilot-mega/ArduCopter/Parameters.h:387: warning: overflow in implicit constant conversion +/root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_loiter_turns()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:301: warning: statement has no effect +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:302: warning: statement has no effect /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_nav_wp()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:412: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:413: warning: comparison between signed and unsigned integer expressions /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_loiter_time()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:439: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:440: warning: comparison between signed and unsigned integer expressions /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_jump()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:652: warning: unused variable 'temp' +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:653: warning: unused variable 'temp' autogenerated: At global scope: -autogenerated:31: warning: 'int alt_hold_velocity()' declared 'static' but never defined autogenerated:83: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined autogenerated:84: warning: 'void send_message(byte)' declared 'static' but never defined autogenerated:85: warning: 'void send_message(byte, long int)' declared 'static' but never defined @@ -30,39 +29,39 @@ autogenerated:67: warning: 'long int convert_to_dec(float)' declared 'static' bu autogenerated:136: warning: 'void Log_Write_Optflow()' declared 'static' but never defined autogenerated:146: warning: 'void decrement_WP_index()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:431: warning: 'bool verify_loiter_unlim()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used /root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used -autogenerated:211: warning: 'void heli_init_swash()' declared 'static' but never defined -autogenerated:212: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined -autogenerated:213: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined -autogenerated:236: warning: 'void debug_motors()' declared 'static' but never defined -autogenerated:252: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/navigation.pde:208: warning: 'int get_loiter_angle()' defined but not used -autogenerated:256: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined -autogenerated:257: warning: 'long int cross_track_test()' declared 'static' but never defined -autogenerated:258: warning: 'void reset_crosstrack()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/navigation.pde:273: warning: 'long int get_altitude_above_home()' defined but not used -/root/apm/ardupilot-mega/ArduCopter/navigation.pde:294: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used -/root/apm/ardupilot-mega/ArduCopter/radio.pde:131: warning: 'void throttle_failsafe(uint16_t)' defined but not used -/root/apm/ardupilot-mega/ArduCopter/radio.pde:188: warning: 'void trim_yaw()' defined but not used -autogenerated:270: warning: 'void readCommands()' declared 'static' but never defined -autogenerated:271: warning: 'void parseCommand(char*)' declared 'static' but never defined +autogenerated:208: warning: 'void heli_init_swash()' declared 'static' but never defined +autogenerated:209: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined +autogenerated:210: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined +autogenerated:233: warning: 'void debug_motors()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used +autogenerated:252: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined +autogenerated:253: warning: 'long int cross_track_test()' declared 'static' but never defined +autogenerated:254: warning: 'void reset_crosstrack()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/radio.pde:129: warning: 'void throttle_failsafe(uint16_t)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/radio.pde:186: warning: 'void trim_yaw()' defined but not used +autogenerated:266: warning: 'void readCommands()' declared 'static' but never defined +autogenerated:267: warning: 'void parseCommand(char*)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used -autogenerated:274: warning: 'long int read_baro_filtered()' declared 'static' but never defined +autogenerated:270: warning: 'long int read_baro_filtered()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used /root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used -autogenerated:288: warning: 'void report_heli()' declared 'static' but never defined -autogenerated:289: warning: 'void report_gyro()' declared 'static' but never defined -autogenerated:296: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined -autogenerated:297: warning: 'int read_num_from_serial()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/system.pde:448: warning: 'void set_failsafe(boolean)' defined but not used -autogenerated:311: warning: 'void init_optflow()' declared 'static' but never defined -autogenerated:319: warning: 'void fake_out_gps()' declared 'static' but never defined +autogenerated:284: warning: 'void report_heli()' declared 'static' but never defined +autogenerated:285: warning: 'void report_gyro()' declared 'static' but never defined +autogenerated:292: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined +autogenerated:293: warning: 'int read_num_from_serial()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/system.pde:459: warning: 'void set_failsafe(boolean)' defined but not used +autogenerated:307: warning: 'void init_optflow()' declared 'static' but never defined +autogenerated:315: warning: 'void fake_out_gps()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:444: warning: 'undo_event' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'condition_rate' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:464: warning: 'simple_WP' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:469: warning: 'new_location' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'undo_event' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:456: warning: 'condition_rate' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:470: warning: 'simple_WP' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:475: warning: 'new_location' defined but not used +/root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(uint8_t, const Menu::arg*)' declared 'static' but never defined %% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_PI/APM_PI.o %% libraries/APM_RC/APM_RC.o @@ -100,6 +99,7 @@ In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_Optic %% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o %% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o %% libraries/AP_RangeFinder/RangeFinder.o +%% libraries/AP_Relay/AP_Relay.o %% libraries/DataFlash/DataFlash.o In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.size.txt index d940c4580b..de120aab96 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.size.txt @@ -36,12 +36,12 @@ 00000001 b yaw_mode 00000001 b GPS_light 00000001 b do_simple -00000001 b loop_step 00000001 b trim_flag 00000001 b dancing_light()::step 00000001 b read_control_switch()::switch_debouncer 00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav 00000001 B mavdelay +00000001 B relay 00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char) 00000002 b climb_rate 00000002 b loiter_sum @@ -50,15 +50,20 @@ 00000002 b event_repeat 00000002 b loiter_total 00000002 b nav_throttle +00000002 b x_rate_error +00000002 b y_rate_error 00000002 b altitude_rate 00000002 b gps_fix_count 00000002 b velocity_land +00000002 b x_actual_speed +00000002 b y_actual_speed 00000002 b loiter_time_max 00000002 b command_yaw_time 00000002 b event_undo_value 00000002 b command_yaw_speed 00000002 b auto_level_counter 00000002 b ground_temperature +00000002 b waypoint_speed_gov 00000002 b superslow_loopCounter 00000002 r comma 00000002 b g_gps @@ -74,11 +79,6 @@ 00000002 r test_wp(unsigned char, Menu::arg const*)::__c 00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c 00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c -00000002 B adc -00000002 B x_actual_speed -00000002 B x_rate_error -00000002 B y_actual_speed -00000002 B y_rate_error 00000003 r select_logs(unsigned char, Menu::arg const*)::__c 00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c 00000003 r print_enabled(unsigned char)::__c @@ -107,7 +107,6 @@ 00000004 b fast_loopTimer 00000004 b perf_mon_timer 00000004 b target_bearing -00000004 b throttle_timer 00000004 d battery_voltage 00000004 b command_yaw_end 00000004 b condition_start @@ -254,6 +253,7 @@ 00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c @@ -265,7 +265,6 @@ 0000000a r print_log_menu()::__c 0000000a r Log_Read_Startup()::__c 0000000a r test_wp(unsigned char, Menu::arg const*)::__c -0000000a r test_mag(unsigned char, Menu::arg const*)::__c 0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c @@ -345,7 +344,6 @@ 0000000f r report_batt_monitor()::__c 0000000f r test_imu(unsigned char, Menu::arg const*)::__c 0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c -00000010 r flight_mode_strings 00000010 r planner_menu_commands 00000010 b motor_out 00000010 W AP_VarT::cast_to_float() const @@ -357,6 +355,7 @@ 00000012 B Serial 00000012 B Serial1 00000012 B Serial3 +00000012 r flight_mode_strings 00000012 W AP_Float16::~AP_Float16() 00000012 W AP_VarA::~AP_VarA() 00000012 W AP_VarS >::~AP_VarS() @@ -401,7 +400,6 @@ 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001d r Log_Read_Attitude()::__c 0000001e r Log_Read_Optflow()::__c -0000001f r test_mag(unsigned char, Menu::arg const*)::__c 00000020 r test_current(unsigned char, Menu::arg const*)::__c 00000020 t byte_swap_4 00000021 r print_log_menu()::__c @@ -429,7 +427,6 @@ 00000026 t print_hit_enter() 00000026 t Log_Read_Startup() 00000026 r Log_Read_Control_Tuning()::__c -00000027 r test_xbee(unsigned char, Menu::arg const*)::__c 00000028 t test_battery(unsigned char, Menu::arg const*) 00000028 t main_menu_help(unsigned char, Menu::arg const*) 00000028 t help_log(unsigned char, Menu::arg const*) @@ -467,6 +464,7 @@ 0000003e W AP_VarT::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char) 00000040 t read_AHRS() 00000040 W AP_Float16::unserialize(void*, unsigned int) +00000040 B adc 00000040 t byte_swap_8 00000042 t report_sonar() 00000044 t setup_show(unsigned char, Menu::arg const*) @@ -492,7 +490,6 @@ 0000005c t setup_esc(unsigned char, Menu::arg const*) 0000005e t update_GPS_light() 0000005e T GCS_MAVLINK::_count_parameters() -00000064 t test_xbee(unsigned char, Menu::arg const*) 00000064 B barometer 00000064 t mavlink_msg_param_value_send 00000068 t zero_eeprom() @@ -535,16 +532,16 @@ 000000aa t test_sonar(unsigned char, Menu::arg const*) 000000aa t Log_Read_Nav_Tuning() 000000ae t report_frame() +000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b2 t erase_logs(unsigned char, Menu::arg const*) -000000b4 t test_relay(unsigned char, Menu::arg const*) 000000b4 t planner_gcs(unsigned char, Menu::arg const*) 000000b6 t get_log_boundaries(unsigned char, int&, int&) 000000b7 B compass +000000be t update_events() 000000c2 t setup_compass(unsigned char, Menu::arg const*) 000000c2 t send_radio_out(mavlink_channel_t) 000000c2 t Log_Read_Attitude() 000000c4 t get_distance(Location*, Location*) -000000c4 t update_events() 000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c 000000c6 t test_eedump(unsigned char, Menu::arg const*) 000000c6 t send_radio_in(mavlink_channel_t) @@ -567,24 +564,24 @@ 000000ea t Log_Read_Control_Tuning() 000000ee t report_batt_monitor() 000000f6 t Log_Read_Cmd() -000000fa t calc_nav_pitch_roll() +000000fa t calc_loiter_pitch_roll() +00000100 r test_menu_commands 0000010a t send_raw_imu2(mavlink_channel_t) 0000010a t test_gps(unsigned char, Menu::arg const*) 0000010c t test_current(unsigned char, Menu::arg const*) -0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 0000010e t send_servo_out(mavlink_channel_t) -00000112 t send_extended_status1(mavlink_channel_t, unsigned int) +0000010e t send_extended_status1(mavlink_channel_t, unsigned int) +0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000118 t set_command_with_index(Location, int) 00000118 T GCS_MAVLINK::_queued_send() 0000011c t get_command_with_index(int) -00000120 r test_menu_commands 00000130 t report_compass() -00000132 t set_next_WP(Location*) 00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long) 00000138 t get_stabilize_roll(long) 00000138 t get_stabilize_pitch(long) +0000013a t set_next_WP(Location*) 00000148 t Log_Read_GPS() 00000152 T GCS_MAVLINK::update() 00000158 t update_commands() @@ -593,9 +590,8 @@ 00000160 t send_nav_controller_output(mavlink_channel_t) 00000166 t select_logs(unsigned char, Menu::arg const*) 00000166 t send_vfr_hud(mavlink_channel_t) +0000016c t test_imu(unsigned char, Menu::arg const*) 0000016e t send_attitude(mavlink_channel_t) -00000170 t test_imu(unsigned char, Menu::arg const*) -00000170 t test_mag(unsigned char, Menu::arg const*) 000001a8 t print_radio_values() 000001be t arm_motors() 000001be T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) @@ -604,25 +600,25 @@ 000001d6 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int) 000001e4 t setup_flightmodes(unsigned char, Menu::arg const*) 000001ea t init_home() -00000206 t set_mode(unsigned char) 00000210 t setup_motors(unsigned char, Menu::arg const*) 0000021a t send_raw_imu1(mavlink_channel_t) 00000220 t test_wp(unsigned char, Menu::arg const*) 00000228 t setup_radio(unsigned char, Menu::arg const*) +00000228 t set_mode(unsigned char) 0000022a t send_gps_raw(mavlink_channel_t) +00000242 t calc_loiter(int, int) 00000268 t send_raw_imu3(mavlink_channel_t) -000002ea t tuning() -00000354 t calc_nav_rate(int, int, int, int) +00000330 t tuning() 00000384 t print_log_menu() +0000039a T update_throttle_mode() 000003a0 t read_battery() -000003ae T update_throttle_mode() 00000410 T update_yaw_mode() 0000046e T update_roll_pitch_mode() -000005ee t init_ardupilot() -000006e6 t update_nav_wp() -000007b0 t __static_initialization_and_destruction_0(int, int) -000007ea b g -00000874 t process_next_command() -00000894 W Parameters::Parameters() +000005fc t init_ardupilot() +000006fa t update_nav_wp() +000007b8 t __static_initialization_and_destruction_0(int, int) +00000824 b g +0000086a t process_next_command() +000008f4 W Parameters::Parameters() 00001228 T GCS_MAVLINK::handleMessage(__mavlink_message*) -00001c6a T loop +00001c58 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.build.log index 51603ba231..4798c845b1 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.build.log @@ -3,19 +3,18 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition -In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:76: +In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77: /root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()': -/root/apm/ardupilot-mega/ArduCopter/Parameters.h:387: warning: overflow in implicit constant conversion +/root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_loiter_turns()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:301: warning: statement has no effect +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:302: warning: statement has no effect /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_nav_wp()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:412: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:413: warning: comparison between signed and unsigned integer expressions /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_loiter_time()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:439: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:440: warning: comparison between signed and unsigned integer expressions /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_jump()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:652: warning: unused variable 'temp' +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:653: warning: unused variable 'temp' autogenerated: At global scope: -autogenerated:31: warning: 'int alt_hold_velocity()' declared 'static' but never defined autogenerated:83: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined autogenerated:84: warning: 'void send_message(byte)' declared 'static' but never defined autogenerated:85: warning: 'void send_message(byte, long int)' declared 'static' but never defined @@ -30,39 +29,39 @@ autogenerated:67: warning: 'long int convert_to_dec(float)' declared 'static' bu autogenerated:136: warning: 'void Log_Write_Optflow()' declared 'static' but never defined autogenerated:146: warning: 'void decrement_WP_index()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:431: warning: 'bool verify_loiter_unlim()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used /root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used -autogenerated:211: warning: 'void heli_init_swash()' declared 'static' but never defined -autogenerated:212: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined -autogenerated:213: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined -autogenerated:236: warning: 'void debug_motors()' declared 'static' but never defined -autogenerated:252: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/navigation.pde:208: warning: 'int get_loiter_angle()' defined but not used -autogenerated:256: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined -autogenerated:257: warning: 'long int cross_track_test()' declared 'static' but never defined -autogenerated:258: warning: 'void reset_crosstrack()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/navigation.pde:273: warning: 'long int get_altitude_above_home()' defined but not used -/root/apm/ardupilot-mega/ArduCopter/navigation.pde:294: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used -/root/apm/ardupilot-mega/ArduCopter/radio.pde:131: warning: 'void throttle_failsafe(uint16_t)' defined but not used -/root/apm/ardupilot-mega/ArduCopter/radio.pde:188: warning: 'void trim_yaw()' defined but not used -autogenerated:270: warning: 'void readCommands()' declared 'static' but never defined -autogenerated:271: warning: 'void parseCommand(char*)' declared 'static' but never defined +autogenerated:208: warning: 'void heli_init_swash()' declared 'static' but never defined +autogenerated:209: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined +autogenerated:210: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined +autogenerated:233: warning: 'void debug_motors()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used +autogenerated:252: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined +autogenerated:253: warning: 'long int cross_track_test()' declared 'static' but never defined +autogenerated:254: warning: 'void reset_crosstrack()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/radio.pde:129: warning: 'void throttle_failsafe(uint16_t)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/radio.pde:186: warning: 'void trim_yaw()' defined but not used +autogenerated:266: warning: 'void readCommands()' declared 'static' but never defined +autogenerated:267: warning: 'void parseCommand(char*)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used -autogenerated:274: warning: 'long int read_baro_filtered()' declared 'static' but never defined +autogenerated:270: warning: 'long int read_baro_filtered()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used /root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used -autogenerated:288: warning: 'void report_heli()' declared 'static' but never defined -autogenerated:289: warning: 'void report_gyro()' declared 'static' but never defined -autogenerated:296: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined -autogenerated:297: warning: 'int read_num_from_serial()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/system.pde:448: warning: 'void set_failsafe(boolean)' defined but not used -autogenerated:311: warning: 'void init_optflow()' declared 'static' but never defined -autogenerated:319: warning: 'void fake_out_gps()' declared 'static' but never defined +autogenerated:284: warning: 'void report_heli()' declared 'static' but never defined +autogenerated:285: warning: 'void report_gyro()' declared 'static' but never defined +autogenerated:292: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined +autogenerated:293: warning: 'int read_num_from_serial()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/system.pde:459: warning: 'void set_failsafe(boolean)' defined but not used +autogenerated:307: warning: 'void init_optflow()' declared 'static' but never defined +autogenerated:315: warning: 'void fake_out_gps()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:444: warning: 'undo_event' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'condition_rate' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:464: warning: 'simple_WP' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:469: warning: 'new_location' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'undo_event' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:456: warning: 'condition_rate' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:470: warning: 'simple_WP' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:475: warning: 'new_location' defined but not used +/root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(uint8_t, const Menu::arg*)' declared 'static' but never defined %% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_PI/APM_PI.o %% libraries/APM_RC/APM_RC.o @@ -100,6 +99,7 @@ In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_Optic %% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o %% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o %% libraries/AP_RangeFinder/RangeFinder.o +%% libraries/AP_Relay/AP_Relay.o %% libraries/DataFlash/DataFlash.o In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.size.txt index c4d00f2ef6..37a0d6ac54 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.size.txt @@ -36,12 +36,12 @@ 00000001 b yaw_mode 00000001 b GPS_light 00000001 b do_simple -00000001 b loop_step 00000001 b trim_flag 00000001 b dancing_light()::step 00000001 b read_control_switch()::switch_debouncer 00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav 00000001 B mavdelay +00000001 B relay 00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char) 00000002 b climb_rate 00000002 b loiter_sum @@ -50,15 +50,20 @@ 00000002 b event_repeat 00000002 b loiter_total 00000002 b nav_throttle +00000002 b x_rate_error +00000002 b y_rate_error 00000002 b altitude_rate 00000002 b gps_fix_count 00000002 b velocity_land +00000002 b x_actual_speed +00000002 b y_actual_speed 00000002 b loiter_time_max 00000002 b command_yaw_time 00000002 b event_undo_value 00000002 b command_yaw_speed 00000002 b auto_level_counter 00000002 b ground_temperature +00000002 b waypoint_speed_gov 00000002 b superslow_loopCounter 00000002 r comma 00000002 b g_gps @@ -74,11 +79,6 @@ 00000002 r test_wp(unsigned char, Menu::arg const*)::__c 00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c 00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c -00000002 B adc -00000002 B x_actual_speed -00000002 B x_rate_error -00000002 B y_actual_speed -00000002 B y_rate_error 00000003 r select_logs(unsigned char, Menu::arg const*)::__c 00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c 00000003 r print_enabled(unsigned char)::__c @@ -107,7 +107,6 @@ 00000004 b fast_loopTimer 00000004 b perf_mon_timer 00000004 b target_bearing -00000004 b throttle_timer 00000004 d battery_voltage 00000004 b command_yaw_end 00000004 b condition_start @@ -254,6 +253,7 @@ 00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c @@ -265,7 +265,6 @@ 0000000a r print_log_menu()::__c 0000000a r Log_Read_Startup()::__c 0000000a r test_wp(unsigned char, Menu::arg const*)::__c -0000000a r test_mag(unsigned char, Menu::arg const*)::__c 0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c @@ -345,7 +344,6 @@ 0000000f r report_batt_monitor()::__c 0000000f r test_imu(unsigned char, Menu::arg const*)::__c 0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c -00000010 r flight_mode_strings 00000010 r planner_menu_commands 00000010 b motor_out 00000010 W AP_VarT::cast_to_float() const @@ -357,6 +355,7 @@ 00000012 B Serial 00000012 B Serial1 00000012 B Serial3 +00000012 r flight_mode_strings 00000012 W AP_Float16::~AP_Float16() 00000012 W AP_VarA::~AP_VarA() 00000012 W AP_VarS >::~AP_VarS() @@ -401,7 +400,6 @@ 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001d r Log_Read_Attitude()::__c 0000001e r Log_Read_Optflow()::__c -0000001f r test_mag(unsigned char, Menu::arg const*)::__c 00000020 r test_current(unsigned char, Menu::arg const*)::__c 00000020 t byte_swap_4 00000021 r print_log_menu()::__c @@ -429,7 +427,6 @@ 00000026 t print_hit_enter() 00000026 t Log_Read_Startup() 00000026 r Log_Read_Control_Tuning()::__c -00000027 r test_xbee(unsigned char, Menu::arg const*)::__c 00000028 t test_battery(unsigned char, Menu::arg const*) 00000028 t main_menu_help(unsigned char, Menu::arg const*) 00000028 t help_log(unsigned char, Menu::arg const*) @@ -467,6 +464,7 @@ 0000003e W AP_VarT::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char) 00000040 t read_AHRS() 00000040 W AP_Float16::unserialize(void*, unsigned int) +00000040 B adc 00000040 t byte_swap_8 00000042 t report_sonar() 00000044 t setup_show(unsigned char, Menu::arg const*) @@ -492,7 +490,6 @@ 0000005c t setup_esc(unsigned char, Menu::arg const*) 0000005e t update_GPS_light() 0000005e T GCS_MAVLINK::_count_parameters() -00000064 t test_xbee(unsigned char, Menu::arg const*) 00000064 B barometer 00000064 t mavlink_msg_param_value_send 00000068 t zero_eeprom() @@ -535,17 +532,17 @@ 000000a8 t test_sonar(unsigned char, Menu::arg const*) 000000aa t Log_Read_Nav_Tuning() 000000ae t report_frame() +000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b2 t erase_logs(unsigned char, Menu::arg const*) -000000b4 t test_relay(unsigned char, Menu::arg const*) 000000b4 t planner_gcs(unsigned char, Menu::arg const*) 000000b6 t get_log_boundaries(unsigned char, int&, int&) 000000b7 B compass +000000be t update_events() 000000c2 t test_eedump(unsigned char, Menu::arg const*) 000000c2 t setup_compass(unsigned char, Menu::arg const*) 000000c2 t send_radio_out(mavlink_channel_t) 000000c2 t Log_Read_Attitude() 000000c4 t get_distance(Location*, Location*) -000000c4 t update_events() 000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c 000000c6 t send_radio_in(mavlink_channel_t) 000000c6 t Log_Read_Performance() @@ -567,24 +564,24 @@ 000000ea t Log_Read_Control_Tuning() 000000ee t report_batt_monitor() 000000f6 t Log_Read_Cmd() -000000fa t calc_nav_pitch_roll() +000000fa t calc_loiter_pitch_roll() +00000100 r test_menu_commands 0000010a t send_raw_imu2(mavlink_channel_t) 0000010a t test_gps(unsigned char, Menu::arg const*) 0000010c t test_current(unsigned char, Menu::arg const*) -0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 0000010e t send_servo_out(mavlink_channel_t) -00000112 t send_extended_status1(mavlink_channel_t, unsigned int) +0000010e t send_extended_status1(mavlink_channel_t, unsigned int) +0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000118 t set_command_with_index(Location, int) 00000118 T GCS_MAVLINK::_queued_send() 0000011c t get_command_with_index(int) -00000120 r test_menu_commands 00000130 t report_compass() -00000132 t set_next_WP(Location*) 00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long) 00000138 t get_stabilize_roll(long) 00000138 t get_stabilize_pitch(long) +0000013a t set_next_WP(Location*) 00000148 t Log_Read_GPS() 00000152 T GCS_MAVLINK::update() 00000158 t update_commands() @@ -593,9 +590,8 @@ 00000160 t send_nav_controller_output(mavlink_channel_t) 00000166 t select_logs(unsigned char, Menu::arg const*) 00000166 t send_vfr_hud(mavlink_channel_t) +0000016c t test_imu(unsigned char, Menu::arg const*) 0000016e t send_attitude(mavlink_channel_t) -00000170 t test_imu(unsigned char, Menu::arg const*) -00000170 t test_mag(unsigned char, Menu::arg const*) 000001a8 t print_radio_values() 000001be t arm_motors() 000001be T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) @@ -604,25 +600,25 @@ 000001d6 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int) 000001e4 t setup_flightmodes(unsigned char, Menu::arg const*) 000001ea t init_home() -00000206 t set_mode(unsigned char) 00000210 t setup_motors(unsigned char, Menu::arg const*) 0000021a t send_raw_imu1(mavlink_channel_t) 0000021c t test_wp(unsigned char, Menu::arg const*) 00000228 t setup_radio(unsigned char, Menu::arg const*) +00000228 t set_mode(unsigned char) 0000022a t send_gps_raw(mavlink_channel_t) +00000242 t calc_loiter(int, int) 00000268 t send_raw_imu3(mavlink_channel_t) -000002ea t tuning() -00000354 t calc_nav_rate(int, int, int, int) +00000330 t tuning() 00000382 t print_log_menu() +0000039a T update_throttle_mode() 000003a0 t read_battery() -000003ae T update_throttle_mode() 00000410 T update_yaw_mode() 0000046e T update_roll_pitch_mode() -000005ee t init_ardupilot() -000006e6 t update_nav_wp() -000007b0 t __static_initialization_and_destruction_0(int, int) -000007ea b g -00000874 t process_next_command() -00000894 W Parameters::Parameters() +000005fc t init_ardupilot() +000006fa t update_nav_wp() +000007b8 t __static_initialization_and_destruction_0(int, int) +00000824 b g +0000086a t process_next_command() +000008f4 W Parameters::Parameters() 00001228 T GCS_MAVLINK::handleMessage(__mavlink_message*) -00001c68 T loop +00001c56 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.build.log index 4f632afe15..7110a3e77f 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.build.log @@ -3,19 +3,18 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition -In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:76: +In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77: /root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()': -/root/apm/ardupilot-mega/ArduCopter/Parameters.h:387: warning: overflow in implicit constant conversion +/root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_loiter_turns()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:301: warning: statement has no effect +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:302: warning: statement has no effect /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_nav_wp()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:412: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:413: warning: comparison between signed and unsigned integer expressions /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_loiter_time()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:439: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:440: warning: comparison between signed and unsigned integer expressions /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_jump()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:652: warning: unused variable 'temp' +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:653: warning: unused variable 'temp' autogenerated: At global scope: -autogenerated:31: warning: 'int alt_hold_velocity()' declared 'static' but never defined autogenerated:83: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined autogenerated:84: warning: 'void send_message(byte)' declared 'static' but never defined autogenerated:85: warning: 'void send_message(byte, long int)' declared 'static' but never defined @@ -33,48 +32,48 @@ autogenerated:138: warning: 'void Log_Write_Control_Tuning()' declared 'static' /root/apm/ardupilot-mega/ArduCopter/Log.pde:738: warning: 'void Log_Write_Attitude()' defined but not used autogenerated:146: warning: 'void decrement_WP_index()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:431: warning: 'bool verify_loiter_unlim()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used /root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used -autogenerated:211: warning: 'void heli_init_swash()' declared 'static' but never defined -autogenerated:212: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined -autogenerated:213: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined -autogenerated:236: warning: 'void debug_motors()' declared 'static' but never defined -autogenerated:252: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/navigation.pde:208: warning: 'int get_loiter_angle()' defined but not used -autogenerated:256: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined -autogenerated:257: warning: 'long int cross_track_test()' declared 'static' but never defined -autogenerated:258: warning: 'void reset_crosstrack()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/navigation.pde:273: warning: 'long int get_altitude_above_home()' defined but not used -/root/apm/ardupilot-mega/ArduCopter/navigation.pde:294: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used -/root/apm/ardupilot-mega/ArduCopter/radio.pde:131: warning: 'void throttle_failsafe(uint16_t)' defined but not used -/root/apm/ardupilot-mega/ArduCopter/radio.pde:188: warning: 'void trim_yaw()' defined but not used -autogenerated:270: warning: 'void readCommands()' declared 'static' but never defined -autogenerated:271: warning: 'void parseCommand(char*)' declared 'static' but never defined -autogenerated:272: warning: 'void ReadSCP1000()' declared 'static' but never defined -autogenerated:273: warning: 'void init_barometer()' declared 'static' but never defined -autogenerated:274: warning: 'long int read_baro_filtered()' declared 'static' but never defined -autogenerated:275: warning: 'long int read_barometer()' declared 'static' but never defined -autogenerated:276: warning: 'void read_airspeed()' declared 'static' but never defined -autogenerated:277: warning: 'void zero_airspeed()' declared 'static' but never defined -autogenerated:288: warning: 'void report_heli()' declared 'static' but never defined -autogenerated:289: warning: 'void report_gyro()' declared 'static' but never defined -autogenerated:296: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined -autogenerated:297: warning: 'int read_num_from_serial()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/system.pde:448: warning: 'void set_failsafe(boolean)' defined but not used -autogenerated:311: warning: 'void init_optflow()' declared 'static' but never defined -autogenerated:319: warning: 'void fake_out_gps()' declared 'static' but never defined +autogenerated:208: warning: 'void heli_init_swash()' declared 'static' but never defined +autogenerated:209: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined +autogenerated:210: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined +autogenerated:233: warning: 'void debug_motors()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used +autogenerated:252: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined +autogenerated:253: warning: 'long int cross_track_test()' declared 'static' but never defined +autogenerated:254: warning: 'void reset_crosstrack()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/radio.pde:129: warning: 'void throttle_failsafe(uint16_t)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/radio.pde:186: warning: 'void trim_yaw()' defined but not used +autogenerated:266: warning: 'void readCommands()' declared 'static' but never defined +autogenerated:267: warning: 'void parseCommand(char*)' declared 'static' but never defined +autogenerated:268: warning: 'void ReadSCP1000()' declared 'static' but never defined +autogenerated:269: warning: 'void init_barometer()' declared 'static' but never defined +autogenerated:270: warning: 'long int read_baro_filtered()' declared 'static' but never defined +autogenerated:271: warning: 'long int read_barometer()' declared 'static' but never defined +autogenerated:272: warning: 'void read_airspeed()' declared 'static' but never defined +autogenerated:273: warning: 'void zero_airspeed()' declared 'static' but never defined +autogenerated:284: warning: 'void report_heli()' declared 'static' but never defined +autogenerated:285: warning: 'void report_gyro()' declared 'static' but never defined +autogenerated:292: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined +autogenerated:293: warning: 'int read_num_from_serial()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/system.pde:459: warning: 'void set_failsafe(boolean)' defined but not used +autogenerated:307: warning: 'void init_optflow()' declared 'static' but never defined +autogenerated:315: warning: 'void fake_out_gps()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:352: warning: 'old_altitude' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:370: warning: 'abs_pressure' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:371: warning: 'ground_pressure' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:372: warning: 'ground_temperature' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:377: warning: 'baro_alt' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:444: warning: 'undo_event' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'condition_rate' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:464: warning: 'simple_WP' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:469: warning: 'new_location' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:358: warning: 'old_altitude' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:376: warning: 'abs_pressure' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:377: warning: 'ground_pressure' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:378: warning: 'ground_temperature' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:383: warning: 'baro_alt' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'undo_event' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:456: warning: 'condition_rate' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:470: warning: 'simple_WP' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:475: warning: 'new_location' defined but not used /root/apm/ardupilot-mega/ArduCopter/test.pde:13: warning: 'int8_t test_adc(uint8_t, const Menu::arg*)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/test.pde:26: warning: 'int8_t test_baro(uint8_t, const Menu::arg*)' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(uint8_t, const Menu::arg*)' declared 'static' but never defined %% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_PI/APM_PI.o %% libraries/APM_RC/APM_RC.o @@ -112,6 +111,7 @@ In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_Optic %% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o %% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o %% libraries/AP_RangeFinder/RangeFinder.o +%% libraries/AP_Relay/AP_Relay.o %% libraries/DataFlash/DataFlash.o In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.size.txt index c7af4acd1d..7ea940be66 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.size.txt @@ -36,12 +36,12 @@ 00000001 b yaw_mode 00000001 b GPS_light 00000001 b do_simple -00000001 b loop_step 00000001 b trim_flag 00000001 b dancing_light()::step 00000001 b read_control_switch()::switch_debouncer 00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav 00000001 B mavdelay +00000001 B relay 00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char) 00000002 b climb_rate 00000002 b loiter_sum @@ -50,14 +50,19 @@ 00000002 b event_repeat 00000002 b loiter_total 00000002 b nav_throttle +00000002 b x_rate_error +00000002 b y_rate_error 00000002 b altitude_rate 00000002 b gps_fix_count 00000002 b velocity_land +00000002 b x_actual_speed +00000002 b y_actual_speed 00000002 b loiter_time_max 00000002 b command_yaw_time 00000002 b event_undo_value 00000002 b command_yaw_speed 00000002 b auto_level_counter +00000002 b waypoint_speed_gov 00000002 b superslow_loopCounter 00000002 r comma 00000002 b g_gps @@ -75,10 +80,6 @@ 00000002 r test_wp(unsigned char, Menu::arg const*)::__c 00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c 00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c -00000002 B x_actual_speed -00000002 B x_rate_error -00000002 B y_actual_speed -00000002 B y_rate_error 00000003 r select_logs(unsigned char, Menu::arg const*)::__c 00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c 00000003 r print_enabled(unsigned char)::__c @@ -106,7 +107,6 @@ 00000004 b fast_loopTimer 00000004 b perf_mon_timer 00000004 b target_bearing -00000004 b throttle_timer 00000004 d battery_voltage 00000004 b command_yaw_end 00000004 b condition_start @@ -251,6 +251,7 @@ 00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c @@ -262,7 +263,6 @@ 0000000a r print_log_menu()::__c 0000000a r Log_Read_Startup()::__c 0000000a r test_wp(unsigned char, Menu::arg const*)::__c -0000000a r test_mag(unsigned char, Menu::arg const*)::__c 0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c @@ -342,7 +342,6 @@ 0000000f r report_version()::__c 0000000f r report_batt_monitor()::__c 0000000f r test_imu(unsigned char, Menu::arg const*)::__c -00000010 r flight_mode_strings 00000010 r planner_menu_commands 00000010 b motor_out 00000010 W AP_VarT::cast_to_float() const @@ -355,6 +354,7 @@ 00000012 B Serial 00000012 B Serial1 00000012 B Serial3 +00000012 r flight_mode_strings 00000012 W AP_Float16::~AP_Float16() 00000012 W AP_VarS >::~AP_VarS() 00000012 W AP_VarS >::~AP_VarS() @@ -397,7 +397,6 @@ 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001d r Log_Read_Attitude()::__c 0000001e r Log_Read_Optflow()::__c -0000001f r test_mag(unsigned char, Menu::arg const*)::__c 00000020 r test_current(unsigned char, Menu::arg const*)::__c 00000020 t byte_swap_4 00000021 r print_log_menu()::__c @@ -423,7 +422,6 @@ 00000026 t print_hit_enter() 00000026 t Log_Read_Startup() 00000026 r Log_Read_Control_Tuning()::__c -00000027 r test_xbee(unsigned char, Menu::arg const*)::__c 00000028 t test_battery(unsigned char, Menu::arg const*) 00000028 t main_menu_help(unsigned char, Menu::arg const*) 00000028 t help_log(unsigned char, Menu::arg const*) @@ -489,7 +487,6 @@ 0000005e T GCS_MAVLINK::_count_parameters() 00000064 t print_gyro_offsets() 00000064 t print_accel_offsets() -00000064 t test_xbee(unsigned char, Menu::arg const*) 00000064 t mavlink_msg_param_value_send 00000068 t zero_eeprom() 00000068 t find_last_log_page(int) @@ -528,15 +525,15 @@ 000000aa t Log_Read_Nav_Tuning() 000000ab B compass 000000ae t report_frame() +000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b2 t erase_logs(unsigned char, Menu::arg const*) -000000b4 t test_relay(unsigned char, Menu::arg const*) 000000b4 t planner_gcs(unsigned char, Menu::arg const*) 000000b6 t get_log_boundaries(unsigned char, int&, int&) +000000be t update_events() 000000c2 t setup_compass(unsigned char, Menu::arg const*) 000000c2 t send_radio_out(mavlink_channel_t) 000000c2 t Log_Read_Attitude() 000000c4 t get_distance(Location*, Location*) -000000c4 t update_events() 000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c 000000c6 t test_eedump(unsigned char, Menu::arg const*) 000000c6 t send_radio_in(mavlink_channel_t) @@ -547,6 +544,7 @@ 000000d2 t print_switch(unsigned char, unsigned char, bool) 000000d4 t Log_Read(int, int) 000000d8 t test_radio(unsigned char, Menu::arg const*) +000000e0 r test_menu_commands 000000e0 r setup_menu_commands 000000e4 t test_radio_pwm(unsigned char, Menu::arg const*) 000000e4 t Log_Read_Optflow() @@ -555,12 +553,11 @@ 000000ea t Log_Read_Control_Tuning() 000000ee t report_batt_monitor() 000000f6 t Log_Read_Cmd() -000000fa t calc_nav_pitch_roll() -00000100 r test_menu_commands +000000fa t calc_loiter_pitch_roll() 0000010a t test_gps(unsigned char, Menu::arg const*) 0000010c t test_current(unsigned char, Menu::arg const*) -0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 0000010e t send_servo_out(mavlink_channel_t) +0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 00000112 t send_extended_status1(mavlink_channel_t, unsigned int) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) @@ -569,10 +566,10 @@ 0000011c t get_command_with_index(int) 00000130 t report_compass() 00000132 t arm_motors() -00000132 t set_next_WP(Location*) 00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long) 00000138 t get_stabilize_roll(long) 00000138 t get_stabilize_pitch(long) +0000013a t set_next_WP(Location*) 00000148 t Log_Read_GPS() 00000152 T GCS_MAVLINK::update() 00000158 t update_commands() @@ -582,8 +579,7 @@ 00000166 t select_logs(unsigned char, Menu::arg const*) 00000166 t send_vfr_hud(mavlink_channel_t) 0000016e t send_attitude(mavlink_channel_t) -00000170 t test_mag(unsigned char, Menu::arg const*) -00000188 t test_imu(unsigned char, Menu::arg const*) +00000184 t test_imu(unsigned char, Menu::arg const*) 00000198 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int) 000001a8 t print_radio_values() 000001c8 t setup_motors(unsigned char, Menu::arg const*) @@ -592,22 +588,22 @@ 000001e4 t setup_flightmodes(unsigned char, Menu::arg const*) 000001ea t init_home() 000001ea T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) -00000206 t set_mode(unsigned char) 00000220 t test_wp(unsigned char, Menu::arg const*) 00000228 t setup_radio(unsigned char, Menu::arg const*) +00000228 t set_mode(unsigned char) 0000022a t send_gps_raw(mavlink_channel_t) -000002ea t tuning() -00000354 t calc_nav_rate(int, int, int, int) +00000242 t calc_loiter(int, int) +00000330 t tuning() 00000384 t print_log_menu() +0000039a T update_throttle_mode() 000003a0 t read_battery() -000003ae T update_throttle_mode() 00000410 T update_yaw_mode() 0000046e T update_roll_pitch_mode() -00000580 t __static_initialization_and_destruction_0(int, int) -000005d6 t init_ardupilot() -000006e6 t update_nav_wp() -000007ea b g -00000874 t process_next_command() -00000894 W Parameters::Parameters() +00000588 t __static_initialization_and_destruction_0(int, int) +000005de t init_ardupilot() +000006fa t update_nav_wp() +00000824 b g +0000086a t process_next_command() +000008f4 W Parameters::Parameters() 000014f2 T GCS_MAVLINK::handleMessage(__mavlink_message*) -000015c0 T loop +000015ac T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.build.log index 4f632afe15..7110a3e77f 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.build.log @@ -3,19 +3,18 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition -In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:76: +In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77: /root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()': -/root/apm/ardupilot-mega/ArduCopter/Parameters.h:387: warning: overflow in implicit constant conversion +/root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_loiter_turns()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:301: warning: statement has no effect +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:302: warning: statement has no effect /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_nav_wp()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:412: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:413: warning: comparison between signed and unsigned integer expressions /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_loiter_time()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:439: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:440: warning: comparison between signed and unsigned integer expressions /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_jump()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:652: warning: unused variable 'temp' +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:653: warning: unused variable 'temp' autogenerated: At global scope: -autogenerated:31: warning: 'int alt_hold_velocity()' declared 'static' but never defined autogenerated:83: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined autogenerated:84: warning: 'void send_message(byte)' declared 'static' but never defined autogenerated:85: warning: 'void send_message(byte, long int)' declared 'static' but never defined @@ -33,48 +32,48 @@ autogenerated:138: warning: 'void Log_Write_Control_Tuning()' declared 'static' /root/apm/ardupilot-mega/ArduCopter/Log.pde:738: warning: 'void Log_Write_Attitude()' defined but not used autogenerated:146: warning: 'void decrement_WP_index()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:431: warning: 'bool verify_loiter_unlim()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used /root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used -autogenerated:211: warning: 'void heli_init_swash()' declared 'static' but never defined -autogenerated:212: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined -autogenerated:213: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined -autogenerated:236: warning: 'void debug_motors()' declared 'static' but never defined -autogenerated:252: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/navigation.pde:208: warning: 'int get_loiter_angle()' defined but not used -autogenerated:256: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined -autogenerated:257: warning: 'long int cross_track_test()' declared 'static' but never defined -autogenerated:258: warning: 'void reset_crosstrack()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/navigation.pde:273: warning: 'long int get_altitude_above_home()' defined but not used -/root/apm/ardupilot-mega/ArduCopter/navigation.pde:294: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used -/root/apm/ardupilot-mega/ArduCopter/radio.pde:131: warning: 'void throttle_failsafe(uint16_t)' defined but not used -/root/apm/ardupilot-mega/ArduCopter/radio.pde:188: warning: 'void trim_yaw()' defined but not used -autogenerated:270: warning: 'void readCommands()' declared 'static' but never defined -autogenerated:271: warning: 'void parseCommand(char*)' declared 'static' but never defined -autogenerated:272: warning: 'void ReadSCP1000()' declared 'static' but never defined -autogenerated:273: warning: 'void init_barometer()' declared 'static' but never defined -autogenerated:274: warning: 'long int read_baro_filtered()' declared 'static' but never defined -autogenerated:275: warning: 'long int read_barometer()' declared 'static' but never defined -autogenerated:276: warning: 'void read_airspeed()' declared 'static' but never defined -autogenerated:277: warning: 'void zero_airspeed()' declared 'static' but never defined -autogenerated:288: warning: 'void report_heli()' declared 'static' but never defined -autogenerated:289: warning: 'void report_gyro()' declared 'static' but never defined -autogenerated:296: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined -autogenerated:297: warning: 'int read_num_from_serial()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/system.pde:448: warning: 'void set_failsafe(boolean)' defined but not used -autogenerated:311: warning: 'void init_optflow()' declared 'static' but never defined -autogenerated:319: warning: 'void fake_out_gps()' declared 'static' but never defined +autogenerated:208: warning: 'void heli_init_swash()' declared 'static' but never defined +autogenerated:209: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined +autogenerated:210: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined +autogenerated:233: warning: 'void debug_motors()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used +autogenerated:252: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined +autogenerated:253: warning: 'long int cross_track_test()' declared 'static' but never defined +autogenerated:254: warning: 'void reset_crosstrack()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/radio.pde:129: warning: 'void throttle_failsafe(uint16_t)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/radio.pde:186: warning: 'void trim_yaw()' defined but not used +autogenerated:266: warning: 'void readCommands()' declared 'static' but never defined +autogenerated:267: warning: 'void parseCommand(char*)' declared 'static' but never defined +autogenerated:268: warning: 'void ReadSCP1000()' declared 'static' but never defined +autogenerated:269: warning: 'void init_barometer()' declared 'static' but never defined +autogenerated:270: warning: 'long int read_baro_filtered()' declared 'static' but never defined +autogenerated:271: warning: 'long int read_barometer()' declared 'static' but never defined +autogenerated:272: warning: 'void read_airspeed()' declared 'static' but never defined +autogenerated:273: warning: 'void zero_airspeed()' declared 'static' but never defined +autogenerated:284: warning: 'void report_heli()' declared 'static' but never defined +autogenerated:285: warning: 'void report_gyro()' declared 'static' but never defined +autogenerated:292: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined +autogenerated:293: warning: 'int read_num_from_serial()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/system.pde:459: warning: 'void set_failsafe(boolean)' defined but not used +autogenerated:307: warning: 'void init_optflow()' declared 'static' but never defined +autogenerated:315: warning: 'void fake_out_gps()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:352: warning: 'old_altitude' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:370: warning: 'abs_pressure' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:371: warning: 'ground_pressure' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:372: warning: 'ground_temperature' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:377: warning: 'baro_alt' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:444: warning: 'undo_event' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'condition_rate' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:464: warning: 'simple_WP' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:469: warning: 'new_location' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:358: warning: 'old_altitude' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:376: warning: 'abs_pressure' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:377: warning: 'ground_pressure' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:378: warning: 'ground_temperature' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:383: warning: 'baro_alt' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'undo_event' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:456: warning: 'condition_rate' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:470: warning: 'simple_WP' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:475: warning: 'new_location' defined but not used /root/apm/ardupilot-mega/ArduCopter/test.pde:13: warning: 'int8_t test_adc(uint8_t, const Menu::arg*)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/test.pde:26: warning: 'int8_t test_baro(uint8_t, const Menu::arg*)' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(uint8_t, const Menu::arg*)' declared 'static' but never defined %% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_PI/APM_PI.o %% libraries/APM_RC/APM_RC.o @@ -112,6 +111,7 @@ In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_Optic %% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o %% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o %% libraries/AP_RangeFinder/RangeFinder.o +%% libraries/AP_Relay/AP_Relay.o %% libraries/DataFlash/DataFlash.o In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.size.txt index 5802bfb15a..c91355ace0 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.size.txt @@ -36,12 +36,12 @@ 00000001 b yaw_mode 00000001 b GPS_light 00000001 b do_simple -00000001 b loop_step 00000001 b trim_flag 00000001 b dancing_light()::step 00000001 b read_control_switch()::switch_debouncer 00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav 00000001 B mavdelay +00000001 B relay 00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char) 00000002 b climb_rate 00000002 b loiter_sum @@ -50,14 +50,19 @@ 00000002 b event_repeat 00000002 b loiter_total 00000002 b nav_throttle +00000002 b x_rate_error +00000002 b y_rate_error 00000002 b altitude_rate 00000002 b gps_fix_count 00000002 b velocity_land +00000002 b x_actual_speed +00000002 b y_actual_speed 00000002 b loiter_time_max 00000002 b command_yaw_time 00000002 b event_undo_value 00000002 b command_yaw_speed 00000002 b auto_level_counter +00000002 b waypoint_speed_gov 00000002 b superslow_loopCounter 00000002 r comma 00000002 b g_gps @@ -75,10 +80,6 @@ 00000002 r test_wp(unsigned char, Menu::arg const*)::__c 00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c 00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c -00000002 B x_actual_speed -00000002 B x_rate_error -00000002 B y_actual_speed -00000002 B y_rate_error 00000003 r select_logs(unsigned char, Menu::arg const*)::__c 00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c 00000003 r print_enabled(unsigned char)::__c @@ -106,7 +107,6 @@ 00000004 b fast_loopTimer 00000004 b perf_mon_timer 00000004 b target_bearing -00000004 b throttle_timer 00000004 d battery_voltage 00000004 b command_yaw_end 00000004 b condition_start @@ -251,6 +251,7 @@ 00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c @@ -262,7 +263,6 @@ 0000000a r print_log_menu()::__c 0000000a r Log_Read_Startup()::__c 0000000a r test_wp(unsigned char, Menu::arg const*)::__c -0000000a r test_mag(unsigned char, Menu::arg const*)::__c 0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c @@ -342,7 +342,6 @@ 0000000f r report_version()::__c 0000000f r report_batt_monitor()::__c 0000000f r test_imu(unsigned char, Menu::arg const*)::__c -00000010 r flight_mode_strings 00000010 r planner_menu_commands 00000010 b motor_out 00000010 W AP_VarT::cast_to_float() const @@ -355,6 +354,7 @@ 00000012 B Serial 00000012 B Serial1 00000012 B Serial3 +00000012 r flight_mode_strings 00000012 W AP_Float16::~AP_Float16() 00000012 W AP_VarS >::~AP_VarS() 00000012 W AP_VarS >::~AP_VarS() @@ -397,7 +397,6 @@ 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001d r Log_Read_Attitude()::__c 0000001e r Log_Read_Optflow()::__c -0000001f r test_mag(unsigned char, Menu::arg const*)::__c 00000020 r test_current(unsigned char, Menu::arg const*)::__c 00000020 t byte_swap_4 00000021 r print_log_menu()::__c @@ -423,7 +422,6 @@ 00000026 t print_hit_enter() 00000026 t Log_Read_Startup() 00000026 r Log_Read_Control_Tuning()::__c -00000027 r test_xbee(unsigned char, Menu::arg const*)::__c 00000028 t test_battery(unsigned char, Menu::arg const*) 00000028 t main_menu_help(unsigned char, Menu::arg const*) 00000028 t help_log(unsigned char, Menu::arg const*) @@ -489,7 +487,6 @@ 0000005e T GCS_MAVLINK::_count_parameters() 00000064 t print_gyro_offsets() 00000064 t print_accel_offsets() -00000064 t test_xbee(unsigned char, Menu::arg const*) 00000064 t mavlink_msg_param_value_send 00000068 t zero_eeprom() 00000068 t find_last_log_page(int) @@ -528,16 +525,16 @@ 000000aa t Log_Read_Nav_Tuning() 000000ab B compass 000000ae t report_frame() +000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b2 t erase_logs(unsigned char, Menu::arg const*) -000000b4 t test_relay(unsigned char, Menu::arg const*) 000000b4 t planner_gcs(unsigned char, Menu::arg const*) 000000b6 t get_log_boundaries(unsigned char, int&, int&) +000000be t update_events() 000000c2 t test_eedump(unsigned char, Menu::arg const*) 000000c2 t setup_compass(unsigned char, Menu::arg const*) 000000c2 t send_radio_out(mavlink_channel_t) 000000c2 t Log_Read_Attitude() 000000c4 t get_distance(Location*, Location*) -000000c4 t update_events() 000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c 000000c6 t send_radio_in(mavlink_channel_t) 000000c6 t Log_Read_Performance() @@ -547,6 +544,7 @@ 000000d0 t print_switch(unsigned char, unsigned char, bool) 000000d4 t Log_Read(int, int) 000000d8 t test_radio(unsigned char, Menu::arg const*) +000000e0 r test_menu_commands 000000e0 r setup_menu_commands 000000e4 t test_radio_pwm(unsigned char, Menu::arg const*) 000000e4 t Log_Read_Optflow() @@ -555,12 +553,11 @@ 000000ea t Log_Read_Control_Tuning() 000000ee t report_batt_monitor() 000000f6 t Log_Read_Cmd() -000000fa t calc_nav_pitch_roll() -00000100 r test_menu_commands +000000fa t calc_loiter_pitch_roll() 0000010a t test_gps(unsigned char, Menu::arg const*) 0000010c t test_current(unsigned char, Menu::arg const*) -0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 0000010e t send_servo_out(mavlink_channel_t) +0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 00000112 t send_extended_status1(mavlink_channel_t, unsigned int) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) @@ -569,10 +566,10 @@ 0000011c t get_command_with_index(int) 00000130 t report_compass() 00000132 t arm_motors() -00000132 t set_next_WP(Location*) 00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long) 00000138 t get_stabilize_roll(long) 00000138 t get_stabilize_pitch(long) +0000013a t set_next_WP(Location*) 00000148 t Log_Read_GPS() 00000152 T GCS_MAVLINK::update() 00000158 t update_commands() @@ -582,8 +579,7 @@ 00000166 t select_logs(unsigned char, Menu::arg const*) 00000166 t send_vfr_hud(mavlink_channel_t) 0000016e t send_attitude(mavlink_channel_t) -00000170 t test_mag(unsigned char, Menu::arg const*) -00000188 t test_imu(unsigned char, Menu::arg const*) +00000184 t test_imu(unsigned char, Menu::arg const*) 00000198 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int) 000001a8 t print_radio_values() 000001c8 t setup_motors(unsigned char, Menu::arg const*) @@ -592,22 +588,22 @@ 000001e4 t setup_flightmodes(unsigned char, Menu::arg const*) 000001ea t init_home() 000001ea T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) -00000206 t set_mode(unsigned char) 0000021c t test_wp(unsigned char, Menu::arg const*) 00000228 t setup_radio(unsigned char, Menu::arg const*) +00000228 t set_mode(unsigned char) 0000022a t send_gps_raw(mavlink_channel_t) -000002ea t tuning() -00000354 t calc_nav_rate(int, int, int, int) +00000242 t calc_loiter(int, int) +00000330 t tuning() 00000382 t print_log_menu() +0000039a T update_throttle_mode() 000003a0 t read_battery() -000003ae T update_throttle_mode() 00000410 T update_yaw_mode() 0000046e T update_roll_pitch_mode() -00000580 t __static_initialization_and_destruction_0(int, int) -000005d6 t init_ardupilot() -000006e6 t update_nav_wp() -000007ea b g -00000874 t process_next_command() -00000894 W Parameters::Parameters() +00000588 t __static_initialization_and_destruction_0(int, int) +000005de t init_ardupilot() +000006fa t update_nav_wp() +00000824 b g +0000086a t process_next_command() +000008f4 W Parameters::Parameters() 000014f2 T GCS_MAVLINK::handleMessage(__mavlink_message*) -000015be T loop +000015aa T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.build.log index 51603ba231..4798c845b1 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.build.log @@ -3,19 +3,18 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition -In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:76: +In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77: /root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()': -/root/apm/ardupilot-mega/ArduCopter/Parameters.h:387: warning: overflow in implicit constant conversion +/root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_loiter_turns()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:301: warning: statement has no effect +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:302: warning: statement has no effect /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_nav_wp()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:412: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:413: warning: comparison between signed and unsigned integer expressions /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_loiter_time()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:439: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:440: warning: comparison between signed and unsigned integer expressions /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_jump()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:652: warning: unused variable 'temp' +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:653: warning: unused variable 'temp' autogenerated: At global scope: -autogenerated:31: warning: 'int alt_hold_velocity()' declared 'static' but never defined autogenerated:83: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined autogenerated:84: warning: 'void send_message(byte)' declared 'static' but never defined autogenerated:85: warning: 'void send_message(byte, long int)' declared 'static' but never defined @@ -30,39 +29,39 @@ autogenerated:67: warning: 'long int convert_to_dec(float)' declared 'static' bu autogenerated:136: warning: 'void Log_Write_Optflow()' declared 'static' but never defined autogenerated:146: warning: 'void decrement_WP_index()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:431: warning: 'bool verify_loiter_unlim()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used /root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used -autogenerated:211: warning: 'void heli_init_swash()' declared 'static' but never defined -autogenerated:212: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined -autogenerated:213: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined -autogenerated:236: warning: 'void debug_motors()' declared 'static' but never defined -autogenerated:252: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/navigation.pde:208: warning: 'int get_loiter_angle()' defined but not used -autogenerated:256: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined -autogenerated:257: warning: 'long int cross_track_test()' declared 'static' but never defined -autogenerated:258: warning: 'void reset_crosstrack()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/navigation.pde:273: warning: 'long int get_altitude_above_home()' defined but not used -/root/apm/ardupilot-mega/ArduCopter/navigation.pde:294: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used -/root/apm/ardupilot-mega/ArduCopter/radio.pde:131: warning: 'void throttle_failsafe(uint16_t)' defined but not used -/root/apm/ardupilot-mega/ArduCopter/radio.pde:188: warning: 'void trim_yaw()' defined but not used -autogenerated:270: warning: 'void readCommands()' declared 'static' but never defined -autogenerated:271: warning: 'void parseCommand(char*)' declared 'static' but never defined +autogenerated:208: warning: 'void heli_init_swash()' declared 'static' but never defined +autogenerated:209: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined +autogenerated:210: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined +autogenerated:233: warning: 'void debug_motors()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used +autogenerated:252: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined +autogenerated:253: warning: 'long int cross_track_test()' declared 'static' but never defined +autogenerated:254: warning: 'void reset_crosstrack()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/radio.pde:129: warning: 'void throttle_failsafe(uint16_t)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/radio.pde:186: warning: 'void trim_yaw()' defined but not used +autogenerated:266: warning: 'void readCommands()' declared 'static' but never defined +autogenerated:267: warning: 'void parseCommand(char*)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used -autogenerated:274: warning: 'long int read_baro_filtered()' declared 'static' but never defined +autogenerated:270: warning: 'long int read_baro_filtered()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used /root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used -autogenerated:288: warning: 'void report_heli()' declared 'static' but never defined -autogenerated:289: warning: 'void report_gyro()' declared 'static' but never defined -autogenerated:296: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined -autogenerated:297: warning: 'int read_num_from_serial()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/system.pde:448: warning: 'void set_failsafe(boolean)' defined but not used -autogenerated:311: warning: 'void init_optflow()' declared 'static' but never defined -autogenerated:319: warning: 'void fake_out_gps()' declared 'static' but never defined +autogenerated:284: warning: 'void report_heli()' declared 'static' but never defined +autogenerated:285: warning: 'void report_gyro()' declared 'static' but never defined +autogenerated:292: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined +autogenerated:293: warning: 'int read_num_from_serial()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/system.pde:459: warning: 'void set_failsafe(boolean)' defined but not used +autogenerated:307: warning: 'void init_optflow()' declared 'static' but never defined +autogenerated:315: warning: 'void fake_out_gps()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:444: warning: 'undo_event' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'condition_rate' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:464: warning: 'simple_WP' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:469: warning: 'new_location' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'undo_event' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:456: warning: 'condition_rate' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:470: warning: 'simple_WP' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:475: warning: 'new_location' defined but not used +/root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(uint8_t, const Menu::arg*)' declared 'static' but never defined %% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_PI/APM_PI.o %% libraries/APM_RC/APM_RC.o @@ -100,6 +99,7 @@ In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_Optic %% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o %% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o %% libraries/AP_RangeFinder/RangeFinder.o +%% libraries/AP_Relay/AP_Relay.o %% libraries/DataFlash/DataFlash.o In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.size.txt index 4ffeed7005..ca35f8a250 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.size.txt @@ -36,12 +36,12 @@ 00000001 b yaw_mode 00000001 b GPS_light 00000001 b do_simple -00000001 b loop_step 00000001 b trim_flag 00000001 b dancing_light()::step 00000001 b read_control_switch()::switch_debouncer 00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav 00000001 B mavdelay +00000001 B relay 00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char) 00000002 b climb_rate 00000002 b loiter_sum @@ -50,15 +50,20 @@ 00000002 b event_repeat 00000002 b loiter_total 00000002 b nav_throttle +00000002 b x_rate_error +00000002 b y_rate_error 00000002 b altitude_rate 00000002 b gps_fix_count 00000002 b velocity_land +00000002 b x_actual_speed +00000002 b y_actual_speed 00000002 b loiter_time_max 00000002 b command_yaw_time 00000002 b event_undo_value 00000002 b command_yaw_speed 00000002 b auto_level_counter 00000002 b ground_temperature +00000002 b waypoint_speed_gov 00000002 b superslow_loopCounter 00000002 r comma 00000002 b g_gps @@ -74,11 +79,6 @@ 00000002 r test_wp(unsigned char, Menu::arg const*)::__c 00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c 00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c -00000002 B adc -00000002 B x_actual_speed -00000002 B x_rate_error -00000002 B y_actual_speed -00000002 B y_rate_error 00000003 r select_logs(unsigned char, Menu::arg const*)::__c 00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c 00000003 r print_enabled(unsigned char)::__c @@ -107,7 +107,6 @@ 00000004 b fast_loopTimer 00000004 b perf_mon_timer 00000004 b target_bearing -00000004 b throttle_timer 00000004 d battery_voltage 00000004 b command_yaw_end 00000004 b condition_start @@ -254,6 +253,7 @@ 00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c @@ -265,7 +265,6 @@ 0000000a r print_log_menu()::__c 0000000a r Log_Read_Startup()::__c 0000000a r test_wp(unsigned char, Menu::arg const*)::__c -0000000a r test_mag(unsigned char, Menu::arg const*)::__c 0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c @@ -345,7 +344,6 @@ 0000000f r report_batt_monitor()::__c 0000000f r test_imu(unsigned char, Menu::arg const*)::__c 0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c -00000010 r flight_mode_strings 00000010 r planner_menu_commands 00000010 b motor_out 00000010 W AP_VarT::cast_to_float() const @@ -357,6 +355,7 @@ 00000012 B Serial 00000012 B Serial1 00000012 B Serial3 +00000012 r flight_mode_strings 00000012 W AP_Float16::~AP_Float16() 00000012 W AP_VarA::~AP_VarA() 00000012 W AP_VarS >::~AP_VarS() @@ -401,7 +400,6 @@ 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001d r Log_Read_Attitude()::__c 0000001e r Log_Read_Optflow()::__c -0000001f r test_mag(unsigned char, Menu::arg const*)::__c 00000020 r test_current(unsigned char, Menu::arg const*)::__c 00000020 t byte_swap_4 00000021 r print_log_menu()::__c @@ -429,7 +427,6 @@ 00000026 t print_hit_enter() 00000026 t Log_Read_Startup() 00000026 r Log_Read_Control_Tuning()::__c -00000027 r test_xbee(unsigned char, Menu::arg const*)::__c 00000028 t test_battery(unsigned char, Menu::arg const*) 00000028 t main_menu_help(unsigned char, Menu::arg const*) 00000028 t help_log(unsigned char, Menu::arg const*) @@ -467,6 +464,7 @@ 0000003e W AP_VarT::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char) 00000040 t read_AHRS() 00000040 W AP_Float16::unserialize(void*, unsigned int) +00000040 B adc 00000040 t byte_swap_8 00000042 t report_sonar() 00000044 t setup_show(unsigned char, Menu::arg const*) @@ -492,7 +490,6 @@ 0000005c t setup_esc(unsigned char, Menu::arg const*) 0000005e t update_GPS_light() 0000005e T GCS_MAVLINK::_count_parameters() -00000064 t test_xbee(unsigned char, Menu::arg const*) 00000064 B barometer 00000064 t mavlink_msg_param_value_send 00000068 t zero_eeprom() @@ -535,16 +532,16 @@ 000000aa t test_sonar(unsigned char, Menu::arg const*) 000000aa t Log_Read_Nav_Tuning() 000000ae t report_frame() +000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b2 t erase_logs(unsigned char, Menu::arg const*) -000000b4 t test_relay(unsigned char, Menu::arg const*) 000000b4 t planner_gcs(unsigned char, Menu::arg const*) 000000b6 t get_log_boundaries(unsigned char, int&, int&) 000000b7 B compass +000000be t update_events() 000000c2 t setup_compass(unsigned char, Menu::arg const*) 000000c2 t send_radio_out(mavlink_channel_t) 000000c2 t Log_Read_Attitude() 000000c4 t get_distance(Location*, Location*) -000000c4 t update_events() 000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c 000000c6 t test_eedump(unsigned char, Menu::arg const*) 000000c6 t send_radio_in(mavlink_channel_t) @@ -567,24 +564,24 @@ 000000ea t Log_Read_Control_Tuning() 000000ee t report_batt_monitor() 000000f6 t Log_Read_Cmd() -000000fa t calc_nav_pitch_roll() +000000fa t calc_loiter_pitch_roll() +00000100 r test_menu_commands 0000010a t send_raw_imu2(mavlink_channel_t) 0000010a t test_gps(unsigned char, Menu::arg const*) 0000010c t test_current(unsigned char, Menu::arg const*) -0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 0000010e t send_servo_out(mavlink_channel_t) -00000112 t send_extended_status1(mavlink_channel_t, unsigned int) +0000010e t send_extended_status1(mavlink_channel_t, unsigned int) +0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000118 t set_command_with_index(Location, int) 00000118 T GCS_MAVLINK::_queued_send() 0000011c t get_command_with_index(int) -00000120 r test_menu_commands 00000130 t report_compass() -00000132 t set_next_WP(Location*) 00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long) 00000138 t get_stabilize_roll(long) 00000138 t get_stabilize_pitch(long) +0000013a t set_next_WP(Location*) 00000148 t Log_Read_GPS() 00000152 T GCS_MAVLINK::update() 00000158 t update_commands() @@ -593,9 +590,8 @@ 00000160 t send_nav_controller_output(mavlink_channel_t) 00000166 t select_logs(unsigned char, Menu::arg const*) 00000166 t send_vfr_hud(mavlink_channel_t) +0000016c t test_imu(unsigned char, Menu::arg const*) 0000016e t send_attitude(mavlink_channel_t) -00000170 t test_imu(unsigned char, Menu::arg const*) -00000170 t test_mag(unsigned char, Menu::arg const*) 000001a8 t print_radio_values() 000001be t arm_motors() 000001be T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) @@ -605,24 +601,24 @@ 000001d6 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int) 000001e4 t setup_flightmodes(unsigned char, Menu::arg const*) 000001ea t init_home() -00000206 t set_mode(unsigned char) 0000021a t send_raw_imu1(mavlink_channel_t) 00000220 t test_wp(unsigned char, Menu::arg const*) 00000228 t setup_radio(unsigned char, Menu::arg const*) +00000228 t set_mode(unsigned char) 0000022a t send_gps_raw(mavlink_channel_t) +00000242 t calc_loiter(int, int) 00000268 t send_raw_imu3(mavlink_channel_t) -000002ea t tuning() -00000354 t calc_nav_rate(int, int, int, int) +00000330 t tuning() 00000384 t print_log_menu() +0000039a T update_throttle_mode() 000003a0 t read_battery() -000003ae T update_throttle_mode() 00000410 T update_yaw_mode() 0000046e T update_roll_pitch_mode() -000005ee t init_ardupilot() -000006e6 t update_nav_wp() -000007b0 t __static_initialization_and_destruction_0(int, int) -000007ea b g -00000874 t process_next_command() -00000894 W Parameters::Parameters() +000005fc t init_ardupilot() +000006fa t update_nav_wp() +000007b8 t __static_initialization_and_destruction_0(int, int) +00000824 b g +0000086a t process_next_command() +000008f4 W Parameters::Parameters() 00001228 T GCS_MAVLINK::handleMessage(__mavlink_message*) -00001b38 T loop +00001b26 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.build.log index 51603ba231..4798c845b1 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.build.log @@ -3,19 +3,18 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition -In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:76: +In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77: /root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()': -/root/apm/ardupilot-mega/ArduCopter/Parameters.h:387: warning: overflow in implicit constant conversion +/root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_loiter_turns()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:301: warning: statement has no effect +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:302: warning: statement has no effect /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_nav_wp()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:412: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:413: warning: comparison between signed and unsigned integer expressions /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_loiter_time()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:439: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:440: warning: comparison between signed and unsigned integer expressions /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_jump()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:652: warning: unused variable 'temp' +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:653: warning: unused variable 'temp' autogenerated: At global scope: -autogenerated:31: warning: 'int alt_hold_velocity()' declared 'static' but never defined autogenerated:83: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined autogenerated:84: warning: 'void send_message(byte)' declared 'static' but never defined autogenerated:85: warning: 'void send_message(byte, long int)' declared 'static' but never defined @@ -30,39 +29,39 @@ autogenerated:67: warning: 'long int convert_to_dec(float)' declared 'static' bu autogenerated:136: warning: 'void Log_Write_Optflow()' declared 'static' but never defined autogenerated:146: warning: 'void decrement_WP_index()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:431: warning: 'bool verify_loiter_unlim()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used /root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used -autogenerated:211: warning: 'void heli_init_swash()' declared 'static' but never defined -autogenerated:212: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined -autogenerated:213: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined -autogenerated:236: warning: 'void debug_motors()' declared 'static' but never defined -autogenerated:252: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/navigation.pde:208: warning: 'int get_loiter_angle()' defined but not used -autogenerated:256: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined -autogenerated:257: warning: 'long int cross_track_test()' declared 'static' but never defined -autogenerated:258: warning: 'void reset_crosstrack()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/navigation.pde:273: warning: 'long int get_altitude_above_home()' defined but not used -/root/apm/ardupilot-mega/ArduCopter/navigation.pde:294: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used -/root/apm/ardupilot-mega/ArduCopter/radio.pde:131: warning: 'void throttle_failsafe(uint16_t)' defined but not used -/root/apm/ardupilot-mega/ArduCopter/radio.pde:188: warning: 'void trim_yaw()' defined but not used -autogenerated:270: warning: 'void readCommands()' declared 'static' but never defined -autogenerated:271: warning: 'void parseCommand(char*)' declared 'static' but never defined +autogenerated:208: warning: 'void heli_init_swash()' declared 'static' but never defined +autogenerated:209: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined +autogenerated:210: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined +autogenerated:233: warning: 'void debug_motors()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used +autogenerated:252: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined +autogenerated:253: warning: 'long int cross_track_test()' declared 'static' but never defined +autogenerated:254: warning: 'void reset_crosstrack()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/radio.pde:129: warning: 'void throttle_failsafe(uint16_t)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/radio.pde:186: warning: 'void trim_yaw()' defined but not used +autogenerated:266: warning: 'void readCommands()' declared 'static' but never defined +autogenerated:267: warning: 'void parseCommand(char*)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used -autogenerated:274: warning: 'long int read_baro_filtered()' declared 'static' but never defined +autogenerated:270: warning: 'long int read_baro_filtered()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used /root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used -autogenerated:288: warning: 'void report_heli()' declared 'static' but never defined -autogenerated:289: warning: 'void report_gyro()' declared 'static' but never defined -autogenerated:296: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined -autogenerated:297: warning: 'int read_num_from_serial()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/system.pde:448: warning: 'void set_failsafe(boolean)' defined but not used -autogenerated:311: warning: 'void init_optflow()' declared 'static' but never defined -autogenerated:319: warning: 'void fake_out_gps()' declared 'static' but never defined +autogenerated:284: warning: 'void report_heli()' declared 'static' but never defined +autogenerated:285: warning: 'void report_gyro()' declared 'static' but never defined +autogenerated:292: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined +autogenerated:293: warning: 'int read_num_from_serial()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/system.pde:459: warning: 'void set_failsafe(boolean)' defined but not used +autogenerated:307: warning: 'void init_optflow()' declared 'static' but never defined +autogenerated:315: warning: 'void fake_out_gps()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:444: warning: 'undo_event' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'condition_rate' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:464: warning: 'simple_WP' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:469: warning: 'new_location' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'undo_event' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:456: warning: 'condition_rate' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:470: warning: 'simple_WP' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:475: warning: 'new_location' defined but not used +/root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(uint8_t, const Menu::arg*)' declared 'static' but never defined %% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_PI/APM_PI.o %% libraries/APM_RC/APM_RC.o @@ -100,6 +99,7 @@ In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_Optic %% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o %% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o %% libraries/AP_RangeFinder/RangeFinder.o +%% libraries/AP_Relay/AP_Relay.o %% libraries/DataFlash/DataFlash.o In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.size.txt index 29bf5162d3..b3bbaa9d5e 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.size.txt @@ -36,12 +36,12 @@ 00000001 b yaw_mode 00000001 b GPS_light 00000001 b do_simple -00000001 b loop_step 00000001 b trim_flag 00000001 b dancing_light()::step 00000001 b read_control_switch()::switch_debouncer 00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav 00000001 B mavdelay +00000001 B relay 00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char) 00000002 b climb_rate 00000002 b loiter_sum @@ -50,15 +50,20 @@ 00000002 b event_repeat 00000002 b loiter_total 00000002 b nav_throttle +00000002 b x_rate_error +00000002 b y_rate_error 00000002 b altitude_rate 00000002 b gps_fix_count 00000002 b velocity_land +00000002 b x_actual_speed +00000002 b y_actual_speed 00000002 b loiter_time_max 00000002 b command_yaw_time 00000002 b event_undo_value 00000002 b command_yaw_speed 00000002 b auto_level_counter 00000002 b ground_temperature +00000002 b waypoint_speed_gov 00000002 b superslow_loopCounter 00000002 r comma 00000002 b g_gps @@ -74,11 +79,6 @@ 00000002 r test_wp(unsigned char, Menu::arg const*)::__c 00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c 00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c -00000002 B adc -00000002 B x_actual_speed -00000002 B x_rate_error -00000002 B y_actual_speed -00000002 B y_rate_error 00000003 r select_logs(unsigned char, Menu::arg const*)::__c 00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c 00000003 r print_enabled(unsigned char)::__c @@ -107,7 +107,6 @@ 00000004 b fast_loopTimer 00000004 b perf_mon_timer 00000004 b target_bearing -00000004 b throttle_timer 00000004 d battery_voltage 00000004 b command_yaw_end 00000004 b condition_start @@ -254,6 +253,7 @@ 00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c @@ -265,7 +265,6 @@ 0000000a r print_log_menu()::__c 0000000a r Log_Read_Startup()::__c 0000000a r test_wp(unsigned char, Menu::arg const*)::__c -0000000a r test_mag(unsigned char, Menu::arg const*)::__c 0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c @@ -345,7 +344,6 @@ 0000000f r report_batt_monitor()::__c 0000000f r test_imu(unsigned char, Menu::arg const*)::__c 0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c -00000010 r flight_mode_strings 00000010 r planner_menu_commands 00000010 b motor_out 00000010 W AP_VarT::cast_to_float() const @@ -357,6 +355,7 @@ 00000012 B Serial 00000012 B Serial1 00000012 B Serial3 +00000012 r flight_mode_strings 00000012 W AP_Float16::~AP_Float16() 00000012 W AP_VarA::~AP_VarA() 00000012 W AP_VarS >::~AP_VarS() @@ -401,7 +400,6 @@ 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001d r Log_Read_Attitude()::__c 0000001e r Log_Read_Optflow()::__c -0000001f r test_mag(unsigned char, Menu::arg const*)::__c 00000020 r test_current(unsigned char, Menu::arg const*)::__c 00000020 t byte_swap_4 00000021 r print_log_menu()::__c @@ -429,7 +427,6 @@ 00000026 t print_hit_enter() 00000026 t Log_Read_Startup() 00000026 r Log_Read_Control_Tuning()::__c -00000027 r test_xbee(unsigned char, Menu::arg const*)::__c 00000028 t test_battery(unsigned char, Menu::arg const*) 00000028 t main_menu_help(unsigned char, Menu::arg const*) 00000028 t help_log(unsigned char, Menu::arg const*) @@ -467,6 +464,7 @@ 0000003e W AP_VarT::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char) 00000040 t read_AHRS() 00000040 W AP_Float16::unserialize(void*, unsigned int) +00000040 B adc 00000040 t byte_swap_8 00000042 t report_sonar() 00000044 t setup_show(unsigned char, Menu::arg const*) @@ -492,7 +490,6 @@ 0000005c t setup_esc(unsigned char, Menu::arg const*) 0000005e t update_GPS_light() 0000005e T GCS_MAVLINK::_count_parameters() -00000064 t test_xbee(unsigned char, Menu::arg const*) 00000064 B barometer 00000064 t mavlink_msg_param_value_send 00000068 t zero_eeprom() @@ -535,17 +532,17 @@ 000000a8 t test_sonar(unsigned char, Menu::arg const*) 000000aa t Log_Read_Nav_Tuning() 000000ae t report_frame() +000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b2 t erase_logs(unsigned char, Menu::arg const*) -000000b4 t test_relay(unsigned char, Menu::arg const*) 000000b4 t planner_gcs(unsigned char, Menu::arg const*) 000000b6 t get_log_boundaries(unsigned char, int&, int&) 000000b7 B compass +000000be t update_events() 000000c2 t test_eedump(unsigned char, Menu::arg const*) 000000c2 t setup_compass(unsigned char, Menu::arg const*) 000000c2 t send_radio_out(mavlink_channel_t) 000000c2 t Log_Read_Attitude() 000000c4 t get_distance(Location*, Location*) -000000c4 t update_events() 000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c 000000c6 t send_radio_in(mavlink_channel_t) 000000c6 t Log_Read_Performance() @@ -567,24 +564,24 @@ 000000ea t Log_Read_Control_Tuning() 000000ee t report_batt_monitor() 000000f6 t Log_Read_Cmd() -000000fa t calc_nav_pitch_roll() +000000fa t calc_loiter_pitch_roll() +00000100 r test_menu_commands 0000010a t send_raw_imu2(mavlink_channel_t) 0000010a t test_gps(unsigned char, Menu::arg const*) 0000010c t test_current(unsigned char, Menu::arg const*) -0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 0000010e t send_servo_out(mavlink_channel_t) -00000112 t send_extended_status1(mavlink_channel_t, unsigned int) +0000010e t send_extended_status1(mavlink_channel_t, unsigned int) +0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000118 t set_command_with_index(Location, int) 00000118 T GCS_MAVLINK::_queued_send() 0000011c t get_command_with_index(int) -00000120 r test_menu_commands 00000130 t report_compass() -00000132 t set_next_WP(Location*) 00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long) 00000138 t get_stabilize_roll(long) 00000138 t get_stabilize_pitch(long) +0000013a t set_next_WP(Location*) 00000148 t Log_Read_GPS() 00000152 T GCS_MAVLINK::update() 00000158 t update_commands() @@ -593,9 +590,8 @@ 00000160 t send_nav_controller_output(mavlink_channel_t) 00000166 t select_logs(unsigned char, Menu::arg const*) 00000166 t send_vfr_hud(mavlink_channel_t) +0000016c t test_imu(unsigned char, Menu::arg const*) 0000016e t send_attitude(mavlink_channel_t) -00000170 t test_imu(unsigned char, Menu::arg const*) -00000170 t test_mag(unsigned char, Menu::arg const*) 000001a8 t print_radio_values() 000001be t arm_motors() 000001be T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) @@ -605,24 +601,24 @@ 000001d6 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int) 000001e4 t setup_flightmodes(unsigned char, Menu::arg const*) 000001ea t init_home() -00000206 t set_mode(unsigned char) 0000021a t send_raw_imu1(mavlink_channel_t) 0000021c t test_wp(unsigned char, Menu::arg const*) 00000228 t setup_radio(unsigned char, Menu::arg const*) +00000228 t set_mode(unsigned char) 0000022a t send_gps_raw(mavlink_channel_t) +00000242 t calc_loiter(int, int) 00000268 t send_raw_imu3(mavlink_channel_t) -000002ea t tuning() -00000354 t calc_nav_rate(int, int, int, int) +00000330 t tuning() 00000382 t print_log_menu() +0000039a T update_throttle_mode() 000003a0 t read_battery() -000003ae T update_throttle_mode() 00000410 T update_yaw_mode() 0000046e T update_roll_pitch_mode() -000005ee t init_ardupilot() -000006e6 t update_nav_wp() -000007b0 t __static_initialization_and_destruction_0(int, int) -000007ea b g -00000874 t process_next_command() -00000894 W Parameters::Parameters() +000005fc t init_ardupilot() +000006fa t update_nav_wp() +000007b8 t __static_initialization_and_destruction_0(int, int) +00000824 b g +0000086a t process_next_command() +000008f4 W Parameters::Parameters() 00001228 T GCS_MAVLINK::handleMessage(__mavlink_message*) -00001b36 T loop +00001b24 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.build.log index 51603ba231..4798c845b1 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.build.log @@ -3,19 +3,18 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition -In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:76: +In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77: /root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()': -/root/apm/ardupilot-mega/ArduCopter/Parameters.h:387: warning: overflow in implicit constant conversion +/root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_loiter_turns()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:301: warning: statement has no effect +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:302: warning: statement has no effect /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_nav_wp()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:412: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:413: warning: comparison between signed and unsigned integer expressions /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_loiter_time()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:439: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:440: warning: comparison between signed and unsigned integer expressions /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_jump()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:652: warning: unused variable 'temp' +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:653: warning: unused variable 'temp' autogenerated: At global scope: -autogenerated:31: warning: 'int alt_hold_velocity()' declared 'static' but never defined autogenerated:83: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined autogenerated:84: warning: 'void send_message(byte)' declared 'static' but never defined autogenerated:85: warning: 'void send_message(byte, long int)' declared 'static' but never defined @@ -30,39 +29,39 @@ autogenerated:67: warning: 'long int convert_to_dec(float)' declared 'static' bu autogenerated:136: warning: 'void Log_Write_Optflow()' declared 'static' but never defined autogenerated:146: warning: 'void decrement_WP_index()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:431: warning: 'bool verify_loiter_unlim()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used /root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used -autogenerated:211: warning: 'void heli_init_swash()' declared 'static' but never defined -autogenerated:212: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined -autogenerated:213: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined -autogenerated:236: warning: 'void debug_motors()' declared 'static' but never defined -autogenerated:252: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/navigation.pde:208: warning: 'int get_loiter_angle()' defined but not used -autogenerated:256: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined -autogenerated:257: warning: 'long int cross_track_test()' declared 'static' but never defined -autogenerated:258: warning: 'void reset_crosstrack()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/navigation.pde:273: warning: 'long int get_altitude_above_home()' defined but not used -/root/apm/ardupilot-mega/ArduCopter/navigation.pde:294: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used -/root/apm/ardupilot-mega/ArduCopter/radio.pde:131: warning: 'void throttle_failsafe(uint16_t)' defined but not used -/root/apm/ardupilot-mega/ArduCopter/radio.pde:188: warning: 'void trim_yaw()' defined but not used -autogenerated:270: warning: 'void readCommands()' declared 'static' but never defined -autogenerated:271: warning: 'void parseCommand(char*)' declared 'static' but never defined +autogenerated:208: warning: 'void heli_init_swash()' declared 'static' but never defined +autogenerated:209: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined +autogenerated:210: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined +autogenerated:233: warning: 'void debug_motors()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used +autogenerated:252: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined +autogenerated:253: warning: 'long int cross_track_test()' declared 'static' but never defined +autogenerated:254: warning: 'void reset_crosstrack()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/radio.pde:129: warning: 'void throttle_failsafe(uint16_t)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/radio.pde:186: warning: 'void trim_yaw()' defined but not used +autogenerated:266: warning: 'void readCommands()' declared 'static' but never defined +autogenerated:267: warning: 'void parseCommand(char*)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used -autogenerated:274: warning: 'long int read_baro_filtered()' declared 'static' but never defined +autogenerated:270: warning: 'long int read_baro_filtered()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used /root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used -autogenerated:288: warning: 'void report_heli()' declared 'static' but never defined -autogenerated:289: warning: 'void report_gyro()' declared 'static' but never defined -autogenerated:296: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined -autogenerated:297: warning: 'int read_num_from_serial()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/system.pde:448: warning: 'void set_failsafe(boolean)' defined but not used -autogenerated:311: warning: 'void init_optflow()' declared 'static' but never defined -autogenerated:319: warning: 'void fake_out_gps()' declared 'static' but never defined +autogenerated:284: warning: 'void report_heli()' declared 'static' but never defined +autogenerated:285: warning: 'void report_gyro()' declared 'static' but never defined +autogenerated:292: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined +autogenerated:293: warning: 'int read_num_from_serial()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/system.pde:459: warning: 'void set_failsafe(boolean)' defined but not used +autogenerated:307: warning: 'void init_optflow()' declared 'static' but never defined +autogenerated:315: warning: 'void fake_out_gps()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:444: warning: 'undo_event' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'condition_rate' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:464: warning: 'simple_WP' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:469: warning: 'new_location' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'undo_event' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:456: warning: 'condition_rate' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:470: warning: 'simple_WP' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:475: warning: 'new_location' defined but not used +/root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(uint8_t, const Menu::arg*)' declared 'static' but never defined %% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_PI/APM_PI.o %% libraries/APM_RC/APM_RC.o @@ -100,6 +99,7 @@ In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_Optic %% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o %% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o %% libraries/AP_RangeFinder/RangeFinder.o +%% libraries/AP_Relay/AP_Relay.o %% libraries/DataFlash/DataFlash.o In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.size.txt index 84195093a9..edc5e2da21 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.size.txt @@ -36,12 +36,12 @@ 00000001 b yaw_mode 00000001 b GPS_light 00000001 b do_simple -00000001 b loop_step 00000001 b trim_flag 00000001 b dancing_light()::step 00000001 b read_control_switch()::switch_debouncer 00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav 00000001 B mavdelay +00000001 B relay 00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char) 00000002 b climb_rate 00000002 b loiter_sum @@ -50,15 +50,20 @@ 00000002 b event_repeat 00000002 b loiter_total 00000002 b nav_throttle +00000002 b x_rate_error +00000002 b y_rate_error 00000002 b altitude_rate 00000002 b gps_fix_count 00000002 b velocity_land +00000002 b x_actual_speed +00000002 b y_actual_speed 00000002 b loiter_time_max 00000002 b command_yaw_time 00000002 b event_undo_value 00000002 b command_yaw_speed 00000002 b auto_level_counter 00000002 b ground_temperature +00000002 b waypoint_speed_gov 00000002 b superslow_loopCounter 00000002 r comma 00000002 b g_gps @@ -74,11 +79,6 @@ 00000002 r test_wp(unsigned char, Menu::arg const*)::__c 00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c 00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c -00000002 B adc -00000002 B x_actual_speed -00000002 B x_rate_error -00000002 B y_actual_speed -00000002 B y_rate_error 00000003 r select_logs(unsigned char, Menu::arg const*)::__c 00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c 00000003 r print_enabled(unsigned char)::__c @@ -107,7 +107,6 @@ 00000004 b fast_loopTimer 00000004 b perf_mon_timer 00000004 b target_bearing -00000004 b throttle_timer 00000004 d battery_voltage 00000004 b command_yaw_end 00000004 b condition_start @@ -254,6 +253,7 @@ 00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c @@ -265,7 +265,6 @@ 0000000a r print_log_menu()::__c 0000000a r Log_Read_Startup()::__c 0000000a r test_wp(unsigned char, Menu::arg const*)::__c -0000000a r test_mag(unsigned char, Menu::arg const*)::__c 0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c @@ -345,7 +344,6 @@ 0000000f r report_batt_monitor()::__c 0000000f r test_imu(unsigned char, Menu::arg const*)::__c 0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c -00000010 r flight_mode_strings 00000010 r planner_menu_commands 00000010 b motor_out 00000010 W AP_VarT::cast_to_float() const @@ -357,6 +355,7 @@ 00000012 B Serial 00000012 B Serial1 00000012 B Serial3 +00000012 r flight_mode_strings 00000012 W AP_Float16::~AP_Float16() 00000012 W AP_VarA::~AP_VarA() 00000012 W AP_VarS >::~AP_VarS() @@ -401,7 +400,6 @@ 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001d r Log_Read_Attitude()::__c 0000001e r Log_Read_Optflow()::__c -0000001f r test_mag(unsigned char, Menu::arg const*)::__c 00000020 r test_current(unsigned char, Menu::arg const*)::__c 00000020 t byte_swap_4 00000021 r print_log_menu()::__c @@ -429,7 +427,6 @@ 00000026 t print_hit_enter() 00000026 t Log_Read_Startup() 00000026 r Log_Read_Control_Tuning()::__c -00000027 r test_xbee(unsigned char, Menu::arg const*)::__c 00000028 t test_battery(unsigned char, Menu::arg const*) 00000028 t main_menu_help(unsigned char, Menu::arg const*) 00000028 t help_log(unsigned char, Menu::arg const*) @@ -467,6 +464,7 @@ 0000003e W AP_VarT::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char) 00000040 t read_AHRS() 00000040 W AP_Float16::unserialize(void*, unsigned int) +00000040 B adc 00000040 t byte_swap_8 00000042 t report_sonar() 00000044 t setup_show(unsigned char, Menu::arg const*) @@ -492,7 +490,6 @@ 0000005c t setup_esc(unsigned char, Menu::arg const*) 0000005e t update_GPS_light() 0000005e T GCS_MAVLINK::_count_parameters() -00000064 t test_xbee(unsigned char, Menu::arg const*) 00000064 B barometer 00000064 t mavlink_msg_param_value_send 00000068 t zero_eeprom() @@ -535,16 +532,16 @@ 000000aa t test_sonar(unsigned char, Menu::arg const*) 000000aa t Log_Read_Nav_Tuning() 000000ae t report_frame() +000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b2 t erase_logs(unsigned char, Menu::arg const*) -000000b4 t test_relay(unsigned char, Menu::arg const*) 000000b4 t planner_gcs(unsigned char, Menu::arg const*) 000000b6 t get_log_boundaries(unsigned char, int&, int&) 000000b7 B compass +000000be t update_events() 000000c2 t setup_compass(unsigned char, Menu::arg const*) 000000c2 t send_radio_out(mavlink_channel_t) 000000c2 t Log_Read_Attitude() 000000c4 t get_distance(Location*, Location*) -000000c4 t update_events() 000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c 000000c6 t test_eedump(unsigned char, Menu::arg const*) 000000c6 t send_radio_in(mavlink_channel_t) @@ -568,24 +565,24 @@ 000000ea t Log_Read_Control_Tuning() 000000ee t report_batt_monitor() 000000f6 t Log_Read_Cmd() -000000fa t calc_nav_pitch_roll() +000000fa t calc_loiter_pitch_roll() +00000100 r test_menu_commands 0000010a t send_raw_imu2(mavlink_channel_t) 0000010a t test_gps(unsigned char, Menu::arg const*) 0000010c t test_current(unsigned char, Menu::arg const*) -0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 0000010e t send_servo_out(mavlink_channel_t) +0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 00000112 t send_extended_status1(mavlink_channel_t, unsigned int) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000118 t set_command_with_index(Location, int) 00000118 T GCS_MAVLINK::_queued_send() 0000011c t get_command_with_index(int) -00000120 r test_menu_commands 00000130 t report_compass() -00000132 t set_next_WP(Location*) 00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long) 00000138 t get_stabilize_roll(long) 00000138 t get_stabilize_pitch(long) +0000013a t set_next_WP(Location*) 00000148 t Log_Read_GPS() 00000152 T GCS_MAVLINK::update() 00000158 t update_commands() @@ -594,9 +591,8 @@ 00000160 t send_nav_controller_output(mavlink_channel_t) 00000166 t select_logs(unsigned char, Menu::arg const*) 00000166 t send_vfr_hud(mavlink_channel_t) +0000016c t test_imu(unsigned char, Menu::arg const*) 0000016e t send_attitude(mavlink_channel_t) -00000170 t test_imu(unsigned char, Menu::arg const*) -00000170 t test_mag(unsigned char, Menu::arg const*) 000001a8 t print_radio_values() 000001be t arm_motors() 000001be T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) @@ -605,24 +601,24 @@ 000001d6 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int) 000001e4 t setup_flightmodes(unsigned char, Menu::arg const*) 000001ea t init_home() -00000206 t set_mode(unsigned char) 0000021a t send_raw_imu1(mavlink_channel_t) 00000220 t test_wp(unsigned char, Menu::arg const*) 00000228 t setup_radio(unsigned char, Menu::arg const*) +00000228 t set_mode(unsigned char) 0000022a t send_gps_raw(mavlink_channel_t) +00000242 t calc_loiter(int, int) 00000268 t send_raw_imu3(mavlink_channel_t) -000002ea t tuning() -00000354 t calc_nav_rate(int, int, int, int) +00000330 t tuning() 00000384 t print_log_menu() +0000039a T update_throttle_mode() 000003a0 t read_battery() -000003ae T update_throttle_mode() 00000410 T update_yaw_mode() 0000046e T update_roll_pitch_mode() -000005ee t init_ardupilot() -000006e6 t update_nav_wp() -000007b0 t __static_initialization_and_destruction_0(int, int) -000007ea b g -00000874 t process_next_command() -00000894 W Parameters::Parameters() +000005fc t init_ardupilot() +000006fa t update_nav_wp() +000007b8 t __static_initialization_and_destruction_0(int, int) +00000824 b g +0000086a t process_next_command() +000008f4 W Parameters::Parameters() 00001228 T GCS_MAVLINK::handleMessage(__mavlink_message*) -00001a98 T loop +00001a86 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.build.log index 51603ba231..4798c845b1 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.build.log @@ -3,19 +3,18 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition -In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:76: +In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77: /root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()': -/root/apm/ardupilot-mega/ArduCopter/Parameters.h:387: warning: overflow in implicit constant conversion +/root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_loiter_turns()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:301: warning: statement has no effect +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:302: warning: statement has no effect /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_nav_wp()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:412: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:413: warning: comparison between signed and unsigned integer expressions /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_loiter_time()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:439: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:440: warning: comparison between signed and unsigned integer expressions /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_jump()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:652: warning: unused variable 'temp' +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:653: warning: unused variable 'temp' autogenerated: At global scope: -autogenerated:31: warning: 'int alt_hold_velocity()' declared 'static' but never defined autogenerated:83: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined autogenerated:84: warning: 'void send_message(byte)' declared 'static' but never defined autogenerated:85: warning: 'void send_message(byte, long int)' declared 'static' but never defined @@ -30,39 +29,39 @@ autogenerated:67: warning: 'long int convert_to_dec(float)' declared 'static' bu autogenerated:136: warning: 'void Log_Write_Optflow()' declared 'static' but never defined autogenerated:146: warning: 'void decrement_WP_index()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:431: warning: 'bool verify_loiter_unlim()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used /root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used -autogenerated:211: warning: 'void heli_init_swash()' declared 'static' but never defined -autogenerated:212: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined -autogenerated:213: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined -autogenerated:236: warning: 'void debug_motors()' declared 'static' but never defined -autogenerated:252: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/navigation.pde:208: warning: 'int get_loiter_angle()' defined but not used -autogenerated:256: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined -autogenerated:257: warning: 'long int cross_track_test()' declared 'static' but never defined -autogenerated:258: warning: 'void reset_crosstrack()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/navigation.pde:273: warning: 'long int get_altitude_above_home()' defined but not used -/root/apm/ardupilot-mega/ArduCopter/navigation.pde:294: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used -/root/apm/ardupilot-mega/ArduCopter/radio.pde:131: warning: 'void throttle_failsafe(uint16_t)' defined but not used -/root/apm/ardupilot-mega/ArduCopter/radio.pde:188: warning: 'void trim_yaw()' defined but not used -autogenerated:270: warning: 'void readCommands()' declared 'static' but never defined -autogenerated:271: warning: 'void parseCommand(char*)' declared 'static' but never defined +autogenerated:208: warning: 'void heli_init_swash()' declared 'static' but never defined +autogenerated:209: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined +autogenerated:210: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined +autogenerated:233: warning: 'void debug_motors()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used +autogenerated:252: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined +autogenerated:253: warning: 'long int cross_track_test()' declared 'static' but never defined +autogenerated:254: warning: 'void reset_crosstrack()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/radio.pde:129: warning: 'void throttle_failsafe(uint16_t)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/radio.pde:186: warning: 'void trim_yaw()' defined but not used +autogenerated:266: warning: 'void readCommands()' declared 'static' but never defined +autogenerated:267: warning: 'void parseCommand(char*)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used -autogenerated:274: warning: 'long int read_baro_filtered()' declared 'static' but never defined +autogenerated:270: warning: 'long int read_baro_filtered()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used /root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used -autogenerated:288: warning: 'void report_heli()' declared 'static' but never defined -autogenerated:289: warning: 'void report_gyro()' declared 'static' but never defined -autogenerated:296: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined -autogenerated:297: warning: 'int read_num_from_serial()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/system.pde:448: warning: 'void set_failsafe(boolean)' defined but not used -autogenerated:311: warning: 'void init_optflow()' declared 'static' but never defined -autogenerated:319: warning: 'void fake_out_gps()' declared 'static' but never defined +autogenerated:284: warning: 'void report_heli()' declared 'static' but never defined +autogenerated:285: warning: 'void report_gyro()' declared 'static' but never defined +autogenerated:292: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined +autogenerated:293: warning: 'int read_num_from_serial()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/system.pde:459: warning: 'void set_failsafe(boolean)' defined but not used +autogenerated:307: warning: 'void init_optflow()' declared 'static' but never defined +autogenerated:315: warning: 'void fake_out_gps()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:444: warning: 'undo_event' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'condition_rate' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:464: warning: 'simple_WP' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:469: warning: 'new_location' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'undo_event' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:456: warning: 'condition_rate' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:470: warning: 'simple_WP' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:475: warning: 'new_location' defined but not used +/root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(uint8_t, const Menu::arg*)' declared 'static' but never defined %% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_PI/APM_PI.o %% libraries/APM_RC/APM_RC.o @@ -100,6 +99,7 @@ In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_Optic %% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o %% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o %% libraries/AP_RangeFinder/RangeFinder.o +%% libraries/AP_Relay/AP_Relay.o %% libraries/DataFlash/DataFlash.o In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.size.txt index 1e861b9add..df7966ae9f 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.size.txt @@ -36,12 +36,12 @@ 00000001 b yaw_mode 00000001 b GPS_light 00000001 b do_simple -00000001 b loop_step 00000001 b trim_flag 00000001 b dancing_light()::step 00000001 b read_control_switch()::switch_debouncer 00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav 00000001 B mavdelay +00000001 B relay 00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char) 00000002 b climb_rate 00000002 b loiter_sum @@ -50,15 +50,20 @@ 00000002 b event_repeat 00000002 b loiter_total 00000002 b nav_throttle +00000002 b x_rate_error +00000002 b y_rate_error 00000002 b altitude_rate 00000002 b gps_fix_count 00000002 b velocity_land +00000002 b x_actual_speed +00000002 b y_actual_speed 00000002 b loiter_time_max 00000002 b command_yaw_time 00000002 b event_undo_value 00000002 b command_yaw_speed 00000002 b auto_level_counter 00000002 b ground_temperature +00000002 b waypoint_speed_gov 00000002 b superslow_loopCounter 00000002 r comma 00000002 b g_gps @@ -74,11 +79,6 @@ 00000002 r test_wp(unsigned char, Menu::arg const*)::__c 00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c 00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c -00000002 B adc -00000002 B x_actual_speed -00000002 B x_rate_error -00000002 B y_actual_speed -00000002 B y_rate_error 00000003 r select_logs(unsigned char, Menu::arg const*)::__c 00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c 00000003 r print_enabled(unsigned char)::__c @@ -107,7 +107,6 @@ 00000004 b fast_loopTimer 00000004 b perf_mon_timer 00000004 b target_bearing -00000004 b throttle_timer 00000004 d battery_voltage 00000004 b command_yaw_end 00000004 b condition_start @@ -254,6 +253,7 @@ 00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c @@ -265,7 +265,6 @@ 0000000a r print_log_menu()::__c 0000000a r Log_Read_Startup()::__c 0000000a r test_wp(unsigned char, Menu::arg const*)::__c -0000000a r test_mag(unsigned char, Menu::arg const*)::__c 0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c @@ -345,7 +344,6 @@ 0000000f r report_batt_monitor()::__c 0000000f r test_imu(unsigned char, Menu::arg const*)::__c 0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c -00000010 r flight_mode_strings 00000010 r planner_menu_commands 00000010 b motor_out 00000010 W AP_VarT::cast_to_float() const @@ -357,6 +355,7 @@ 00000012 B Serial 00000012 B Serial1 00000012 B Serial3 +00000012 r flight_mode_strings 00000012 W AP_Float16::~AP_Float16() 00000012 W AP_VarA::~AP_VarA() 00000012 W AP_VarS >::~AP_VarS() @@ -401,7 +400,6 @@ 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001d r Log_Read_Attitude()::__c 0000001e r Log_Read_Optflow()::__c -0000001f r test_mag(unsigned char, Menu::arg const*)::__c 00000020 r test_current(unsigned char, Menu::arg const*)::__c 00000020 t byte_swap_4 00000021 r print_log_menu()::__c @@ -429,7 +427,6 @@ 00000026 t print_hit_enter() 00000026 t Log_Read_Startup() 00000026 r Log_Read_Control_Tuning()::__c -00000027 r test_xbee(unsigned char, Menu::arg const*)::__c 00000028 t test_battery(unsigned char, Menu::arg const*) 00000028 t main_menu_help(unsigned char, Menu::arg const*) 00000028 t help_log(unsigned char, Menu::arg const*) @@ -467,6 +464,7 @@ 0000003e W AP_VarT::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char) 00000040 t read_AHRS() 00000040 W AP_Float16::unserialize(void*, unsigned int) +00000040 B adc 00000040 t byte_swap_8 00000042 t report_sonar() 00000044 t setup_show(unsigned char, Menu::arg const*) @@ -492,7 +490,6 @@ 0000005c t setup_esc(unsigned char, Menu::arg const*) 0000005e t update_GPS_light() 0000005e T GCS_MAVLINK::_count_parameters() -00000064 t test_xbee(unsigned char, Menu::arg const*) 00000064 B barometer 00000064 t mavlink_msg_param_value_send 00000068 t zero_eeprom() @@ -535,17 +532,17 @@ 000000a8 t test_sonar(unsigned char, Menu::arg const*) 000000aa t Log_Read_Nav_Tuning() 000000ae t report_frame() +000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b2 t erase_logs(unsigned char, Menu::arg const*) -000000b4 t test_relay(unsigned char, Menu::arg const*) 000000b4 t planner_gcs(unsigned char, Menu::arg const*) 000000b6 t get_log_boundaries(unsigned char, int&, int&) 000000b7 B compass +000000be t update_events() 000000c2 t test_eedump(unsigned char, Menu::arg const*) 000000c2 t setup_compass(unsigned char, Menu::arg const*) 000000c2 t send_radio_out(mavlink_channel_t) 000000c2 t Log_Read_Attitude() 000000c4 t get_distance(Location*, Location*) -000000c4 t update_events() 000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c 000000c6 t send_radio_in(mavlink_channel_t) 000000c6 t Log_Read_Performance() @@ -568,24 +565,24 @@ 000000ea t Log_Read_Control_Tuning() 000000ee t report_batt_monitor() 000000f6 t Log_Read_Cmd() -000000fa t calc_nav_pitch_roll() +000000fa t calc_loiter_pitch_roll() +00000100 r test_menu_commands 0000010a t send_raw_imu2(mavlink_channel_t) 0000010a t test_gps(unsigned char, Menu::arg const*) 0000010c t test_current(unsigned char, Menu::arg const*) -0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 0000010e t send_servo_out(mavlink_channel_t) +0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 00000112 t send_extended_status1(mavlink_channel_t, unsigned int) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000118 t set_command_with_index(Location, int) 00000118 T GCS_MAVLINK::_queued_send() 0000011c t get_command_with_index(int) -00000120 r test_menu_commands 00000130 t report_compass() -00000132 t set_next_WP(Location*) 00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long) 00000138 t get_stabilize_roll(long) 00000138 t get_stabilize_pitch(long) +0000013a t set_next_WP(Location*) 00000148 t Log_Read_GPS() 00000152 T GCS_MAVLINK::update() 00000158 t update_commands() @@ -594,9 +591,8 @@ 00000160 t send_nav_controller_output(mavlink_channel_t) 00000166 t select_logs(unsigned char, Menu::arg const*) 00000166 t send_vfr_hud(mavlink_channel_t) +0000016c t test_imu(unsigned char, Menu::arg const*) 0000016e t send_attitude(mavlink_channel_t) -00000170 t test_imu(unsigned char, Menu::arg const*) -00000170 t test_mag(unsigned char, Menu::arg const*) 000001a8 t print_radio_values() 000001be t arm_motors() 000001be T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) @@ -605,24 +601,24 @@ 000001d6 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int) 000001e4 t setup_flightmodes(unsigned char, Menu::arg const*) 000001ea t init_home() -00000206 t set_mode(unsigned char) 0000021a t send_raw_imu1(mavlink_channel_t) 0000021c t test_wp(unsigned char, Menu::arg const*) 00000228 t setup_radio(unsigned char, Menu::arg const*) +00000228 t set_mode(unsigned char) 0000022a t send_gps_raw(mavlink_channel_t) +00000242 t calc_loiter(int, int) 00000268 t send_raw_imu3(mavlink_channel_t) -000002ea t tuning() -00000354 t calc_nav_rate(int, int, int, int) +00000330 t tuning() 00000382 t print_log_menu() +0000039a T update_throttle_mode() 000003a0 t read_battery() -000003ae T update_throttle_mode() 00000410 T update_yaw_mode() 0000046e T update_roll_pitch_mode() -000005ee t init_ardupilot() -000006e6 t update_nav_wp() -000007b0 t __static_initialization_and_destruction_0(int, int) -000007ea b g -00000874 t process_next_command() -00000894 W Parameters::Parameters() +000005fc t init_ardupilot() +000006fa t update_nav_wp() +000007b8 t __static_initialization_and_destruction_0(int, int) +00000824 b g +0000086a t process_next_command() +000008f4 W Parameters::Parameters() 00001228 T GCS_MAVLINK::handleMessage(__mavlink_message*) -00001a96 T loop +00001a84 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.build.log index 51603ba231..4798c845b1 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.build.log @@ -3,19 +3,18 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition -In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:76: +In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77: /root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()': -/root/apm/ardupilot-mega/ArduCopter/Parameters.h:387: warning: overflow in implicit constant conversion +/root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_loiter_turns()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:301: warning: statement has no effect +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:302: warning: statement has no effect /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_nav_wp()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:412: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:413: warning: comparison between signed and unsigned integer expressions /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_loiter_time()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:439: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:440: warning: comparison between signed and unsigned integer expressions /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_jump()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:652: warning: unused variable 'temp' +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:653: warning: unused variable 'temp' autogenerated: At global scope: -autogenerated:31: warning: 'int alt_hold_velocity()' declared 'static' but never defined autogenerated:83: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined autogenerated:84: warning: 'void send_message(byte)' declared 'static' but never defined autogenerated:85: warning: 'void send_message(byte, long int)' declared 'static' but never defined @@ -30,39 +29,39 @@ autogenerated:67: warning: 'long int convert_to_dec(float)' declared 'static' bu autogenerated:136: warning: 'void Log_Write_Optflow()' declared 'static' but never defined autogenerated:146: warning: 'void decrement_WP_index()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:431: warning: 'bool verify_loiter_unlim()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used /root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used -autogenerated:211: warning: 'void heli_init_swash()' declared 'static' but never defined -autogenerated:212: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined -autogenerated:213: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined -autogenerated:236: warning: 'void debug_motors()' declared 'static' but never defined -autogenerated:252: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/navigation.pde:208: warning: 'int get_loiter_angle()' defined but not used -autogenerated:256: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined -autogenerated:257: warning: 'long int cross_track_test()' declared 'static' but never defined -autogenerated:258: warning: 'void reset_crosstrack()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/navigation.pde:273: warning: 'long int get_altitude_above_home()' defined but not used -/root/apm/ardupilot-mega/ArduCopter/navigation.pde:294: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used -/root/apm/ardupilot-mega/ArduCopter/radio.pde:131: warning: 'void throttle_failsafe(uint16_t)' defined but not used -/root/apm/ardupilot-mega/ArduCopter/radio.pde:188: warning: 'void trim_yaw()' defined but not used -autogenerated:270: warning: 'void readCommands()' declared 'static' but never defined -autogenerated:271: warning: 'void parseCommand(char*)' declared 'static' but never defined +autogenerated:208: warning: 'void heli_init_swash()' declared 'static' but never defined +autogenerated:209: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined +autogenerated:210: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined +autogenerated:233: warning: 'void debug_motors()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used +autogenerated:252: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined +autogenerated:253: warning: 'long int cross_track_test()' declared 'static' but never defined +autogenerated:254: warning: 'void reset_crosstrack()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/radio.pde:129: warning: 'void throttle_failsafe(uint16_t)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/radio.pde:186: warning: 'void trim_yaw()' defined but not used +autogenerated:266: warning: 'void readCommands()' declared 'static' but never defined +autogenerated:267: warning: 'void parseCommand(char*)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used -autogenerated:274: warning: 'long int read_baro_filtered()' declared 'static' but never defined +autogenerated:270: warning: 'long int read_baro_filtered()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used /root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used -autogenerated:288: warning: 'void report_heli()' declared 'static' but never defined -autogenerated:289: warning: 'void report_gyro()' declared 'static' but never defined -autogenerated:296: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined -autogenerated:297: warning: 'int read_num_from_serial()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/system.pde:448: warning: 'void set_failsafe(boolean)' defined but not used -autogenerated:311: warning: 'void init_optflow()' declared 'static' but never defined -autogenerated:319: warning: 'void fake_out_gps()' declared 'static' but never defined +autogenerated:284: warning: 'void report_heli()' declared 'static' but never defined +autogenerated:285: warning: 'void report_gyro()' declared 'static' but never defined +autogenerated:292: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined +autogenerated:293: warning: 'int read_num_from_serial()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/system.pde:459: warning: 'void set_failsafe(boolean)' defined but not used +autogenerated:307: warning: 'void init_optflow()' declared 'static' but never defined +autogenerated:315: warning: 'void fake_out_gps()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:444: warning: 'undo_event' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'condition_rate' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:464: warning: 'simple_WP' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:469: warning: 'new_location' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'undo_event' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:456: warning: 'condition_rate' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:470: warning: 'simple_WP' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:475: warning: 'new_location' defined but not used +/root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(uint8_t, const Menu::arg*)' declared 'static' but never defined %% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_PI/APM_PI.o %% libraries/APM_RC/APM_RC.o @@ -100,6 +99,7 @@ In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_Optic %% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o %% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o %% libraries/AP_RangeFinder/RangeFinder.o +%% libraries/AP_Relay/AP_Relay.o %% libraries/DataFlash/DataFlash.o In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.size.txt index b58eb6e773..03f66e47c7 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.size.txt @@ -36,12 +36,12 @@ 00000001 b yaw_mode 00000001 b GPS_light 00000001 b do_simple -00000001 b loop_step 00000001 b trim_flag 00000001 b dancing_light()::step 00000001 b read_control_switch()::switch_debouncer 00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav 00000001 B mavdelay +00000001 B relay 00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char) 00000002 b climb_rate 00000002 b loiter_sum @@ -50,15 +50,20 @@ 00000002 b event_repeat 00000002 b loiter_total 00000002 b nav_throttle +00000002 b x_rate_error +00000002 b y_rate_error 00000002 b altitude_rate 00000002 b gps_fix_count 00000002 b velocity_land +00000002 b x_actual_speed +00000002 b y_actual_speed 00000002 b loiter_time_max 00000002 b command_yaw_time 00000002 b event_undo_value 00000002 b command_yaw_speed 00000002 b auto_level_counter 00000002 b ground_temperature +00000002 b waypoint_speed_gov 00000002 b superslow_loopCounter 00000002 r comma 00000002 b g_gps @@ -74,11 +79,6 @@ 00000002 r test_wp(unsigned char, Menu::arg const*)::__c 00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c 00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c -00000002 B adc -00000002 B x_actual_speed -00000002 B x_rate_error -00000002 B y_actual_speed -00000002 B y_rate_error 00000003 r select_logs(unsigned char, Menu::arg const*)::__c 00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c 00000003 r print_enabled(unsigned char)::__c @@ -107,7 +107,6 @@ 00000004 b fast_loopTimer 00000004 b perf_mon_timer 00000004 b target_bearing -00000004 b throttle_timer 00000004 d battery_voltage 00000004 b command_yaw_end 00000004 b condition_start @@ -254,6 +253,7 @@ 00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c @@ -266,7 +266,6 @@ 0000000a r print_log_menu()::__c 0000000a r Log_Read_Startup()::__c 0000000a r test_wp(unsigned char, Menu::arg const*)::__c -0000000a r test_mag(unsigned char, Menu::arg const*)::__c 0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c @@ -345,7 +344,6 @@ 0000000f r report_batt_monitor()::__c 0000000f r test_imu(unsigned char, Menu::arg const*)::__c 0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c -00000010 r flight_mode_strings 00000010 r planner_menu_commands 00000010 b motor_out 00000010 W AP_VarT::cast_to_float() const @@ -357,6 +355,7 @@ 00000012 B Serial 00000012 B Serial1 00000012 B Serial3 +00000012 r flight_mode_strings 00000012 W AP_Float16::~AP_Float16() 00000012 W AP_VarA::~AP_VarA() 00000012 W AP_VarS >::~AP_VarS() @@ -401,7 +400,6 @@ 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001d r Log_Read_Attitude()::__c 0000001e r Log_Read_Optflow()::__c -0000001f r test_mag(unsigned char, Menu::arg const*)::__c 00000020 r test_current(unsigned char, Menu::arg const*)::__c 00000020 t byte_swap_4 00000021 r print_log_menu()::__c @@ -429,7 +427,6 @@ 00000026 t print_hit_enter() 00000026 t Log_Read_Startup() 00000026 r Log_Read_Control_Tuning()::__c -00000027 r test_xbee(unsigned char, Menu::arg const*)::__c 00000028 t test_battery(unsigned char, Menu::arg const*) 00000028 t main_menu_help(unsigned char, Menu::arg const*) 00000028 t help_log(unsigned char, Menu::arg const*) @@ -467,6 +464,7 @@ 0000003e W AP_VarT::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char) 00000040 t read_AHRS() 00000040 W AP_Float16::unserialize(void*, unsigned int) +00000040 B adc 00000040 t byte_swap_8 00000042 t report_sonar() 00000044 t setup_show(unsigned char, Menu::arg const*) @@ -492,7 +490,6 @@ 0000005c t setup_esc(unsigned char, Menu::arg const*) 0000005e t update_GPS_light() 0000005e T GCS_MAVLINK::_count_parameters() -00000064 t test_xbee(unsigned char, Menu::arg const*) 00000064 B barometer 00000064 t mavlink_msg_param_value_send 00000068 t zero_eeprom() @@ -535,16 +532,16 @@ 000000aa t test_sonar(unsigned char, Menu::arg const*) 000000aa t Log_Read_Nav_Tuning() 000000ae t report_frame() +000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b2 t erase_logs(unsigned char, Menu::arg const*) -000000b4 t test_relay(unsigned char, Menu::arg const*) 000000b4 t planner_gcs(unsigned char, Menu::arg const*) 000000b6 t get_log_boundaries(unsigned char, int&, int&) 000000b7 B compass +000000be t update_events() 000000c2 t setup_compass(unsigned char, Menu::arg const*) 000000c2 t send_radio_out(mavlink_channel_t) 000000c2 t Log_Read_Attitude() 000000c4 t get_distance(Location*, Location*) -000000c4 t update_events() 000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c 000000c6 t test_eedump(unsigned char, Menu::arg const*) 000000c6 t send_radio_in(mavlink_channel_t) @@ -567,24 +564,24 @@ 000000ea t Log_Read_Control_Tuning() 000000ee t report_batt_monitor() 000000f6 t Log_Read_Cmd() -000000fa t calc_nav_pitch_roll() +000000fa t calc_loiter_pitch_roll() +00000100 r test_menu_commands 0000010a t send_raw_imu2(mavlink_channel_t) 0000010a t test_gps(unsigned char, Menu::arg const*) 0000010c t test_current(unsigned char, Menu::arg const*) -0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 0000010e t send_servo_out(mavlink_channel_t) -00000112 t send_extended_status1(mavlink_channel_t, unsigned int) +0000010e t send_extended_status1(mavlink_channel_t, unsigned int) +0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000118 t set_command_with_index(Location, int) 00000118 T GCS_MAVLINK::_queued_send() 0000011c t get_command_with_index(int) -00000120 r test_menu_commands 00000130 t report_compass() -00000132 t set_next_WP(Location*) 00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long) 00000138 t get_stabilize_roll(long) 00000138 t get_stabilize_pitch(long) +0000013a t set_next_WP(Location*) 00000148 t Log_Read_GPS() 00000152 T GCS_MAVLINK::update() 00000158 t update_commands() @@ -594,9 +591,8 @@ 00000160 t send_nav_controller_output(mavlink_channel_t) 00000166 t select_logs(unsigned char, Menu::arg const*) 00000166 t send_vfr_hud(mavlink_channel_t) +0000016c t test_imu(unsigned char, Menu::arg const*) 0000016e t send_attitude(mavlink_channel_t) -00000170 t test_imu(unsigned char, Menu::arg const*) -00000170 t test_mag(unsigned char, Menu::arg const*) 000001a8 t print_radio_values() 000001be t arm_motors() 000001be T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) @@ -605,24 +601,24 @@ 000001d6 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int) 000001e4 t setup_flightmodes(unsigned char, Menu::arg const*) 000001ea t init_home() -00000206 t set_mode(unsigned char) 0000021a t send_raw_imu1(mavlink_channel_t) 00000220 t test_wp(unsigned char, Menu::arg const*) 00000228 t setup_radio(unsigned char, Menu::arg const*) +00000228 t set_mode(unsigned char) 0000022a t send_gps_raw(mavlink_channel_t) +00000242 t calc_loiter(int, int) 00000268 t send_raw_imu3(mavlink_channel_t) -000002ea t tuning() -00000354 t calc_nav_rate(int, int, int, int) +00000330 t tuning() 00000384 t print_log_menu() +0000039a T update_throttle_mode() 000003a0 t read_battery() -000003ae T update_throttle_mode() 00000410 T update_yaw_mode() 0000046e T update_roll_pitch_mode() -000005ee t init_ardupilot() -000006e6 t update_nav_wp() -000007b0 t __static_initialization_and_destruction_0(int, int) -000007ea b g -00000874 t process_next_command() -00000894 W Parameters::Parameters() +000005fc t init_ardupilot() +000006fa t update_nav_wp() +000007b8 t __static_initialization_and_destruction_0(int, int) +00000824 b g +0000086a t process_next_command() +000008f4 W Parameters::Parameters() 00001228 T GCS_MAVLINK::handleMessage(__mavlink_message*) -00001b78 T loop +00001b66 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.build.log index 51603ba231..4798c845b1 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.build.log @@ -3,19 +3,18 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition -In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:76: +In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77: /root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()': -/root/apm/ardupilot-mega/ArduCopter/Parameters.h:387: warning: overflow in implicit constant conversion +/root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_loiter_turns()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:301: warning: statement has no effect +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:302: warning: statement has no effect /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_nav_wp()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:412: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:413: warning: comparison between signed and unsigned integer expressions /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_loiter_time()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:439: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:440: warning: comparison between signed and unsigned integer expressions /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_jump()': -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:652: warning: unused variable 'temp' +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:653: warning: unused variable 'temp' autogenerated: At global scope: -autogenerated:31: warning: 'int alt_hold_velocity()' declared 'static' but never defined autogenerated:83: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined autogenerated:84: warning: 'void send_message(byte)' declared 'static' but never defined autogenerated:85: warning: 'void send_message(byte, long int)' declared 'static' but never defined @@ -30,39 +29,39 @@ autogenerated:67: warning: 'long int convert_to_dec(float)' declared 'static' bu autogenerated:136: warning: 'void Log_Write_Optflow()' declared 'static' but never defined autogenerated:146: warning: 'void decrement_WP_index()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used -/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:431: warning: 'bool verify_loiter_unlim()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used /root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used -autogenerated:211: warning: 'void heli_init_swash()' declared 'static' but never defined -autogenerated:212: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined -autogenerated:213: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined -autogenerated:236: warning: 'void debug_motors()' declared 'static' but never defined -autogenerated:252: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/navigation.pde:208: warning: 'int get_loiter_angle()' defined but not used -autogenerated:256: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined -autogenerated:257: warning: 'long int cross_track_test()' declared 'static' but never defined -autogenerated:258: warning: 'void reset_crosstrack()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/navigation.pde:273: warning: 'long int get_altitude_above_home()' defined but not used -/root/apm/ardupilot-mega/ArduCopter/navigation.pde:294: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used -/root/apm/ardupilot-mega/ArduCopter/radio.pde:131: warning: 'void throttle_failsafe(uint16_t)' defined but not used -/root/apm/ardupilot-mega/ArduCopter/radio.pde:188: warning: 'void trim_yaw()' defined but not used -autogenerated:270: warning: 'void readCommands()' declared 'static' but never defined -autogenerated:271: warning: 'void parseCommand(char*)' declared 'static' but never defined +autogenerated:208: warning: 'void heli_init_swash()' declared 'static' but never defined +autogenerated:209: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined +autogenerated:210: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined +autogenerated:233: warning: 'void debug_motors()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used +autogenerated:252: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined +autogenerated:253: warning: 'long int cross_track_test()' declared 'static' but never defined +autogenerated:254: warning: 'void reset_crosstrack()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/radio.pde:129: warning: 'void throttle_failsafe(uint16_t)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/radio.pde:186: warning: 'void trim_yaw()' defined but not used +autogenerated:266: warning: 'void readCommands()' declared 'static' but never defined +autogenerated:267: warning: 'void parseCommand(char*)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used -autogenerated:274: warning: 'long int read_baro_filtered()' declared 'static' but never defined +autogenerated:270: warning: 'long int read_baro_filtered()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used /root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used -autogenerated:288: warning: 'void report_heli()' declared 'static' but never defined -autogenerated:289: warning: 'void report_gyro()' declared 'static' but never defined -autogenerated:296: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined -autogenerated:297: warning: 'int read_num_from_serial()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/system.pde:448: warning: 'void set_failsafe(boolean)' defined but not used -autogenerated:311: warning: 'void init_optflow()' declared 'static' but never defined -autogenerated:319: warning: 'void fake_out_gps()' declared 'static' but never defined +autogenerated:284: warning: 'void report_heli()' declared 'static' but never defined +autogenerated:285: warning: 'void report_gyro()' declared 'static' but never defined +autogenerated:292: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined +autogenerated:293: warning: 'int read_num_from_serial()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/system.pde:459: warning: 'void set_failsafe(boolean)' defined but not used +autogenerated:307: warning: 'void init_optflow()' declared 'static' but never defined +autogenerated:315: warning: 'void fake_out_gps()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:444: warning: 'undo_event' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'condition_rate' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:464: warning: 'simple_WP' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:469: warning: 'new_location' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'undo_event' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:456: warning: 'condition_rate' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:470: warning: 'simple_WP' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:475: warning: 'new_location' defined but not used +/root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(uint8_t, const Menu::arg*)' declared 'static' but never defined %% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_PI/APM_PI.o %% libraries/APM_RC/APM_RC.o @@ -100,6 +99,7 @@ In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_Optic %% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o %% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o %% libraries/AP_RangeFinder/RangeFinder.o +%% libraries/AP_Relay/AP_Relay.o %% libraries/DataFlash/DataFlash.o In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.size.txt index b7fb2ec9e6..aa65b1b1b3 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.size.txt @@ -36,12 +36,12 @@ 00000001 b yaw_mode 00000001 b GPS_light 00000001 b do_simple -00000001 b loop_step 00000001 b trim_flag 00000001 b dancing_light()::step 00000001 b read_control_switch()::switch_debouncer 00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav 00000001 B mavdelay +00000001 B relay 00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char) 00000002 b climb_rate 00000002 b loiter_sum @@ -50,15 +50,20 @@ 00000002 b event_repeat 00000002 b loiter_total 00000002 b nav_throttle +00000002 b x_rate_error +00000002 b y_rate_error 00000002 b altitude_rate 00000002 b gps_fix_count 00000002 b velocity_land +00000002 b x_actual_speed +00000002 b y_actual_speed 00000002 b loiter_time_max 00000002 b command_yaw_time 00000002 b event_undo_value 00000002 b command_yaw_speed 00000002 b auto_level_counter 00000002 b ground_temperature +00000002 b waypoint_speed_gov 00000002 b superslow_loopCounter 00000002 r comma 00000002 b g_gps @@ -74,11 +79,6 @@ 00000002 r test_wp(unsigned char, Menu::arg const*)::__c 00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c 00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c -00000002 B adc -00000002 B x_actual_speed -00000002 B x_rate_error -00000002 B y_actual_speed -00000002 B y_rate_error 00000003 r select_logs(unsigned char, Menu::arg const*)::__c 00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c 00000003 r print_enabled(unsigned char)::__c @@ -107,7 +107,6 @@ 00000004 b fast_loopTimer 00000004 b perf_mon_timer 00000004 b target_bearing -00000004 b throttle_timer 00000004 d battery_voltage 00000004 b command_yaw_end 00000004 b condition_start @@ -254,6 +253,7 @@ 00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c @@ -266,7 +266,6 @@ 0000000a r print_log_menu()::__c 0000000a r Log_Read_Startup()::__c 0000000a r test_wp(unsigned char, Menu::arg const*)::__c -0000000a r test_mag(unsigned char, Menu::arg const*)::__c 0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c @@ -345,7 +344,6 @@ 0000000f r report_batt_monitor()::__c 0000000f r test_imu(unsigned char, Menu::arg const*)::__c 0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c -00000010 r flight_mode_strings 00000010 r planner_menu_commands 00000010 b motor_out 00000010 W AP_VarT::cast_to_float() const @@ -357,6 +355,7 @@ 00000012 B Serial 00000012 B Serial1 00000012 B Serial3 +00000012 r flight_mode_strings 00000012 W AP_Float16::~AP_Float16() 00000012 W AP_VarA::~AP_VarA() 00000012 W AP_VarS >::~AP_VarS() @@ -401,7 +400,6 @@ 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001d r Log_Read_Attitude()::__c 0000001e r Log_Read_Optflow()::__c -0000001f r test_mag(unsigned char, Menu::arg const*)::__c 00000020 r test_current(unsigned char, Menu::arg const*)::__c 00000020 t byte_swap_4 00000021 r print_log_menu()::__c @@ -429,7 +427,6 @@ 00000026 t print_hit_enter() 00000026 t Log_Read_Startup() 00000026 r Log_Read_Control_Tuning()::__c -00000027 r test_xbee(unsigned char, Menu::arg const*)::__c 00000028 t test_battery(unsigned char, Menu::arg const*) 00000028 t main_menu_help(unsigned char, Menu::arg const*) 00000028 t help_log(unsigned char, Menu::arg const*) @@ -467,6 +464,7 @@ 0000003e W AP_VarT::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char) 00000040 t read_AHRS() 00000040 W AP_Float16::unserialize(void*, unsigned int) +00000040 B adc 00000040 t byte_swap_8 00000042 t report_sonar() 00000044 t setup_show(unsigned char, Menu::arg const*) @@ -492,7 +490,6 @@ 0000005c t setup_esc(unsigned char, Menu::arg const*) 0000005e t update_GPS_light() 0000005e T GCS_MAVLINK::_count_parameters() -00000064 t test_xbee(unsigned char, Menu::arg const*) 00000064 B barometer 00000064 t mavlink_msg_param_value_send 00000068 t zero_eeprom() @@ -535,17 +532,17 @@ 000000a8 t test_sonar(unsigned char, Menu::arg const*) 000000aa t Log_Read_Nav_Tuning() 000000ae t report_frame() +000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b2 t erase_logs(unsigned char, Menu::arg const*) -000000b4 t test_relay(unsigned char, Menu::arg const*) 000000b4 t planner_gcs(unsigned char, Menu::arg const*) 000000b6 t get_log_boundaries(unsigned char, int&, int&) 000000b7 B compass +000000be t update_events() 000000c2 t test_eedump(unsigned char, Menu::arg const*) 000000c2 t setup_compass(unsigned char, Menu::arg const*) 000000c2 t send_radio_out(mavlink_channel_t) 000000c2 t Log_Read_Attitude() 000000c4 t get_distance(Location*, Location*) -000000c4 t update_events() 000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c 000000c6 t send_radio_in(mavlink_channel_t) 000000c6 t Log_Read_Performance() @@ -567,24 +564,24 @@ 000000ea t Log_Read_Control_Tuning() 000000ee t report_batt_monitor() 000000f6 t Log_Read_Cmd() -000000fa t calc_nav_pitch_roll() +000000fa t calc_loiter_pitch_roll() +00000100 r test_menu_commands 0000010a t send_raw_imu2(mavlink_channel_t) 0000010a t test_gps(unsigned char, Menu::arg const*) 0000010c t test_current(unsigned char, Menu::arg const*) -0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 0000010e t send_servo_out(mavlink_channel_t) -00000112 t send_extended_status1(mavlink_channel_t, unsigned int) +0000010e t send_extended_status1(mavlink_channel_t, unsigned int) +0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000118 t set_command_with_index(Location, int) 00000118 T GCS_MAVLINK::_queued_send() 0000011c t get_command_with_index(int) -00000120 r test_menu_commands 00000130 t report_compass() -00000132 t set_next_WP(Location*) 00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long) 00000138 t get_stabilize_roll(long) 00000138 t get_stabilize_pitch(long) +0000013a t set_next_WP(Location*) 00000148 t Log_Read_GPS() 00000152 T GCS_MAVLINK::update() 00000158 t update_commands() @@ -594,9 +591,8 @@ 00000160 t send_nav_controller_output(mavlink_channel_t) 00000166 t select_logs(unsigned char, Menu::arg const*) 00000166 t send_vfr_hud(mavlink_channel_t) +0000016c t test_imu(unsigned char, Menu::arg const*) 0000016e t send_attitude(mavlink_channel_t) -00000170 t test_imu(unsigned char, Menu::arg const*) -00000170 t test_mag(unsigned char, Menu::arg const*) 000001a8 t print_radio_values() 000001be t arm_motors() 000001be T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) @@ -605,24 +601,24 @@ 000001d6 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int) 000001e4 t setup_flightmodes(unsigned char, Menu::arg const*) 000001ea t init_home() -00000206 t set_mode(unsigned char) 0000021a t send_raw_imu1(mavlink_channel_t) 0000021c t test_wp(unsigned char, Menu::arg const*) 00000228 t setup_radio(unsigned char, Menu::arg const*) +00000228 t set_mode(unsigned char) 0000022a t send_gps_raw(mavlink_channel_t) +00000242 t calc_loiter(int, int) 00000268 t send_raw_imu3(mavlink_channel_t) -000002ea t tuning() -00000354 t calc_nav_rate(int, int, int, int) +00000330 t tuning() 00000382 t print_log_menu() +0000039a T update_throttle_mode() 000003a0 t read_battery() -000003ae T update_throttle_mode() 00000410 T update_yaw_mode() 0000046e T update_roll_pitch_mode() -000005ee t init_ardupilot() -000006e6 t update_nav_wp() -000007b0 t __static_initialization_and_destruction_0(int, int) -000007ea b g -00000874 t process_next_command() -00000894 W Parameters::Parameters() +000005fc t init_ardupilot() +000006fa t update_nav_wp() +000007b8 t __static_initialization_and_destruction_0(int, int) +00000824 b g +0000086a t process_next_command() +000008f4 W Parameters::Parameters() 00001228 T GCS_MAVLINK::handleMessage(__mavlink_message*) -00001b76 T loop +00001b64 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml b/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml index 583339250a..bab99983d7 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml +++ b/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml @@ -58,7 +58,7 @@ http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.hex http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.hex - ArduCopter V2.0.45 Beta Quad + ArduCopter V2.0.47 Beta Quad #define FRAME_CONFIG QUAD_FRAME #define FRAME_ORIENTATION X_FRAME @@ -69,7 +69,7 @@ http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.hex http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.hex - ArduCopter V2.0.45 Beta Tri + ArduCopter V2.0.47 Beta Tri #define FRAME_CONFIG TRI_FRAME #define FRAME_ORIENTATION X_FRAME @@ -80,7 +80,7 @@ http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.hex http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.hex - ArduCopter V2.0.45 Beta Hexa + ArduCopter V2.0.47 Beta Hexa #define FRAME_CONFIG HEXA_FRAME #define FRAME_ORIENTATION X_FRAME @@ -91,7 +91,7 @@ http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.hex http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.hex - ArduCopter V2.0.45 Beta Y6 + ArduCopter V2.0.47 Beta Y6 #define FRAME_CONFIG Y6_FRAME #define FRAME_ORIENTATION X_FRAME @@ -148,7 +148,7 @@ http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.hex http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.hex - ArduCopter V2.0.45 Beta Quad Hil + ArduCopter V2.0.47 Beta Quad Hil #define FRAME_CONFIG QUAD_FRAME #define FRAME_ORIENTATION PLUS_FRAME diff --git a/Tools/ArdupilotMegaPlanner/Firmware/git.log b/Tools/ArdupilotMegaPlanner/Firmware/git.log index eadadd9370..266e6adffc 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/git.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/git.log @@ -1,9 +1,12 @@ From https://code.google.com/p/ardupilot-mega - e7d6202..4743949 master -> origin/master -Updating e7d6202..4743949 + 2ceba2f..eb0b7eb master -> origin/master +Updating 2ceba2f..eb0b7eb Fast-forward - ArduCopter/ArduCopter.pde | 2 -- - ArduCopter/Attitude.pde | 14 +------------- - ArduCopter/config.h | 2 +- - ArduCopter/control_modes.pde | 2 +- - 4 files changed, 3 insertions(+), 17 deletions(-) + ArduCopter/ArduCopter.pde | 6 +- + Tools/ArdupilotMegaPlanner/ArdupilotMega.suo | Bin 83456 -> 0 bytes + Tools/ArdupilotMegaPlanner/Capture.cs | 125 +- + .../GCSViews/Configuration.Designer.cs | 114 +- + .../ArdupilotMegaPlanner/GCSViews/Configuration.cs | 82 +- + .../GCSViews/Configuration.resx | 1936 ++++++++++++++------ + 6 files changed, 1573 insertions(+), 690 deletions(-) + delete mode 100644 Tools/ArdupilotMegaPlanner/ArdupilotMega.suo diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.Designer.cs index 1a6523f2c4..3fc2de663c 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.Designer.cs @@ -141,6 +141,12 @@ this.RLL2SRV_P = new System.Windows.Forms.DomainUpDown(); this.label52 = new System.Windows.Forms.Label(); this.TabAC2 = new System.Windows.Forms.TabPage(); + this.groupBox5 = new System.Windows.Forms.GroupBox(); + this.THR_RATE_IMAX = new System.Windows.Forms.DomainUpDown(); + this.THR_RATE_I = new System.Windows.Forms.DomainUpDown(); + this.label20 = new System.Windows.Forms.Label(); + this.THR_RATE_P = new System.Windows.Forms.DomainUpDown(); + this.label25 = new System.Windows.Forms.Label(); this.CHK_lockrollpitch = new System.Windows.Forms.CheckBox(); this.groupBox4 = new System.Windows.Forms.GroupBox(); this.WP_SPEED_MAX = new System.Windows.Forms.DomainUpDown(); @@ -161,11 +167,11 @@ this.XTRACK_P = new System.Windows.Forms.DomainUpDown(); this.label18 = new System.Windows.Forms.Label(); this.groupBox7 = new System.Windows.Forms.GroupBox(); - this.THR_HOLD_IMAX = new System.Windows.Forms.DomainUpDown(); + this.THR_ALT_IMAX = new System.Windows.Forms.DomainUpDown(); this.label19 = new System.Windows.Forms.Label(); - this.THR_HOLD_I = new System.Windows.Forms.DomainUpDown(); + this.THR_ALT_I = new System.Windows.Forms.DomainUpDown(); this.label21 = new System.Windows.Forms.Label(); - this.THR_HOLD_P = new System.Windows.Forms.DomainUpDown(); + this.THR_ALT_P = new System.Windows.Forms.DomainUpDown(); this.label22 = new System.Windows.Forms.Label(); this.groupBox19 = new System.Windows.Forms.GroupBox(); this.HLD_LAT_IMAX = new System.Windows.Forms.DomainUpDown(); @@ -217,6 +223,9 @@ this.RATE_RLL_P = new System.Windows.Forms.DomainUpDown(); this.label91 = new System.Windows.Forms.Label(); this.TabPlanner = new System.Windows.Forms.TabPage(); + this.CMB_videoresolutions = new System.Windows.Forms.ComboBox(); + this.label12 = new System.Windows.Forms.Label(); + this.CHK_GDIPlus = new System.Windows.Forms.CheckBox(); this.label24 = new System.Windows.Forms.Label(); this.CHK_loadwponconnect = new System.Windows.Forms.CheckBox(); this.label23 = new System.Windows.Forms.Label(); @@ -257,14 +266,15 @@ this.BUT_videostop = new ArdupilotMega.MyButton(); this.BUT_videostart = new ArdupilotMega.MyButton(); this.TabSetup = new System.Windows.Forms.TabPage(); + this.label109 = new System.Windows.Forms.Label(); this.BUT_rerequestparams = new ArdupilotMega.MyButton(); this.BUT_writePIDS = new ArdupilotMega.MyButton(); this.BUT_save = new ArdupilotMega.MyButton(); this.BUT_load = new ArdupilotMega.MyButton(); this.toolTip1 = new System.Windows.Forms.ToolTip(this.components); this.BUT_compare = new ArdupilotMega.MyButton(); - this.label12 = new System.Windows.Forms.Label(); - this.CHK_GDIPlus = new System.Windows.Forms.CheckBox(); + this.label14 = new System.Windows.Forms.Label(); + this.label26 = new System.Windows.Forms.Label(); ((System.ComponentModel.ISupportInitialize)(this.Params)).BeginInit(); this.ConfigTabs.SuspendLayout(); this.TabAPM2.SuspendLayout(); @@ -281,6 +291,7 @@ this.groupBox9.SuspendLayout(); this.groupBox8.SuspendLayout(); this.TabAC2.SuspendLayout(); + this.groupBox5.SuspendLayout(); this.groupBox4.SuspendLayout(); this.groupBox6.SuspendLayout(); this.groupBox7.SuspendLayout(); @@ -984,6 +995,7 @@ // // TabAC2 // + this.TabAC2.Controls.Add(this.groupBox5); this.TabAC2.Controls.Add(this.CHK_lockrollpitch); this.TabAC2.Controls.Add(this.groupBox4); this.TabAC2.Controls.Add(this.groupBox6); @@ -998,6 +1010,43 @@ resources.ApplyResources(this.TabAC2, "TabAC2"); this.TabAC2.Name = "TabAC2"; // + // groupBox5 + // + this.groupBox5.Controls.Add(this.label14); + this.groupBox5.Controls.Add(this.THR_RATE_IMAX); + this.groupBox5.Controls.Add(this.THR_RATE_I); + this.groupBox5.Controls.Add(this.label20); + this.groupBox5.Controls.Add(this.THR_RATE_P); + this.groupBox5.Controls.Add(this.label25); + resources.ApplyResources(this.groupBox5, "groupBox5"); + this.groupBox5.Name = "groupBox5"; + this.groupBox5.TabStop = false; + // + // THR_RATE_IMAX + // + resources.ApplyResources(this.THR_RATE_IMAX, "THR_RATE_IMAX"); + this.THR_RATE_IMAX.Name = "THR_RATE_IMAX"; + // + // THR_RATE_I + // + resources.ApplyResources(this.THR_RATE_I, "THR_RATE_I"); + this.THR_RATE_I.Name = "THR_RATE_I"; + // + // label20 + // + resources.ApplyResources(this.label20, "label20"); + this.label20.Name = "label20"; + // + // THR_RATE_P + // + resources.ApplyResources(this.THR_RATE_P, "THR_RATE_P"); + this.THR_RATE_P.Name = "THR_RATE_P"; + // + // label25 + // + resources.ApplyResources(this.label25, "label25"); + this.label25.Name = "label25"; + // // CHK_lockrollpitch // resources.ApplyResources(this.CHK_lockrollpitch, "CHK_lockrollpitch"); @@ -1114,40 +1163,40 @@ // // groupBox7 // - this.groupBox7.Controls.Add(this.THR_HOLD_IMAX); + this.groupBox7.Controls.Add(this.THR_ALT_IMAX); this.groupBox7.Controls.Add(this.label19); - this.groupBox7.Controls.Add(this.THR_HOLD_I); + this.groupBox7.Controls.Add(this.THR_ALT_I); this.groupBox7.Controls.Add(this.label21); - this.groupBox7.Controls.Add(this.THR_HOLD_P); + this.groupBox7.Controls.Add(this.THR_ALT_P); this.groupBox7.Controls.Add(this.label22); resources.ApplyResources(this.groupBox7, "groupBox7"); this.groupBox7.Name = "groupBox7"; this.groupBox7.TabStop = false; // - // THR_HOLD_IMAX + // THR_ALT_IMAX // - resources.ApplyResources(this.THR_HOLD_IMAX, "THR_HOLD_IMAX"); - this.THR_HOLD_IMAX.Name = "THR_HOLD_IMAX"; + resources.ApplyResources(this.THR_ALT_IMAX, "THR_ALT_IMAX"); + this.THR_ALT_IMAX.Name = "THR_ALT_IMAX"; // // label19 // resources.ApplyResources(this.label19, "label19"); this.label19.Name = "label19"; // - // THR_HOLD_I + // THR_ALT_I // - resources.ApplyResources(this.THR_HOLD_I, "THR_HOLD_I"); - this.THR_HOLD_I.Name = "THR_HOLD_I"; + resources.ApplyResources(this.THR_ALT_I, "THR_ALT_I"); + this.THR_ALT_I.Name = "THR_ALT_I"; // // label21 // resources.ApplyResources(this.label21, "label21"); this.label21.Name = "label21"; // - // THR_HOLD_P + // THR_ALT_P // - resources.ApplyResources(this.THR_HOLD_P, "THR_HOLD_P"); - this.THR_HOLD_P.Name = "THR_HOLD_P"; + resources.ApplyResources(this.THR_ALT_P, "THR_ALT_P"); + this.THR_ALT_P.Name = "THR_ALT_P"; // // label22 // @@ -1450,6 +1499,8 @@ // // TabPlanner // + this.TabPlanner.Controls.Add(this.label26); + this.TabPlanner.Controls.Add(this.CMB_videoresolutions); this.TabPlanner.Controls.Add(this.label12); this.TabPlanner.Controls.Add(this.CHK_GDIPlus); this.TabPlanner.Controls.Add(this.label24); @@ -1494,6 +1545,26 @@ resources.ApplyResources(this.TabPlanner, "TabPlanner"); this.TabPlanner.Name = "TabPlanner"; // + // CMB_videoresolutions + // + this.CMB_videoresolutions.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; + this.CMB_videoresolutions.FormattingEnabled = true; + resources.ApplyResources(this.CMB_videoresolutions, "CMB_videoresolutions"); + this.CMB_videoresolutions.Name = "CMB_videoresolutions"; + // + // label12 + // + resources.ApplyResources(this.label12, "label12"); + this.label12.Name = "label12"; + // + // CHK_GDIPlus + // + resources.ApplyResources(this.CHK_GDIPlus, "CHK_GDIPlus"); + this.CHK_GDIPlus.Name = "CHK_GDIPlus"; + this.toolTip1.SetToolTip(this.CHK_GDIPlus, resources.GetString("CHK_GDIPlus.ToolTip")); + this.CHK_GDIPlus.UseVisualStyleBackColor = true; + this.CHK_GDIPlus.CheckedChanged += new System.EventHandler(this.CHK_GDIPlus_CheckedChanged); + // // label24 // resources.ApplyResources(this.label24, "label24"); @@ -1766,6 +1837,7 @@ this.CMB_videosources.FormattingEnabled = true; resources.ApplyResources(this.CMB_videosources, "CMB_videosources"); this.CMB_videosources.Name = "CMB_videosources"; + this.CMB_videosources.SelectedIndexChanged += new System.EventHandler(this.CMB_videosources_SelectedIndexChanged); this.CMB_videosources.MouseClick += new System.Windows.Forms.MouseEventHandler(this.CMB_videosources_MouseClick); // // BUT_Joystick @@ -1795,6 +1867,11 @@ this.TabSetup.Name = "TabSetup"; this.TabSetup.UseVisualStyleBackColor = true; // + // label109 + // + resources.ApplyResources(this.label109, "label109"); + this.label109.Name = "label109"; + // // BUT_rerequestparams // resources.ApplyResources(this.BUT_rerequestparams, "BUT_rerequestparams"); @@ -1834,18 +1911,15 @@ this.BUT_compare.UseVisualStyleBackColor = true; this.BUT_compare.Click += new System.EventHandler(this.BUT_compare_Click); // - // label12 + // label14 // - resources.ApplyResources(this.label12, "label12"); - this.label12.Name = "label12"; + resources.ApplyResources(this.label14, "label14"); + this.label14.Name = "label14"; // - // CHK_GDIPlus + // label26 // - resources.ApplyResources(this.CHK_GDIPlus, "CHK_GDIPlus"); - this.CHK_GDIPlus.Name = "CHK_GDIPlus"; - this.toolTip1.SetToolTip(this.CHK_GDIPlus, resources.GetString("CHK_GDIPlus.ToolTip")); - this.CHK_GDIPlus.UseVisualStyleBackColor = true; - this.CHK_GDIPlus.CheckedChanged += new System.EventHandler(this.CHK_GDIPlus_CheckedChanged); + resources.ApplyResources(this.label26, "label26"); + this.label26.Name = "label26"; // // Configuration // @@ -1878,6 +1952,7 @@ this.groupBox8.ResumeLayout(false); this.TabAC2.ResumeLayout(false); this.TabAC2.PerformLayout(); + this.groupBox5.ResumeLayout(false); this.groupBox4.ResumeLayout(false); this.groupBox6.ResumeLayout(false); this.groupBox7.ResumeLayout(false); @@ -2018,11 +2093,11 @@ private System.Windows.Forms.DomainUpDown XTRACK_P; private System.Windows.Forms.Label label18; private System.Windows.Forms.GroupBox groupBox7; - private System.Windows.Forms.DomainUpDown THR_HOLD_IMAX; + private System.Windows.Forms.DomainUpDown THR_ALT_IMAX; private System.Windows.Forms.Label label19; - private System.Windows.Forms.DomainUpDown THR_HOLD_I; + private System.Windows.Forms.DomainUpDown THR_ALT_I; private System.Windows.Forms.Label label21; - private System.Windows.Forms.DomainUpDown THR_HOLD_P; + private System.Windows.Forms.DomainUpDown THR_ALT_P; private System.Windows.Forms.Label label22; private System.Windows.Forms.GroupBox groupBox19; private System.Windows.Forms.DomainUpDown HLD_LAT_IMAX; @@ -2129,5 +2204,15 @@ private MyButton BUT_compare; private System.Windows.Forms.Label label12; private System.Windows.Forms.CheckBox CHK_GDIPlus; + private System.Windows.Forms.GroupBox groupBox5; + private System.Windows.Forms.DomainUpDown THR_RATE_IMAX; + private System.Windows.Forms.DomainUpDown THR_RATE_I; + private System.Windows.Forms.Label label20; + private System.Windows.Forms.DomainUpDown THR_RATE_P; + private System.Windows.Forms.Label label25; + private System.Windows.Forms.ComboBox CMB_videoresolutions; + private System.Windows.Forms.Label label109; + private System.Windows.Forms.Label label14; + private System.Windows.Forms.Label label26; } } diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs index d411445607..924463c992 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs @@ -11,6 +11,8 @@ using System.Text.RegularExpressions; using System.Collections; using System.Globalization; using System.Threading; +using DirectShowLib; +using System.Runtime.InteropServices; namespace ArdupilotMega.GCSViews { @@ -22,6 +24,29 @@ namespace ArdupilotMega.GCSViews internal bool startup = true; List languages = new List(); + public class GCSBitmapInfo + { + public int Width { get; set; } + public int Height { get; set; } + public long Fps { get; set; } + public string Standard { get; set; } + public AMMediaType Media { get; set; } + + public GCSBitmapInfo(int width, int height, long fps, string standard, AMMediaType media) + { + Width = width; + Height = height; + Fps = fps; + Standard = standard; + Media = media; + } + + public override string ToString() + { + return Width.ToString() + " x " + Height.ToString() + String.Format(" {0:0.00} fps ", 10000000.0 / Fps) + Standard; + } + } + public struct paramsettings // hk's { public string name; @@ -138,7 +163,7 @@ namespace ArdupilotMega.GCSViews // setup language selection CultureInfo ci = null; - foreach (string name in new string[] { "en-US", "zh-Hans" }) + foreach (string name in new string[] { "en-US", "zh-Hans", "ru-RU" }) { ci = MainV2.getcultureinfo(name); if (ci != null) @@ -202,6 +227,7 @@ namespace ArdupilotMega.GCSViews System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Configuration)); string data = resources.GetString("MAVParam"); + string[] tips = data.Split(new char[] { '\r', '\n' }, StringSplitOptions.RemoveEmptyEntries); foreach (var tip in tips) @@ -630,9 +656,11 @@ namespace ArdupilotMega.GCSViews // stop first BUT_videostop_Click(sender, e); + GCSBitmapInfo bmp = (GCSBitmapInfo)CMB_videoresolutions.SelectedItem; + try { - MainV2.cam = new WebCamService.Capture(CMB_videosources.SelectedIndex, 0, 0, 0); + MainV2.cam = new WebCamService.Capture(CMB_videosources.SelectedIndex, bmp.Media); MainV2.cam.showhud = CHK_hudshow.Checked; @@ -666,6 +694,58 @@ namespace ArdupilotMega.GCSViews capt.Dispose(); } + private void CMB_videosources_SelectedIndexChanged(object sender, EventArgs e) + { + int hr; + int count; + int size; + object o; + IBaseFilter capFilter = null; + ICaptureGraphBuilder2 capGraph = null; + AMMediaType media = null; + VideoInfoHeader v; + VideoStreamConfigCaps c; + List modes = new List(); + + // Get the ICaptureGraphBuilder2 + capGraph = (ICaptureGraphBuilder2)new CaptureGraphBuilder2(); + IFilterGraph2 m_FilterGraph = (IFilterGraph2)new FilterGraph(); + + DsDevice[] capDevices; + capDevices = DsDevice.GetDevicesOfCat(FilterCategory.VideoInputDevice); + + // Add the video device + hr = m_FilterGraph.AddSourceFilterForMoniker(capDevices[CMB_videosources.SelectedIndex].Mon, null, "Video input", out capFilter); + DsError.ThrowExceptionForHR(hr); + + // Find the stream config interface + hr = capGraph.FindInterface(PinCategory.Capture, MediaType.Video, capFilter, typeof(IAMStreamConfig).GUID, out o); + DsError.ThrowExceptionForHR(hr); + + IAMStreamConfig videoStreamConfig = o as IAMStreamConfig; + if (videoStreamConfig == null) + { + throw new Exception("Failed to get IAMStreamConfig"); + } + + hr = videoStreamConfig.GetNumberOfCapabilities(out count, out size); + DsError.ThrowExceptionForHR(hr); + IntPtr TaskMemPointer = Marshal.AllocCoTaskMem(size); + for (int i = 0; i < count; i++) + { + IntPtr ptr = IntPtr.Zero; + + hr = videoStreamConfig.GetStreamCaps(i, out media, TaskMemPointer); + v = (VideoInfoHeader)Marshal.PtrToStructure(media.formatPtr, typeof(VideoInfoHeader)); + c = (VideoStreamConfigCaps)Marshal.PtrToStructure(TaskMemPointer, typeof(VideoStreamConfigCaps)); + modes.Add(new GCSBitmapInfo(v.BmiHeader.Width, v.BmiHeader.Height, c.MaxFrameInterval, c.VideoStandard.ToString(), media)); + } + Marshal.FreeCoTaskMem(TaskMemPointer); + DsUtils.FreeAMMediaType(media); + + CMB_videoresolutions.DataSource = modes; + } + private void CHK_hudshow_CheckedChanged(object sender, EventArgs e) { GCSViews.FlightData.myhud.hudon = CHK_hudshow.Checked; diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.resx b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.resx index 738382f0ef..d92d68bcd0 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.resx @@ -117,2546 +117,5679 @@ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - THR_FS_VALUE + + + Top, Bottom, Left - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + True + + + Command - - 29 - - - groupBox14 - - - - 722, 434 - - - label50 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - P - - - ConfigTabs - - - groupBox10 - - - I - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 3 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 11 - - - 78, 20 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 390, 11 - - - - - - RATE_YAW_IMAX - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - label51 - - - groupBox15 - - - - - - 5 - - - Setup - - - 3 - - - 61, 13 - - - INT_MAX - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - - - - RATE_RLL_IMAX - - - 6, 87 - - - - - - XTRK_ANGLE_CD1 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - NoControl - - - label56 - - - 111, 59 - - - groupBox16 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 40 - - - 5 - - - 27, 203 - - - 13 - - - groupBox21 - - - - - - 69, 13 - - - 80, 13 - - - label28 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - WP_SPEED_MAX - - - GDI+ (old type) - - - groupBox24 - - - - - - label57 - - - - - - 111, 36 - - - 7 - - - 65, 13 - - - P - - - Default - - - groupBox8 - - - NoControl - - - 3, 416 - - - 22, 13 - - - 3, 3, 3, 3 - - - groupBox24 - - - 80, 21 - - - IMAX - - - INT_MAX - - - I - - - 136, 203 - - - Dist Units - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 30, 16 - - - NoControl - - - 722, 434 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabPlanner - - - NoControl - - - Battery Warning - - - Load param's from file - - - FBW max - - - 80, 63 - - - 65, 13 - - - CHK_hudshow - - - groupBox12 - - - STB_PIT_I - - - - - - 3 - - - 78, 20 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - 9 - - - label52 - - - - - - 78, 20 - - - label102 - - - groupBox7 - - - YW2SRV_IMAX - - - 4, 109 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 78, 20 - - - 78, 20 - - - 5 - - - 11 - - - 111, 36 - - - 78, 20 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 0 - - - - - - groupBox7 - - - - - - 78, 20 - - - 65, 13 - - - label53 - - - RATE_PIT_IMAX - - - 531, 6 - - - groupBox23 - - - 0 - - - 0 - - - 4 - - - 2 - - - label94 - - - 7 - - - - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 43, 13 - - - label58 - - - INT_MAX - - - 11 - - - 4, 22 - - - UI Language - - - groupBox1 - - - groupBox16 - - - - - - NAV_LAT_I - - - 111, 13 - - - 205, 1 - - - 1 - - - label95 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 730, 460 - - - 7 - - - - - - label59 - - - TabAPM2 - - - label24 - - - NoControl - - - 0 - - - 111, 36 - - - - - - groupBox25 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - RATE_YAW_P - - - 6 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox22 - - - 78, 20 - - - HDNG2RLL_P - - - 78, 20 - - - NoControl - - - 11 - - - NoControl - - - 139, 299 - - - 170, 91 - - - 25 - - - 80, 13 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 154, 17 - - - - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox9 - - - TabPlanner - - - 78, 20 - - - - - - 2 - - - NoControl - - - groupBox20 - - - label3 - - - - - - - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 111, 13 - - - NoControl - - - TabPlanner - - - label46 - - - 2 - - - 7 - - - 78, 20 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 12 - - - 6, 16 - - - groupBox7 - - - NoControl - - - Bottom, Left - - - - - - - - - 12 - - - label91 - - - ENRGY2THR_P - - - 65, 13 - - - - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 1 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 66 - - - 80, 37 - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - CHK_GDIPlus - - - 4 - - - label7 - - - 78, 20 - - - 11 - - - - - - 56, 17 - - - groupBox12 - - - 4 - - - label96 - - - 6 - - - NoControl - - - 0, 0, 0, 0 - - - 14 - - - 16 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 3 - - - - - - 111, 36 - - - groupBox19 - - - 16 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 78, 20 - - - 14 - - - 177, 17 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 138, 21 - - - 5 - - - NoControl - - - - - - 5 - - - groupBox10 - - - groupBox8 - - - 78, 20 - - - TabPlanner - - - 7 - - - 4 - - - 52, 13 - - - 5 - - - 15, 13 - - - 6, 66 - - - NoControl - - - - - - - - - - - - - - - 1 - - - 4 - - - 1 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 10, 13 - - - 150 - - - Cruise - - - - - - Max - - - groupBox25 - - - 3 - - - NoControl - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 111, 59 - - - 3 - - - toolTip1 - - - 111, 82 - - - IMAX - - - 6, 63 - - - groupBox9 - - - groupBox9 - - - 111, 36 - - - RLL2SRV_IMAX - - - 12 - - - ARSP2PTCH_P - - - 27 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 5 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - 80, 86 - - - 5 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox10 - - - 5 - - - 27, 13 - - - Nav Pitch AS Pid - - - 245, 67 - - - 590, 203 - - - label93 - - - 80, 63 - - - groupBox12 - - - RLL2SRV_I - - - label101 - - - 11 - - - CHK_mavdebug - - - 78, 20 - - - 139, 276 - - - label22 - - - 15 - - - 78, 20 - - - 5 - - - Stabilize Roll - - - 4 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 18 - - - 11 - - - - - - 5 - - - 10, 13 - - - CHK_speechwaypoint - - - - - - Enable Speech - - - CHK_speechaltwarning - - - - - - NoControl - - - 14, 13 - - - NUM_tracklength - - - BUT_Joystick - - - label23 - - - 6, 17 - - - - - - 65, 13 - - - 579, 67 - - - IMAX - - - 139, 117 - - - 78, 20 - - - P - - - - - - 68, 13 - - - 80, 13 - - - 78, 20 - - - groupBox8 - - - 0 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 9 - - - 0 - - - NoControl - - - label107 - - - 61, 13 - - - groupBox3 - - - - - - NoControl - - - Energy/Alt Pid - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - - - - - - - 78, 20 - - - Load - - - groupBox9 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 0 - - - 111, 82 - - - 195, 108 - - - - - - 358, 6 - - - 0 - - - Enable HUD Overlay - - - NoControl - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 205, 217 - - - 0 - - - ENRGY2THR_D - - - - - - - - - - - - groupBox10 - - - 3 - - - 80, 37 - - - 195, 108 - - - - - - - - - 139, 90 - - - groupBox23 - - - 722, 434 - - - 50, 13 - - - label64 - - - System.Windows.Forms.ToolTip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 1 - - - - - - 65, 13 - - - - - - 14, 13 - - - 14, 13 - - - P to T - - - groupBox10 - - - groupBox3 - - - 334, 200 - - - - - - BUT_writePIDS - - - Save params to file - - - 78, 20 - - - label65 - - - - - - 111, 13 - - - 10, 13 - - - - - - 3 - - - Reload params from device - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - Waypoint - - - 0 - - - 80, 37 - - - YW2SRV_I - - - 7 - - - 75, 23 - - - 80, 21 - - - 5 - - - 111, 13 - - - 28 - - - - - - 103, 19 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 0 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 195, 108 - - - 78, 20 - - - - - - TabPlanner - - - 24 - - - IMAX - - - 406, 325 - - - P - - - - - - 6 - - - IMAX - - - P - - - 5 - - - TabAPM2 - - - 80, 13 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 14, 13 - - - 4, 22 - - - NoControl - - - label60 - - - 170, 95 - - - 14, 13 - - - System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - TabAPM2 - - - 78, 20 - - - TabPlanner - - - 139, 146 - - - 10 - - - 5 - - - 3 - - - label61 - - - 20 - - - 10 - - - I - - - - 150 - - D - - - 30, 228 - - - 8 - - - 3 - - - groupBox21 - - - 6, 17 - - - 4, 22 - - + True - - - 78, 20 - - - - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 5 - - - HDNG2RLL_D - - - 111, 59 - - - NoControl - - - 14 - - - 10, 13 - - - NoControl - - - 2 - - - 205, 109 - - - 5 - - - 139, 40 - - - 11 - - - 5 - - - - - - 3, 198 - - - NoControl - - - IMAX - - - TabAC2 - - - 1 - - - 111, 82 - - - groupBox6 - - - 15 - - - APM 2.x - - - 6, 40 - - - label67 - - - P - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 13 - - - P - - - P - - - 1 - - - Joystick - - - 195, 108 - - - 78, 20 - - - 5 - - - 15 - - - Joystick Setup - - - 6, 17 - - - 2 - - - TRIM_THROTTLE - - - $this - - - 1 - - - groupBox6 - - - BUT_rerequestparams - - - 6, 17 - - - groupBox21 - - - 58 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 40 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 78, 20 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 195, 108 - - - - - - 111, 13 - - - 195, 108 - - - TabAC2 - - - NoControl - - - D - - - 1 - - - groupBox4 - - - 6, 17 - - - - - - - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Value 80 - - + + True + + + Default - - 6, 64 + + False - + + mavScale + + + False + + + True + + + RawValue + + + False + + + + 4, 4 + + + 4, 4, 4, 4 + + + 150 + + + 359, 503 + + + 58 + + + Params + + + System.Windows.Forms.DataGridView, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 6 + + + Top, Bottom, Left, Right + + + 148, 101 + + + 4, 4, 4, 4 + + + 104, 22 + + + 11 + + + THR_FS_VALUE + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox3 + + + 0 + + + NoControl + + + 8, 106 + + + 4, 0, 4, 0 + + + 67, 16 + + + 12 + + + FS Value + + + label5 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 15, 13 + + groupBox3 - - 6, 17 - - - - - - 7 - - - 2 - - - 44, 13 - - - groupBox14 - - - 195, 108 - - - groupBox6 - - - 78, 20 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 80, 37 - - - TabPlanner - - - 10, 13 - - - RATE_PIT_I - - - 78, 20 - - - 4 - - - 22 - - - PTCH2SRV_P - - - 6, 16 - - - 7 - - - 5 - - - NoControl - - - Rudder Mix - - - XTRK_GAIN_SC - - - - - - NoControl - - - Video Device - - - 4 - - - 14 - - - TabPlanner - - - 75, 23 - - - TabAPM2 - - - 78, 20 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 10 - - - - - + 1 - - INT_MAX + + 148, 73 - - 10, 13 + + 4, 4, 4, 4 - - label68 + + 104, 22 - - 6, 40 + + 9 - - 188, 200 - - - ENRGY2THR_I - - - + + THR_MAX System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - STB_PIT_P + + groupBox3 - - 283, 168 + + 2 - - 6 + + NoControl - - ARSP2PTCH_D + + 8, 78 - - 6, 40 + + 4, 0, 4, 0 - + + 36, 16 + + + 13 + + + Max + + + label6 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox3 + + + 3 + + + 148, 44 + + + 4, 4, 4, 4 + + + 104, 22 + + + 7 + + + THR_MIN + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - HLD_LAT_P + + groupBox3 - + + 4 + + + NoControl + + + 8, 49 + + + 4, 0, 4, 0 + + + 32, 16 + + + 14 + + + Min + + + label7 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 30 + + groupBox3 - + + 5 + + + 148, 16 + + + 4, 4, 4, 4 + + + 104, 22 + + + 5 + + + TRIM_THROTTLE + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox3 + + + 6 + + + NoControl + + + 8, 21 + + + 4, 0, 4, 0 + + + 48, 16 + + + 15 + + + Cruise + + + label8 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + groupBox3 + + + 7 + + + 540, 267 + + + 4, 4, 4, 4 + + + 4, 4, 4, 4 + + + 260, 133 + + + 0 + + + Throttle 0-100% + + + groupBox3 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAPM2 + + + 0 + + + 148, 101 + + + 4, 4, 4, 4 + + + 104, 22 + + + 0 + + + ARSPD_RATIO + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 0 + + + NoControl + + + 8, 107 + + + 4, 0, 4, 0 + + + 43, 16 + + + 1 + + + Ratio + + + label1 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 1 + + + 148, 73 + + + 4, 4, 4, 4 + + + 104, 22 + + + 2 + + + ARSPD_FBW_MAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 2 + + + NoControl + + + 8, 73 + + + 4, 0, 4, 0 + + + 71, 16 + + + 3 + + + FBW max + + + label2 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 3 + + + 148, 44 + + + 4, 4, 4, 4 + + + 104, 22 + + + 4 + + + ARSPD_FBW_MIN + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 4 + + + NoControl + + + 8, 49 + + + 4, 0, 4, 0 + + + 67, 16 + + + 5 + + + FBW min + + + label3 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 5 + + + 148, 16 + + + 4, 4, 4, 4 + + + 104, 22 + + + 5 + + + TRIM_ARSPD_CM + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 6 + + + NoControl + + + 8, 21 + + + 4, 0, 4, 0 + + + 85, 16 + + + 6 + + + Cruise + + + label4 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 7 + + + 541, 400 + + + 4, 4, 4, 4 + + + 4, 4, 4, 4 + + + 260, 133 + + + 1 + + + Airspeed m/s + + + groupBox1 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + TabAPM2 - - 170, 110 + + 1 + + + 148, 73 + + + 4, 4, 4, 4 + + + 104, 22 + + + 9 + + + LIM_PITCH_MIN + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 0 + + + NoControl + + + 8, 78 + + + 4, 0, 4, 0 + + + 68, 16 + + + 10 + + + Pitch Min + + + label39 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 1 + + + 148, 44 + + + 4, 4, 4, 4 + + + 104, 22 + + + 7 + + + LIM_PITCH_MAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 2 + + + NoControl + + + 8, 49 + + + 4, 0, 4, 0 + + + 72, 16 + + + 11 + + + Pitch Max + + + label38 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 3 + + + 148, 16 + + + 4, 4, 4, 4 + + + 104, 22 + + + 5 + + + LIM_ROLL_CD + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 4 + + + NoControl + + + 8, 21 + + + 4, 0, 4, 0 + + + 73, 16 + + + 12 + + + Bank Max + + + label37 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 5 + + + 273, 400 + + + 4, 4, 4, 4 + + + 4, 4, 4, 4 + + + 260, 133 + + + 2 + + + Navigation Angles + + + groupBox2 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAPM2 + + + 2 + + + 148, 44 + + + 4, 4, 4, 4 + + + 104, 22 + + + 7 + + + XTRK_ANGLE_CD + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox15 + + + 0 + + + NoControl + + + 8, 49 + + + 4, 0, 4, 0 + + + 81, 16 + + + 8 + + + Entry Angle + + + label79 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox15 + + + 1 + + + 148, 16 + + + 4, 4, 4, 4 + + + 104, 22 + + + 5 + + + XTRK_GAIN_SC + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox15 + + + 2 + + + NoControl + + + 8, 21 + + + 4, 0, 4, 0 + + + 69, 16 + + + 9 + + + Gain (cm) + + + label80 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox15 + + + 3 + + + 5, 400 + + + 4, 4, 4, 4 + + + 4, 4, 4, 4 + + + 260, 133 + + + 3 + + + Xtrack Pids + + + groupBox15 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAPM2 + + + 3 + + + 148, 16 + + + 4, 4, 4, 4 + + + 104, 22 + + + 13 + + + KFF_PTCH2THR + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox16 + + + 0 + + + NoControl + + + 8, 21 + + + 4, 0, 4, 0 + + + 48, 16 + + + 14 + + + P to T + + + label83 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox16 + + + 1 + + + 148, 73 + + + 4, 4, 4, 4 + + + 104, 22 + + + 9 + + + KFF_RDDRMIX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox16 + + + 2 + + + NoControl + + + 8, 78 + + + 4, 0, 4, 0 + + + 81, 16 + + + 15 + + + Rudder Mix + + + label78 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox16 + + + 3 + + + 148, 44 + + + 4, 4, 4, 4 + + + 104, 22 + + + 7 + + + KFF_PTCHCOMP + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox16 + + + 4 + + + NoControl + + + 8, 49 + + + 4, 0, 4, 0 - 61, 13 + 81, 16 - - 44, 13 + + 16 + + + Pitch Comp + + + label81 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox16 + + + 5 + + + 273, 267 + + + 4, 4, 4, 4 + + + 4, 4, 4, 4 + + + 260, 133 + + + 4 + + + Other Mix's + + + groupBox16 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAPM2 + + + 4 + + + 148, 101 + + + 4, 4, 4, 4 + + + 104, 22 + + + 11 + + + ENRGY2THR_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox14 + + + 0 + + + NoControl + + + 8, 106 + + + 4, 0, 4, 0 + + + 72, 16 + + + 12 + + + INT_MAX + + + label73 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox14 + + + 1 + + + 148, 73 + + + 4, 4, 4, 4 + + + 104, 22 + + + 9 + + + ENRGY2THR_D + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox14 + + + 2 + + + NoControl + + + 8, 78 + + + 4, 0, 4, 0 + + + 20, 16 + + + 13 + + + D + + + label74 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox14 + + + 3 + + + 148, 44 + + + 4, 4, 4, 4 + + + 104, 22 + + + 7 + + + ENRGY2THR_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox14 + + + 4 + + + NoControl + + + 8, 49 + + + 4, 0, 4, 0 + + + 13, 16 + + + 14 + + + I + + + label75 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox14 + + + 5 + + + 148, 16 + + + 4, 4, 4, 4 + + + 104, 22 + + + 5 + + + ENRGY2THR_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox14 + + + 6 + + + NoControl + + + 8, 21 + + + 4, 0, 4, 0 + + + 19, 16 + + + 15 + + + P + + + label76 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox14 + + + 7 + + + 5, 267 + + + 4, 4, 4, 4 + + + 4, 4, 4, 4 + + + 260, 133 + + + 5 + + + Energy/Alt Pid + + + groupBox14 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAPM2 + + + 5 + + + 148, 101 + + + 4, 4, 4, 4 + + + 104, 22 + + + 0 + + + ALT2PTCH_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox13 + + + 0 + + + NoControl + + + 8, 106 + + + 4, 0, 4, 0 + + + 72, 16 + + + 1 + + + INT_MAX label69 - - + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 182, 6 + + groupBox13 - + + 1 + + + 148, 73 + + + 4, 4, 4, 4 + + + 104, 22 + + + 2 + + + ALT2PTCH_D + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 15, 13 + + groupBox13 - + + 2 + + NoControl - - + + 8, 78 - + + 4, 0, 4, 0 + + + 20, 16 + + + 3 + + + D + + + label70 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox13 + + + 3 + + + 148, 44 + + + 4, 4, 4, 4 + + + 104, 22 + + + 4 + + + ALT2PTCH_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox13 + + + 4 + + + NoControl + + + 8, 49 + + + 4, 0, 4, 0 + + + 13, 16 + + + 5 + + + I + + + label71 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox13 + + + 5 + + + 148, 16 + + + 4, 4, 4, 4 + + + 104, 22 + + + 6 + + + ALT2PTCH_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox13 + + + 6 + + + NoControl + + + 8, 21 + + + 4, 0, 4, 0 + + + 19, 16 + + + 7 + + + P + + + label72 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox13 + + + 7 + + + 541, 134 + + + 4, 4, 4, 4 + + + 4, 4, 4, 4 + + + 260, 133 + + + 6 + + + Nav Pitch Alt Pid + + + groupBox13 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAPM2 + + + 6 + + + 148, 101 + + + 4, 4, 4, 4 + + + 104, 22 + + + 0 + + + ARSP2PTCH_IMAX + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 groupBox12 - + + 0 + + NoControl - - + + 8, 106 - - + + 4, 0, 4, 0 - - THR_MIN + + 72, 16 - - 65 - - - 170, 110 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - 78, 20 - - - - - - 6, 66 - - - 4 - - - Command - - - 5 - - - 13 - - - groupBox11 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 40 - - - 80, 37 - - - 4 - - - 6 - - - TabAPM2 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - + 1 - - NoControl + + INT_MAX - - 5 + + label65 - + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 11 + + groupBox12 - - + + 1 - - I + + 148, 73 - - 0 + + 4, 4, 4, 4 - - 34 + + 104, 22 - - 0 - - - 78, 20 - - - 111, 36 - - - groupBox23 - - - groupBox6 - - + 2 - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + ARSP2PTCH_D - - 15, 13 + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - label78 + + groupBox12 - - ConfigTabs - - + 2 - - TabAC2 - - - Top, Bottom, Left, Right - - - Ratio - - - groupBox16 - - - 65, 13 - - - groupBox8 - - - groupBox7 - - - ConfigTabs - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - ALT2PTCH_I - - - - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - + NoControl - - + + 8, 78 - - 14, 13 + + 4, 0, 4, 0 - - + + 20, 16 - - + + 3 - - 102, 17 + + D + + + label66 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox12 + + + 3 + + + 148, 44 + + + 4, 4, 4, 4 + + + 104, 22 + + + 4 ARSP2PTCH_I - - groupBox1 - - - 15 - - - 11 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 278, 0 - - + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - groupBox22 + + groupBox12 - - 6, 40 + + 4 - - 6, 40 - - + NoControl - - 111, 36 + + 8, 49 - - + + 4, 0, 4, 0 - - + + 13, 16 - - 12 + + 5 - + + I + + + label67 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox12 + + + 5 + + + 148, 16 + + + 4, 4, 4, 4 + + + 104, 22 + + + 6 + + + ARSP2PTCH_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox12 + + + 6 + + + NoControl + + + 8, 21 + + + 4, 0, 4, 0 + + + 19, 16 + + 7 - - 3 + + P - - + + label68 - - NoControl + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 14 + + groupBox12 - - 33 + + 7 - - 15 + + 273, 134 - - 6, 16 + + 4, 4, 4, 4 - + + 4, 4, 4, 4 + + + 260, 133 + + + 7 + + + Nav Pitch AS Pid + + + groupBox12 + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 TabAPM2 - - Track Length - - - label86 - - - 3 - - - CMB_distunits - - - label4 - - - groupBox15 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 31 - - - 6, 40 - - - NoControl - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox13 - - - label2 - - - 12 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 66 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - 12 - - - 15 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 402, 13 - - - 2 - - - 15 - - - Min - - - label6 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 63 - - - 61, 13 - - - 111, 82 - - - P - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - label8 - - - groupBox19 - - - 30, 277 - - - 125, 17 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 78, 20 - - - 14, 13 - - - 80, 63 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - groupBox13 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 80, 37 - - + 7 - - 30, 149 + + 148, 101 - - + + 4, 4, 4, 4 - - 111, 59 + + 104, 22 - - groupBox1 + + 11 - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + HDNG2RLL_IMAX - - 22 + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 10, 13 + + groupBox11 - - + + 0 - - Nav Pitch Alt Pid + + NoControl - - Write Params + + 8, 106 - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 4, 0, 4, 0 - - + + 72, 16 - - 30, 122 - - - groupBox21 - - - 2 - - - - - - Servo Roll Pid - - + 12 - - RLL2SRV_P + + INT_MAX - + + label61 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox11 + + + 1 + + + 148, 73 + + + 4, 4, 4, 4 + + + 104, 22 + + + 9 + + + HDNG2RLL_D + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox11 + + + 2 + + + NoControl + + + 8, 78 + + + 4, 0, 4, 0 + + + 20, 16 + + + 13 + + + D + + + label62 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox11 + + + 3 + + + 148, 44 + + + 4, 4, 4, 4 + + + 104, 22 + + + 7 + + + HDNG2RLL_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox11 + + + 4 + + + NoControl + + + 8, 49 + + + 4, 0, 4, 0 + + + 13, 16 + + + 14 + + + I + + + label63 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox11 + + + 5 + + + 148, 16 + + + 4, 4, 4, 4 + + + 104, 22 + + + 5 + + + HDNG2RLL_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox11 + + + 6 + + + NoControl + + + 8, 21 + + + 4, 0, 4, 0 + + + 19, 16 + + + 15 + + + P + + + label64 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox11 + + + 7 + + + 5, 134 + + + 4, 4, 4, 4 + + + 4, 4, 4, 4 + + + 260, 133 + + + 8 + + + Nav Roll Pid + + + groupBox11 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAPM2 + + + 8 + + + 148, 101 + + + 4, 4, 4, 4 + + + 104, 22 + + + 11 + + + YW2SRV_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox10 + + + 0 + + + NoControl + + + 8, 106 + + + 4, 0, 4, 0 + + + 72, 16 + + + 12 + + + INT_MAX + + + label57 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox10 + + + 1 + + + 148, 73 + + + 4, 4, 4, 4 + + + 104, 22 + + 9 YW2SRV_D - + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox10 + + + 2 + + + NoControl + + + 8, 78 + + + 4, 0, 4, 0 + + + 20, 16 + + + 13 + + + D + + + label58 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox10 + + + 3 + + + 148, 44 + + + 4, 4, 4, 4 + + + 104, 22 + + 7 + + YW2SRV_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox10 + + + 4 + + + NoControl + + + 8, 49 + + + 4, 0, 4, 0 + + + 13, 16 + + + 14 + + + I + + + label59 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox10 + + + 5 + + + 148, 16 + + + 4, 4, 4, 4 + + + 104, 22 + + + 5 + + + YW2SRV_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox10 + + + 6 + + + NoControl + + + 8, 21 + + + 4, 0, 4, 0 + + + 19, 16 + + + 15 + + + P + + + label60 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox10 + + + 7 + + + 541, 1 + + + 4, 4, 4, 4 + + + 4, 4, 4, 4 + + + 260, 133 + + + 9 + + + Servo Yaw Pid + + + groupBox10 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAPM2 + + + 9 + + + 148, 101 + + + 4, 4, 4, 4 + + + 104, 22 + + + 11 + + + PTCH2SRV_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox9 + + + 0 + + + NoControl + + + 8, 106 + + + 4, 0, 4, 0 + + + 72, 16 + + + 12 + + + INT_MAX + + + label53 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox9 + + + 1 + + + 148, 73 + + + 4, 4, 4, 4 + + + 104, 22 + + + 9 + + + PTCH2SRV_D + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox9 + + + 2 + + + NoControl + + + 8, 78 + + + 4, 0, 4, 0 + + + 20, 16 + + + 13 + + + D + + + label54 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox9 + + + 3 + + + 148, 44 + + + 4, 4, 4, 4 + + + 104, 22 + + + 7 + + + PTCH2SRV_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox9 + + + 4 + + + NoControl + + + 8, 49 + + + 4, 0, 4, 0 + + + 13, 16 + + + 14 + + + I + + + label55 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox9 + + + 5 + + + 148, 16 + + + 4, 4, 4, 4 + + + 104, 22 + + + 5 + + + PTCH2SRV_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox9 + + + 6 + + + NoControl + + + 8, 21 + + + 4, 0, 4, 0 + + + 19, 16 + + + 15 + + + P + + + label56 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox9 + + + 7 + + + 273, 1 + + + 4, 4, 4, 4 + + + 4, 4, 4, 4 + + + 260, 133 + + + 10 + + + Servo Pitch Pid + + + groupBox9 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAPM2 + + + 10 + + + 148, 101 + + + 4, 4, 4, 4 + + + 104, 22 + + + 11 + + + RLL2SRV_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox8 + + + 0 + + + NoControl + + + 8, 106 + + + 4, 0, 4, 0 + + + 72, 16 + + + 12 + + + INT_MAX + + + label49 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox8 + + + 1 + + + 148, 73 + + + 4, 4, 4, 4 + + + 104, 22 + + + 9 + + + RLL2SRV_D + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox8 + + + 2 + + + NoControl + + + 8, 78 + + + 4, 0, 4, 0 + + + 20, 16 + + + 13 + + + D + + + label50 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox8 + + + 3 + + + 148, 44 + + + 4, 4, 4, 4 + + + 104, 22 + + + 7 + + + RLL2SRV_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox8 + + + 4 + + + NoControl + + + 8, 49 + + + 4, 0, 4, 0 + + + 13, 16 + + + 14 + + + I + + + label51 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox8 + + + 5 + + + 148, 16 + + + 4, 4, 4, 4 + + + 104, 22 + + + 5 + + + RLL2SRV_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox8 + + + 6 + + + NoControl + + + 8, 21 + + + 4, 0, 4, 0 + + + 19, 16 + + + 15 + + + P + + + label52 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox8 + + + 7 + + + 5, 1 + + + 4, 4, 4, 4 + + + 4, 4, 4, 4 + + + 260, 133 + + + 11 + + + Servo Roll Pid + + + groupBox8 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAPM2 + + + 11 + + + 4, 22 + + + 0, 0, 0, 0 + + + 965, 540 + + + 0 + + + APM 2.x + + + TabAPM2 + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + ConfigTabs + + + 0 + + + NoControl + + + 8, 81 + + + 4, 0, 4, 0 + + + 87, 16 + + + 16 + + + IMAX + + + label14 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox5 + + + 0 + + + 107, 78 + + + 4, 4, 4, 4 + + + 104, 22 + + + 11 + + + THR_RATE_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox5 + + + 1 + + + 107, 46 + + + 4, 4, 4, 4 + + + 104, 22 + + + 7 + + + THR_RATE_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox5 + + + 2 + + + NoControl + + + 8, 49 + + + 4, 0, 4, 0 + + + 13, 16 + + + 14 + + + I + + + label20 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox5 + + + 3 + + + 107, 16 + + + 4, 4, 4, 4 + + + 104, 22 + + + 5 + + + THR_RATE_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox5 + + + 4 + + + NoControl + + + 8, 20 + + + 4, 0, 4, 0 + + + 19, 16 + + + 15 + + + P + + + label25 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox5 + + + 5 + + + 8, 292 + + + 4, 4, 4, 4 + + + 4, 4, 4, 4 + + + 227, 135 + + + 16 + + + Throttle Rate + + + groupBox5 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAC2 + + + 0 + + + True + + + 4, 244 + + + 4, 4, 4, 4 + + + 198, 21 + + + 13 + + + Lock Pitch and Roll Values + + + CHK_lockrollpitch + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAC2 + + + 1 + + + 107, 106 + + + 4, 4, 4, 4 + + + 104, 22 + + + 16 + + + WP_SPEED_MAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 0 + + + NoControl + + + 8, 110 + + + 4, 0, 4, 0 + + + 72, 16 + + + 17 + + + m/s + + + label9 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 1 + + + 107, 78 + + + 4, 4, 4, 4 + + + 104, 22 + + + 11 + + + NAV_LAT_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 2 + + + NoControl + + + 8, 81 + + + 4, 0, 4, 0 + + + 87, 16 + + + 12 + + + IMAX + + + label13 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 3 + + + 107, 46 + + + 4, 4, 4, 4 + + + 104, 22 + + + 7 + + + NAV_LAT_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 4 + + + NoControl + + + 8, 49 + + + 4, 0, 4, 0 + + + 13, 16 + + + 14 + + + I + + + label15 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 5 + + + 107, 16 + + + 4, 4, 4, 4 + + + 104, 22 + + + 5 + + + NAV_LAT_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 6 + + + NoControl + + + 8, 20 + + + 4, 0, 4, 0 + + + 19, 16 + + + 15 + + + P + + + label16 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 7 + + + 712, 132 + + + 4, 4, 4, 4 + + + 4, 4, 4, 4 + + + 227, 133 + + + 0 + + + Nav WP + + + groupBox4 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAC2 + + + 2 + + + 107, 106 + + + 4, 4, 4, 4 + + + 104, 22 + + + 18 + + + XTRK_ANGLE_CD1 + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox6 + + + 0 + + + NoControl + + + 8, 110 + + + 4, 0, 4, 0 + + + 109, 16 + + + 19 + + + Error Max + + + label10 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox6 + + + 1 + + + 107, 78 + + + 4, 4, 4, 4 + + + 104, 22 + + + 11 + + + XTRACK_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox6 + + + 2 + + + NoControl + + + 8, 81 + + + 4, 0, 4, 0 + + + 87, 16 + + + 12 + + + IMAX + + + label11 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox6 + + + 3 + + + 107, 46 + + + 4, 4, 4, 4 + + + 104, 22 + + + 7 + + + XTRACK_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox6 + + + 4 + + + NoControl + + + 8, 49 + + + 4, 0, 4, 0 + + + 13, 16 + + + 14 + + + I + + + label17 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox6 + + + 5 + + + 107, 16 + + + 4, 4, 4, 4 + + + 104, 22 + + + 5 + + + XTRACK_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox6 + + + 6 + + + NoControl + + + 8, 20 + + + 4, 0, 4, 0 + + + 19, 16 + + + 15 + + + P + + + label18 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox6 + + + 7 + + + 477, 292 + + + 4, 4, 4, 4 + + + 4, 4, 4, 4 + + + 227, 135 + + + 2 + + + Crosstrack Correction + + + groupBox6 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAC2 + + + 3 + + + 107, 78 + + + 4, 4, 4, 4 + + + 104, 22 + + + 11 + + + THR_ALT_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox7 + + + 0 + + + NoControl + + + 8, 81 + + + 4, 0, 4, 0 + + + 87, 16 + + + 12 + + + IMAX + + + label19 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox7 + + + 1 + + + 107, 46 + + + 4, 4, 4, 4 + + + 104, 22 + + + 7 + + + THR_ALT_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox7 + + + 2 + + + NoControl + + + 8, 49 + + + 4, 0, 4, 0 + + + 13, 16 + + + 14 + + + I + + + label21 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox7 + + + 3 + + + 107, 16 + + + 4, 4, 4, 4 + + + 104, 22 + + + 5 + + + THR_ALT_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox7 + + + 4 + + + NoControl + + + 8, 20 + + + 4, 0, 4, 0 + + + 19, 16 + + + 15 + + + P + + + label22 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox7 + + + 5 + + + 243, 292 + + + 4, 4, 4, 4 + + + 4, 4, 4, 4 + + + 227, 135 + + + 3 + + + Altitude Hold + groupBox7 - - 28 + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 80, 13 + + TabAC2 - + + 4 + + + 107, 75 + + + 4, 4, 4, 4 + + + 104, 22 + + + 11 + + + HLD_LAT_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox19 + + + 0 + + + NoControl + + + 8, 79 + + + 4, 0, 4, 0 + + + 87, 16 + + + 12 + + + IMAX + + + label28 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox19 + + + 1 + + + 107, 46 + + + 4, 4, 4, 4 + + + 104, 22 + + + 7 + + + HLD_LAT_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox19 + + + 2 + + + NoControl + + + 8, 49 + + + 4, 0, 4, 0 + + + 13, 16 + + + 14 + + + I + + + label30 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox19 + + + 3 + + + 107, 16 + + + 4, 4, 4, 4 + + + 104, 22 + + + 5 + + + HLD_LAT_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox19 + + + 4 + + + NoControl + + + 8, 20 + + + 4, 0, 4, 0 + + + 19, 16 + + + 15 + + + P + + + label31 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox19 + + + 5 + + + 708, 7 + + + 4, 4, 4, 4 + + + 4, 4, 4, 4 + + + 227, 117 + + + 6 + + + Loiter + + + groupBox19 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAC2 + + + 5 + + + 107, 78 + + + 4, 4, 4, 4 + + + 104, 22 + + + 11 + + + STB_YAW_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox20 + + + 0 + + + NoControl + + + 8, 81 + + + 4, 0, 4, 0 + + + 87, 16 + + + 12 + + + IMAX + + + label32 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox20 + + + 1 + + + 107, 46 + + + 4, 4, 4, 4 + + + 104, 22 + + + 7 + + + STB_YAW_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox20 + + + 2 + + + NoControl + + + 8, 49 + + + 4, 0, 4, 0 + + + 13, 16 + + + 14 + + + I + + + label34 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox20 + + + 3 + + + 107, 16 + + + 4, 4, 4, 4 + + + 104, 22 + + + 5 + + + STB_YAW_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox20 + + + 4 + + + NoControl + + + 8, 20 + + + 4, 0, 4, 0 + + + 19, 16 + + + 15 + + + P + + + label35 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox20 + + + 5 + + + 477, 7 + + + 4, 4, 4, 4 + + + 4, 4, 4, 4 + + + 227, 117 + + + 7 + + + Stabilize Yaw + + + groupBox20 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAC2 + + + 6 + + + 107, 78 + + + 4, 4, 4, 4 + + + 104, 22 + + + 11 + + + STB_PIT_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox21 + + + 0 + + + NoControl + + + 8, 81 + + + 4, 0, 4, 0 + + + 87, 16 + + + 12 + + + IMAX + + + label36 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox21 + + + 1 + + + 107, 46 + + + 4, 4, 4, 4 + + + 104, 22 + + + 7 + + + STB_PIT_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox21 + + + 2 + + + NoControl + + + 8, 49 + + + 4, 0, 4, 0 + + + 13, 16 + + + 14 + + + I + + + label41 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox21 + + + 3 + + + 107, 16 + + + 4, 4, 4, 4 + + + 104, 22 + + + 5 + + + STB_PIT_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox21 + + + 4 + + + NoControl + + + 8, 20 + + + 4, 0, 4, 0 + + + 19, 16 + + + 15 + + + P + + + label42 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox21 + + + 5 + + + 243, 7 + + + 4, 4, 4, 4 + + + 4, 4, 4, 4 + + + 227, 117 + + + 8 + + + Stabilize Pitch + + + groupBox21 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAC2 + + + 7 + + + 107, 78 + + + 4, 4, 4, 4 + + + 104, 22 + + + 11 + + + STB_RLL_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox22 + + + 0 + + + NoControl + + + 8, 81 + + + 4, 0, 4, 0 + + + 87, 16 + + + 12 + + + IMAX + + + label43 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox22 + + + 1 + + + 107, 46 + + + 4, 4, 4, 4 + + + 104, 22 + + + 7 + + + STB_RLL_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox22 + + + 2 + + + NoControl + + + 8, 49 + + + 4, 0, 4, 0 + + + 13, 16 + + + 14 + + + I + + + label45 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox22 + + + 3 + + + 107, 16 + + + 4, 4, 4, 4 + + + 104, 22 + + + 5 + + + STB_RLL_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox22 + + + 4 + + + NoControl + + + 8, 20 + + + 4, 0, 4, 0 + + + 19, 16 + + + 15 + + + P + + + label46 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 groupBox22 - - 11 + + 5 - - mavScale + + 8, 7 - - label90 + + 4, 4, 4, 4 - - + + 4, 4, 4, 4 - - NoControl - - - Servo Pitch Pid - - - TabPlanner - - - - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 13 + + 227, 117 9 - - Bottom, Left + + Stabilize Roll - - 1 + + groupBox22 - - 78, 20 + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + TabAC2 - - PTCH2SRV_D + + 8 - - m/s + + 107, 78 - - 7 + + 4, 4, 4, 4 - - 195, 108 + + 104, 22 - - P + + 0 - - Telemetry Rates + + RATE_YAW_IMAX - - label45 - - - I - - - groupBox15 - - - 111, 82 - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - - - - 78, 20 - - - - - - 1 - - + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + + groupBox23 + + + 0 + + + NoControl + + + 8, 81 + + + 4, 0, 4, 0 + + + 87, 16 + + + 1 + + + IMAX + + + label47 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - NoControl + + groupBox23 - - groupBox4 + + 1 - - 18 + + 107, 46 - - 78, 20 + + 4, 4, 4, 4 - + + 104, 22 + + + 4 + + + RATE_YAW_I + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 30, 176 + + groupBox23 - - 65, 13 + + 2 - - HDNG2RLL_IMAX - - - 6, 66 - - + NoControl - - 78, 20 + + 8, 49 + + + 4, 0, 4, 0 - 10, 13 + 13, 16 - - + + 5 - - Nav Roll Pid + + I - + + label77 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox23 + + 3 - + + 107, 16 + + + 4, 4, 4, 4 + + + 104, 22 + + + 6 + + + RATE_YAW_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox23 + + + 4 + + + NoControl + + + 8, 20 + + + 4, 0, 4, 0 + + + 19, 16 + + + 7 + + + P + + + label82 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + groupBox23 + + + 5 + + + 477, 132 + + + 4, 4, 4, 4 + + + 4, 4, 4, 4 + + + 227, 112 + + + 10 + + + Rate Yaw + + + groupBox23 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAC2 + + + 9 + + + 107, 78 + + + 4, 4, 4, 4 + + + 104, 22 + + + 0 + + + RATE_PIT_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox24 + + + 0 + + + NoControl + + + 8, 81 + + + 4, 0, 4, 0 + + + 87, 16 + + + 1 + IMAX - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + label84 - - STB_PIT_IMAX + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 5 + + groupBox24 - - 30, 94 + + 1 - + + 107, 46 + + + 4, 4, 4, 4 + + + 104, 22 + + + 4 + + + RATE_PIT_I + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - label97 + + groupBox24 + + + 2 + + + NoControl + + + 8, 49 + + + 4, 0, 4, 0 - 10, 13 + 13, 16 - - 23 + + 5 - + + I + + + label86 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox24 + + + 3 + + + 107, 16 + + + 4, 4, 4, 4 + + + 104, 22 + + + 6 + + + RATE_PIT_P + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - Stabilize Pitch + + groupBox24 - - 6, 86 + + 4 - - ENRGY2THR_IMAX + + NoControl - - 4, 1 + + 8, 20 - - 29 + + 4, 0, 4, 0 + + + 19, 16 + + + 7 + + + P + + + label87 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox24 + + + 5 + + + 243, 132 + + + 4, 4, 4, 4 + + + 4, 4, 4, 4 + + + 227, 112 + + + 11 + + + Rate Pitch + + + groupBox24 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAC2 + + + 10 + + + 107, 78 + + + 4, 4, 4, 4 + + + 104, 22 + + + 0 + + + RATE_RLL_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox25 + + + 0 + + + NoControl + + + 8, 81 + + + 4, 0, 4, 0 + + + 91, 16 + + + 1 + + + IMAX + + + label88 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox25 + + + 1 + + + 107, 46 + + + 4, 4, 4, 4 + + + 104, 22 + + + 4 + + + RATE_RLL_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox25 + + + 2 + + + NoControl + + + 8, 49 + + + 4, 0, 4, 0 + + + 13, 16 + + + 5 + + + I + + + label90 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox25 + + + 3 + + + 107, 16 + + + 4, 4, 4, 4 + + + 104, 22 + + + 6 + + + RATE_RLL_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox25 + + + 4 + + + NoControl + + + 8, 20 + + + 4, 0, 4, 0 + + + 19, 16 + + + 7 + + + P + + + label91 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox25 + + + 5 + + + 8, 132 + + + 4, 4, 4, 4 + + + 4, 4, 4, 4 + + + 227, 112 + + + 12 + + + Rate Roll + + + groupBox25 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAC2 + + + 11 + + + 4, 22 + + + 4, 4, 4, 4 + + + 4, 4, 4, 4 + + + 965, 540 + + + 1 + + + AC2 + + + TabAC2 + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + ConfigTabs + + + 1 + + + NoControl + + + 40, 61 + + + 4, 0, 4, 0 + + + 133, 28 + + + 41 + + + Video Format + + + label26 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 0 + + + 185, 58 + + + 4, 4, 4, 4 + + + 543, 24 + + + 0 + + + CMB_videoresolutions + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 1 + + + NoControl + + + 40, 419 + + + 4, 0, 4, 0 + + + 81, 16 + + + 39 + + + HUD + + + label12 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 2 + + + NoControl + + + 185, 418 + + + 4, 4, 4, 4 + + + 236, 21 + + + 40 + + + GDI+ (old type) + + + 17, 17 + + + OpenGL = Disabled +GDI+ = Enabled + + + CHK_GDIPlus + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 3 + + + NoControl + + + 40, 391 + + + 4, 0, 4, 0 + + + 81, 16 + + + 37 + + + Waypoints + + + label24 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 4 + + + NoControl + + + 185, 390 + + + 4, 4, 4, 4 + + + 236, 21 + + + 38 + + + Load Waypoints on connect? + + + CHK_loadwponconnect + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 5 + + + NoControl + + + 40, 360 + + + 4, 0, 4, 0 + + + 137, 22 + + + 36 + + + Track Length + + + label23 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 6 + + + 185, 358 + + + 4, 4, 4, 4 + + + 89, 22 + + + 35 + + + On the Flight Data Tab + + + NUM_tracklength + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 7 + + + NoControl + + + 772, 132 + + + 4, 4, 4, 4 + + + 136, 21 + + + 34 + + + Alt Warning + + + CHK_speechaltwarning + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 8 + + + NoControl + + + 40, 331 + + + 4, 0, 4, 0 + + + 81, 16 + + + 0 + + + APM Reset + + + label108 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 TabPlanner - - groupBox4 + + 9 - - groupBox20 + + NoControl + + + 185, 329 + + + 4, 4, 4, 4 + + + 217, 21 + + + 1 + + + Reset APM on USB Connect + + + CHK_resetapmonconnect + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 10 + + + Bottom, Left + + + NoControl + + + 44, 506 + + + 4, 4, 4, 4 + + + 192, 21 + + + 2 + + + Mavlink Message Debug + + + CHK_mavdebug + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 11 + + + NoControl + + + 787, 300 + + + 4, 0, 4, 0 + + + 29, 16 + + + 3 + + + RC + + + label107 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 12 + + + 0 + + + 1 + + + 3 + + + 10 + + + 828, 296 + + + 4, 4, 4, 4 + + + 105, 24 + + + 4 + + + CMB_raterc + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 13 + + + NoControl + + + 567, 300 + + + 4, 0, 4, 0 + + + 92, 16 + + + 5 + + + Mode/Status + + + label104 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 14 + + + NoControl + + + 373, 300 + + + 4, 0, 4, 0 + + + 59, 16 + + + 6 + + + Position + + + label103 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 15 + + + NoControl + + + 181, 300 + + + 4, 0, 4, 0 + + + 57, 16 + + + 7 + + + Attitude + + + label102 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 16 + + + NoControl + + + 36, 300 + + + 4, 0, 4, 0 + + + 112, 16 + + + 8 + + + Telemetry Rates + + + label101 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 17 + + + 0 + + + 1 3 @@ -2664,3867 +5797,1064 @@ 10 - - 4 - - - 4 - - - 13 - - - groupBox7 - - - 23 - - - groupBox2 - - - groupBox1 - - - NoControl - - - 3, 3 - - - groupBox6 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - P - - - TabAC2 - - - groupBox6 - - - - - - - - - - - - NoControl - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 16 - - - HUD - - - 0 - - - - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 40 - - - TabAC2 - - - 10, 13 - - - 7 - - - 0 - - - 0 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 7 - - - NoControl - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NAV_LAT_IMAX - - - 54, 13 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 52, 13 - - - I - - - 111, 59 - - - 50, 13 - - - 4, 217 - - - 80, 37 - - - TabAC2 - - - INT_MAX - - - - - - 14 - - - Bottom, Left - - - 78, 20 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 1 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox8 - - - label47 - - - NoControl - - - 195, 108 - - - Save - - - - - - ALT2PTCH_D - - - 6, 63 - - - TabPlanner - - - 3 - - - 9 - - - Bottom, Left - - - 14, 13 - - - Airspeed m/s - - - 102, 17 - - - label98 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 0, 0, 0, 0 - - - - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 86 - - - 6 - - - 3 - - - 78, 20 - - - 10 - - - 6 - - - 6, 16 - - - 2 - - - NoControl - - - Navigation Angles - - - groupBox24 - - - 5 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 1 - - - groupBox7 - - - False - - - CHK_speechcustom - - - groupBox20 - - - 16 - - - 78, 20 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - XTRK_ANGLE_CD - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 7 - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - 6 - - - NoControl - - - 17 - - - P - - - label42 - - - groupBox19 - - - D - - - 3 - - - CHK_loadwponconnect - - - 2 - - - Loiter - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - Throttle 0-100% - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - 15 - - - groupBox1 - - - 2 - - - 205, 325 - - - Start - - - NoControl - - - Nav WP - - - label43 - - - 78, 20 - - - 78, 20 - - - 65, 13 - - - 11 - - - - - - 78, 20 - - - 0 - - - 111, 82 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 36, 13 - - - 78, 20 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 78, 20 - - - 5 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - label108 - - - ConfigTabs - - - 12 - - - - - - 111, 36 - - - 78, 20 - - - 31 - - - groupBox14 - - - label49 - - - groupBox10 - - - Crosstrack Correction - - - 35 - - - - - - - - - - - - P - - - 30, 47 - - - THR_HOLD_I - - - groupBox19 - - - NoControl - - - ALT2PTCH_IMAX - - - - - - - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox2 - - - 15 - - - 8 - - - 26 - - - Altitude Hold - - - 57, 13 - - - groupBox1 - - - 12 - - - 6, 63 - - - 17 - - - groupBox19 - - - TabPlanner - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox4 - - - Lock Pitch and Roll Values - - - - - - 103, 18 - - - 13 - - - NoControl - - - NoControl - - - groupBox24 - - - 38 - - - 80, 63 - - - 71, 17 - - - 0 - - - 2 - - - 111, 82 - - - groupBox21 - - - 6, 86 - - - 0 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 37 - - - NoControl - - - groupBox13 - - - 11 - - - 3 - - - groupBox6 - - - 1 - - - NoControl - - - groupBox2 - - - 78, 20 - - - 80, 13 - - - groupBox11 - - - INT_MAX - - - 54, 13 - - - 30, 71 - - - 4, 22 - - - 4 - - - 6, 40 - - - 0 - - - NoControl - - - Value - - - NoControl - - - ARSPD_FBW_MIN - - - 14 - - - 7 - - - - - - 0 - - - 78, 20 - - - 14 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - Reset APM on USB Connect - - - 5 - - - 170, 91 - - - groupBox24 - - - TabPlanner - - - 78, 20 - - - 1 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - - - - 11 - - - 1 - - - 78, 20 - - - YW2SRV_P - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 59 - - - 10 - - - groupBox8 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 0 - - - 31, 438 - - - 78, 20 - - - ARSPD_FBW_MAX - - - Compare Params - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - label41 - - - groupBox25 - - - groupBox20 - - - CMB_speedunits - - - 722, 434 - - - - - - 20 - - - groupBox23 - - - groupBox3 - - - - - - - - - - - - 5 - - - 2 - - - 111, 59 - - - 15, 13 - - - 13 - - - 4, 325 - - - 11 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox23 - - - 78, 20 - - - - - - 78, 20 - - - - - - NoControl - - - 26 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 5 - - - 144, 17 - - - 78, 20 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox10 - - - 182, 241 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 78, 20 - - - groupBox2 - - - 78, 20 - - - - - - STB_YAW_P - - 499, 200 + 665, 296 - - + + 4, 4, 4, 4 - - - - - TabPlanner - - - 111, 13 - - - System.Windows.Forms.TabControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 78, 20 - - - 7 - - - D - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 621, 200 - - - 322, 67 - - - groupBox2 - - - groupBox11 - - - 2 - - - NoControl - - - groupBox2 - - - - - - 80, 13 - - - 4 - - - 6, 86 - - - 0 - - - 7 - - - 6, 17 - - - XTRACK_I - - - 7 - - - - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 2 - - - 30 - - - NoControl - - - 0, 0 - - - 169, 441 - - - 14 - - - 6 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 7 - - - NoControl - - - 15 - - - 54, 13 - - - 9 - - - 80, 37 - - - groupBox12 - - - 7 - - - groupBox24 - - - KFF_PTCH2THR - - - PTCH2SRV_IMAX - - - Bottom, Left - - - groupBox19 - - - Top, Bottom, Left - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 8 - - - $this - - - 25 - - - KFF_PTCHCOMP - - - 9 - - - 17 - - - I - - - 4 - - - 78, 20 - - - NoControl - - - 1 - - - 14 - - - On the Flight Data Tab - - - - - - 6, 107 - - - 45, 13 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 78, 20 - - - 138, 21 - - - groupBox3 + + 105, 24 9 - - groupBox20 + + CMB_ratestatus - - NoControl + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + TabPlanner - - THR_HOLD_IMAX + + 18 - - 4 - - - 4 - - + 0 - - Gain (cm) - - - 6 - - - NoControl - - - RATE_PIT_P - - - groupBox4 - - - - - - 5 - - - 7 - - - 4 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 6, 40 - - - - - - 170, 95 - - - - - - Rate Pitch - - - 4 - - - LIM_PITCH_MIN - - - TabPlanner - - - - - - 80, 21 - - - APM Reset - - + 1 - + 3 - - 7 - - - groupBox9 - - - 63 - - + 10 - - 13 + + 445, 296 - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 4, 4, 4, 4 - - CHK_enablespeech + + 105, 24 - - 7 + + 10 - - 21 + + CMB_rateposition - - groupBox22 + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 5 - - - 5 - - - groupBox2 - - + TabPlanner - - System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 19 - - 67, 20 + + 0 - - 14, 13 - - - TabPlanner - - - False - - - 75, 19 - - + 1 - - 30, 252 - - - 3, 3, 3, 3 - - - TabAC2 - - - 111, 13 - - - TabPlanner - - - 38 - - - NoControl - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 15 - - - 80, 63 - - - 1 - - - 4 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - + 3 10 - - 40 + + 251, 296 - - NoControl + + 4, 4, 4, 4 - - 2 + + 105, 24 - - 15, 13 - - - 111, 13 - - - 3 - - - - - - 5 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 0 - - - NoControl - - - 14, 13 - - - System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 1 - - - 5 - - - Cruise - - - 1 - - - 0 - - - 1 - - - 78, 20 - - - 78, 20 - - - TabPlanner - - - 5 - - - I - - - NoControl - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - Mode/Status - - - 2 - - - 9 - - - 80, 37 - - - 6 - - - NoControl - - - TabAC2 - - - 87, 17 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - label84 - - - 1 - - - 7 - - - - - - - - - label73 - - - 53, 13 - - - Servo Yaw Pid - - - 78, 20 - - - P - - - - - - Pitch Max - - - TabAPM2 - - - D - - - NoControl - - - label103 - - - 6 - - - groupBox14 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 1 - - + 11 - - 36 - - - - - - 6 - - - 3 - - - 78, 20 - - - Stabilize Yaw - - - 3 - - - groupBox20 - - - label34 - - - NoControl - - - 14, 13 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - groupBox15 - - - BUT_videostart - - - 5 - - - IMAX - - - - - - 33 - - - 3 - - - NoControl - - - 10, 13 - - - groupBox4 - - - 6 - - - 32, 13 - - - 5 - - - 1 - - - STB_RLL_P - - - label35 - - - TabPlanner - - - $this - - - 406, 109 - - - I - - - label62 - - - 4 - - - 1 - - - STB_YAW_IMAX - - - 177, 17 - - - NoControl - - - - - - 5 - - - TabPlanner - - - CMB_osdcolor - - - 3 - - - 0 - - - - - - - - - 78, 20 - - - CMB_ratestatus - - - 7 - - - 182, 107 - - - TabPlanner - - - label80 - - - - - - TabPlanner - - - THR_HOLD_P - - - 6, 63 - - - groupBox4 - - - 7 - - - 78, 20 - - - groupBox16 - - - NoControl - - - 5 - - - groupBox14 - - - 5 - - - 11 - - - - - - Speed Units - - - NoControl - - - label81 - - - 1 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 86 - - - - - - - - - BUT_save - - - 3 - - - groupBox20 - - - 14 - - - P - - - CHK_speechbattery - - - I - - - 24 - - - label30 - - - RawValue - - - label17 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - False - - - $this - - - Configuration - - - 40 - - - groupBox11 - - - HLD_LAT_IMAX - - - groupBox1 - - - 21 - - - groupBox13 - - - label31 - - - THR_MAX - - - 61, 13 - - - 14, 13 - - - TabPlanner - - - Alt Warning - - - 54, 13 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 36, 13 - - - STB_RLL_IMAX - - - 80, 13 - - - label87 - - - 6, 40 - - - 75, 19 - - - 6, 89 - - - 1 - - - KFF_RDDRMIX - - - groupBox14 - - - 4 - - - TabPlanner - - - label36 - - - TabPlanner - - - ARSP2PTCH_IMAX - - - groupBox9 - - - 78, 20 - - - groupBox25 - - - 4 - - - Time Interval - - - Other Mix's - - - - - - Mode - - - groupBox23 - - - - - - 405, 217 - - - RATE_YAW_I - - - 7 - - - 80, 13 - - - label12 - - - 0 - - - label37 - - - 5 - - - TabPlanner - - - 5 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - I - - - Attitude - - - P - - - 1 - - - RC - - - 6, 86 - - - 3 - - - NoControl - - - label82 - - - TabPlanner - - - 34 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 54, 13 - - - 1 - - - CMB_rateposition - - - groupBox21 - - - Speech - - - - - - 0 - - - 9 - - - - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 14, 13 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 3 - - - 5 - - - 1008, 461 - - - - - - TabAPM2 - - - Error Max - - - label83 - - - 3 - - - 0 - - - 0 - - - NoControl - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 195, 108 - - - 6 - - - 6 - - - 6, 40 - - - 7 - - - 6 - - - 111, 59 - - - label32 - - - groupBox13 - - - 1 - - - label88 - - - 78, 20 - - - groupBox22 - - - NoControl - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - NoControl - - - 2 - - - 170, 95 - - - 163, 17 - - - groupBox3 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 3 - - - 170, 91 - - - groupBox14 - - - label15 - - - groupBox4 - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 86 - - - RATE_RLL_P - - - 3 - - - 195, 108 - - - 3 - - - 19 - - - groupBox9 - - - 534, 107 - - - TabPlanner - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - 64 - - - 4 - - - 13 - - - label38 - - - groupBox1 - - - $this - - - 111, 59 - - - groupBox16 - - - 12 - - - 1 - - - TabPlanner - - - 82, 13 - - - groupBox6 - - - 0 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - 100, 23 - - - XTRACK_IMAX - - - label39 - - - 6, 16 - - - 78, 20 - - - RawValue - - - 12 - - - 6 - - - groupBox15 - - - 14 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - groupBox4 - - - - - - 1 - - - TabPlanner - - - - - - Default - - - 12 - - - TabAPM2 - - - LIM_PITCH_MAX - - - label10 - - - 0 - - - groupBox8 - - - 3 - - - - - - - - - 378, 67 - - - - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 99, 23 - - - 80, 63 - - - - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 14 - - - groupBox8 - - - TabPlanner - - - 6 - - - label11 - - - 6, 17 - - - 15 - - - 14 - - - - - - - - - 6, 16 - - - label1 - - - - - - 6, 66 - - - 111, 82 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - label16 - - - - - - 6, 66 - - - 80, 21 - - - ConfigTabs - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 241 - - - 0 - - - - - - 7 - - - 4 - - - INT_MAX - - - 65, 13 - - - 30, 300 - - - D - - - 9 - - - 12 - - - 6 - - - NoControl - - - label5 - - - groupBox14 - - - 111, 59 - - - 6, 17 - - - NoControl - - - 170, 95 - - - 10, 13 - - - - - - TabAPM2 - - - - - - 4 - - - 6, 40 - - - NoControl - - - 6, 40 - - - 14, 13 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - Refresh Params - - - CHK_lockrollpitch - - - HDNG2RLL_I - - - 12 - - - - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 6, 16 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 10, 13 - - - 19 - - - CMB_language - - - label9 - - - NoControl - - - NoControl - - - 7 - - - 471, 11 - - - groupBox12 - - - groupBox3 - - - - - - TabPlanner - - - 1 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 10 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 40 - - - IMAX - - - NoControl - - - 6, 17 - - - - - - NoControl - - - - - - 2 - - - XTRACK_P - - - 14 - - - NoControl - - - 4 - - - TabPlanner - - - - - - 4 - - - I - - - 425, 203 - - - Value - - - 139, 250 - - - 6, 16 - - - 36 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - - - - TabAPM2 - - - label13 - - - mavScale - - - groupBox16 - - - TabAC2 - - - 80, 86 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabSetup - - - NoControl - - - 4 - - - I - - - P - - - 2 - - - I - - - 111, 13 - - - label18 - - - 0 - - - 14, 13 - - - groupBox3 - - - 0 - - - - - - 5 - - - 6, 66 - - - 80, 61 - - - Waypoints - - - - - - 15 - - - 138, 21 - - - $this - - - label19 - - - - - - groupBox22 - - - 78, 20 - - - 78, 20 - - - 6, 17 - - - 1 - - - TabAC2 - - - 39 - - - Command - - - - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - 10 - - - 170, 108 - - - 27 - - - 2 - - - groupBox11 - - - 6, 40 - - - 2 - - - Pitch Comp - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 19 - - - 5 - - - FBW min - - - NoControl - - - D - - - 51, 13 - - - I - - - 6, 66 - - - - CMB_rateattitude - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - HLD_LAT_I - - - 6, 40 - - - 6, 40 - - - I - - - groupBox12 - - - 12 - - - 2 - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 103, 19 - - - 111, 13 - - - - - + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - groupBox10 - - - 6, 63 - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - 82, 416 - - - - - - 5 - - - 78, 20 - - - Bank Max - - - AC2 - - - groupBox9 - - - 78, 20 - - - - - - 78, 20 - - - 4 - - - 103, 19 - - - groupBox14 - - - groupBox13 - - - - - - 6, 16 - - - 2 - - - 1 - - - - - - 80, 63 - - - 54, 13 - - - 6 - - - 0 - - - - - - 69, 13 - - - 6, 63 - - - Rate Yaw - - - 13 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - TabAC2 - - - FS Value - - - 5 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - + TabPlanner - - 10, 13 + + 20 - + + NoControl + + + 377, 257 + + + 4, 0, 4, 0 + + + 536, 16 + + 12 - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - groupBox16 - - - 111, 36 - - - - - - 7 - - - 15 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 7 - - - - - - BUT_videostop - - - CHK_resetapmonconnect - - - - - - 14, 13 - - - 245, 21 - - - 15 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 11 - - - NoControl - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 1 - - - 3 - - - 2 - - - System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 55, 13 - - - ARSPD_RATIO - - - Params - - - groupBox19 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 35 - - - 0 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox1 - - - 0 - - - 4 - - - 7 - - - - - - TabPlanner - - - TabPlanner - - - NoControl - - - 6, 89 - - - groupBox25 - - - - - - NoControl - - - IMAX - - - - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - Pitch Min - - - 269, 409 - - - 358, 107 - - - groupBox23 - - - NoControl - - - NAV_LAT_P - - - TabAPM2 - - - NoControl - - - 7 - - - 0, 0, 0, 0 - - - - - - 78, 20 - - - NoControl - - - Stop - - - 18 - - - 169, 416 - - - 111, 59 - - - groupBox11 - - - 111, 13 - - - 78, 20 - - - 2 - - - 4 - - - label74 - - - 78, 20 - - - RATE_RLL_I - - - NoControl - - - 7 - - - 6, 66 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 54, 13 - - - CMB_videosources - - - groupBox12 - - - TabPlanner - - - groupBox13 - - - label75 - - - - - - 3 - - - NoControl - - - 5 - - - 6, 40 - - - - - - 139, 173 - - - 6, 63 - - - 2 - - - 2 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabPlanner - - - 33, 411 - - - 6, 17 - - - 7 - - - - - - 12 - - - 16 - - - 10, 13 - - - - - - CHK_speechmode - - - 111, 59 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 2 - - - Entry Angle - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - NOTE: The Configuration Tab will NOT display these units, as those are raw values. - - + + label99 - - 2 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - + + TabPlanner - - 84, 13 + + 21 - - 2 + + NoControl - - 4 + + 40, 267 - - $this + + 4, 0, 4, 0 - - + + 87, 16 - - 8 + + 13 + + + Speed Units + + + label98 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 22 + + + NoControl + + + 40, 233 + + + 4, 0, 4, 0 + + + 69, 16 + + + 14 + + + Dist Units + + + label97 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 23 + + + 185, 263 + + + 4, 4, 4, 4 + + + 183, 24 + + + 15 + + + CMB_speedunits + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 24 + + + 185, 230 + + + 4, 4, 4, 4 + + + 183, 24 + + + 16 + + + CMB_distunits + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 25 + + + NoControl + + + 40, 200 + + + 4, 0, 4, 0 + + + 60, 16 + + + 17 + + + Joystick + + + label96 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 26 + + + NoControl + + + 40, 137 + + + 4, 0, 4, 0 + + + 59, 16 + + + 18 + + + Speech + + + label95 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 27 + + + NoControl + + + 628, 132 + + + 4, 4, 4, 4 + + + 136, 21 + + + 19 + + + Battery Warning + + + CHK_speechbattery + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 28 + + + NoControl + + + 504, 132 + + + 4, 4, 4, 4 + + + 116, 21 + + + 20 + + + Time Interval + + + CHK_speechcustom + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 29 + + + NoControl + + + 429, 132 + + + 4, 4, 4, 4 + + + 75, 21 + + + 21 + + + Mode + + + CHK_speechmode + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 30 + + + NoControl + + + 327, 132 + + + 4, 4, 4, 4 + + + 95, 21 + + + 22 + + + Waypoint + + + CHK_speechwaypoint System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - NoControl - - - Position - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 80, 63 - - - - - - 5 - - - 0 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6 - - - LIM_ROLL_CD - - - groupBox10 - - - label66 - - - label70 - - - groupBox13 - - - - - - - - - 6, 40 - - - System.Windows.Forms.DataGridView, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - OpenGL = Disabled -GDI+ = Enabled - - - 6 - - - 54, 13 - - - 8 - - - 111, 82 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 3 - - - NoControl - - - Xtrack Pids - - - NoControl - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - + TabPlanner - - 24, 13 + + 31 - - label71 - - - 39 - - - 552, 15 - - - groupBox11 - - - BUT_compare - - - 139, 67 - - + NoControl - - Planner + + 40, 102 - - 6, 63 + + 4, 0, 4, 0 - - TabPlanner + + 76, 16 - - I - - - 0 - - - CMB_raterc - - - groupBox21 + + 23 OSD Color - - + + label94 - - Rate Roll - - + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 80, 37 + + TabPlanner - - label76 - - - 6, 86 - - - 406, 1 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - 37 - - - NoControl - - - 6, 6 - - - 111, 36 - - - - - - 64, 13 - - - 111, 36 - - - 11 - - - Mavlink Message Debug - - - 6, 63 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox12 - - - 111, 13 - - - BUT_load - - - label77 - - - 9 - - - 3 - - - 280, 203 - - - 9 - - - 0 - - - NoControl - - - NoControl - - - 5 - - - 195, 108 - - - - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - Bottom, Left - - - - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6 - - - RLL2SRV_D - - + 32 - - + + 185, 99 - - 9 + + 4, 4, 4, 4 - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 183, 23 - - 3 + + 24 - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + CMB_osdcolor - + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 33 + + + 185, 161 + + + 4, 4, 4, 4 + + + 183, 24 + + + 25 + + + CMB_language + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 34 + + NoControl - - 15, 13 + + 40, 166 - - 8 + + 4, 0, 4, 0 - + + 92, 16 + + + 26 + + + UI Language + + + label93 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + TabPlanner + + + 35 + + + NoControl + + + 185, 132 + + + 4, 4, 4, 4 + + + 132, 21 + + + 27 + + + Enable Speech + + + CHK_enablespeech + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 36 + + + NoControl + + + 736, 18 + + + 4, 4, 4, 4 + + + 167, 21 + + + 28 + + + Enable HUD Overlay + + + CHK_hudshow + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 37 + + + NoControl + + + 40, 20 + + + 4, 0, 4, 0 + + + 133, 28 + + + 29 + + + Video Device + label92 - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - label63 - - - TRIM_ARSPD_CM - - - - - - 111, 36 - - - 7 - - - - - - 10, 13 - - - NoControl - - - label21 - - - 13 - - - groupBox9 - - - label72 - - - label54 - - - 471, 67 - - - 10 - - - 2 - - - - - - groupBox11 - - - groupBox11 - - - 99, 17 - - - groupBox6 - - + TabPlanner - - PTCH2SRV_I - - - groupBox24 - - - 139, 227 - - - Load Waypoints on connect? - - - STB_RLL_I - - - label55 - - - 14 - - - 78, 20 - - - 32 - - - 78, 20 - - - 14, 13 - - - groupBox8 - - - - - - 62 - - - - - - 5 - - - - - - groupBox25 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 138, 21 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 54, 13 - - - STB_YAW_I - - - 61, 13 - - - label104 - - - label99 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox25 - - - + + 38 - 139, 13 + 185, 16 - - 80, 13 + + 4, 4, 4, 4 - - 80, 63 + + 325, 24 - - 9 + + 30 - - label79 + + CMB_videosources - - groupBox3 + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - TabAC2 + + TabPlanner - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 39 - - groupBox3 + + NoControl - - + + 185, 194 - - ALT2PTCH_P + + 4, 4, 4, 4 - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 132, 28 - - 15 + + 31 - - 0, 0, 0, 0 + + Joystick Setup - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + BUT_Joystick - - 10, 13 + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - 8 + + TabPlanner - - groupBox13 + + 40 - - Write changed params to device + + NoControl - - groupBox22 + + 628, 14 + + + 4, 4, 4, 4 + + + 100, 28 + + + 32 + + + Stop + + + BUT_videostop + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + TabPlanner + + + 41 + + + NoControl + + + 520, 14 + + + 4, 4, 4, 4 + + + 100, 28 + + + 33 + + + Start + + + BUT_videostart + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + TabPlanner + + + 42 + + + 4, 22 + + + 4, 4, 4, 4 + + + 4, 4, 4, 4 + + + 965, 540 + + + 2 + + + Planner + + + TabPlanner + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + ConfigTabs + + + 2 + + + 4, 22 + + + 4, 4, 4, 4 + + + 965, 540 + + + 3 + + + Setup + + + TabSetup + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + ConfigTabs + + + 3 52, 18 - + + 371, 0 + + + 0, 0, 0, 0 + + + 0, 0 + + + 973, 566 + + + 62 + + + ConfigTabs + + + System.Windows.Forms.TabControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 2 + + + 0, 0 + + + 100, 23 + + + 0 + + + label109 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Bottom, Left + + + NoControl + + + 225, 543 + + + 4, 4, 4, 4 + + + 137, 23 + + + 0 + + + Refresh Params + + + Reload params from device + + + BUT_rerequestparams + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + $this + + + 1 + + + Bottom, Left + + + NoControl + + + 225, 512 + + + 4, 4, 4, 4 + + + 137, 23 + + + 63 + + + Write Params + + + Write changed params to device + + + BUT_writePIDS + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + $this + + + 3 + + + Bottom, Left + + + NoControl + + + 109, 512 + + + 0, 0, 0, 0 + + + 100, 23 + + + 64 + + + Save + + + Save params to file + + + BUT_save + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + $this + + + 4 + + + Bottom, Left + + + NoControl + + + 4, 512 + + + 0, 0, 0, 0 + + + 100, 23 + + + 65 + + + Load + + + Load param's from file + + + BUT_load + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + $this + + + 5 + + + Bottom, Left + + + NoControl + + + 41, 539 + + + 4, 4, 4, 4 + + + 137, 23 + + + 66 + + + Compare Params + + + BUT_compare + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + $this + + + 0 + + True + + + 8, 16 - - True + + 4, 4, 4, 4 - - 17, 17 + + 1344, 567 - - True + + Command - - True + + System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - True + + Value - - ..\Resources\MAVParam.txt;System.String, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089;Windows-1252 + + System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Default + + + System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + mavScale + + + System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + RawValue + + + System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + toolTip1 + + + System.Windows.Forms.ToolTip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Configuration + + + System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.ru-RU.resx b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.ru-RU.resx new file mode 100644 index 0000000000..1eb714bbfc --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.ru-RU.resx @@ -0,0 +1,1237 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + text/microsoft-resx + + + 2.0 + + + System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + P + + + I + + + + + + + + + + + + Настройка + + + INT_MAX + + + + + + + + + + + + + + + GDI+ (старый тип) + + + + + + + + + P + + + IMAX + + + INT_MAX + + + I + + + Ед. измерения + + + Сигнал батареи + + + Загрузить параметры из файла + + + FBW max + + + + + + + + + + + + + + + + + + INT_MAX + + + Язык интерфейса + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Cruise + + + + + + Max + + + IMAX + + + Nav Pitch AS Pid + + + Stabilize Roll + + + + + + + + + Сигнал голосом + + + + + + + + + IMAX + + + P + + + + + + + + + Energy/Alt Pid + + + + + + + + + Загрузить + + + + + + Показывать HUD + + + + + + + + + + + + + + + + + + + + + + + + P to T + + + + + + Сохранить параметры в файл + + + + + + + + + Считать параметры из устройства + + + Точка WP + + + + + + + + + IMAX + + + P + + + + + + IMAX + + + P + + + I + + + + + + D + + + + + + + + + IMAX + + + APM 2.x + + + P + + + P + + + P + + + Джойстик + + + Настройка + + + + + + + + + D + + + + + + + + + + + + + + + Rudder Mix + + + + + + Видео-устройство + + + + + + INT_MAX + + + + + + + + + + + + + + + + + + + + + Команда + + + + + + I + + + Отношение + + + + + + + + + + + + + + + + + + + + + + + + Длина трека + + + Min + + + P + + + + + + + + + + + + + + + Nav Pitch Alt Pid + + + Записать + + + + + + + + + Servo Roll Pid + + + + + + Servo Pitch Pid + + + + + + м/c + + + P + + + Частота обнов. + + + I + + + + + + + + + + + + Nav Roll Pid + + + IMAX + + + Stabilize Pitch + + + P + + + + + + + + + + + + HUD + + + + + + I + + + INT_MAX + + + + + + Сохранить + + + + + + Airspeed m/s + + + + + + Navigation Angles + + + + + + P + + + D + + + Loiter + + + + + + Throttle 0-100% + + + Запустить + + + Nav WP + + + + + + + + + + + + + + + Crosstrack Correction + + + + + + + + + + + + P + + + + + + + + + Altitude Hold + + + Lock Pitch and Roll Values + + + + + + INT_MAX + + + + + + + + + Перезагрузить автопилот при подключении + + + + + + Сравнить Парам. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + D + + + + + + + + + + + + I + + + Длина трека на карте на первой вкладке + + + + + + Gain (cm) + + + + + + + + + + + + + + + Rate Pitch + + + + + + Автопилот + + + + + + + + + + + + Cruise + + + I + + + Режим/Статус + + + + + + + + + Servo Yaw Pid + + + P + + + + + + Pitch Max + + + D + + + + + + Stabilize Yaw + + + + + + IMAX + + + + + + I + + + + + + + + + + + + + + + + + + Ед. скорости + + + + + + + + + P + + + I + + + RawValue + + + + + + Высота + + + Время + + + Other Mix's + + + + + + Режим + + + + + + I + + + Поведение + + + P + + + RC + + + Оповещение + + + + + + + + + + + + Error Max + + + + + + + + + + + + + + + Default + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + INT_MAX + + + D + + + + + + + + + Обновить Парам. + + + + + + + + + + + + IMAX + + + + + + + + + + + + I + + + Значение + + + + + + + + + mavScale + + + I + + + P + + + I + + + + + + Точки (WP) + + + + + + + + + + + + Pitch Comp + + + FBW min + + + D + + + I + + + + + + I + + + + + + + + + Bank Max + + + AC2 + + + + + + + + + + + + + + + Rate Yaw + + + + + + FS Value + + + + + + + + + + + + + + + + + + + + + + + + IMAX + + + + + + Pitch Min + + + + + + Стоп + + + + + + + + + + + + + + + Entry Angle + + + + + + ВНИМАНИЕ! Здесь данные отображены в сыром виде! + + + + + + + + + + + + Положение + + + + + + + + + + + + OpenGL = выключено +GDI+ = Включено + + + Xtrack Pids + + + Планировщик + + + I + + + Цвет оверлея + + + + + + Rate Roll + + + + + + Mavlink Message Debug + + + + + + + + + + + + + + + + + + + + + Считывать точки (WP) при подключении? + + + + + + + + + + + + + + + + + + Записать измененные параметры в устройство + + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs index 71408d070d..d24f7c0f12 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs @@ -695,6 +695,7 @@ namespace ArdupilotMega.GCSViews int optionoffset = 0; int total = 0; + bool hitend = false; while (!sr.EndOfStream) { @@ -726,11 +727,34 @@ namespace ArdupilotMega.GCSViews { optionoffset += (int)Convert.ToUInt16(line.Substring(9, 4), 16) << 4; } + else if (option == 1) + { + hitend = true; + } int checksum = Convert.ToInt32(line.Substring(line.Length - 2, 2), 16); + + byte checksumact = 0; + for (int z = 0; z < ((line.Length - 1 - 2) / 2) ; z++) // minus 1 for : then mins 2 for checksum itself + { + checksumact += Convert.ToByte(line.Substring(z * 2 + 1, 2), 16); + } + checksumact = (byte)(0x100 - checksumact); + + if (checksumact != checksum) + { + MessageBox.Show("The hex file loaded is invalid, please try again."); + throw new Exception("Checksum Failed - Invalid Hex"); + } } //Regex regex = new Regex(@"^:(..)(....)(..)(.*)(..)$"); // length - address - option - data - checksum } + if (!hitend) + { + MessageBox.Show("The hex file did no contain an end flag. aborting"); + throw new Exception("No end flag in file"); + } + Array.Resize(ref FLASH, total); return FLASH; diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.ru-RU.resx b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.ru-RU.resx new file mode 100644 index 0000000000..fa93543ec5 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.ru-RU.resx @@ -0,0 +1,153 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + text/microsoft-resx + + + 2.0 + + + System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Статус + + + ArduPlane + + + Изобр. Max Levine + + + ArduPlane (Xplane симулятор) + + + ArduCopter Quad + + + ArduCopter Hexa + + + ArduCopter Tri + + + ArduCopter Y6 + + + ArduCopter Heli + + + ArduCopter Quad (Симулятор) + + + Настройка автопилота + + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.ru-RU.resx b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.ru-RU.resx new file mode 100644 index 0000000000..305bb6d980 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.ru-RU.resx @@ -0,0 +1,270 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + text/microsoft-resx + + + 2.0 + + + System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Лететь сюда + + + Записывать HUD + + + Остановить запись + + + Джойстик + + + Выбор и настройка джойстика + + + РУЧНОЙ + + + Сменить режим в РУЧНОЙ/СТАБИЛИЗАЦИЯ + + + БАЗА + + + Сменить режим в БАЗА + + + АВТО + + + Сменить режим на АВТО + + + Уст. WP + + + Сменить текущую ТОЧКУ (WP) + + + Уст. Режим + + + Установить другой полетный режим + + + Стереть трек + + + Стирает проложенный путь с карты + + + Уст. высоту + + + Установить текущую высоту как 0. + + + Просмотр сенсоров + + + Смотреть сырые данные с сенсоров + + + Перезап. Миссии + + + Перезапускает миссию с самого начала + + + Выполнить + + + Выполняет действие из списка + + + Действия + + + Двойное нажатие меняет максимальное значение + + + Индикаторы + + + Статус + + + 0.00 % + + + Скорость воспроизведения + + + Лог > KML + + + Старт/Стоп + + + Загрузить + + + Логи телеметрии + + + 0 + + + Изменить уровень увеличения + + + Увел. + + + 0 + + + 0 + + + Центровка + + + Центрирует карту по текущему положению + + + Тюнинг + + + Показывает график для тонкой настройки + + + Скор: 0 + + + Скорость ветра + + + Напр: 0 + + + Направление ветра + + + Вверх + + + Вниз + + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs index 2aa13247c7..f74f23eb8d 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs @@ -1364,7 +1364,13 @@ namespace ArdupilotMega.GCSViews } } - TXT_DefaultAlt.Text = ((float)param["ALT_HOLD_RTL"] * MainV2.cs.multiplierdist).ToString("0"); + string hold_alt = ((float)param["ALT_HOLD_RTL"] * MainV2.cs.multiplierdist).ToString("0"); + + if (hold_alt != "-1") + { + TXT_DefaultAlt.Text = hold_alt; + } + TXT_WPRad.Text = ((float)param["WP_RADIUS"] * MainV2.cs.multiplierdist).ToString("0"); try { diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.ru-RU.resx b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.ru-RU.resx new file mode 100644 index 0000000000..20d71cddee --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.ru-RU.resx @@ -0,0 +1,464 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + text/microsoft-resx + + + 2.0 + + + System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Добавить точку полигона + + + Парам4 + + + Сравнить высоту миссии с высотой по карте + + + + + + Положение курсора + + + + + + + + + + + + Записать WP + + + + + + Добавить WP + + + + + + Перейти + + + Сдвинуть строку вниз + + + Удалить WP + + + panel6 + + + Увел. + + + + + + Кружить + + + Расстояние + + + + + + + + + Абс.Выс. + + + Повернуть карту + + + + + + + + + 45 + + + + + + Считать WP + + + Парам1 + + + + + + + + + + + + + + + + + + Загрузить WP-файл + + + Сдвинуть строку вверх + + + Рад.Кружения + + + WP # + + + Точки (WP) + + + База + + + + + + + + + Коорд. Базы + + + + + + + + + Радиус WP + + + Время + + + Проверить высоту + + + Сетка + + + Сетка + + + + + + + + + Сменить тип карты + + + Измерить расстояние + + + Держать высоту + + + + + + Абс.Высота + + + Добавляет строку в список + + + + + + + + + Долг. + + + + + + + + + + + + График возвышения + + + + + + Выс. + + + Кэш карты + + + + + + Статус + + + Круги + + + Команда + + + + + + Рисует сетку поверх отмеченной зоны + + + + + + Очистить миссию + + + Стереть полигон + + + + + + Кэширует указанную область карты + + + Сохр. WP-файл + + + + + + Высота + + + Парам2 + + + Парам3 + + + Вниз + + + + + + + + + Шир. + + + Всегда + + + + + + Шир. + + + Пред. + + + Команда автопилота + + + Вниз + + + + + + 30 + + + + + + + + + + + + Долг. + + + + + + + + + 1. Подключитесь 2. Считайте точки +3. Проверьте координаты и высоту Базы +4. Кликайте по карте для добавления точек + + + Начало + + + Удалить + + + Действие + + + Вверх + + + + + + 100 + + + Вверх + + + + + + + + + Удалить строку + + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/HUD.ru.resx b/Tools/ArdupilotMegaPlanner/GCSViews/HUD.ru.resx new file mode 100644 index 0000000000..a7d273d622 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/GCSViews/HUD.ru.resx @@ -0,0 +1,132 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + text/microsoft-resx + + + 2.0 + + + System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + GPS: 3D Fix + + + GPS: 3D Fix + + + GPS: No Fix + + + GPS: No GPS + + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Help.ru-RU.resx b/Tools/ArdupilotMegaPlanner/GCSViews/Help.ru-RU.resx new file mode 100644 index 0000000000..056a444403 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Help.ru-RU.resx @@ -0,0 +1,129 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + text/microsoft-resx + + + 2.0 + + + System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + Показать консоль(рестарт) + + + Проверить обновления + + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/JoystickSetup.ru.resx b/Tools/ArdupilotMegaPlanner/GCSViews/JoystickSetup.ru.resx new file mode 100644 index 0000000000..0fc4202ef1 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/GCSViews/JoystickSetup.ru.resx @@ -0,0 +1,126 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + text/microsoft-resx + + + 2.0 + + + System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Джойстик + + + Джойстик + + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs index 2c0469d8ef..ccecf242f8 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs @@ -1555,6 +1555,16 @@ namespace ArdupilotMega.GCSViews ofd.InitialDirectory = @"C:\Program Files\FlightGear\bin\Win32\"; extra = " --fg-root=\"C:\\Program Files\\FlightGear\\data\""; } + else if (File.Exists(@"C:\Program Files\FlightGear 2.4.0\bin\Win32\fgfs.exe")) + { + ofd.InitialDirectory = @"C:\Program Files\FlightGear 2.4.0\bin\Win32\"; + extra = " --fg-root=\"C:\\Program Files\\FlightGear 2.4.0\\data\""; + } + else if (File.Exists(@"C:\Program Files (x86)\FlightGear 2.4.0\bin\Win32\fgfs.exe")) + { + ofd.InitialDirectory = @"C:\Program Files (x86)\FlightGear 2.4.0\bin\Win32\"; + extra = " --fg-root=\"C:\\Program Files (x86)\\FlightGear 2.4.0\\data\""; + } else if (File.Exists(@"/usr/games/fgfs")) { ofd.InitialDirectory = @"/usr/games"; diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.ru-RU.resx b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.ru-RU.resx new file mode 100644 index 0000000000..454546a8f2 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.ru-RU.resx @@ -0,0 +1,198 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + text/microsoft-resx + + + 2.0 + + + System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Реверс Крен + + + Реверс Тангаж + + + Реверс Рысканье + + + Старт/Стоп + + + + + + Сохранить + + + X-plane + + + FlightGear + + + GPS Самолета + + + Высота + + + Долгота + + + Широта + + + Рыск. + + + IMU Самолета + + + Направление + + + Тангаж + + + Крен + + + Расстояние + + + Ошибка курс + + + Ошибка выс. + + + Автопилот + + + Газ + + + Рысканье + + + Тангаж + + + Крен + + + Режим + + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.ru-RU.resx b/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.ru-RU.resx new file mode 100644 index 0000000000..d96daec5cb --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.ru-RU.resx @@ -0,0 +1,138 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + text/microsoft-resx + + + 2.0 + + + System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Смотреть Лог + + + Показать настройки + + + ВНИМАНИЕ! Вы должны переподключиться и передвинуть переключатель для работы с другими вкладками. + + + Тесты + + + Скачать Лог + + + Настр. Радио + + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/JoystickSetup.ru-RU.resx b/Tools/ArdupilotMegaPlanner/JoystickSetup.ru-RU.resx new file mode 100644 index 0000000000..7c01a8ff93 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/JoystickSetup.ru-RU.resx @@ -0,0 +1,180 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + text/microsoft-resx + + + 2.0 + + + System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 30 + + + 30 + + + 0 + + + 30 + + + Крен + + + Тангаж + + + Газ + + + Rudder + + + Джойстик + + + Экспонента + + + Вывод + + + Оси контроллера + + + Реверс + + + Опред. + + + Опред. + + + Опред. + + + Опред. + + + Включить + + + Сохранить + + + Джойстик + + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/MAVLinkTypes.cs b/Tools/ArdupilotMegaPlanner/MAVLinkTypes.cs index 12df0aab59..d5bae2043a 100644 --- a/Tools/ArdupilotMegaPlanner/MAVLinkTypes.cs +++ b/Tools/ArdupilotMegaPlanner/MAVLinkTypes.cs @@ -1,4 +1,6 @@ using System; +using System.Collections.Generic; +using System.Text; using System.Runtime.InteropServices; namespace ArdupilotMega @@ -11,8 +13,8 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_meminfo_t { - public ushort brkval; ///< heap top - public ushort freemem; ///< free memory + public ushort brkval; /// heap top + public ushort freemem; /// free memory }; public const byte MAVLINK_MSG_ID_MEMINFO_LEN = 4; @@ -21,18 +23,18 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_sensor_offsets_t { - public short mag_ofs_x; ///< magnetometer X offset - public short mag_ofs_y; ///< magnetometer Y offset - public short mag_ofs_z; ///< magnetometer Z offset - public float mag_declination; ///< magnetic declination (radians) - public int raw_press; ///< raw pressure from barometer - public int raw_temp; ///< raw temperature from barometer - public float gyro_cal_x; ///< gyro X calibration - public float gyro_cal_y; ///< gyro Y calibration - public float gyro_cal_z; ///< gyro Z calibration - public float accel_cal_x; ///< accel X calibration - public float accel_cal_y; ///< accel Y calibration - public float accel_cal_z; ///< accel Z calibration + public short mag_ofs_x; /// magnetometer X offset + public short mag_ofs_y; /// magnetometer Y offset + public short mag_ofs_z; /// magnetometer Z offset + public float mag_declination; /// magnetic declination (radians) + public int raw_press; /// raw pressure from barometer + public int raw_temp; /// raw temperature from barometer + public float gyro_cal_x; /// gyro X calibration + public float gyro_cal_y; /// gyro Y calibration + public float gyro_cal_z; /// gyro Z calibration + public float accel_cal_x; /// accel X calibration + public float accel_cal_y; /// accel Y calibration + public float accel_cal_z; /// accel Z calibration }; public const byte MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN = 42; @@ -41,11 +43,11 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_set_mag_offsets_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID - public short mag_ofs_x; ///< magnetometer X offset - public short mag_ofs_y; ///< magnetometer Y offset - public short mag_ofs_z; ///< magnetometer Z offset + public byte target_system; /// System ID + public byte target_component; /// Component ID + public short mag_ofs_x; /// magnetometer X offset + public short mag_ofs_y; /// magnetometer Y offset + public short mag_ofs_z; /// magnetometer Z offset }; public const byte MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN = 8; @@ -119,9 +121,9 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_action_t { - public byte target; ///< The system executing the action - public byte target_component; ///< The component executing the action - public byte action; ///< The action id + public byte target; /// The system executing the action + public byte target_component; /// The component executing the action + public byte action; /// The action id }; public const byte MAVLINK_MSG_ID_ACTION_LEN = 3; @@ -130,8 +132,8 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_action_ack_t { - public byte action; ///< The action id - public byte result; ///< 0: Action DENIED, 1: Action executed + public byte action; /// The action id + public byte result; /// 0: Action DENIED, 1: Action executed }; public const byte MAVLINK_MSG_ID_ACTION_ACK_LEN = 2; @@ -140,13 +142,13 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_attitude_t { - public ulong usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) - public float roll; ///< Roll angle (rad) - public float pitch; ///< Pitch angle (rad) - public float yaw; ///< Yaw angle (rad) - public float rollspeed; ///< Roll angular speed (rad/s) - public float pitchspeed; ///< Pitch angular speed (rad/s) - public float yawspeed; ///< Yaw angular speed (rad/s) + public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) + public float roll; /// Roll angle (rad) + public float pitch; /// Pitch angle (rad) + public float yaw; /// Yaw angle (rad) + public float rollspeed; /// Roll angular speed (rad/s) + public float pitchspeed; /// Pitch angular speed (rad/s) + public float yawspeed; /// Yaw angular speed (rad/s) }; public const byte MAVLINK_MSG_ID_ATTITUDE_LEN = 32; @@ -155,11 +157,11 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_attitude_controller_output_t { - public byte enabled; ///< 1: enabled, 0: disabled - public byte roll; ///< Attitude roll: -128: -100%, 127: +100% - public byte pitch; ///< Attitude pitch: -128: -100%, 127: +100% - public byte yaw; ///< Attitude yaw: -128: -100%, 127: +100% - public byte thrust; ///< Attitude thrust: -128: -100%, 127: +100% + public byte enabled; /// 1: enabled, 0: disabled + public byte roll; /// Attitude roll: -128: -100%, 127: +100% + public byte pitch; /// Attitude pitch: -128: -100%, 127: +100% + public byte yaw; /// Attitude yaw: -128: -100%, 127: +100% + public byte thrust; /// Attitude thrust: -128: -100%, 127: +100% }; @@ -167,13 +169,13 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_attitude_new_t { - public ulong usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) - public float roll; ///< Roll angle (rad) - public float pitch; ///< Pitch angle (rad) - public float yaw; ///< Yaw angle (rad) - public float rollspeed; ///< Roll angular speed (rad/s) - public float pitchspeed; ///< Pitch angular speed (rad/s) - public float yawspeed; ///< Yaw angular speed (rad/s) + public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) + public float roll; /// Roll angle (rad) + public float pitch; /// Pitch angle (rad) + public float yaw; /// Yaw angle (rad) + public float rollspeed; /// Roll angular speed (rad/s) + public float pitchspeed; /// Pitch angular speed (rad/s) + public float yawspeed; /// Yaw angular speed (rad/s) }; @@ -184,7 +186,7 @@ namespace ArdupilotMega [MarshalAs( UnmanagedType.ByValArray, SizeConst=32)] - char key; ///< key + char key; /// key }; public const byte MAVLINK_MSG_ID_AUTH_KEY_LEN = 32; @@ -193,7 +195,7 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_boot_t { - public uint version; ///< The onboard software version + public uint version; /// The onboard software version }; public const byte MAVLINK_MSG_ID_BOOT_LEN = 4; @@ -202,13 +204,13 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_change_operator_control_t { - public byte target_system; ///< System the GCS requests control for - public byte control_request; ///< 0: request control of this MAV, 1: Release control of this MAV - public byte version; ///< 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + public byte target_system; /// System the GCS requests control for + public byte control_request; /// 0: request control of this MAV, 1: Release control of this MAV + public byte version; /// 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. [MarshalAs( UnmanagedType.ByValArray, SizeConst=25)] - char passkey; ///< Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" + char passkey; /// Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" }; public const byte MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN = 28; @@ -217,9 +219,9 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_change_operator_control_ack_t { - public byte gcs_system_id; ///< ID of the GCS this message - public byte control_request; ///< 0: request control of this MAV, 1: Release control of this MAV - public byte ack; ///< 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + public byte gcs_system_id; /// ID of the GCS this message + public byte control_request; /// 0: request control of this MAV, 1: Release control of this MAV + public byte ack; /// 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control }; public const byte MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN = 3; @@ -228,14 +230,14 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_command_t { - public byte target_system; ///< System which should execute the command - public byte target_component; ///< Component which should execute the command, 0 for all components - public byte command; ///< Command ID, as defined by MAV_CMD enum. - public byte confirmation; ///< 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) - public float param1; ///< Parameter 1, as defined by MAV_CMD enum. - public float param2; ///< Parameter 2, as defined by MAV_CMD enum. - public float param3; ///< Parameter 3, as defined by MAV_CMD enum. - public float param4; ///< Parameter 4, as defined by MAV_CMD enum. + public byte target_system; /// System which should execute the command + public byte target_component; /// Component which should execute the command, 0 for all components + public byte command; /// Command ID, as defined by MAV_CMD enum. + public byte confirmation; /// 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + public float param1; /// Parameter 1, as defined by MAV_CMD enum. + public float param2; /// Parameter 2, as defined by MAV_CMD enum. + public float param3; /// Parameter 3, as defined by MAV_CMD enum. + public float param4; /// Parameter 4, as defined by MAV_CMD enum. }; public const byte MAVLINK_MSG_ID_COMMAND_LEN = 20; @@ -244,8 +246,8 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_command_ack_t { - public float command; ///< Current airspeed in m/s - public float result; ///< 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION + public float command; /// Current airspeed in m/s + public float result; /// 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION }; public const byte MAVLINK_MSG_ID_COMMAND_ACK_LEN = 8; @@ -254,14 +256,14 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_control_status_t { - public byte position_fix; ///< Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix - public byte vision_fix; ///< Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix - public byte gps_fix; ///< GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix - public byte ahrs_health; ///< Attitude estimation health: 0: poor, 255: excellent - public byte control_att; ///< 0: Attitude control disabled, 1: enabled - public byte control_pos_xy; ///< 0: X, Y position control disabled, 1: enabled - public byte control_pos_z; ///< 0: Z position control disabled, 1: enabled - public byte control_pos_yaw; ///< 0: Yaw angle control disabled, 1: enabled + public byte position_fix; /// Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix + public byte vision_fix; /// Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix + public byte gps_fix; /// GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix + public byte ahrs_health; /// Attitude estimation health: 0: poor, 255: excellent + public byte control_att; /// 0: Attitude control disabled, 1: enabled + public byte control_pos_xy; /// 0: X, Y position control disabled, 1: enabled + public byte control_pos_z; /// 0: Z position control disabled, 1: enabled + public byte control_pos_yaw; /// 0: Yaw angle control disabled, 1: enabled }; public const byte MAVLINK_MSG_ID_CONTROL_STATUS_LEN = 8; @@ -270,8 +272,8 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_debug_t { - public byte ind; ///< index of debug variable - public float value; ///< DEBUG value + public byte ind; /// index of debug variable + public float value; /// DEBUG value }; public const byte MAVLINK_MSG_ID_DEBUG_LEN = 5; @@ -283,11 +285,11 @@ namespace ArdupilotMega [MarshalAs( UnmanagedType.ByValArray, SizeConst=10)] - char name; ///< Name - public ulong usec; ///< Timestamp - public float x; ///< x - public float y; ///< y - public float z; ///< z + char name; /// Name + public ulong usec; /// Timestamp + public float x; /// x + public float y; /// y + public float z; /// z }; public const byte MAVLINK_MSG_ID_DEBUG_VECT_LEN = 30; @@ -296,22 +298,22 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_full_state_t { - public ulong usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) - public float roll; ///< Roll angle (rad) - public float pitch; ///< Pitch angle (rad) - public float yaw; ///< Yaw angle (rad) - public float rollspeed; ///< Roll angular speed (rad/s) - public float pitchspeed; ///< Pitch angular speed (rad/s) - public float yawspeed; ///< Yaw angular speed (rad/s) - public int lat; ///< Latitude, expressed as * 1E7 - public int lon; ///< Longitude, expressed as * 1E7 - public int alt; ///< Altitude in meters, expressed as * 1000 (millimeters) - public short vx; ///< Ground X Speed (Latitude), expressed as m/s * 100 - public short vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100 - public short vz; ///< Ground Z Speed (Altitude), expressed as m/s * 100 - public short xacc; ///< X acceleration (mg) - public short yacc; ///< Y acceleration (mg) - public short zacc; ///< Z acceleration (mg) + public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) + public float roll; /// Roll angle (rad) + public float pitch; /// Pitch angle (rad) + public float yaw; /// Yaw angle (rad) + public float rollspeed; /// Roll angular speed (rad/s) + public float pitchspeed; /// Pitch angular speed (rad/s) + public float yawspeed; /// Yaw angular speed (rad/s) + public int lat; /// Latitude, expressed as * 1E7 + public int lon; /// Longitude, expressed as * 1E7 + public int alt; /// Altitude in meters, expressed as * 1000 (millimeters) + public short vx; /// Ground X Speed (Latitude), expressed as m/s * 100 + public short vy; /// Ground Y Speed (Longitude), expressed as m/s * 100 + public short vz; /// Ground Z Speed (Altitude), expressed as m/s * 100 + public short xacc; /// X acceleration (mg) + public short yacc; /// Y acceleration (mg) + public short zacc; /// Z acceleration (mg) }; @@ -319,13 +321,13 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_global_position_t { - public ulong usec; ///< Timestamp (microseconds since unix epoch) - public float lat; ///< Latitude, in degrees - public float lon; ///< Longitude, in degrees - public float alt; ///< Absolute altitude, in meters - public float vx; ///< X Speed (in Latitude direction, positive: going north) - public float vy; ///< Y Speed (in Longitude direction, positive: going east) - public float vz; ///< Z Speed (in Altitude direction, positive: going up) + public ulong usec; /// Timestamp (microseconds since unix epoch) + public float lat; /// Latitude, in degrees + public float lon; /// Longitude, in degrees + public float alt; /// Absolute altitude, in meters + public float vx; /// X Speed (in Latitude direction, positive: going north) + public float vy; /// Y Speed (in Longitude direction, positive: going east) + public float vz; /// Z Speed (in Altitude direction, positive: going up) }; public const byte MAVLINK_MSG_ID_GLOBAL_POSITION_LEN = 32; @@ -334,12 +336,12 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_global_position_int_t { - public int lat; ///< Latitude, expressed as * 1E7 - public int lon; ///< Longitude, expressed as * 1E7 - public int alt; ///< Altitude in meters, expressed as * 1000 (millimeters) - public short vx; ///< Ground X Speed (Latitude), expressed as m/s * 100 - public short vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100 - public short vz; ///< Ground Z Speed (Altitude), expressed as m/s * 100 + public int lat; /// Latitude, expressed as * 1E7 + public int lon; /// Longitude, expressed as * 1E7 + public int alt; /// Altitude in meters, expressed as * 1000 (millimeters) + public short vx; /// Ground X Speed (Latitude), expressed as m/s * 100 + public short vy; /// Ground Y Speed (Longitude), expressed as m/s * 100 + public short vz; /// Ground Z Speed (Altitude), expressed as m/s * 100 }; public const byte MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN = 18; @@ -348,9 +350,9 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_gps_local_origin_set_t { - public int latitude; ///< Latitude (WGS84), expressed as * 1E7 - public int longitude; ///< Longitude (WGS84), expressed as * 1E7 - public int altitude; ///< Altitude(WGS84), expressed as * 1000 + public int latitude; /// Latitude (WGS84), expressed as * 1E7 + public int longitude; /// Longitude (WGS84), expressed as * 1E7 + public int altitude; /// Altitude(WGS84), expressed as * 1000 }; public const byte MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET_LEN = 12; @@ -359,15 +361,15 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_gps_raw_t { - public ulong usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) - public byte fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - public float lat; ///< Latitude in degrees - public float lon; ///< Longitude in degrees - public float alt; ///< Altitude in meters - public float eph; ///< GPS HDOP - public float epv; ///< GPS VDOP - public float v; ///< GPS ground speed - public float hdg; ///< Compass heading in degrees, 0..360 degrees + public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) + public byte fix_type; /// 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + public float lat; /// Latitude in degrees + public float lon; /// Longitude in degrees + public float alt; /// Altitude in meters + public float eph; /// GPS HDOP + public float epv; /// GPS VDOP + public float v; /// GPS ground speed + public float hdg; /// Compass heading in degrees, 0..360 degrees }; public const byte MAVLINK_MSG_ID_GPS_RAW_LEN = 37; @@ -376,15 +378,15 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_gps_raw_int_t { - public ulong usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) - public byte fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - public int lat; ///< Latitude in 1E7 degrees - public int lon; ///< Longitude in 1E7 degrees - public int alt; ///< Altitude in 1E3 meters (millimeters) - public float eph; ///< GPS HDOP - public float epv; ///< GPS VDOP - public float v; ///< GPS ground speed (m/s) - public float hdg; ///< Compass heading in degrees, 0..360 degrees + public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) + public byte fix_type; /// 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + public int lat; /// Latitude in 1E7 degrees + public int lon; /// Longitude in 1E7 degrees + public int alt; /// Altitude in 1E3 meters (millimeters) + public float eph; /// GPS HDOP + public float epv; /// GPS VDOP + public float v; /// GPS ground speed (m/s) + public float hdg; /// Compass heading in degrees, 0..360 degrees }; public const byte MAVLINK_MSG_ID_GPS_RAW_INT_LEN = 37; @@ -393,11 +395,11 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_gps_set_global_origin_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID - public int latitude; ///< global position * 1E7 - public int longitude; ///< global position * 1E7 - public int altitude; ///< global position * 1000 + public byte target_system; /// System ID + public byte target_component; /// Component ID + public int latitude; /// global position * 1E7 + public int longitude; /// global position * 1E7 + public int altitude; /// global position * 1000 }; public const byte MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN_LEN = 14; @@ -406,27 +408,27 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_gps_status_t { - public byte satellites_visible; ///< Number of satellites visible + public byte satellites_visible; /// Number of satellites visible [MarshalAs( UnmanagedType.ByValArray, SizeConst=20)] - public byte[] satellite_prn; ///< Global satellite ID + public byte[] satellite_prn; /// Global satellite ID [MarshalAs( UnmanagedType.ByValArray, SizeConst=20)] - public byte[] satellite_used; ///< 0: Satellite not used, 1: used for localization + public byte[] satellite_used; /// 0: Satellite not used, 1: used for localization [MarshalAs( UnmanagedType.ByValArray, SizeConst=20)] - public byte[] satellite_elevation; ///< Elevation (0: right on top of receiver, 90: on the horizon) of satellite + public byte[] satellite_elevation; /// Elevation (0: right on top of receiver, 90: on the horizon) of satellite [MarshalAs( UnmanagedType.ByValArray, SizeConst=20)] - public byte[] satellite_azimuth; ///< Direction of satellite, 0: 0 deg, 255: 360 deg. + public byte[] satellite_azimuth; /// Direction of satellite, 0: 0 deg, 255: 360 deg. [MarshalAs( UnmanagedType.ByValArray, SizeConst=20)] - public byte[] satellite_snr; ///< Signal to noise ratio of satellite + public byte[] satellite_snr; /// Signal to noise ratio of satellite }; public const byte MAVLINK_MSG_ID_GPS_STATUS_LEN = 101; @@ -435,9 +437,9 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_heartbeat_t { - public byte type; ///< Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) - public byte autopilot; ///< Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM - public byte mavlink_version; ///< MAVLink version + public byte type; /// Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + public byte autopilot; /// Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM + public byte mavlink_version; /// MAVLink version }; public const byte MAVLINK_MSG_ID_HEARTBEAT_LEN = 3; @@ -446,13 +448,13 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_hil_controls_t { - public ulong time_us; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) - public float roll_ailerons; ///< Control output -3 .. 1 - public float pitch_elevator; ///< Control output -1 .. 1 - public float yaw_rudder; ///< Control output -1 .. 1 - public float throttle; ///< Throttle 0 .. 1 - public byte mode; ///< System mode (MAV_MODE) - public byte nav_mode; ///< Navigation mode (MAV_NAV_MODE) + public ulong time_us; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) + public float roll_ailerons; /// Control output -3 .. 1 + public float pitch_elevator; /// Control output -1 .. 1 + public float yaw_rudder; /// Control output -1 .. 1 + public float throttle; /// Throttle 0 .. 1 + public byte mode; /// System mode (MAV_MODE) + public byte nav_mode; /// Navigation mode (MAV_NAV_MODE) }; public const byte MAVLINK_MSG_ID_HIL_CONTROLS_LEN = 26; @@ -461,22 +463,22 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_hil_state_t { - public ulong usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) - public float roll; ///< Roll angle (rad) - public float pitch; ///< Pitch angle (rad) - public float yaw; ///< Yaw angle (rad) - public float rollspeed; ///< Roll angular speed (rad/s) - public float pitchspeed; ///< Pitch angular speed (rad/s) - public float yawspeed; ///< Yaw angular speed (rad/s) - public int lat; ///< Latitude, expressed as * 1E7 - public int lon; ///< Longitude, expressed as * 1E7 - public int alt; ///< Altitude in meters, expressed as * 1000 (millimeters) - public short vx; ///< Ground X Speed (Latitude), expressed as m/s * 100 - public short vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100 - public short vz; ///< Ground Z Speed (Altitude), expressed as m/s * 100 - public short xacc; ///< X acceleration (mg) - public short yacc; ///< Y acceleration (mg) - public short zacc; ///< Z acceleration (mg) + public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) + public float roll; /// Roll angle (rad) + public float pitch; /// Pitch angle (rad) + public float yaw; /// Yaw angle (rad) + public float rollspeed; /// Roll angular speed (rad/s) + public float pitchspeed; /// Pitch angular speed (rad/s) + public float yawspeed; /// Yaw angular speed (rad/s) + public int lat; /// Latitude, expressed as * 1E7 + public int lon; /// Longitude, expressed as * 1E7 + public int alt; /// Altitude in meters, expressed as * 1000 (millimeters) + public short vx; /// Ground X Speed (Latitude), expressed as m/s * 100 + public short vy; /// Ground Y Speed (Longitude), expressed as m/s * 100 + public short vz; /// Ground Z Speed (Altitude), expressed as m/s * 100 + public short xacc; /// X acceleration (mg) + public short yacc; /// Y acceleration (mg) + public short zacc; /// Z acceleration (mg) }; public const byte MAVLINK_MSG_ID_HIL_STATE_LEN = 56; @@ -485,13 +487,13 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_local_position_t { - public ulong usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) - public float x; ///< X Position - public float y; ///< Y Position - public float z; ///< Z Position - public float vx; ///< X Speed - public float vy; ///< Y Speed - public float vz; ///< Z Speed + public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) + public float x; /// X Position + public float y; /// Y Position + public float z; /// Z Position + public float vx; /// X Speed + public float vy; /// Y Speed + public float vz; /// Z Speed }; public const byte MAVLINK_MSG_ID_LOCAL_POSITION_LEN = 32; @@ -500,10 +502,10 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_local_position_setpoint_t { - public float x; ///< x position - public float y; ///< y position - public float z; ///< z position - public float yaw; ///< Desired yaw angle + public float x; /// x position + public float y; /// y position + public float z; /// z position + public float yaw; /// Desired yaw angle }; public const byte MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN = 16; @@ -512,12 +514,12 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_local_position_setpoint_set_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID - public float x; ///< x position - public float y; ///< y position - public float z; ///< z position - public float yaw; ///< Desired yaw angle + public byte target_system; /// System ID + public byte target_component; /// Component ID + public float x; /// x position + public float y; /// y position + public float z; /// z position + public float yaw; /// Desired yaw angle }; public const byte MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET_LEN = 18; @@ -526,15 +528,15 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_manual_control_t { - public byte target; ///< The system to be controlled - public float roll; ///< roll - public float pitch; ///< pitch - public float yaw; ///< yaw - public float thrust; ///< thrust - public byte roll_manual; ///< roll control enabled auto:0, manual:1 - public byte pitch_manual; ///< pitch auto:0, manual:1 - public byte yaw_manual; ///< yaw auto:0, manual:1 - public byte thrust_manual; ///< thrust auto:0, manual:1 + public byte target; /// The system to be controlled + public float roll; /// roll + public float pitch; /// pitch + public float yaw; /// yaw + public float thrust; /// thrust + public byte roll_manual; /// roll control enabled auto:0, manual:1 + public byte pitch_manual; /// pitch auto:0, manual:1 + public byte yaw_manual; /// yaw auto:0, manual:1 + public byte thrust_manual; /// thrust auto:0, manual:1 }; public const byte MAVLINK_MSG_ID_MANUAL_CONTROL_LEN = 21; @@ -546,8 +548,8 @@ namespace ArdupilotMega [MarshalAs( UnmanagedType.ByValArray, SizeConst=10)] - char name; ///< Name of the debug variable - public float value; ///< Floating point value + char name; /// Name of the debug variable + public float value; /// Floating point value }; public const byte MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN = 14; @@ -559,8 +561,8 @@ namespace ArdupilotMega [MarshalAs( UnmanagedType.ByValArray, SizeConst=10)] - char name; ///< Name of the debug variable - public int value; ///< Signed integer value + char name; /// Name of the debug variable + public int value; /// Signed integer value }; public const byte MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN = 14; @@ -569,14 +571,14 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_nav_controller_output_t { - public float nav_roll; ///< Current desired roll in degrees - public float nav_pitch; ///< Current desired pitch in degrees - public short nav_bearing; ///< Current desired heading in degrees - public short target_bearing; ///< Bearing to current waypoint/target in degrees - public ushort wp_dist; ///< Distance to active waypoint in meters - public float alt_error; ///< Current altitude error in meters - public float aspd_error; ///< Current airspeed error in meters/second - public float xtrack_error; ///< Current crosstrack error on x-y plane in meters + public float nav_roll; /// Current desired roll in degrees + public float nav_pitch; /// Current desired pitch in degrees + public short nav_bearing; /// Current desired heading in degrees + public short target_bearing; /// Bearing to current waypoint/target in degrees + public ushort wp_dist; /// Distance to active waypoint in meters + public float alt_error; /// Current altitude error in meters + public float aspd_error; /// Current airspeed error in meters/second + public float xtrack_error; /// Current crosstrack error on x-y plane in meters }; public const byte MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN = 26; @@ -585,16 +587,16 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_object_detection_event_t { - public uint time; ///< Timestamp in milliseconds since system boot - public ushort object_id; ///< Object ID - public byte type; ///< Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal + public uint time; /// Timestamp in milliseconds since system boot + public ushort object_id; /// Object ID + public byte type; /// Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal [MarshalAs( UnmanagedType.ByValArray, SizeConst=20)] - char name; ///< Name of the object as defined by the detector - public byte quality; ///< Detection quality / confidence. 0: bad, 255: maximum confidence - public float bearing; ///< Angle of the object with respect to the body frame in NED coordinates in radians. 0: front - public float distance; ///< Ground distance in meters + char name; /// Name of the object as defined by the detector + public byte quality; /// Detection quality / confidence. 0: bad, 255: maximum confidence + public float bearing; /// Angle of the object with respect to the body frame in NED coordinates in radians. 0: front + public float distance; /// Ground distance in meters }; public const byte MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT_LEN = 36; @@ -603,12 +605,12 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_optical_flow_t { - public ulong time; ///< Timestamp (UNIX) - public byte sensor_id; ///< Sensor ID - public short flow_x; ///< Flow in pixels in x-sensor direction - public short flow_y; ///< Flow in pixels in y-sensor direction - public byte quality; ///< Optical flow quality / confidence. 0: bad, 255: maximum quality - public float ground_distance; ///< Ground distance in meters + public ulong time; /// Timestamp (UNIX) + public byte sensor_id; /// Sensor ID + public short flow_x; /// Flow in pixels in x-sensor direction + public short flow_y; /// Flow in pixels in y-sensor direction + public byte quality; /// Optical flow quality / confidence. 0: bad, 255: maximum quality + public float ground_distance; /// Ground distance in meters }; public const byte MAVLINK_MSG_ID_OPTICAL_FLOW_LEN = 18; @@ -617,8 +619,8 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_param_request_list_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID + public byte target_system; /// System ID + public byte target_component; /// Component ID }; public const byte MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN = 2; @@ -627,13 +629,13 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_param_request_read_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID + public byte target_system; /// System ID + public byte target_component; /// Component ID [MarshalAs( UnmanagedType.ByValArray, SizeConst=15)] - public byte[] param_id; ///< Onboard parameter id - public short param_index; ///< Parameter index. Send -1 to use the param ID field as identifier + public byte[] param_id; /// Onboard parameter id + public short param_index; /// Parameter index. Send -1 to use the param ID field as identifier }; public const byte MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN = 19; @@ -642,13 +644,13 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_param_set_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID + public byte target_system; /// System ID + public byte target_component; /// Component ID [MarshalAs( UnmanagedType.ByValArray, SizeConst=15)] - public byte[] param_id; ///< Onboard parameter id - public float param_value; ///< Onboard parameter value + public byte[] param_id; /// Onboard parameter id + public float param_value; /// Onboard parameter value }; public const byte MAVLINK_MSG_ID_PARAM_SET_LEN = 21; @@ -660,10 +662,10 @@ namespace ArdupilotMega [MarshalAs( UnmanagedType.ByValArray, SizeConst=15)] - public byte[] param_id; ///< Onboard parameter id - public float param_value; ///< Onboard parameter value - public ushort param_count; ///< Total number of onboard parameters - public ushort param_index; ///< Index of this onboard parameter + public byte[] param_id; /// Onboard parameter id + public float param_value; /// Onboard parameter value + public ushort param_count; /// Total number of onboard parameters + public ushort param_index; /// Index of this onboard parameter }; public const byte MAVLINK_MSG_ID_PARAM_VALUE_LEN = 23; @@ -672,10 +674,10 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_ping_t { - public uint seq; ///< PING sequence - public byte target_system; ///< 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system - public byte target_component; ///< 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system - public ulong time; ///< Unix timestamp in microseconds + public uint seq; /// PING sequence + public byte target_system; /// 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system + public byte target_component; /// 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system + public ulong time; /// Unix timestamp in microseconds }; public const byte MAVLINK_MSG_ID_PING_LEN = 14; @@ -684,11 +686,11 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_position_controller_output_t { - public byte enabled; ///< 1: enabled, 0: disabled - public byte x; ///< Position x: -128: -100%, 127: +100% - public byte y; ///< Position y: -128: -100%, 127: +100% - public byte z; ///< Position z: -128: -100%, 127: +100% - public byte yaw; ///< Position yaw: -128: -100%, 127: +100% + public byte enabled; /// 1: enabled, 0: disabled + public byte x; /// Position x: -128: -100%, 127: +100% + public byte y; /// Position y: -128: -100%, 127: +100% + public byte z; /// Position z: -128: -100%, 127: +100% + public byte yaw; /// Position yaw: -128: -100%, 127: +100% }; @@ -696,10 +698,10 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_position_target_t { - public float x; ///< x position - public float y; ///< y position - public float z; ///< z position - public float yaw; ///< yaw orientation in radians, 0 = NORTH + public float x; /// x position + public float y; /// y position + public float z; /// z position + public float yaw; /// yaw orientation in radians, 0 = NORTH }; public const byte MAVLINK_MSG_ID_POSITION_TARGET_LEN = 16; @@ -708,16 +710,16 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_raw_imu_t { - public ulong usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) - public short xacc; ///< X acceleration (raw) - public short yacc; ///< Y acceleration (raw) - public short zacc; ///< Z acceleration (raw) - public short xgyro; ///< Angular speed around X axis (raw) - public short ygyro; ///< Angular speed around Y axis (raw) - public short zgyro; ///< Angular speed around Z axis (raw) - public short xmag; ///< X Magnetic field (raw) - public short ymag; ///< Y Magnetic field (raw) - public short zmag; ///< Z Magnetic field (raw) + public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) + public short xacc; /// X acceleration (raw) + public short yacc; /// Y acceleration (raw) + public short zacc; /// Z acceleration (raw) + public short xgyro; /// Angular speed around X axis (raw) + public short ygyro; /// Angular speed around Y axis (raw) + public short zgyro; /// Angular speed around Z axis (raw) + public short xmag; /// X Magnetic field (raw) + public short ymag; /// Y Magnetic field (raw) + public short zmag; /// Z Magnetic field (raw) }; public const byte MAVLINK_MSG_ID_RAW_IMU_LEN = 26; @@ -726,11 +728,11 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_raw_pressure_t { - public ulong usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) - public short press_abs; ///< Absolute pressure (raw) - public short press_diff1; ///< Differential pressure 1 (raw) - public short press_diff2; ///< Differential pressure 2 (raw) - public short temperature; ///< Raw Temperature measurement (raw) + public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) + public short press_abs; /// Absolute pressure (raw) + public short press_diff1; /// Differential pressure 1 (raw) + public short press_diff2; /// Differential pressure 2 (raw) + public short temperature; /// Raw Temperature measurement (raw) }; public const byte MAVLINK_MSG_ID_RAW_PRESSURE_LEN = 16; @@ -739,16 +741,16 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_rc_channels_override_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID - public ushort chan1_raw; ///< RC channel 1 value, in microseconds - public ushort chan2_raw; ///< RC channel 2 value, in microseconds - public ushort chan3_raw; ///< RC channel 3 value, in microseconds - public ushort chan4_raw; ///< RC channel 4 value, in microseconds - public ushort chan5_raw; ///< RC channel 5 value, in microseconds - public ushort chan6_raw; ///< RC channel 6 value, in microseconds - public ushort chan7_raw; ///< RC channel 7 value, in microseconds - public ushort chan8_raw; ///< RC channel 8 value, in microseconds + public byte target_system; /// System ID + public byte target_component; /// Component ID + public ushort chan1_raw; /// RC channel 1 value, in microseconds + public ushort chan2_raw; /// RC channel 2 value, in microseconds + public ushort chan3_raw; /// RC channel 3 value, in microseconds + public ushort chan4_raw; /// RC channel 4 value, in microseconds + public ushort chan5_raw; /// RC channel 5 value, in microseconds + public ushort chan6_raw; /// RC channel 6 value, in microseconds + public ushort chan7_raw; /// RC channel 7 value, in microseconds + public ushort chan8_raw; /// RC channel 8 value, in microseconds }; public const byte MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN = 18; @@ -757,15 +759,15 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_rc_channels_raw_t { - public ushort chan1_raw; ///< RC channel 1 value, in microseconds - public ushort chan2_raw; ///< RC channel 2 value, in microseconds - public ushort chan3_raw; ///< RC channel 3 value, in microseconds - public ushort chan4_raw; ///< RC channel 4 value, in microseconds - public ushort chan5_raw; ///< RC channel 5 value, in microseconds - public ushort chan6_raw; ///< RC channel 6 value, in microseconds - public ushort chan7_raw; ///< RC channel 7 value, in microseconds - public ushort chan8_raw; ///< RC channel 8 value, in microseconds - public byte rssi; ///< Receive signal strength indicator, 0: 0%, 255: 100% + public ushort chan1_raw; /// RC channel 1 value, in microseconds + public ushort chan2_raw; /// RC channel 2 value, in microseconds + public ushort chan3_raw; /// RC channel 3 value, in microseconds + public ushort chan4_raw; /// RC channel 4 value, in microseconds + public ushort chan5_raw; /// RC channel 5 value, in microseconds + public ushort chan6_raw; /// RC channel 6 value, in microseconds + public ushort chan7_raw; /// RC channel 7 value, in microseconds + public ushort chan8_raw; /// RC channel 8 value, in microseconds + public byte rssi; /// Receive signal strength indicator, 0: 0%, 255: 100% }; public const byte MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN = 17; @@ -774,15 +776,15 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_rc_channels_scaled_t { - public short chan1_scaled; ///< RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 - public short chan2_scaled; ///< RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 - public short chan3_scaled; ///< RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 - public short chan4_scaled; ///< RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 - public short chan5_scaled; ///< RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 - public short chan6_scaled; ///< RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 - public short chan7_scaled; ///< RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 - public short chan8_scaled; ///< RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 - public byte rssi; ///< Receive signal strength indicator, 0: 0%, 255: 100% + public short chan1_scaled; /// RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + public short chan2_scaled; /// RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + public short chan3_scaled; /// RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + public short chan4_scaled; /// RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + public short chan5_scaled; /// RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + public short chan6_scaled; /// RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + public short chan7_scaled; /// RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + public short chan8_scaled; /// RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + public byte rssi; /// Receive signal strength indicator, 0: 0%, 255: 100% }; public const byte MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN = 17; @@ -791,11 +793,11 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_request_data_stream_t { - public byte target_system; ///< The target requested to send the message stream. - public byte target_component; ///< The target requested to send the message stream. - public byte req_stream_id; ///< The ID of the requested message type - public ushort req_message_rate; ///< Update rate in Hertz - public byte start_stop; ///< 1 to start sending, 0 to stop sending. + public byte target_system; /// The target requested to send the message stream. + public byte target_component; /// The target requested to send the message stream. + public byte req_stream_id; /// The ID of the requested message type + public ushort req_message_rate; /// Update rate in Hertz + public byte start_stop; /// 1 to start sending, 0 to stop sending. }; public const byte MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN = 6; @@ -804,11 +806,11 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_request_dynamic_gyro_calibration_t { - public byte target_system; ///< The system which should auto-calibrate - public byte target_component; ///< The system component which should auto-calibrate - public float mode; ///< The current ground-truth rpm - public byte axis; ///< The axis to calibrate: 0 roll, 1 pitch, 2 yaw - public ushort time; ///< The time to average over in ms + public byte target_system; /// The system which should auto-calibrate + public byte target_component; /// The system component which should auto-calibrate + public float mode; /// The current ground-truth rpm + public byte axis; /// The axis to calibrate: 0 roll, 1 pitch, 2 yaw + public ushort time; /// The time to average over in ms }; @@ -816,9 +818,9 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_request_static_calibration_t { - public byte target_system; ///< The system which should auto-calibrate - public byte target_component; ///< The system component which should auto-calibrate - public ushort time; ///< The time to average over in ms + public byte target_system; /// The system which should auto-calibrate + public byte target_component; /// The system component which should auto-calibrate + public ushort time; /// The time to average over in ms }; @@ -826,11 +828,11 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_roll_pitch_yaw_speed_thrust_setpoint_t { - public ulong time_us; ///< Timestamp in micro seconds since unix epoch - public float roll_speed; ///< Desired roll angular speed in rad/s - public float pitch_speed; ///< Desired pitch angular speed in rad/s - public float yaw_speed; ///< Desired yaw angular speed in rad/s - public float thrust; ///< Collective thrust, normalized to 0 .. 1 + public ulong time_us; /// Timestamp in micro seconds since unix epoch + public float roll_speed; /// Desired roll angular speed in rad/s + public float pitch_speed; /// Desired pitch angular speed in rad/s + public float yaw_speed; /// Desired yaw angular speed in rad/s + public float thrust; /// Collective thrust, normalized to 0 .. 1 }; public const byte MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN = 24; @@ -839,11 +841,11 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_roll_pitch_yaw_thrust_setpoint_t { - public ulong time_us; ///< Timestamp in micro seconds since unix epoch - public float roll; ///< Desired roll angle in radians - public float pitch; ///< Desired pitch angle in radians - public float yaw; ///< Desired yaw angle in radians - public float thrust; ///< Collective thrust, normalized to 0 .. 1 + public ulong time_us; /// Timestamp in micro seconds since unix epoch + public float roll; /// Desired roll angle in radians + public float pitch; /// Desired pitch angle in radians + public float yaw; /// Desired yaw angle in radians + public float thrust; /// Collective thrust, normalized to 0 .. 1 }; public const byte MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN = 24; @@ -852,13 +854,13 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_safety_allowed_area_t { - public byte frame; ///< Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - public float p1x; ///< x position 1 / Latitude 1 - public float p1y; ///< y position 1 / Longitude 1 - public float p1z; ///< z position 1 / Altitude 1 - public float p2x; ///< x position 2 / Latitude 2 - public float p2y; ///< y position 2 / Longitude 2 - public float p2z; ///< z position 2 / Altitude 2 + public byte frame; /// Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + public float p1x; /// x position 1 / Latitude 1 + public float p1y; /// y position 1 / Longitude 1 + public float p1z; /// z position 1 / Altitude 1 + public float p2x; /// x position 2 / Latitude 2 + public float p2y; /// y position 2 / Longitude 2 + public float p2z; /// z position 2 / Altitude 2 }; public const byte MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN = 25; @@ -867,15 +869,15 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_safety_set_allowed_area_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID - public byte frame; ///< Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - public float p1x; ///< x position 1 / Latitude 1 - public float p1y; ///< y position 1 / Longitude 1 - public float p1z; ///< z position 1 / Altitude 1 - public float p2x; ///< x position 2 / Latitude 2 - public float p2y; ///< y position 2 / Longitude 2 - public float p2z; ///< z position 2 / Altitude 2 + public byte target_system; /// System ID + public byte target_component; /// Component ID + public byte frame; /// Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + public float p1x; /// x position 1 / Latitude 1 + public float p1y; /// y position 1 / Longitude 1 + public float p1z; /// z position 1 / Altitude 1 + public float p2x; /// x position 2 / Latitude 2 + public float p2y; /// y position 2 / Longitude 2 + public float p2z; /// z position 2 / Altitude 2 }; public const byte MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN = 27; @@ -884,16 +886,16 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_scaled_imu_t { - public ulong usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) - public short xacc; ///< X acceleration (mg) - public short yacc; ///< Y acceleration (mg) - public short zacc; ///< Z acceleration (mg) - public short xgyro; ///< Angular speed around X axis (millirad /sec) - public short ygyro; ///< Angular speed around Y axis (millirad /sec) - public short zgyro; ///< Angular speed around Z axis (millirad /sec) - public short xmag; ///< X Magnetic field (milli tesla) - public short ymag; ///< Y Magnetic field (milli tesla) - public short zmag; ///< Z Magnetic field (milli tesla) + public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) + public short xacc; /// X acceleration (mg) + public short yacc; /// Y acceleration (mg) + public short zacc; /// Z acceleration (mg) + public short xgyro; /// Angular speed around X axis (millirad /sec) + public short ygyro; /// Angular speed around Y axis (millirad /sec) + public short zgyro; /// Angular speed around Z axis (millirad /sec) + public short xmag; /// X Magnetic field (milli tesla) + public short ymag; /// Y Magnetic field (milli tesla) + public short zmag; /// Z Magnetic field (milli tesla) }; public const byte MAVLINK_MSG_ID_SCALED_IMU_LEN = 26; @@ -902,10 +904,10 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_scaled_pressure_t { - public ulong usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) - public float press_abs; ///< Absolute pressure (hectopascal) - public float press_diff; ///< Differential pressure 1 (hectopascal) - public short temperature; ///< Temperature measurement (0.01 degrees celsius) + public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) + public float press_abs; /// Absolute pressure (hectopascal) + public float press_diff; /// Differential pressure 1 (hectopascal) + public short temperature; /// Temperature measurement (0.01 degrees celsius) }; public const byte MAVLINK_MSG_ID_SCALED_PRESSURE_LEN = 18; @@ -914,14 +916,14 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_servo_output_raw_t { - public ushort servo1_raw; ///< Servo output 1 value, in microseconds - public ushort servo2_raw; ///< Servo output 2 value, in microseconds - public ushort servo3_raw; ///< Servo output 3 value, in microseconds - public ushort servo4_raw; ///< Servo output 4 value, in microseconds - public ushort servo5_raw; ///< Servo output 5 value, in microseconds - public ushort servo6_raw; ///< Servo output 6 value, in microseconds - public ushort servo7_raw; ///< Servo output 7 value, in microseconds - public ushort servo8_raw; ///< Servo output 8 value, in microseconds + public ushort servo1_raw; /// Servo output 1 value, in microseconds + public ushort servo2_raw; /// Servo output 2 value, in microseconds + public ushort servo3_raw; /// Servo output 3 value, in microseconds + public ushort servo4_raw; /// Servo output 4 value, in microseconds + public ushort servo5_raw; /// Servo output 5 value, in microseconds + public ushort servo6_raw; /// Servo output 6 value, in microseconds + public ushort servo7_raw; /// Servo output 7 value, in microseconds + public ushort servo8_raw; /// Servo output 8 value, in microseconds }; public const byte MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN = 16; @@ -930,8 +932,8 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_set_altitude_t { - public byte target; ///< The system setting the altitude - public uint mode; ///< The new altitude in meters + public byte target; /// The system setting the altitude + public uint mode; /// The new altitude in meters }; public const byte MAVLINK_MSG_ID_SET_ALTITUDE_LEN = 5; @@ -940,8 +942,8 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_set_mode_t { - public byte target; ///< The system setting the mode - public byte mode; ///< The new mode + public byte target; /// The system setting the mode + public byte mode; /// The new mode }; public const byte MAVLINK_MSG_ID_SET_MODE_LEN = 2; @@ -950,8 +952,8 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_set_nav_mode_t { - public byte target; ///< The system setting the mode - public byte nav_mode; ///< The new navigation mode + public byte target; /// The system setting the mode + public byte nav_mode; /// The new navigation mode }; public const byte MAVLINK_MSG_ID_SET_NAV_MODE_LEN = 2; @@ -960,11 +962,11 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_set_roll_pitch_yaw_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID - public float roll; ///< Desired roll angle in radians - public float pitch; ///< Desired pitch angle in radians - public float yaw; ///< Desired yaw angle in radians + public byte target_system; /// System ID + public byte target_component; /// Component ID + public float roll; /// Desired roll angle in radians + public float pitch; /// Desired pitch angle in radians + public float yaw; /// Desired yaw angle in radians }; @@ -972,11 +974,11 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_set_roll_pitch_yaw_speed_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID - public float roll_speed; ///< Desired roll angular speed in rad/s - public float pitch_speed; ///< Desired pitch angular speed in rad/s - public float yaw_speed; ///< Desired yaw angular speed in rad/s + public byte target_system; /// System ID + public byte target_component; /// Component ID + public float roll_speed; /// Desired roll angular speed in rad/s + public float pitch_speed; /// Desired pitch angular speed in rad/s + public float yaw_speed; /// Desired yaw angular speed in rad/s }; @@ -984,12 +986,12 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_set_roll_pitch_yaw_speed_thrust_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID - public float roll_speed; ///< Desired roll angular speed in rad/s - public float pitch_speed; ///< Desired pitch angular speed in rad/s - public float yaw_speed; ///< Desired yaw angular speed in rad/s - public float thrust; ///< Collective thrust, normalized to 0 .. 1 + public byte target_system; /// System ID + public byte target_component; /// Component ID + public float roll_speed; /// Desired roll angular speed in rad/s + public float pitch_speed; /// Desired pitch angular speed in rad/s + public float yaw_speed; /// Desired yaw angular speed in rad/s + public float thrust; /// Collective thrust, normalized to 0 .. 1 }; public const byte MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN = 18; @@ -998,12 +1000,12 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_set_roll_pitch_yaw_thrust_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID - public float roll; ///< Desired roll angle in radians - public float pitch; ///< Desired pitch angle in radians - public float yaw; ///< Desired yaw angle in radians - public float thrust; ///< Collective thrust, normalized to 0 .. 1 + public byte target_system; /// System ID + public byte target_component; /// Component ID + public float roll; /// Desired roll angle in radians + public float pitch; /// Desired pitch angle in radians + public float yaw; /// Desired yaw angle in radians + public float thrust; /// Collective thrust, normalized to 0 .. 1 }; public const byte MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN = 18; @@ -1012,15 +1014,15 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_state_correction_t { - public float xErr; ///< x position error - public float yErr; ///< y position error - public float zErr; ///< z position error - public float rollErr; ///< roll error (radians) - public float pitchErr; ///< pitch error (radians) - public float yawErr; ///< yaw error (radians) - public float vxErr; ///< x velocity - public float vyErr; ///< y velocity - public float vzErr; ///< z velocity + public float xErr; /// x position error + public float yErr; /// y position error + public float zErr; /// z position error + public float rollErr; /// roll error (radians) + public float pitchErr; /// pitch error (radians) + public float yawErr; /// yaw error (radians) + public float vxErr; /// x velocity + public float vyErr; /// y velocity + public float vzErr; /// z velocity }; public const byte MAVLINK_MSG_ID_STATE_CORRECTION_LEN = 36; @@ -1029,11 +1031,11 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_statustext_t { - public byte severity; ///< Severity of status, 0 = info message, 255 = critical fault + public byte severity; /// Severity of status, 0 = info message, 255 = critical fault [MarshalAs( UnmanagedType.ByValArray, SizeConst=50)] - public byte[] text; ///< Status text message, without null termination character + public byte[] text; /// Status text message, without null termination character }; public const byte MAVLINK_MSG_ID_STATUSTEXT_LEN = 51; @@ -1044,13 +1046,13 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_sys_status_t { - public byte mode; ///< System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h - public byte nav_mode; ///< Navigation mode, see MAV_NAV_MODE ENUM - public byte status; ///< System status flag, see MAV_STATUS ENUM - public ushort load; ///< Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 - public ushort vbat; ///< Battery voltage, in millivolts (1 = 1 millivolt) - public ushort battery_remaining; ///< Remaining battery energy: (0%: 0, 100%: 1000) - public ushort packet_drop; ///< Dropped packets (packets that were corrupted on reception on the MAV) + public byte mode; /// System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h + public byte nav_mode; /// Navigation mode, see MAV_NAV_MODE ENUM + public byte status; /// System status flag, see MAV_STATUS ENUM + public ushort load; /// Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + public ushort vbat; /// Battery voltage, in millivolts (1 = 1 millivolt) + public ushort battery_remaining; /// Remaining battery energy: (0%: 0, 100%: 1000) + public ushort packet_drop; /// Dropped packets (packets that were corrupted on reception on the MAV) }; public const byte MAVLINK_MSG_ID_SYS_STATUS_LEN = 11; @@ -1059,12 +1061,12 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_vfr_hud_t { - public float airspeed; ///< Current airspeed in m/s - public float groundspeed; ///< Current ground speed in m/s - public short heading; ///< Current heading in degrees, in compass units (0..360, 0=north) - public ushort throttle; ///< Current throttle setting in integer percent, 0 to 100 - public float alt; ///< Current altitude (MSL), in meters - public float climb; ///< Current climb rate in meters/second + public float airspeed; /// Current airspeed in m/s + public float groundspeed; /// Current ground speed in m/s + public short heading; /// Current heading in degrees, in compass units (0..360, 0=north) + public ushort throttle; /// Current throttle setting in integer percent, 0 to 100 + public float alt; /// Current altitude (MSL), in meters + public float climb; /// Current climb rate in meters/second }; public const byte MAVLINK_MSG_ID_VFR_HUD_LEN = 20; @@ -1073,20 +1075,20 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_waypoint_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID - public ushort seq; ///< Sequence - public byte frame; ///< The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h - public byte command; ///< The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs - public byte current; ///< false:0, true:1 - public byte autocontinue; ///< autocontinue to next wp - public float param1; ///< PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters - public float param2; ///< PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds - public float param3; ///< PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. - public float param4; ///< PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH - public float x; ///< PARAM5 / local: x position, global: latitude - public float y; ///< PARAM6 / y position: global: longitude - public float z; ///< PARAM7 / z position: global: altitude + public byte target_system; /// System ID + public byte target_component; /// Component ID + public ushort seq; /// Sequence + public byte frame; /// The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h + public byte command; /// The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs + public byte current; /// false:0, true:1 + public byte autocontinue; /// autocontinue to next wp + public float param1; /// PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters + public float param2; /// PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds + public float param3; /// PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. + public float param4; /// PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH + public float x; /// PARAM5 / local: x position, global: latitude + public float y; /// PARAM6 / y position: global: longitude + public float z; /// PARAM7 / z position: global: altitude }; public const byte MAVLINK_MSG_ID_WAYPOINT_LEN = 36; @@ -1095,9 +1097,9 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_waypoint_ack_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID - public byte type; ///< 0: OK, 1: Error + public byte target_system; /// System ID + public byte target_component; /// Component ID + public byte type; /// 0: OK, 1: Error }; public const byte MAVLINK_MSG_ID_WAYPOINT_ACK_LEN = 3; @@ -1106,8 +1108,8 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_waypoint_clear_all_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID + public byte target_system; /// System ID + public byte target_component; /// Component ID }; public const byte MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL_LEN = 2; @@ -1116,9 +1118,9 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_waypoint_count_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID - public ushort count; ///< Number of Waypoints in the Sequence + public byte target_system; /// System ID + public byte target_component; /// Component ID + public ushort count; /// Number of Waypoints in the Sequence }; public const byte MAVLINK_MSG_ID_WAYPOINT_COUNT_LEN = 4; @@ -1127,7 +1129,7 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_waypoint_current_t { - public ushort seq; ///< Sequence + public ushort seq; /// Sequence }; public const byte MAVLINK_MSG_ID_WAYPOINT_CURRENT_LEN = 2; @@ -1136,7 +1138,7 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_waypoint_reached_t { - public ushort seq; ///< Sequence + public ushort seq; /// Sequence }; public const byte MAVLINK_MSG_ID_WAYPOINT_REACHED_LEN = 2; @@ -1145,9 +1147,9 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_waypoint_request_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID - public ushort seq; ///< Sequence + public byte target_system; /// System ID + public byte target_component; /// Component ID + public ushort seq; /// Sequence }; public const byte MAVLINK_MSG_ID_WAYPOINT_REQUEST_LEN = 4; @@ -1156,8 +1158,8 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_waypoint_request_list_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID + public byte target_system; /// System ID + public byte target_component; /// Component ID }; public const byte MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST_LEN = 2; @@ -1166,9 +1168,9 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_waypoint_set_current_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID - public ushort seq; ///< Sequence + public byte target_system; /// System ID + public byte target_component; /// Component ID + public ushort seq; /// Sequence }; public const byte MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT_LEN = 4; @@ -1177,31 +1179,31 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_waypoint_set_global_reference_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID - public float global_x; ///< global x position - public float global_y; ///< global y position - public float global_z; ///< global z position - public float global_yaw; ///< global yaw orientation in radians, 0 = NORTH - public float local_x; ///< local x position that matches the global x position - public float local_y; ///< local y position that matches the global y position - public float local_z; ///< local z position that matches the global z position - public float local_yaw; ///< local yaw that matches the global yaw orientation + public byte target_system; /// System ID + public byte target_component; /// Component ID + public float global_x; /// global x position + public float global_y; /// global y position + public float global_z; /// global z position + public float global_yaw; /// global yaw orientation in radians, 0 = NORTH + public float local_x; /// local x position that matches the global x position + public float local_y; /// local y position that matches the global y position + public float local_z; /// local z position that matches the global z position + public float local_yaw; /// local yaw that matches the global yaw orientation }; public enum MAV_CLASS { - MAV_CLASS_GENERIC = 0, ///< Generic autopilot, full support for everything - MAV_CLASS_PIXHAWK = 1, ///< PIXHAWK autopilot, http://pixhawk.ethz.ch - MAV_CLASS_SLUGS = 2, ///< SLUGS autopilot, http://slugsuav.soe.ucsc.edu - MAV_CLASS_ARDUPILOTMEGA = 3, ///< ArduPilotMega / ArduCopter, http://diydrones.com - MAV_CLASS_OPENPILOT = 4, ///< OpenPilot, http://openpilot.org - MAV_CLASS_GENERIC_MISSION_WAYPOINTS_ONLY = 5, ///< Generic autopilot only supporting simple waypoints - MAV_CLASS_GENERIC_MISSION_NAVIGATION_ONLY = 6, ///< Generic autopilot supporting waypoints and other simple navigation commands - MAV_CLASS_GENERIC_MISSION_FULL = 7, ///< Generic autopilot supporting the full mission command set - MAV_CLASS_NONE = 8, ///< No valid autopilot - MAV_CLASS_NB ///< Number of autopilot classes + MAV_CLASS_GENERIC = 0, /// Generic autopilot, full support for everything + MAV_CLASS_PIXHAWK = 1, /// PIXHAWK autopilot, http://pixhawk.ethz.ch + MAV_CLASS_SLUGS = 2, /// SLUGS autopilot, http://slugsuav.soe.ucsc.edu + MAV_CLASS_ARDUPILOTMEGA = 3, /// ArduPilotMega / ArduCopter, http://diydrones.com + MAV_CLASS_OPENPILOT = 4, /// OpenPilot, http://openpilot.org + MAV_CLASS_GENERIC_MISSION_WAYPOINTS_ONLY = 5, /// Generic autopilot only supporting simple waypoints + MAV_CLASS_GENERIC_MISSION_NAVIGATION_ONLY = 6, /// Generic autopilot supporting waypoints and other simple navigation commands + MAV_CLASS_GENERIC_MISSION_FULL = 7, /// Generic autopilot supporting the full mission command set + MAV_CLASS_NONE = 8, /// No valid autopilot + MAV_CLASS_NB /// Number of autopilot classes }; public enum MAV_ACTION @@ -1249,21 +1251,21 @@ namespace ArdupilotMega MAV_ACTION_LOITER_MAX_TIME = 40, MAV_ACTION_START_HILSIM = 41, MAV_ACTION_STOP_HILSIM = 42, - MAV_ACTION_NB ///< Number of MAV actions + MAV_ACTION_NB /// Number of MAV actions }; public enum MAV_MODE { - MAV_MODE_UNINIT = 0, ///< System is in undefined state - MAV_MODE_LOCKED = 1, ///< Motors are blocked, system is safe - MAV_MODE_MANUAL = 2, ///< System is allowed to be active, under manual (RC) control - MAV_MODE_GUIDED = 3, ///< System is allowed to be active, under autonomous control, manual setpoint - MAV_MODE_AUTO = 4, ///< System is allowed to be active, under autonomous control and navigation - MAV_MODE_TEST1 = 5, ///< Generic test mode, for custom use - MAV_MODE_TEST2 = 6, ///< Generic test mode, for custom use - MAV_MODE_TEST3 = 7, ///< Generic test mode, for custom use - MAV_MODE_READY = 8, ///< System is ready, motors are unblocked, but controllers are inactive - MAV_MODE_RC_TRAINING = 9 ///< System is blocked, only RC valued are read and reported back + MAV_MODE_UNINIT = 0, /// System is in undefined state + MAV_MODE_LOCKED = 1, /// Motors are blocked, system is safe + MAV_MODE_MANUAL = 2, /// System is allowed to be active, under manual (RC) control + MAV_MODE_GUIDED = 3, /// System is allowed to be active, under autonomous control, manual setpoint + MAV_MODE_AUTO = 4, /// System is allowed to be active, under autonomous control and navigation + MAV_MODE_TEST1 = 5, /// Generic test mode, for custom use + MAV_MODE_TEST2 = 6, /// Generic test mode, for custom use + MAV_MODE_TEST3 = 7, /// Generic test mode, for custom use + MAV_MODE_READY = 8, /// System is ready, motors are unblocked, but controllers are inactive + MAV_MODE_RC_TRAINING = 9 /// System is blocked, only RC valued are read and reported back }; public enum MAV_STATE diff --git a/Tools/ArdupilotMegaPlanner/MainV2.cs b/Tools/ArdupilotMegaPlanner/MainV2.cs index 053f50488e..8d3b7f8006 100644 --- a/Tools/ArdupilotMegaPlanner/MainV2.cs +++ b/Tools/ArdupilotMegaPlanner/MainV2.cs @@ -92,7 +92,7 @@ namespace ArdupilotMega string strVersion = System.Reflection.Assembly.GetExecutingAssembly().GetName().Version.ToString(); strVersion = ""; - splash.Text = "APM Planner " + Application.ProductVersion + " Build " + strVersion + " By Michael Oborne"; + splash.Text = "APM Planner " + Application.ProductVersion + " " + strVersion + " By Michael Oborne"; splash.Refresh(); diff --git a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs index a6ddb45003..f908130f35 100644 --- a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs +++ b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs @@ -34,5 +34,5 @@ using System.Resources; // by using the '*' as shown below: // [assembly: AssemblyVersion("1.0.*")] [assembly: AssemblyVersion("1.0.0.0")] -[assembly: AssemblyFileVersion("1.0.76")] +[assembly: AssemblyFileVersion("1.0.79")] [assembly: NeutralResourcesLanguageAttribute("")] diff --git a/Tools/ArdupilotMegaPlanner/Properties/Settings.Designer.cs b/Tools/ArdupilotMegaPlanner/Properties/Settings.Designer.cs deleted file mode 100644 index 2aaa6a08c6..0000000000 --- a/Tools/ArdupilotMegaPlanner/Properties/Settings.Designer.cs +++ /dev/null @@ -1,26 +0,0 @@ -//------------------------------------------------------------------------------ -// -// This code was generated by a tool. -// Runtime Version:4.0.30319.1 -// -// Changes to this file may cause incorrect behavior and will be lost if -// the code is regenerated. -// -//------------------------------------------------------------------------------ - -namespace ArdupilotMega.Properties { - - - [global::System.Runtime.CompilerServices.CompilerGeneratedAttribute()] - [global::System.CodeDom.Compiler.GeneratedCodeAttribute("Microsoft.VisualStudio.Editors.SettingsDesigner.SettingsSingleFileGenerator", "10.0.0.0")] - internal sealed partial class Settings : global::System.Configuration.ApplicationSettingsBase { - - private static Settings defaultInstance = ((Settings)(global::System.Configuration.ApplicationSettingsBase.Synchronized(new Settings()))); - - public static Settings Default { - get { - return defaultInstance; - } - } - } -} diff --git a/Tools/ArdupilotMegaPlanner/Properties/Settings.settings b/Tools/ArdupilotMegaPlanner/Properties/Settings.settings deleted file mode 100644 index abf36c5d3d..0000000000 --- a/Tools/ArdupilotMegaPlanner/Properties/Settings.settings +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/Tools/ArdupilotMegaPlanner/Resources/MAVParam.txt b/Tools/ArdupilotMegaPlanner/Resources/MAVParam.txt index 011946774a..9a19416a3b 100644 --- a/Tools/ArdupilotMegaPlanner/Resources/MAVParam.txt +++ b/Tools/ArdupilotMegaPlanner/Resources/MAVParam.txt @@ -16,15 +16,15 @@ It includes both fixed wing (APM) and rotary wing (!ArduCopter) parameters. Some ||RLL2SRV_P||0||5||0.4||1||1||SERVO_ROLL_P - Attitude control gains - Tuning values for the attitude control PID loops. The P term is the primary tuning value. This determines how the control deflection varies in proportion to the required correction.|| ||RLL2SRV_I||0||1||0||1||1||SERVO_ROLL_I - Attitude control gains - Tuning values for the attitude control PID loops. The I term is used to help control surfaces settle. This value should normally be kept low.|| ||RLL2SRV_D||0||1||0||1||1||SERVO_ROLL_D - Attitude control gains - Tuning values for the attitude control PID loops. The D term is used to control overshoot. Avoid using or adjusting this term if you are not familiar with tuning PID loops. It should normally be zero for most aircraft.|| -||RLL2SRV_IMAX||0||3000||500||100||1||SERVO_ROLL_INT_MAX_CENTIDEGREE - In Degrees - Maximum control offset due to the integral. This prevents the control output from being overdriven due to a persistent offset (e.g. crosstracking). Default is 5 degrees.|| +||RLL2SRV_IMAX||0||3000||500||100||1||SERVO_ROLL_INT_MAX_DEGREE - In Degrees - Maximum control offset due to the integral. This prevents the control output from being overdriven due to a persistent offset (e.g. crosstracking). Default is 5 degrees.|| ||PTCH2SRV_P||0||5||0.6||1||1||SERVO_PITCH_P - Attitude control gains - Tuning values for the attitude control PID loops. The P term is the primary tuning value. This determines how the control deflection varies in proportion to the required correction.|| ||PTCH2SRV_I||0||1||0||1||1||SERVO_PITCH_I - Attitude control gains - Tuning values for the attitude control PID loops. The I term is used to help control surfaces settle. This value should normally be kept low.|| ||PTCH2SRV_D||0||1||0||1||1||SERVO_PITCH_D - Attitude control gains - Tuning values for the attitude control PID loops. The D term is used to control overshoot. Avoid using or adjusting this term if you are not familiar with tuning PID loops. It should normally be zero for most aircraft.|| -||PTCH2SRV_IMAX||0||3000||500||100||1||SERVO_PITCH_INT_MAX_CENTIDEGREE - In Degrees - Maximum control offset due to the integral. This prevents the control output from being overdriven due to a persistent offset (e.g. crosstracking). Default is 5 degrees.|| +||PTCH2SRV_IMAX||0||3000||500||100||1||SERVO_PITCH_INT_MAX_DEGREE - In Degrees - Maximum control offset due to the integral. This prevents the control output from being overdriven due to a persistent offset (e.g. crosstracking). Default is 5 degrees.|| ||ARSPD2PTCH_P||0||5||0.65||1||1||NAV_PITCH_ASP_P - P. I and D terms for pitch adjustments made to maintain airspeed.|| ||ARSPD2PTCH_I||0||1||0||1||1||NAV_PITCH_ASP_I - P. I and D terms for pitch adjustments made to maintain airspeed.|| ||ARSPD2PTCH_D||0||1||0||1||1||NAV_PITCH_ASP_D - P. I and D terms for pitch adjustments made to maintain airspeed.|| -||ARSPD2PTCH_IMA||0||3000||500||100||1||NAV_PITCH_ASP_INT_MAX_CMSEC - In Degrees - Maximum pitch offset due to the integral. This limits the control output from being overdriven due to a persistent offset (eg. inability to maintain the programmed airspeed).|| +||ARSPD2PTCH_IMA||0||3000||500||100||1||NAV_PITCH_ASP_INT_MAX - In Degrees - Maximum pitch offset due to the integral. This limits the control output from being overdriven due to a persistent offset (eg. inability to maintain the programmed airspeed).|| ||YW2SRV_P||0||5||0||1||1||SERVO_YAW_P - P. I and D terms for the YAW control. Note units of this control loop are unusual. PID input is in m/s**2|| ||YW2SRV_I||0||1||0||1||1||SERVO_YAW_I - P. I and D terms for the YAW control. Note units of this control loop are unusual. PID input is in m/s**2|| ||YW2SRV_D||0||1||0||1||1||SERVO_YAW_D - P. I and D terms for the YAW control. Note units of this control loop are unusual. PID input is in m/s**2|| @@ -36,7 +36,7 @@ It includes both fixed wing (APM) and rotary wing (!ArduCopter) parameters. Some ||ALT2PTCH_P||0||5||0.65||1||1||NAV_PITCH_ALT_P - P. I and D terms for pitch adjustments made to maintain altitude.|| ||ALT2PTCH_I||0||1||0||1||1||NAV_PITCH_ALT_I - P. I and D terms for pitch adjustments made to maintain altitude.|| ||ALT2PTCH_D||0||1||0||1||1||NAV_PITCH_ALT_D - P. I and D terms for pitch adjustments made to maintain altitude.|| -||ALT2PTCH_IMAX||0||3000||500||100||1||NAV_PITCH_ALT_INT_MAX_CM - In Meters - Maximum pitch offset due to the integral. This limits the control output from being overdriven due to a persistent offset (eg. inability to maintain the programmed altitude).|| +||ALT2PTCH_IMAX||0||3000||500||100||1||NAV_PITCH_ALT_INT_MAX - In Meters - Maximum pitch offset due to the integral. This limits the control output from being overdriven due to a persistent offset (eg. inability to maintain the programmed altitude).|| ||KFF_PTCHCOMP||-3||3||0.2||0.01||1||PITCH_COMP - In Percent - Adds pitch input to compensate for the loss of lift due to roll control.|| ||KFF_RDDRMIX||-3||3||0.5||0.01||1||RUDDER_MIX - Roll to yaw mixing. This allows for co-ordinated turns.|| ||KFF_PTCH2THR||-3||3||0||1||1||P_TO_T - Pitch to throttle feed-forward gain.|| @@ -107,13 +107,13 @@ It includes both fixed wing (APM) and rotary wing (!ArduCopter) parameters. Some ||AP_OFFSET|| || ||0|| || ||AP_OFFSET|| ||TRIM_PITCH_CD|| || ||0|| || ||TRIM_PITCH_CD|| ||ALT_HOLD_RTL||0||20000||10000||100||1||ALT_HOLD_HOME_CM - When the user performs a factory reset on the APM. Sets the flag for weather the current altitude or ALT_HOLD_HOME altitude should be used for Return To Launch. Also sets the value of USE_CURRENT_ALT in meters. This is mainly intended to allow users to start using the APM without programming a mission first.|| -||XTRK_ANGLE_CD||0||6000||3000||100||1||XTRACK_ENTRY_ANGLE_CENTIDEGREE - Maximum angle used to correct for track following.|| -||ROLL_SRV_MAX||0||100||4500||100||0||ROLL_SERVO_MAX_CENTIDEGREE|| -||PITCH_SRV_MAX||0||100||4500||100||0||PITCH_SERVO_MAX_CENTIDEGREE|| -||RUDER_SRV_MAX||0||100||4500||100||0||RUDDER_SERVO_MAX_CENTIDEGREE|| -||LIM_ROLL_CD||0||6000||4500||100||1||HEAD_MAX_CENTIDEGREE - The maximum commanded bank angle in either direction. The default is 45 degrees. Decrease this value if your aircraft is not stable or has difficulty maintaining altitude in a steep bank.|| -||LIM_PITCH_MAX||0||6000||1500||100||1||PITCH_MAX_CENTIDEGREE - The maximum commanded pitch up angle. The default is 15 degrees. Care should be taken not to set this value too large, as the aircraft may stall|| -||LIM_PITCH_MIN||-6000||0||-2500||100||1||PITCH_MIN_CENTIDEGREE - The maximum commanded pitch down angle. Note that this value must be negative. The default is -25 degrees. Care should be taken not to set this value too large as it may result in overspeeding the aircraft.|| +||XTRK_ANGLE_CD||0||6000||3000||100||1||XTRACK_ENTRY_ANGLE_DEGREE - Maximum angle used to correct for track following.|| +||ROLL_SRV_MAX||0||100||4500||100||0||ROLL_SERVO_MAX_DEGREE|| +||PITCH_SRV_MAX||0||100||4500||100||0||PITCH_SERVO_MAX_DEGREE|| +||RUDER_SRV_MAX||0||100||4500||100||0||RUDDER_SERVO_MAX_DEGREE|| +||LIM_ROLL_CD||0||6000||4500||100||1||HEAD_MAX_DEGREE - The maximum commanded bank angle in either direction. The default is 45 degrees. Decrease this value if your aircraft is not stable or has difficulty maintaining altitude in a steep bank.|| +||LIM_PITCH_MAX||0||6000||1500||100||1||PITCH_MAX_DEGREE - The maximum commanded pitch up angle. The default is 15 degrees. Care should be taken not to set this value too large, as the aircraft may stall|| +||LIM_PITCH_MIN||-6000||0||-2500||100||1||PITCH_MIN_DEGREE - The maximum commanded pitch down angle. Note that this value must be negative. The default is -25 degrees. Care should be taken not to set this value too large as it may result in overspeeding the aircraft.|| ||GND_ALT_CM||0||500000||0||100||1||GND_ALT_CM|| ||GND_ABS_PRESS|| || ||0|| || ||GND_ABS_PRESS|| ||COMPASS_DEC||-1.57075||1.57075||0||1|| ||COMPASS_DEC - Compass Declination|| diff --git a/Tools/ArdupilotMegaPlanner/Resources/Welcome CN.rtf b/Tools/ArdupilotMegaPlanner/Resources/Welcome CN.rtf deleted file mode 100644 index 253db97fbb..0000000000 Binary files a/Tools/ArdupilotMegaPlanner/Resources/Welcome CN.rtf and /dev/null differ diff --git a/Tools/ArdupilotMegaPlanner/Resources/Welcome to Michael Oborne.rtf b/Tools/ArdupilotMegaPlanner/Resources/Welcome to Michael Oborne.rtf deleted file mode 100644 index a87e389297..0000000000 --- a/Tools/ArdupilotMegaPlanner/Resources/Welcome to Michael Oborne.rtf +++ /dev/null @@ -1,201 +0,0 @@ -{\rtf1\adeflang1025\ansi\ansicpg1252\uc1\adeff31507\deff0\stshfdbch0\stshfloch31506\stshfhich31506\stshfbi31506\deflang3081\deflangfe3081\themelang3081\themelangfe0\themelangcs0{\fonttbl{\f0\fbidi \froman\fcharset0\fprq2{\*\panose 02020603050405020304}Times New Roman;}{\f34\fbidi \froman\fcharset0\fprq2{\*\panose 02040503050406030204}Cambria Math;} -{\f37\fbidi \fswiss\fcharset0\fprq2{\*\panose 020f0502020204030204}Calibri;}{\flomajor\f31500\fbidi \froman\fcharset0\fprq2{\*\panose 02020603050405020304}Times New Roman;} -{\fdbmajor\f31501\fbidi \froman\fcharset0\fprq2{\*\panose 02020603050405020304}Times New Roman;}{\fhimajor\f31502\fbidi \froman\fcharset0\fprq2{\*\panose 02040503050406030204}Cambria;} -{\fbimajor\f31503\fbidi \froman\fcharset0\fprq2{\*\panose 02020603050405020304}Times New Roman;}{\flominor\f31504\fbidi \froman\fcharset0\fprq2{\*\panose 02020603050405020304}Times New Roman;} -{\fdbminor\f31505\fbidi \froman\fcharset0\fprq2{\*\panose 02020603050405020304}Times New Roman;}{\fhiminor\f31506\fbidi \fswiss\fcharset0\fprq2{\*\panose 020f0502020204030204}Calibri;} -{\fbiminor\f31507\fbidi \froman\fcharset0\fprq2{\*\panose 02020603050405020304}Times New Roman;}{\f39\fbidi \froman\fcharset238\fprq2 Times New Roman CE;}{\f40\fbidi \froman\fcharset204\fprq2 Times New Roman Cyr;} -{\f42\fbidi \froman\fcharset161\fprq2 Times New Roman Greek;}{\f43\fbidi \froman\fcharset162\fprq2 Times New Roman Tur;}{\f44\fbidi \froman\fcharset177\fprq2 Times New Roman (Hebrew);}{\f45\fbidi \froman\fcharset178\fprq2 Times New Roman (Arabic);} -{\f46\fbidi \froman\fcharset186\fprq2 Times New Roman Baltic;}{\f47\fbidi \froman\fcharset163\fprq2 Times New Roman (Vietnamese);}{\f379\fbidi \froman\fcharset238\fprq2 Cambria Math CE;}{\f380\fbidi \froman\fcharset204\fprq2 Cambria Math Cyr;} -{\f382\fbidi \froman\fcharset161\fprq2 Cambria Math Greek;}{\f383\fbidi \froman\fcharset162\fprq2 Cambria Math Tur;}{\f386\fbidi \froman\fcharset186\fprq2 Cambria Math Baltic;}{\f387\fbidi \froman\fcharset163\fprq2 Cambria Math (Vietnamese);} -{\f409\fbidi \fswiss\fcharset238\fprq2 Calibri CE;}{\f410\fbidi \fswiss\fcharset204\fprq2 Calibri Cyr;}{\f412\fbidi \fswiss\fcharset161\fprq2 Calibri Greek;}{\f413\fbidi \fswiss\fcharset162\fprq2 Calibri Tur;} -{\f416\fbidi \fswiss\fcharset186\fprq2 Calibri Baltic;}{\f417\fbidi \fswiss\fcharset163\fprq2 Calibri (Vietnamese);}{\flomajor\f31508\fbidi \froman\fcharset238\fprq2 Times New Roman CE;} -{\flomajor\f31509\fbidi \froman\fcharset204\fprq2 Times New Roman Cyr;}{\flomajor\f31511\fbidi \froman\fcharset161\fprq2 Times New Roman Greek;}{\flomajor\f31512\fbidi \froman\fcharset162\fprq2 Times New Roman Tur;} -{\flomajor\f31513\fbidi \froman\fcharset177\fprq2 Times New Roman (Hebrew);}{\flomajor\f31514\fbidi \froman\fcharset178\fprq2 Times New Roman (Arabic);}{\flomajor\f31515\fbidi \froman\fcharset186\fprq2 Times New Roman Baltic;} -{\flomajor\f31516\fbidi \froman\fcharset163\fprq2 Times New Roman (Vietnamese);}{\fdbmajor\f31518\fbidi \froman\fcharset238\fprq2 Times New Roman CE;}{\fdbmajor\f31519\fbidi \froman\fcharset204\fprq2 Times New Roman Cyr;} -{\fdbmajor\f31521\fbidi \froman\fcharset161\fprq2 Times New Roman Greek;}{\fdbmajor\f31522\fbidi \froman\fcharset162\fprq2 Times New Roman Tur;}{\fdbmajor\f31523\fbidi \froman\fcharset177\fprq2 Times New Roman (Hebrew);} -{\fdbmajor\f31524\fbidi \froman\fcharset178\fprq2 Times New Roman (Arabic);}{\fdbmajor\f31525\fbidi \froman\fcharset186\fprq2 Times New Roman Baltic;}{\fdbmajor\f31526\fbidi \froman\fcharset163\fprq2 Times New Roman (Vietnamese);} -{\fhimajor\f31528\fbidi \froman\fcharset238\fprq2 Cambria CE;}{\fhimajor\f31529\fbidi \froman\fcharset204\fprq2 Cambria Cyr;}{\fhimajor\f31531\fbidi \froman\fcharset161\fprq2 Cambria Greek;}{\fhimajor\f31532\fbidi \froman\fcharset162\fprq2 Cambria Tur;} -{\fhimajor\f31535\fbidi \froman\fcharset186\fprq2 Cambria Baltic;}{\fhimajor\f31536\fbidi \froman\fcharset163\fprq2 Cambria (Vietnamese);}{\fbimajor\f31538\fbidi \froman\fcharset238\fprq2 Times New Roman CE;} -{\fbimajor\f31539\fbidi \froman\fcharset204\fprq2 Times New Roman Cyr;}{\fbimajor\f31541\fbidi \froman\fcharset161\fprq2 Times New Roman Greek;}{\fbimajor\f31542\fbidi \froman\fcharset162\fprq2 Times New Roman Tur;} -{\fbimajor\f31543\fbidi \froman\fcharset177\fprq2 Times New Roman (Hebrew);}{\fbimajor\f31544\fbidi \froman\fcharset178\fprq2 Times New Roman (Arabic);}{\fbimajor\f31545\fbidi \froman\fcharset186\fprq2 Times New Roman Baltic;} -{\fbimajor\f31546\fbidi \froman\fcharset163\fprq2 Times New Roman (Vietnamese);}{\flominor\f31548\fbidi \froman\fcharset238\fprq2 Times New Roman CE;}{\flominor\f31549\fbidi \froman\fcharset204\fprq2 Times New Roman Cyr;} -{\flominor\f31551\fbidi \froman\fcharset161\fprq2 Times New Roman Greek;}{\flominor\f31552\fbidi \froman\fcharset162\fprq2 Times New Roman Tur;}{\flominor\f31553\fbidi \froman\fcharset177\fprq2 Times New Roman (Hebrew);} -{\flominor\f31554\fbidi \froman\fcharset178\fprq2 Times New Roman (Arabic);}{\flominor\f31555\fbidi \froman\fcharset186\fprq2 Times New Roman Baltic;}{\flominor\f31556\fbidi \froman\fcharset163\fprq2 Times New Roman (Vietnamese);} -{\fdbminor\f31558\fbidi \froman\fcharset238\fprq2 Times New Roman CE;}{\fdbminor\f31559\fbidi \froman\fcharset204\fprq2 Times New Roman Cyr;}{\fdbminor\f31561\fbidi \froman\fcharset161\fprq2 Times New Roman Greek;} -{\fdbminor\f31562\fbidi \froman\fcharset162\fprq2 Times New Roman Tur;}{\fdbminor\f31563\fbidi \froman\fcharset177\fprq2 Times New Roman (Hebrew);}{\fdbminor\f31564\fbidi \froman\fcharset178\fprq2 Times New Roman (Arabic);} -{\fdbminor\f31565\fbidi \froman\fcharset186\fprq2 Times New Roman Baltic;}{\fdbminor\f31566\fbidi \froman\fcharset163\fprq2 Times New Roman (Vietnamese);}{\fhiminor\f31568\fbidi \fswiss\fcharset238\fprq2 Calibri CE;} -{\fhiminor\f31569\fbidi \fswiss\fcharset204\fprq2 Calibri Cyr;}{\fhiminor\f31571\fbidi \fswiss\fcharset161\fprq2 Calibri Greek;}{\fhiminor\f31572\fbidi \fswiss\fcharset162\fprq2 Calibri Tur;} -{\fhiminor\f31575\fbidi \fswiss\fcharset186\fprq2 Calibri Baltic;}{\fhiminor\f31576\fbidi \fswiss\fcharset163\fprq2 Calibri (Vietnamese);}{\fbiminor\f31578\fbidi \froman\fcharset238\fprq2 Times New Roman CE;} -{\fbiminor\f31579\fbidi \froman\fcharset204\fprq2 Times New Roman Cyr;}{\fbiminor\f31581\fbidi \froman\fcharset161\fprq2 Times New Roman Greek;}{\fbiminor\f31582\fbidi \froman\fcharset162\fprq2 Times New Roman Tur;} -{\fbiminor\f31583\fbidi \froman\fcharset177\fprq2 Times New Roman (Hebrew);}{\fbiminor\f31584\fbidi \froman\fcharset178\fprq2 Times New Roman (Arabic);}{\fbiminor\f31585\fbidi \froman\fcharset186\fprq2 Times New Roman Baltic;} -{\fbiminor\f31586\fbidi \froman\fcharset163\fprq2 Times New Roman (Vietnamese);}}{\colortbl;\red0\green0\blue0;\red0\green0\blue255;\red0\green255\blue255;\red0\green255\blue0;\red255\green0\blue255;\red255\green0\blue0;\red255\green255\blue0; -\red255\green255\blue255;\red0\green0\blue128;\red0\green128\blue128;\red0\green128\blue0;\red128\green0\blue128;\red128\green0\blue0;\red128\green128\blue0;\red128\green128\blue128;\red192\green192\blue192; -\cbackgroundone\ctint255\cshade255\red255\green255\blue255;}{\*\defchp \f31506\fs22\lang3081\langfe1033\langfenp1033 }{\*\defpap \ql \li0\ri0\sa200\sl276\slmult1\widctlpar\wrapdefault\aspalpha\aspnum\faauto\adjustright\rin0\lin0\itap0 } -\noqfpromote {\stylesheet{\ql \li0\ri0\sa200\sl276\slmult1\widctlpar\wrapdefault\aspalpha\aspnum\faauto\adjustright\rin0\lin0\itap0 \rtlch\fcs1 \af31507\afs22\alang1025 \ltrch\fcs0 \f31506\fs22\lang3081\langfe1033\cgrid\langnp3081\langfenp1033 -\snext0 \sqformat \spriority0 \styrsid16143823 Normal;}{\*\cs10 \additive \ssemihidden \sunhideused \spriority1 Default Paragraph Font;}{\* -\ts11\tsrowd\trftsWidthB3\trpaddl108\trpaddr108\trpaddfl3\trpaddft3\trpaddfb3\trpaddfr3\trcbpat1\trcfpat1\tblind0\tblindtype3\tscellwidthfts0\tsvertalt\tsbrdrt\tsbrdrl\tsbrdrb\tsbrdrr\tsbrdrdgl\tsbrdrdgr\tsbrdrh\tsbrdrv \ql \li0\ri0\sa200\sl276\slmult1 -\widctlpar\wrapdefault\aspalpha\aspnum\faauto\adjustright\rin0\lin0\itap0 \rtlch\fcs1 \af31506\afs22\alang1025 \ltrch\fcs0 \f31506\fs22\lang3081\langfe1033\cgrid\langnp3081\langfenp1033 \snext11 \ssemihidden \sunhideused \sqformat Normal Table;}{ -\s15\ql \li0\ri0\widctlpar\wrapdefault\aspalpha\aspnum\faauto\adjustright\rin0\lin0\itap0 \rtlch\fcs1 \af31507\afs22\alang1025 \ltrch\fcs0 \f31506\fs22\lang3081\langfe1033\cgrid\langnp3081\langfenp1033 \snext15 \sqformat \spriority1 \styrsid726741 -No Spacing;}}{\*\rsidtbl \rsid7442\rsid339864\rsid681062\rsid726741\rsid6191487\rsid6893676\rsid7282557\rsid9392979\rsid10362823\rsid10640918\rsid10889776\rsid11735092\rsid12676204\rsid15301506\rsid15608641\rsid16143823\rsid16653158}{\mmathPr\mmathFont34 -\mbrkBin0\mbrkBinSub0\msmallFrac0\mdispDef1\mlMargin0\mrMargin0\mdefJc1\mwrapIndent1440\mintLim0\mnaryLim1}{\info{\author Michael}{\operator Michael}{\creatim\yr2011\mo6\dy4\hr10\min22}{\revtim\yr2011\mo6\dy4\hr10\min32}{\version4}{\edmins1}{\nofpages1} -{\nofwords117}{\nofchars747}{\*\company .}{\nofcharsws863}{\vern32771}}{\*\xmlnstbl {\xmlns1 http://schemas.microsoft.com/office/word/2003/wordml}}\paperw11906\paperh16838\margl1440\margr1440\margt1440\margb1440\gutter0\ltrsect -\widowctrl\ftnbj\aenddoc\trackmoves1\trackformatting1\donotembedsysfont1\relyonvml0\donotembedlingdata0\grfdocevents0\validatexml1\showplaceholdtext0\ignoremixedcontent0\saveinvalidxml0\showxmlerrors1\noxlattoyen -\expshrtn\noultrlspc\dntblnsbdb\nospaceforul\formshade\horzdoc\dgmargin\dghspace180\dgvspace180\dghorigin150\dgvorigin0\dghshow1\dgvshow1 -\jexpand\viewkind5\viewscale100\pgbrdrhead\pgbrdrfoot\splytwnine\ftnlytwnine\htmautsp\nolnhtadjtbl\useltbaln\alntblind\lytcalctblwd\lyttblrtgr\lnbrkrule\nobrkwrptbl\snaptogridincell\allowfieldendsel\wrppunct -\asianbrkrule\rsidroot726741\newtblstyruls\nogrowautofit\usenormstyforlist\noindnmbrts\felnbrelev\nocxsptable\indrlsweleven\noafcnsttbl\afelev\utinl\hwelev\spltpgpar\notcvasp\notbrkcnstfrctbl\notvatxbx\krnprsnet\cachedcolbal \nouicompat \fet0 -{\*\wgrffmtfilter 2450}\nofeaturethrottle1\ilfomacatclnup0\ltrpar \sectd \ltrsect\linex0\headery708\footery708\colsx708\endnhere\sectlinegrid360\sectdefaultcl\sectrsid16143823\sftnbj {\*\pnseclvl1\pnucrm\pnstart1\pnindent720\pnhang {\pntxta .}} -{\*\pnseclvl2\pnucltr\pnstart1\pnindent720\pnhang {\pntxta .}}{\*\pnseclvl3\pndec\pnstart1\pnindent720\pnhang {\pntxta .}}{\*\pnseclvl4\pnlcltr\pnstart1\pnindent720\pnhang {\pntxta )}}{\*\pnseclvl5\pndec\pnstart1\pnindent720\pnhang {\pntxtb (}{\pntxta )}} -{\*\pnseclvl6\pnlcltr\pnstart1\pnindent720\pnhang {\pntxtb (}{\pntxta )}}{\*\pnseclvl7\pnlcrm\pnstart1\pnindent720\pnhang {\pntxtb (}{\pntxta )}}{\*\pnseclvl8\pnlcltr\pnstart1\pnindent720\pnhang {\pntxtb (}{\pntxta )}}{\*\pnseclvl9 -\pnlcrm\pnstart1\pnindent720\pnhang {\pntxtb (}{\pntxta )}}\pard\plain \ltrpar\ql \li0\ri0\sa200\sl276\slmult1\widctlpar\wrapdefault\aspalpha\aspnum\faauto\adjustright\rin0\lin0\itap0\pararsid726741 \rtlch\fcs1 \af31507\afs22\alang1025 \ltrch\fcs0 -\f31506\fs22\lang3081\langfe1033\cgrid\langnp3081\langfenp1033 {\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid7442 -\par }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid726741\charrsid10889776 \tab Welcome to }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \b\cf17\insrsid726741\charrsid10889776 Michael Oborne\rquote s APM Planner}{\rtlch\fcs1 \af31507 \ltrch\fcs0 -\cf17\insrsid726741\charrsid10889776 , mission planning for Unmanned Aerial Vehicles (}{\rtlch\fcs1 \af31507 \ltrch\fcs0 \b\cf17\insrsid726741\charrsid10889776 UAV}{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid726741\charrsid10889776 ). -\par \tab Getting started: -\par }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid10640918\charrsid10889776 \tab \tab }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \b\cf17\insrsid10640918\charrsid10889776 Flight mode Options}{\rtlch\fcs1 \af31507 \ltrch\fcs0 \b\cf17\insrsid9392979\charrsid10889776 -}{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid9392979\charrsid10889776 (switch away from }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid12676204\charrsid10889776 RC}{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid9392979\charrsid10889776 header)}{ -\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid10640918\charrsid10889776 -\par \tab }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid726741\charrsid10889776 \tab \tab }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \b\cf17\insrsid726741\charrsid10889776 Flight Data }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \b\cf17\insrsid10640918\charrsid10889776 -\endash }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \b\cf17\insrsid726741\charrsid10889776 }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid10362823\charrsid10889776 Flying screen}{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid6191487\charrsid10889776 - with location and attitude.}{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid726741\charrsid10889776 -\par }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \b\cf17\insrsid10640918\charrsid10889776 \tab }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \b\cf17\insrsid726741\charrsid10889776 \tab \tab Flight Planner }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \b\cf17\insrsid6191487\charrsid10889776 -\endash }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \b\cf17\insrsid726741\charrsid10889776 }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid10362823\charrsid10889776 Plans your flight a}{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid6191487\charrsid10889776 -nd other scripted actions}{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid10362823\charrsid10889776 .}{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid726741\charrsid10889776 -\par }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \b\cf17\insrsid10640918\charrsid10889776 \tab }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \b\cf17\insrsid726741\charrsid10889776 \tab \tab Configuration }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \b\cf17\insrsid15301506\charrsid10889776 -\endash }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \b\cf17\insrsid726741\charrsid10889776 }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid10362823\charrsid10889776 Customises}{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid15301506\charrsid10889776 - the PIDS and other critical settings.}{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid726741\charrsid10889776 -\par }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \b\cf17\insrsid10640918\charrsid10889776 \tab }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \b\cf17\insrsid726741\charrsid10889776 \tab \tab Simulation }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \b\cf17\insrsid15301506\charrsid10889776 -\endash }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \b\cf17\insrsid726741\charrsid10889776 }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid15608641\charrsid10889776 Use}{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid681062\charrsid10889776 d}{\rtlch\fcs1 -\af31507 \ltrch\fcs0 \cf17\insrsid15301506\charrsid10889776 with Xplanes and Flightgear for HIL simulation when used with ArduPilot Mega}{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid15608641\charrsid10889776 .}{\rtlch\fcs1 \af31507 \ltrch\fcs0 -\cf17\insrsid726741\charrsid10889776 -\par }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \b\cf17\insrsid10640918\charrsid10889776 \tab \tab CLI/Setup mode Options}{\rtlch\fcs1 \af31507 \ltrch\fcs0 \b\cf17\insrsid9392979\charrsid10889776 }{\rtlch\fcs1 \af31507 \ltrch\fcs0 -\cf17\insrsid9392979\charrsid10889776 (switch towards }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid12676204\charrsid10889776 RC}{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid9392979\charrsid10889776 header)}{\rtlch\fcs1 \af31507 \ltrch\fcs0 -\cf17\insrsid726741\charrsid10889776 \tab }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid10640918\charrsid10889776 -\par }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \b\cf17\insrsid10640918\charrsid10889776 \tab \tab }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \b\cf17\insrsid726741\charrsid10889776 \tab Firmware }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \b\cf17\insrsid16653158\charrsid10889776 -\endash }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \b\cf17\insrsid726741\charrsid10889776 }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid15608641\charrsid10889776 Updates}{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid16653158\charrsid10889776 - your APM Firmware with the latest stable build}{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid15608641\charrsid10889776 , }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid6893676\charrsid10889776 set}{\rtlch\fcs1 \af31507 \ltrch\fcs0 -\cf17\insrsid15608641\charrsid10889776 s }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid681062\charrsid10889776 up your new ArduC}{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid6893676\charrsid10889776 opter}{\rtlch\fcs1 \af31507 \ltrch\fcs0 -\cf17\insrsid15608641\charrsid10889776 .}{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid726741\charrsid10889776 -\par }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \b\cf17\insrsid10640918\charrsid10889776 \tab }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \b\cf17\insrsid726741\charrsid10889776 \tab \tab Terminal }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \b\cf17\insrsid16653158\charrsid10889776 -\endash }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \b\cf17\insrsid726741\charrsid10889776 }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid11735092\charrsid10889776 Manual}{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid15608641\charrsid10889776 set up}{ -\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid16653158\charrsid10889776 }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid11735092\charrsid10889776 of }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid16653158\charrsid10889776 yo}{\rtlch\fcs1 \af31507 -\ltrch\fcs0 \cf17\insrsid15608641\charrsid10889776 ur APM and run tests on sensors, }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid16653158\charrsid10889776 log reading and setting functions}{\rtlch\fcs1 \af31507 \ltrch\fcs0 -\cf17\insrsid15608641\charrsid10889776 .}{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid726741\charrsid10889776 -\par }\pard \ltrpar\ql \li0\ri0\widctlpar\wrapdefault\aspalpha\aspnum\faauto\adjustright\rin0\lin0\itap0\pararsid726741 {\rtlch\fcs1 \af31507 \ltrch\fcs0 \b\cf17\insrsid726741\charrsid10889776 \tab Developer:}{\rtlch\fcs1 \af31507 \ltrch\fcs0 -\cf17\insrsid726741\charrsid10889776 Michael Oborne -\par \tab }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \b\cf17\insrsid15301506\charrsid10889776 Design:}{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid15301506\charrsid10889776 Samantha Nelson -\par }\pard \ltrpar\ql \fi720\li0\ri0\widctlpar\wrapdefault\aspalpha\aspnum\faauto\adjustright\rin0\lin0\itap0\pararsid15301506 {\rtlch\fcs1 \af31507 \ltrch\fcs0 \b\cf17\insrsid15301506\charrsid10889776 ArduCopter }{\rtlch\fcs1 \af31507 \ltrch\fcs0 -\b\cf17\insrsid339864\charrsid10889776 Illustrations}{\rtlch\fcs1 \af31507 \ltrch\fcs0 \b\cf17\insrsid726741\charrsid10889776 :}{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid726741\charrsid10889776 Max Levine -\par }\pard\plain \ltrpar\s15\ql \fi720\li0\ri0\widctlpar\wrapdefault\aspalpha\aspnum\faauto\adjustright\rin0\lin0\itap0\pararsid726741 \rtlch\fcs1 \af31507\afs22\alang1025 \ltrch\fcs0 \f31506\fs22\lang3081\langfe1033\cgrid\langnp3081\langfenp1033 { -\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid726741\charrsid10889776 -\par Please visit http://www.diydrones.com for further information.}{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid16143823 -\par }{\rtlch\fcs1 \af31507 \ltrch\fcs0 \cf17\insrsid7442\charrsid10889776 -\par }{\*\themedata 504b030414000600080000002100828abc13fa0000001c020000130000005b436f6e74656e745f54797065735d2e786d6cac91cb6ac3301045f785fe83d0b6d8 -72ba28a5d8cea249777d2cd20f18e4b12d6a8f843409c9df77ecb850ba082d74231062ce997b55ae8fe3a00e1893f354e9555e6885647de3a8abf4fbee29bbd7 -2a3150038327acf409935ed7d757e5ee14302999a654e99e393c18936c8f23a4dc072479697d1c81e51a3b13c07e4087e6b628ee8cf5c4489cf1c4d075f92a0b -44d7a07a83c82f308ac7b0a0f0fbf90c2480980b58abc733615aa2d210c2e02cb04430076a7ee833dfb6ce62e3ed7e14693e8317d8cd0433bf5c60f53fea2fe7 -065bd80facb647e9e25c7fc421fd2ddb526b2e9373fed4bb902e182e97b7b461e6bfad3f010000ffff0300504b030414000600080000002100a5d6a7e7c00000 -00360100000b0000005f72656c732f2e72656c73848fcf6ac3300c87ef85bd83d17d51d2c31825762fa590432fa37d00e1287f68221bdb1bebdb4fc7060abb08 -84a4eff7a93dfeae8bf9e194e720169aaa06c3e2433fcb68e1763dbf7f82c985a4a725085b787086a37bdbb55fbc50d1a33ccd311ba548b63095120f88d94fbc -52ae4264d1c910d24a45db3462247fa791715fd71f989e19e0364cd3f51652d73760ae8fa8c9ffb3c330cc9e4fc17faf2ce545046e37944c69e462a1a82fe353 -bd90a865aad41ed0b5b8f9d6fd010000ffff0300504b0304140006000800000021006b799616830000008a0000001c0000007468656d652f7468656d652f7468 -656d654d616e616765722e786d6c0ccc4d0ac3201040e17da17790d93763bb284562b2cbaebbf600439c1a41c7a0d29fdbd7e5e38337cedf14d59b4b0d592c9c -070d8a65cd2e88b7f07c2ca71ba8da481cc52c6ce1c715e6e97818c9b48d13df49c873517d23d59085adb5dd20d6b52bd521ef2cdd5eb9246a3d8b4757e8d3f7 -29e245eb2b260a0238fd010000ffff0300504b03041400060008000000210096b5ade296060000501b0000160000007468656d652f7468656d652f7468656d65 -312e786d6cec594f6fdb3614bf0fd87720746f6327761a07758ad8b19b2d4d1bc46e871e698996d850a240d2497d1bdae38001c3ba618715d86d87615b8116d8 -a5fb34d93a6c1dd0afb0475292c5585e9236d88aad3e2412f9e3fbff1e1fa9abd7eec70c1d1221294fda5efd72cd4324f1794093b0eddd1ef62fad79482a9c04 -98f184b4bd2991deb58df7dfbb8ad755446282607d22d771db8b944ad79796a40fc3585ee62949606ecc458c15bc8a702910f808e8c66c69b9565b5d8a314d3c -94e018c8de1a8fa94fd05093f43672e23d06af89927ac06762a049136785c10607758d9053d965021d62d6f6804fc08f86e4bef210c352c144dbab999fb7b471 -7509af678b985ab0b6b4ae6f7ed9ba6c4170b06c788a705430adf71bad2b5b057d03606a1ed7ebf5babd7a41cf00b0ef83a6569632cd467faddec9699640f671 -9e76b7d6ac355c7c89feca9cccad4ea7d36c65b258a206641f1b73f8b5da6a6373d9c11b90c537e7f08dce66b7bbeae00dc8e257e7f0fd2badd5868b37a088d1 -e4600ead1ddaef67d40bc898b3ed4af81ac0d76a197c86826828a24bb318f3442d8ab518dfe3a20f000d6458d104a9694ac6d88728eee2782428d60cf03ac1a5 -193be4cbb921cd0b495fd054b5bd0f530c1931a3f7eaf9f7af9e3f45c70f9e1d3ff8e9f8e1c3e3073f5a42ceaa6d9c84e5552fbffdeccfc71fa33f9e7ef3f2d1 -17d57859c6fffac327bffcfc793510d26726ce8b2f9ffcf6ecc98baf3efdfdbb4715f04d814765f890c644a29be408edf3181433567125272371be15c308d3f2 -8acd249438c19a4b05fd9e8a1cf4cd296699771c393ac4b5e01d01e5a30a787d72cf1178108989a2159c77a2d801ee72ce3a5c545a6147f32a99793849c26ae6 -6252c6ed637c58c5bb8b13c7bfbd490a75330f4b47f16e441c31f7184e140e494214d273fc80900aedee52ead87597fa824b3e56e82e451d4c2b4d32a423279a -668bb6690c7e9956e90cfe766cb37b077538abd27a8b1cba48c80acc2a841f12e698f13a9e281c57911ce298950d7e03aba84ac8c154f8655c4f2af074481847 -bd804859b5e696007d4b4edfc150b12addbecba6b18b148a1e54d1bc81392f23b7f84137c2715a851dd0242a633f900710a218ed715505dfe56e86e877f0034e -16bafb0e258ebb4faf06b769e888340b103d3311da9750aa9d0a1cd3e4efca31a3508f6d0c5c5c398602f8e2ebc71591f5b616e24dd893aa3261fb44f95d843b -5974bb5c04f4edafb95b7892ec1108f3f98de75dc97d5772bdff7cc95d94cf672db4b3da0a6557f70db629362d72bcb0431e53c6066acac80d699a6409fb44d0 -8741bdce9c0e4971624a2378cceaba830b05366b90e0ea23aaa241845368b0eb9e2612ca8c742851ca251ceccc70256d8d87265dd96361531f186c3d9058edf2 -c00eafe8e1fc5c509031bb4d680e9f39a3154de0accc56ae644441edd76156d7429d995bdd88664a9dc3ad50197c38af1a0c16d684060441db02565e85f3b966 -0d0713cc48a0ed6ef7dedc2dc60b17e92219e180643ed27acffba86e9c94c78ab90980d8a9f0913ee49d62b512b79626fb06dccee2a432bbc60276b9f7dec44b -7904cfbca4f3f6443ab2a49c9c2c41476dafd55c6e7ac8c769db1bc399161ee314bc2e75cf8759081743be1236ec4f4d6693e5336fb672c5dc24a8c33585b5fb -9cc24e1d4885545b58463634cc5416022cd19cacfccb4d30eb45296023fd35a458598360f8d7a4003bbaae25e331f155d9d9a5116d3bfb9a95523e51440ca2e0 -088dd844ec6370bf0e55d027a012ae264c45d02f708fa6ad6da6dce29c255df9f6cae0ec38666984b372ab5334cf640b37795cc860de4ae2816e95b21be5ceaf -8a49f90b52a51cc6ff3355f47e0237052b81f6800fd7b802239daf6d8f0b1571a8426944fdbe80c6c1d40e8816b88b8569082ab84c36ff0539d4ff6dce591a26 -ade1c0a7f669880485fd484582903d284b26fa4e2156cff62e4b9265844c4495c495a9157b440e091bea1ab8aaf7760f4510eaa69a6465c0e04ec69ffb9e65d0 -28d44d4e39df9c1a52ecbd3607fee9cec7263328e5d661d3d0e4f62f44acd855ed7ab33cdf7bcb8ae889599bd5c8b3029895b6825696f6af29c239b75a5bb1e6 -345e6ee6c28117e73586c1a2214ae1be07e93fb0ff51e133fb65426fa843be0fb515c187064d0cc206a2fa926d3c902e907670048d931db4c1a44959d366ad93 -b65abe595f70a75bf03d616c2dd959fc7d4e6317cd99cbcec9c58b34766661c7d6766ca1a9c1b327531486c6f941c638c67cd22a7f75e2a37be0e82db8df9f30 -254d30c1372581a1f51c983c80e4b71ccdd28dbf000000ffff0300504b0304140006000800000021000dd1909fb60000001b010000270000007468656d652f74 -68656d652f5f72656c732f7468656d654d616e616765722e786d6c2e72656c73848f4d0ac2301484f78277086f6fd3ba109126dd88d0add40384e4350d363f24 -51eced0dae2c082e8761be9969bb979dc9136332de3168aa1a083ae995719ac16db8ec8e4052164e89d93b64b060828e6f37ed1567914b284d262452282e3198 -720e274a939cd08a54f980ae38a38f56e422a3a641c8bbd048f7757da0f19b017cc524bd62107bd5001996509affb3fd381a89672f1f165dfe514173d9850528 -a2c6cce0239baa4c04ca5bbabac4df000000ffff0300504b01022d0014000600080000002100828abc13fa0000001c0200001300000000000000000000000000 -000000005b436f6e74656e745f54797065735d2e786d6c504b01022d0014000600080000002100a5d6a7e7c0000000360100000b000000000000000000000000 -002b0100005f72656c732f2e72656c73504b01022d00140006000800000021006b799616830000008a0000001c00000000000000000000000000140200007468 -656d652f7468656d652f7468656d654d616e616765722e786d6c504b01022d001400060008000000210096b5ade296060000501b000016000000000000000000 -00000000d10200007468656d652f7468656d652f7468656d65312e786d6c504b01022d00140006000800000021000dd1909fb60000001b010000270000000000 -00000000000000009b0900007468656d652f7468656d652f5f72656c732f7468656d654d616e616765722e786d6c2e72656c73504b050600000000050005005d010000960a00000000} -{\*\colorschememapping 3c3f786d6c2076657273696f6e3d22312e302220656e636f64696e673d225554462d3822207374616e64616c6f6e653d22796573223f3e0d0a3c613a636c724d -617020786d6c6e733a613d22687474703a2f2f736368656d61732e6f70656e786d6c666f726d6174732e6f72672f64726177696e676d6c2f323030362f6d6169 -6e22206267313d226c743122207478313d22646b3122206267323d226c743222207478323d22646b322220616363656e74313d22616363656e74312220616363 -656e74323d22616363656e74322220616363656e74333d22616363656e74332220616363656e74343d22616363656e74342220616363656e74353d22616363656e74352220616363656e74363d22616363656e74362220686c696e6b3d22686c696e6b2220666f6c486c696e6b3d22666f6c486c696e6b222f3e} -{\*\latentstyles\lsdstimax267\lsdlockeddef0\lsdsemihiddendef1\lsdunhideuseddef1\lsdqformatdef0\lsdprioritydef99{\lsdlockedexcept \lsdsemihidden0 \lsdunhideused0 \lsdqformat1 \lsdpriority0 \lsdlocked0 Normal; -\lsdsemihidden0 \lsdunhideused0 \lsdqformat1 \lsdpriority9 \lsdlocked0 heading 1;\lsdqformat1 \lsdpriority9 \lsdlocked0 heading 2;\lsdqformat1 \lsdpriority9 \lsdlocked0 heading 3;\lsdqformat1 \lsdpriority9 \lsdlocked0 heading 4; -\lsdqformat1 \lsdpriority9 \lsdlocked0 heading 5;\lsdqformat1 \lsdpriority9 \lsdlocked0 heading 6;\lsdqformat1 \lsdpriority9 \lsdlocked0 heading 7;\lsdqformat1 \lsdpriority9 \lsdlocked0 heading 8;\lsdqformat1 \lsdpriority9 \lsdlocked0 heading 9; -\lsdpriority39 \lsdlocked0 toc 1;\lsdpriority39 \lsdlocked0 toc 2;\lsdpriority39 \lsdlocked0 toc 3;\lsdpriority39 \lsdlocked0 toc 4;\lsdpriority39 \lsdlocked0 toc 5;\lsdpriority39 \lsdlocked0 toc 6;\lsdpriority39 \lsdlocked0 toc 7; -\lsdpriority39 \lsdlocked0 toc 8;\lsdpriority39 \lsdlocked0 toc 9;\lsdqformat1 \lsdpriority35 \lsdlocked0 caption;\lsdsemihidden0 \lsdunhideused0 \lsdqformat1 \lsdpriority10 \lsdlocked0 Title;\lsdpriority1 \lsdlocked0 Default Paragraph Font; -\lsdsemihidden0 \lsdunhideused0 \lsdqformat1 \lsdpriority11 \lsdlocked0 Subtitle;\lsdsemihidden0 \lsdunhideused0 \lsdqformat1 \lsdpriority22 \lsdlocked0 Strong;\lsdsemihidden0 \lsdunhideused0 \lsdqformat1 \lsdpriority20 \lsdlocked0 Emphasis; -\lsdsemihidden0 \lsdunhideused0 \lsdpriority59 \lsdlocked0 Table Grid;\lsdunhideused0 \lsdlocked0 Placeholder Text;\lsdsemihidden0 \lsdunhideused0 \lsdqformat1 \lsdpriority1 \lsdlocked0 No Spacing; -\lsdsemihidden0 \lsdunhideused0 \lsdpriority60 \lsdlocked0 Light Shading;\lsdsemihidden0 \lsdunhideused0 \lsdpriority61 \lsdlocked0 Light List;\lsdsemihidden0 \lsdunhideused0 \lsdpriority62 \lsdlocked0 Light Grid; -\lsdsemihidden0 \lsdunhideused0 \lsdpriority63 \lsdlocked0 Medium Shading 1;\lsdsemihidden0 \lsdunhideused0 \lsdpriority64 \lsdlocked0 Medium Shading 2;\lsdsemihidden0 \lsdunhideused0 \lsdpriority65 \lsdlocked0 Medium List 1; -\lsdsemihidden0 \lsdunhideused0 \lsdpriority66 \lsdlocked0 Medium List 2;\lsdsemihidden0 \lsdunhideused0 \lsdpriority67 \lsdlocked0 Medium Grid 1;\lsdsemihidden0 \lsdunhideused0 \lsdpriority68 \lsdlocked0 Medium Grid 2; -\lsdsemihidden0 \lsdunhideused0 \lsdpriority69 \lsdlocked0 Medium Grid 3;\lsdsemihidden0 \lsdunhideused0 \lsdpriority70 \lsdlocked0 Dark List;\lsdsemihidden0 \lsdunhideused0 \lsdpriority71 \lsdlocked0 Colorful Shading; -\lsdsemihidden0 \lsdunhideused0 \lsdpriority72 \lsdlocked0 Colorful List;\lsdsemihidden0 \lsdunhideused0 \lsdpriority73 \lsdlocked0 Colorful Grid;\lsdsemihidden0 \lsdunhideused0 \lsdpriority60 \lsdlocked0 Light Shading Accent 1; -\lsdsemihidden0 \lsdunhideused0 \lsdpriority61 \lsdlocked0 Light List Accent 1;\lsdsemihidden0 \lsdunhideused0 \lsdpriority62 \lsdlocked0 Light Grid Accent 1;\lsdsemihidden0 \lsdunhideused0 \lsdpriority63 \lsdlocked0 Medium Shading 1 Accent 1; -\lsdsemihidden0 \lsdunhideused0 \lsdpriority64 \lsdlocked0 Medium Shading 2 Accent 1;\lsdsemihidden0 \lsdunhideused0 \lsdpriority65 \lsdlocked0 Medium List 1 Accent 1;\lsdunhideused0 \lsdlocked0 Revision; -\lsdsemihidden0 \lsdunhideused0 \lsdqformat1 \lsdpriority34 \lsdlocked0 List Paragraph;\lsdsemihidden0 \lsdunhideused0 \lsdqformat1 \lsdpriority29 \lsdlocked0 Quote;\lsdsemihidden0 \lsdunhideused0 \lsdqformat1 \lsdpriority30 \lsdlocked0 Intense Quote; -\lsdsemihidden0 \lsdunhideused0 \lsdpriority66 \lsdlocked0 Medium List 2 Accent 1;\lsdsemihidden0 \lsdunhideused0 \lsdpriority67 \lsdlocked0 Medium Grid 1 Accent 1;\lsdsemihidden0 \lsdunhideused0 \lsdpriority68 \lsdlocked0 Medium Grid 2 Accent 1; -\lsdsemihidden0 \lsdunhideused0 \lsdpriority69 \lsdlocked0 Medium Grid 3 Accent 1;\lsdsemihidden0 \lsdunhideused0 \lsdpriority70 \lsdlocked0 Dark List Accent 1;\lsdsemihidden0 \lsdunhideused0 \lsdpriority71 \lsdlocked0 Colorful Shading Accent 1; -\lsdsemihidden0 \lsdunhideused0 \lsdpriority72 \lsdlocked0 Colorful List Accent 1;\lsdsemihidden0 \lsdunhideused0 \lsdpriority73 \lsdlocked0 Colorful Grid Accent 1;\lsdsemihidden0 \lsdunhideused0 \lsdpriority60 \lsdlocked0 Light Shading Accent 2; -\lsdsemihidden0 \lsdunhideused0 \lsdpriority61 \lsdlocked0 Light List Accent 2;\lsdsemihidden0 \lsdunhideused0 \lsdpriority62 \lsdlocked0 Light Grid Accent 2;\lsdsemihidden0 \lsdunhideused0 \lsdpriority63 \lsdlocked0 Medium Shading 1 Accent 2; -\lsdsemihidden0 \lsdunhideused0 \lsdpriority64 \lsdlocked0 Medium Shading 2 Accent 2;\lsdsemihidden0 \lsdunhideused0 \lsdpriority65 \lsdlocked0 Medium List 1 Accent 2;\lsdsemihidden0 \lsdunhideused0 \lsdpriority66 \lsdlocked0 Medium List 2 Accent 2; -\lsdsemihidden0 \lsdunhideused0 \lsdpriority67 \lsdlocked0 Medium Grid 1 Accent 2;\lsdsemihidden0 \lsdunhideused0 \lsdpriority68 \lsdlocked0 Medium Grid 2 Accent 2;\lsdsemihidden0 \lsdunhideused0 \lsdpriority69 \lsdlocked0 Medium Grid 3 Accent 2; -\lsdsemihidden0 \lsdunhideused0 \lsdpriority70 \lsdlocked0 Dark List Accent 2;\lsdsemihidden0 \lsdunhideused0 \lsdpriority71 \lsdlocked0 Colorful Shading Accent 2;\lsdsemihidden0 \lsdunhideused0 \lsdpriority72 \lsdlocked0 Colorful List Accent 2; -\lsdsemihidden0 \lsdunhideused0 \lsdpriority73 \lsdlocked0 Colorful Grid Accent 2;\lsdsemihidden0 \lsdunhideused0 \lsdpriority60 \lsdlocked0 Light Shading Accent 3;\lsdsemihidden0 \lsdunhideused0 \lsdpriority61 \lsdlocked0 Light List Accent 3; -\lsdsemihidden0 \lsdunhideused0 \lsdpriority62 \lsdlocked0 Light Grid Accent 3;\lsdsemihidden0 \lsdunhideused0 \lsdpriority63 \lsdlocked0 Medium Shading 1 Accent 3;\lsdsemihidden0 \lsdunhideused0 \lsdpriority64 \lsdlocked0 Medium Shading 2 Accent 3; -\lsdsemihidden0 \lsdunhideused0 \lsdpriority65 \lsdlocked0 Medium List 1 Accent 3;\lsdsemihidden0 \lsdunhideused0 \lsdpriority66 \lsdlocked0 Medium List 2 Accent 3;\lsdsemihidden0 \lsdunhideused0 \lsdpriority67 \lsdlocked0 Medium Grid 1 Accent 3; -\lsdsemihidden0 \lsdunhideused0 \lsdpriority68 \lsdlocked0 Medium Grid 2 Accent 3;\lsdsemihidden0 \lsdunhideused0 \lsdpriority69 \lsdlocked0 Medium Grid 3 Accent 3;\lsdsemihidden0 \lsdunhideused0 \lsdpriority70 \lsdlocked0 Dark List Accent 3; -\lsdsemihidden0 \lsdunhideused0 \lsdpriority71 \lsdlocked0 Colorful Shading Accent 3;\lsdsemihidden0 \lsdunhideused0 \lsdpriority72 \lsdlocked0 Colorful List Accent 3;\lsdsemihidden0 \lsdunhideused0 \lsdpriority73 \lsdlocked0 Colorful Grid Accent 3; -\lsdsemihidden0 \lsdunhideused0 \lsdpriority60 \lsdlocked0 Light Shading Accent 4;\lsdsemihidden0 \lsdunhideused0 \lsdpriority61 \lsdlocked0 Light List Accent 4;\lsdsemihidden0 \lsdunhideused0 \lsdpriority62 \lsdlocked0 Light Grid Accent 4; -\lsdsemihidden0 \lsdunhideused0 \lsdpriority63 \lsdlocked0 Medium Shading 1 Accent 4;\lsdsemihidden0 \lsdunhideused0 \lsdpriority64 \lsdlocked0 Medium Shading 2 Accent 4;\lsdsemihidden0 \lsdunhideused0 \lsdpriority65 \lsdlocked0 Medium List 1 Accent 4; -\lsdsemihidden0 \lsdunhideused0 \lsdpriority66 \lsdlocked0 Medium List 2 Accent 4;\lsdsemihidden0 \lsdunhideused0 \lsdpriority67 \lsdlocked0 Medium Grid 1 Accent 4;\lsdsemihidden0 \lsdunhideused0 \lsdpriority68 \lsdlocked0 Medium Grid 2 Accent 4; -\lsdsemihidden0 \lsdunhideused0 \lsdpriority69 \lsdlocked0 Medium Grid 3 Accent 4;\lsdsemihidden0 \lsdunhideused0 \lsdpriority70 \lsdlocked0 Dark List Accent 4;\lsdsemihidden0 \lsdunhideused0 \lsdpriority71 \lsdlocked0 Colorful Shading Accent 4; -\lsdsemihidden0 \lsdunhideused0 \lsdpriority72 \lsdlocked0 Colorful List Accent 4;\lsdsemihidden0 \lsdunhideused0 \lsdpriority73 \lsdlocked0 Colorful Grid Accent 4;\lsdsemihidden0 \lsdunhideused0 \lsdpriority60 \lsdlocked0 Light Shading Accent 5; -\lsdsemihidden0 \lsdunhideused0 \lsdpriority61 \lsdlocked0 Light List Accent 5;\lsdsemihidden0 \lsdunhideused0 \lsdpriority62 \lsdlocked0 Light Grid Accent 5;\lsdsemihidden0 \lsdunhideused0 \lsdpriority63 \lsdlocked0 Medium Shading 1 Accent 5; -\lsdsemihidden0 \lsdunhideused0 \lsdpriority64 \lsdlocked0 Medium Shading 2 Accent 5;\lsdsemihidden0 \lsdunhideused0 \lsdpriority65 \lsdlocked0 Medium List 1 Accent 5;\lsdsemihidden0 \lsdunhideused0 \lsdpriority66 \lsdlocked0 Medium List 2 Accent 5; -\lsdsemihidden0 \lsdunhideused0 \lsdpriority67 \lsdlocked0 Medium Grid 1 Accent 5;\lsdsemihidden0 \lsdunhideused0 \lsdpriority68 \lsdlocked0 Medium Grid 2 Accent 5;\lsdsemihidden0 \lsdunhideused0 \lsdpriority69 \lsdlocked0 Medium Grid 3 Accent 5; -\lsdsemihidden0 \lsdunhideused0 \lsdpriority70 \lsdlocked0 Dark List Accent 5;\lsdsemihidden0 \lsdunhideused0 \lsdpriority71 \lsdlocked0 Colorful Shading Accent 5;\lsdsemihidden0 \lsdunhideused0 \lsdpriority72 \lsdlocked0 Colorful List Accent 5; -\lsdsemihidden0 \lsdunhideused0 \lsdpriority73 \lsdlocked0 Colorful Grid Accent 5;\lsdsemihidden0 \lsdunhideused0 \lsdpriority60 \lsdlocked0 Light Shading Accent 6;\lsdsemihidden0 \lsdunhideused0 \lsdpriority61 \lsdlocked0 Light List Accent 6; -\lsdsemihidden0 \lsdunhideused0 \lsdpriority62 \lsdlocked0 Light Grid Accent 6;\lsdsemihidden0 \lsdunhideused0 \lsdpriority63 \lsdlocked0 Medium Shading 1 Accent 6;\lsdsemihidden0 \lsdunhideused0 \lsdpriority64 \lsdlocked0 Medium Shading 2 Accent 6; -\lsdsemihidden0 \lsdunhideused0 \lsdpriority65 \lsdlocked0 Medium List 1 Accent 6;\lsdsemihidden0 \lsdunhideused0 \lsdpriority66 \lsdlocked0 Medium List 2 Accent 6;\lsdsemihidden0 \lsdunhideused0 \lsdpriority67 \lsdlocked0 Medium Grid 1 Accent 6; -\lsdsemihidden0 \lsdunhideused0 \lsdpriority68 \lsdlocked0 Medium Grid 2 Accent 6;\lsdsemihidden0 \lsdunhideused0 \lsdpriority69 \lsdlocked0 Medium Grid 3 Accent 6;\lsdsemihidden0 \lsdunhideused0 \lsdpriority70 \lsdlocked0 Dark List Accent 6; -\lsdsemihidden0 \lsdunhideused0 \lsdpriority71 \lsdlocked0 Colorful Shading Accent 6;\lsdsemihidden0 \lsdunhideused0 \lsdpriority72 \lsdlocked0 Colorful List Accent 6;\lsdsemihidden0 \lsdunhideused0 \lsdpriority73 \lsdlocked0 Colorful Grid Accent 6; -\lsdsemihidden0 \lsdunhideused0 \lsdqformat1 \lsdpriority19 \lsdlocked0 Subtle Emphasis;\lsdsemihidden0 \lsdunhideused0 \lsdqformat1 \lsdpriority21 \lsdlocked0 Intense Emphasis; -\lsdsemihidden0 \lsdunhideused0 \lsdqformat1 \lsdpriority31 \lsdlocked0 Subtle Reference;\lsdsemihidden0 \lsdunhideused0 \lsdqformat1 \lsdpriority32 \lsdlocked0 Intense Reference; -\lsdsemihidden0 \lsdunhideused0 \lsdqformat1 \lsdpriority33 \lsdlocked0 Book Title;\lsdpriority37 \lsdlocked0 Bibliography;\lsdqformat1 \lsdpriority39 \lsdlocked0 TOC Heading;}}{\*\datastore 010500000200000018000000 -4d73786d6c322e534158584d4c5265616465722e352e3000000000000000000000060000 -d0cf11e0a1b11ae1000000000000000000000000000000003e000300feff090006000000000000000000000001000000010000000000000000100000feffffff00000000feffffff0000000000000000ffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffff -ffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffff -ffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffff -ffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffff -fffffffffffffffffdfffffffeffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffff -ffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffff -ffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffff -ffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffffff -ffffffffffffffffffffffffffffffff52006f006f007400200045006e00740072007900000000000000000000000000000000000000000000000000000000000000000000000000000000000000000016000500ffffffffffffffffffffffffec69d9888b8b3d4c859eaf6cd158be0f000000000000000000000000e05c -de945f22cc01feffffff00000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000ffffffffffffffffffffffff00000000000000000000000000000000000000000000000000000000 -00000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000ffffffffffffffffffffffff0000000000000000000000000000000000000000000000000000 -000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000ffffffffffffffffffffffff000000000000000000000000000000000000000000000000 -0000000000000000000000000000000000000000000000000105000000000000}} \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/Resources/apm.ico b/Tools/ArdupilotMegaPlanner/Resources/apm.ico deleted file mode 100644 index 573bf06031..0000000000 Binary files a/Tools/ArdupilotMegaPlanner/Resources/apm.ico and /dev/null differ diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/GCSViews/Configuration.resx b/Tools/ArdupilotMegaPlanner/bin/Release/GCSViews/Configuration.resx index 738382f0ef..7cd7b972d8 100644 --- a/Tools/ArdupilotMegaPlanner/bin/Release/GCSViews/Configuration.resx +++ b/Tools/ArdupilotMegaPlanner/bin/Release/GCSViews/Configuration.resx @@ -117,2546 +117,4956 @@ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - THR_FS_VALUE - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Top, Bottom, Left - - 29 + + True - - groupBox14 - - - - 722, 434 - - - label50 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - P - - - ConfigTabs - - - groupBox10 - - - I - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 3 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 11 - - - 78, 20 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 390, 11 - - - - - - RATE_YAW_IMAX - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - label51 - - - groupBox15 - - - - - - 5 - - - Setup - - - 3 - - - 61, 13 - - - INT_MAX - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - - - - RATE_RLL_IMAX - - - 6, 87 - - - - - - XTRK_ANGLE_CD1 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - NoControl - - - label56 - - - 111, 59 - - - groupBox16 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 40 - - - 5 - - - 27, 203 - - - 13 - - - groupBox21 - - - - - - 69, 13 - - - 80, 13 - - - label28 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - WP_SPEED_MAX - - - GDI+ (old type) - - - groupBox24 - - - - - - label57 - - - - - - 111, 36 - - - 7 - - - 65, 13 - - - P - - - Default - - - groupBox8 - - - NoControl - - - 3, 416 - - - 22, 13 - - - 3, 3, 3, 3 - - - groupBox24 - - - 80, 21 - - - IMAX - - - INT_MAX - - - I - - - 136, 203 - - - Dist Units - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 30, 16 - - - NoControl - - - 722, 434 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabPlanner - - - NoControl - - - Battery Warning - - - Load param's from file - - - FBW max - - - 80, 63 - - - 65, 13 - - - CHK_hudshow - - - groupBox12 - - - STB_PIT_I - - - - - - 3 - - - 78, 20 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - 9 - - - label52 - - - - - - 78, 20 - - - label102 - - - groupBox7 - - - YW2SRV_IMAX - - - 4, 109 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 78, 20 - - - 78, 20 - - - 5 - - - 11 - - - 111, 36 - - - 78, 20 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 0 - - - - - - groupBox7 - - - - - - 78, 20 - - - 65, 13 - - - label53 - - - RATE_PIT_IMAX - - - 531, 6 - - - groupBox23 - - - 0 - - - 0 - - - 4 - - - 2 - - - label94 - - - 7 - - - - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 43, 13 - - - label58 - - - INT_MAX - - - 11 - - - 4, 22 - - - UI Language - - - groupBox1 - - - groupBox16 - - - - - - NAV_LAT_I - - - 111, 13 - - - 205, 1 - - - 1 - - - label95 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 730, 460 - - - 7 - - - - - - label59 - - - TabAPM2 - - - label24 - - - NoControl - - - 0 - - - 111, 36 - - - - - - groupBox25 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - RATE_YAW_P - - - 6 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox22 - - - 78, 20 - - - HDNG2RLL_P - - - 78, 20 - - - NoControl - - - 11 - - - NoControl - - - 139, 299 - - - 170, 91 - - - 25 - - - 80, 13 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 154, 17 - - - - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox9 - - - TabPlanner - - - 78, 20 - - - - - - 2 - - - NoControl - - - groupBox20 - - - label3 - - - - - - - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 111, 13 - - - NoControl - - - TabPlanner - - - label46 - - - 2 - - - 7 - - - 78, 20 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 12 - - - 6, 16 - - - groupBox7 - - - NoControl - - - Bottom, Left - - - - - - - - - 12 - - - label91 - - - ENRGY2THR_P - - - 65, 13 - - - - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 1 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 66 - - - 80, 37 - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - CHK_GDIPlus - - - 4 - - - label7 - - - 78, 20 - - - 11 - - - - - - 56, 17 - - - groupBox12 - - - 4 - - - label96 - - - 6 - - - NoControl - - - 0, 0, 0, 0 - - - 14 - - - 16 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 3 - - - - - - 111, 36 - - - groupBox19 - - - 16 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 78, 20 - - - 14 - - - 177, 17 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 138, 21 - - - 5 - - - NoControl - - - - - - 5 - - - groupBox10 - - - groupBox8 - - - 78, 20 - - - TabPlanner - - - 7 - - - 4 - - - 52, 13 - - - 5 - - - 15, 13 - - - 6, 66 - - - NoControl - - - - - - - - - - - - - - - 1 - - - 4 - - - 1 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 10, 13 - - - 150 - - - Cruise - - - - - - Max - - - groupBox25 - - - 3 - - - NoControl - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 111, 59 - - - 3 - - - toolTip1 - - - 111, 82 - - - IMAX - - - 6, 63 - - - groupBox9 - - - groupBox9 - - - 111, 36 - - - RLL2SRV_IMAX - - - 12 - - - ARSP2PTCH_P - - - 27 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 5 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - 80, 86 - - - 5 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox10 - - - 5 - - - 27, 13 - - - Nav Pitch AS Pid - - - 245, 67 - - - 590, 203 - - - label93 - - - 80, 63 - - - groupBox12 - - - RLL2SRV_I - - - label101 - - - 11 - - - CHK_mavdebug - - - 78, 20 - - - 139, 276 - - - label22 - - - 15 - - - 78, 20 - - - 5 - - - Stabilize Roll - - - 4 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 18 - - - 11 - - - - - - 5 - - - 10, 13 - - - CHK_speechwaypoint - - - - - - Enable Speech - - - CHK_speechaltwarning - - - - - - NoControl - - - 14, 13 - - - NUM_tracklength - - - BUT_Joystick - - - label23 - - - 6, 17 - - - - - - 65, 13 - - - 579, 67 - - - IMAX - - - 139, 117 - - - 78, 20 - - - P - - - - - - 68, 13 - - - 80, 13 - - - 78, 20 - - - groupBox8 - - - 0 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 9 - - - 0 - - - NoControl - - - label107 - - - 61, 13 - - - groupBox3 - - - - - - NoControl - - - Energy/Alt Pid - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - - - - - - - 78, 20 - - - Load - - - groupBox9 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 0 - - - 111, 82 - - - 195, 108 - - - - - - 358, 6 - - - 0 - - - Enable HUD Overlay - - - NoControl - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 205, 217 - - - 0 - - - ENRGY2THR_D - - - - - - - - - - - - groupBox10 - - - 3 - - - 80, 37 - - - 195, 108 - - - - - - - - - 139, 90 - - - groupBox23 - - - 722, 434 - - - 50, 13 - - - label64 - - - System.Windows.Forms.ToolTip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 1 - - - - - - 65, 13 - - - - - - 14, 13 - - - 14, 13 - - - P to T - - - groupBox10 - - - groupBox3 - - - 334, 200 - - - - - - BUT_writePIDS - - - Save params to file - - - 78, 20 - - - label65 - - - - - - 111, 13 - - - 10, 13 - - - - - - 3 - - - Reload params from device - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - Waypoint - - - 0 - - - 80, 37 - - - YW2SRV_I - - - 7 - - - 75, 23 - - - 80, 21 - - - 5 - - - 111, 13 - - - 28 - - - - - - 103, 19 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 0 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 195, 108 - - - 78, 20 - - - - - - TabPlanner - - - 24 - - - IMAX - - - 406, 325 - - - P - - - - - - 6 - - - IMAX - - - P - - - 5 - - - TabAPM2 - - - 80, 13 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 14, 13 - - - 4, 22 - - - NoControl - - - label60 - - - 170, 95 - - - 14, 13 - - - System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - TabAPM2 - - - 78, 20 - - - TabPlanner - - - 139, 146 - - - 10 - - - 5 - - - 3 - - - label61 - - - 20 - - - 10 - - - I - - - + + Command 150 - - D - - - 30, 228 - - - 8 - - - 3 - - - groupBox21 - - - 6, 17 - - - 4, 22 - - + True - - 78, 20 - - - - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 5 - - - HDNG2RLL_D - - - 111, 59 - - - NoControl - - - 14 - - - 10, 13 - - - NoControl - - - 2 - - - 205, 109 - - - 5 - - - 139, 40 - - - 11 - - - 5 - - - - - - 3, 198 - - - NoControl - - - IMAX - - - TabAC2 - - - 1 - - - 111, 82 - - - groupBox6 - - - 15 - - - APM 2.x - - - 6, 40 - - - label67 - - - P - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 13 - - - P - - - P - - - 1 - - - Joystick - - - 195, 108 - - - 78, 20 - - - 5 - - - 15 - - - Joystick Setup - - - 6, 17 - - - 2 - - - TRIM_THROTTLE - - - $this - - - 1 - - - groupBox6 - - - BUT_rerequestparams - - - 6, 17 - - - groupBox21 - - - 58 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 40 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 78, 20 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 195, 108 - - - - - - 111, 13 - - - 195, 108 - - - TabAC2 - - - NoControl - - - D - - - 1 - - - groupBox4 - - - 6, 17 - - - - - - - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + Value 80 - - + + True - - 6, 64 + + Default - + + False + + + mavScale + + + False + + + True + + + RawValue + + + False + + + + 3, 3 + + + 150 + + + 269, 409 + + + 58 + + + Params + + + System.Windows.Forms.DataGridView, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 6 + + + Top, Bottom, Left, Right + + + 111, 82 + + + 78, 20 + + + 11 + + + THR_FS_VALUE + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox3 + + + 0 + + + NoControl + + + 6, 86 + + + 50, 13 + + + 12 + + + FS Value + + + label5 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 15, 13 + + groupBox3 - - 6, 17 - - - - - - 7 - - - 2 - - - 44, 13 - - - groupBox14 - - - 195, 108 - - - groupBox6 - - - 78, 20 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 80, 37 - - - TabPlanner - - - 10, 13 - - - RATE_PIT_I - - - 78, 20 - - - 4 - - - 22 - - - PTCH2SRV_P - - - 6, 16 - - - 7 - - - 5 - - - NoControl - - - Rudder Mix - - - XTRK_GAIN_SC - - - - - - NoControl - - - Video Device - - - 4 - - - 14 - - - TabPlanner - - - 75, 23 - - - TabAPM2 - - - 78, 20 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 10 - - - - - + 1 - - INT_MAX + + 111, 59 - - 10, 13 + + 78, 20 - - label68 + + 9 - - 6, 40 - - - 188, 200 - - - ENRGY2THR_I - - - + + THR_MAX System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - STB_PIT_P + + groupBox3 - - 283, 168 + + 2 - - 6 + + NoControl - - ARSP2PTCH_D + + 6, 63 - - 6, 40 + + 27, 13 - + + 13 + + + Max + + + label6 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox3 + + + 3 + + + 111, 36 + + + 78, 20 + + + 7 + + + THR_MIN + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - HLD_LAT_P + + groupBox3 - + + 4 + + + NoControl + + + 6, 40 + + + 24, 13 + + + 14 + + + Min + + + label7 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 30 + + groupBox3 - + + 5 + + + 111, 13 + + + 78, 20 + + + 5 + + + TRIM_THROTTLE + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox3 + + + 6 + + + NoControl + + + 6, 17 + + + 36, 13 + + + 15 + + + Cruise + + + label8 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + groupBox3 + + + 7 + + + 405, 217 + + + 195, 108 + + + 0 + + + Throttle 0-100% + + + groupBox3 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAPM2 + + + 0 + + + 111, 82 + + + 78, 20 + + + 0 + + + ARSPD_RATIO + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 0 + + + NoControl + + + 6, 87 + + + 32, 13 + + + 1 + + + Ratio + + + label1 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 1 + + + 111, 59 + + + 78, 20 + + + 2 + + + ARSPD_FBW_MAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 2 + + + NoControl + + + 6, 59 + + + 53, 13 + + + 3 + + + FBW max + + + label2 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 3 + + + 111, 36 + + + 78, 20 + + + 4 + + + ARSPD_FBW_MIN + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 4 + + + NoControl + + + 6, 40 + + + 50, 13 + + + 5 + + + FBW min + + + label3 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 5 + + + 111, 13 + + + 78, 20 + + + 5 + + + TRIM_ARSPD_CM + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 6 + + + NoControl + + + 6, 17 + + + 64, 13 + + + 6 + + + Cruise + + + label4 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 7 + + + 406, 325 + + + 195, 108 + + + 1 + + + Airspeed m/s + + + groupBox1 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + TabAPM2 - - 170, 110 + + 1 + + + 111, 59 + + + 78, 20 + + + 9 + + + LIM_PITCH_MIN + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 0 + + + NoControl + + + 6, 63 + + + 51, 13 + + + 10 + + + Pitch Min + + + label39 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 1 + + + 111, 36 + + + 78, 20 + + + 7 + + + LIM_PITCH_MAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 2 + + + NoControl + + + 6, 40 + + + 54, 13 + + + 11 + + + Pitch Max + + + label38 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 3 + + + 111, 13 + + + 78, 20 + + + 5 + + + LIM_ROLL_CD + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 4 + + + NoControl + + + 6, 17 + + + 55, 13 + + + 12 + + + Bank Max + + + label37 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 5 + + + 205, 325 + + + 195, 108 + + + 2 + + + Navigation Angles + + + groupBox2 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAPM2 + + + 2 + + + 111, 36 + + + 78, 20 + + + 7 + + + XTRK_ANGLE_CD + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox15 + + + 0 + + + NoControl + + + 6, 40 + + + 61, 13 + + + 8 + + + Entry Angle + + + label79 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox15 + + + 1 + + + 111, 13 + + + 78, 20 + + + 5 + + + XTRK_GAIN_SC + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox15 + + + 2 + + + NoControl + + + 6, 17 + + + 52, 13 + + + 9 + + + Gain (cm) + + + label80 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox15 + + + 3 + + + 4, 325 + + + 195, 108 + + + 3 + + + Xtrack Pids + + + groupBox15 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAPM2 + + + 3 + + + 111, 13 + + + 78, 20 + + + 13 + + + KFF_PTCH2THR + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox16 + + + 0 + + + NoControl + + + 6, 17 + + + 36, 13 + + + 14 + + + P to T + + + label83 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox16 + + + 1 + + + 111, 59 + + + 78, 20 + + + 9 + + + KFF_RDDRMIX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox16 + + + 2 + + + NoControl + + + 6, 63 + + + 61, 13 + + + 15 + + + Rudder Mix + + + label78 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox16 + + + 3 + + + 111, 36 + + + 78, 20 + + + 7 + + + KFF_PTCHCOMP + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox16 + + + 4 + + + NoControl + + + 6, 40 61, 13 - - 44, 13 + + 16 + + + Pitch Comp + + + label81 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox16 + + + 5 + + + 205, 217 + + + 195, 108 + + + 4 + + + Other Mix's + + + groupBox16 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAPM2 + + + 4 + + + 111, 82 + + + 78, 20 + + + 11 + + + ENRGY2THR_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox14 + + + 0 + + + NoControl + + + 6, 86 + + + 54, 13 + + + 12 + + + INT_MAX + + + label73 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox14 + + + 1 + + + 111, 59 + + + 78, 20 + + + 9 + + + ENRGY2THR_D + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox14 + + + 2 + + + NoControl + + + 6, 63 + + + 15, 13 + + + 13 + + + D + + + label74 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox14 + + + 3 + + + 111, 36 + + + 78, 20 + + + 7 + + + ENRGY2THR_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox14 + + + 4 + + + NoControl + + + 6, 40 + + + 10, 13 + + + 14 + + + I + + + label75 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox14 + + + 5 + + + 111, 13 + + + 78, 20 + + + 5 + + + ENRGY2THR_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox14 + + + 6 + + + NoControl + + + 6, 17 + + + 14, 13 + + + 15 + + + P + + + label76 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox14 + + + 7 + + + 4, 217 + + + 195, 108 + + + 5 + + + Energy/Alt Pid + + + groupBox14 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAPM2 + + + 5 + + + 111, 82 + + + 78, 20 + + + 0 + + + ALT2PTCH_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox13 + + + 0 + + + NoControl + + + 6, 86 + + + 54, 13 + + + 1 + + + INT_MAX label69 - - + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 182, 6 + + groupBox13 - + + 1 + + + 111, 59 + + + 78, 20 + + + 2 + + + ALT2PTCH_D + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 15, 13 + + groupBox13 - + + 2 + + NoControl - - + + 6, 63 - + + 15, 13 + + + 3 + + + D + + + label70 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox13 + + + 3 + + + 111, 36 + + + 78, 20 + + + 4 + + + ALT2PTCH_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox13 + + + 4 + + + NoControl + + + 6, 40 + + + 10, 13 + + + 5 + + + I + + + label71 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox13 + + + 5 + + + 111, 13 + + + 78, 20 + + + 6 + + + ALT2PTCH_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox13 + + + 6 + + + NoControl + + + 6, 17 + + + 14, 13 + + + 7 + + + P + + + label72 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox13 + + + 7 + + + 406, 109 + + + 195, 108 + + + 6 + + + Nav Pitch Alt Pid + + + groupBox13 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAPM2 + + + 6 + + + 111, 82 + + + 78, 20 + + + 0 + + + ARSP2PTCH_IMAX + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 groupBox12 - + + 0 + + NoControl - - + + 6, 86 - - + + 54, 13 - - THR_MIN - - - 65 - - - 170, 110 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - 78, 20 - - - - - - 6, 66 - - - 4 - - - Command - - - 5 - - - 13 - - - groupBox11 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 40 - - - 80, 37 - - - 4 - - - 6 - - - TabAPM2 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - + 1 - - NoControl + + INT_MAX - - 5 + + label65 - + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 11 + + groupBox12 - - + + 1 - - I + + 111, 59 - - 0 - - - 34 - - - 0 - - + 78, 20 - - 111, 36 - - - groupBox23 - - - groupBox6 - - + 2 - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + ARSP2PTCH_D - - 15, 13 + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - label78 + + groupBox12 - - ConfigTabs - - + 2 - - TabAC2 - - - Top, Bottom, Left, Right - - - Ratio - - - groupBox16 - - - 65, 13 - - - groupBox8 - - - groupBox7 - - - ConfigTabs - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - ALT2PTCH_I - - - - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - + NoControl - - + + 6, 63 - - 14, 13 + + 15, 13 - - + + 3 - - + + D - - 102, 17 + + label66 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox12 + + + 3 + + + 111, 36 + + + 78, 20 + + + 4 ARSP2PTCH_I - - groupBox1 - - - 15 - - - 11 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 278, 0 - - + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - groupBox22 + + groupBox12 - - 6, 40 + + 4 - - 6, 40 - - + NoControl - - 111, 36 + + 6, 40 - - + + 10, 13 - - + + 5 - - 12 + + I - + + label67 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox12 + + + 5 + + + 111, 13 + + + 78, 20 + + + 6 + + + ARSP2PTCH_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox12 + + + 6 + + + NoControl + + + 6, 17 + + + 14, 13 + + 7 - - 3 + + P - - + + label68 - - NoControl + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 14 + + groupBox12 - - 33 + + 7 - - 15 + + 205, 109 - - 6, 16 + + 195, 108 - + + 7 + + + Nav Pitch AS Pid + + + groupBox12 + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 TabAPM2 - - Track Length + + 7 - - label86 + + 111, 82 - - 3 + + 78, 20 - - CMB_distunits + + 11 - - label4 + + HDNG2RLL_IMAX - - groupBox15 + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + + groupBox11 + + + 0 + + + NoControl + + + 6, 86 + + + 54, 13 + + + 12 + + + INT_MAX + + + label61 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 31 + + groupBox11 + + + 1 + + + 111, 59 + + + 78, 20 + + + 9 + + + HDNG2RLL_D + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox11 + + + 2 + + + NoControl + + + 6, 63 + + + 15, 13 + + + 13 + + + D + + + label62 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox11 + + + 3 + + + 111, 36 + + + 78, 20 + + + 7 + + + HDNG2RLL_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox11 + + + 4 + + + NoControl 6, 40 - - NoControl - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox13 - - - label2 - - - 12 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 66 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - 12 - - - 15 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 402, 13 - - - 2 - - - 15 - - - Min - - - label6 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 63 - - - 61, 13 - - - 111, 82 - - - P - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - label8 - - - groupBox19 - - - 30, 277 - - - 125, 17 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 78, 20 - - - 14, 13 - - - 80, 63 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - groupBox13 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 80, 37 - - - 7 - - - 30, 149 - - - - - - 111, 59 - - - groupBox1 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 22 - - + 10, 13 - - + + 14 - - Nav Pitch Alt Pid + + I - - Write Params + + label63 - + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - + + groupBox11 - - 30, 122 + + 5 - - groupBox21 + + 111, 13 - - 2 + + 78, 20 - - + + 5 - - Servo Roll Pid + + HDNG2RLL_P - + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox11 + + + 6 + + + NoControl + + + 6, 17 + + + 14, 13 + + + 15 + + + P + + + label64 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox11 + + + 7 + + + 4, 109 + + + 195, 108 + + + 8 + + + Nav Roll Pid + + + groupBox11 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAPM2 + + + 8 + + + 111, 82 + + + 78, 20 + + + 11 + + + YW2SRV_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox10 + + + 0 + + + NoControl + + + 6, 86 + + + 54, 13 + + 12 - - RLL2SRV_P + + INT_MAX - + + label57 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox10 + + + 1 + + + 111, 59 + + + 78, 20 + + 9 YW2SRV_D - + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox10 + + + 2 + + + NoControl + + + 6, 63 + + + 15, 13 + + + 13 + + + D + + + label58 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox10 + + + 3 + + + 111, 36 + + + 78, 20 + + 7 + + YW2SRV_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox10 + + + 4 + + + NoControl + + + 6, 40 + + + 10, 13 + + + 14 + + + I + + + label59 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox10 + + + 5 + + + 111, 13 + + + 78, 20 + + + 5 + + + YW2SRV_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox10 + + + 6 + + + NoControl + + + 6, 17 + + + 14, 13 + + + 15 + + + P + + + label60 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox10 + + + 7 + + + 406, 1 + + + 195, 108 + + + 9 + + + Servo Yaw Pid + + + groupBox10 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAPM2 + + + 9 + + + 111, 82 + + + 78, 20 + + + 11 + + + PTCH2SRV_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox9 + + + 0 + + + NoControl + + + 6, 86 + + + 54, 13 + + + 12 + + + INT_MAX + + + label53 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox9 + + + 1 + + + 111, 59 + + + 78, 20 + + + 9 + + + PTCH2SRV_D + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox9 + + + 2 + + + NoControl + + + 6, 63 + + + 15, 13 + + + 13 + + + D + + + label54 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox9 + + + 3 + + + 111, 36 + + + 78, 20 + + + 7 + + + PTCH2SRV_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox9 + + + 4 + + + NoControl + + + 6, 40 + + + 10, 13 + + + 14 + + + I + + + label55 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox9 + + + 5 + + + 111, 13 + + + 78, 20 + + + 5 + + + PTCH2SRV_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox9 + + + 6 + + + NoControl + + + 6, 17 + + + 14, 13 + + + 15 + + + P + + + label56 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox9 + + + 7 + + + 205, 1 + + + 195, 108 + + + 10 + + + Servo Pitch Pid + + + groupBox9 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAPM2 + + + 10 + + + 111, 82 + + + 78, 20 + + + 11 + + + RLL2SRV_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox8 + + + 0 + + + NoControl + + + 6, 86 + + + 54, 13 + + + 12 + + + INT_MAX + + + label49 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox8 + + + 1 + + + 111, 59 + + + 78, 20 + + + 9 + + + RLL2SRV_D + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox8 + + + 2 + + + NoControl + + + 6, 63 + + + 15, 13 + + + 13 + + + D + + + label50 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox8 + + + 3 + + + 111, 36 + + + 78, 20 + + + 7 + + + RLL2SRV_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox8 + + + 4 + + + NoControl + + + 6, 40 + + + 10, 13 + + + 14 + + + I + + + label51 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox8 + + + 5 + + + 111, 13 + + + 78, 20 + + + 5 + + + RLL2SRV_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox8 + + + 6 + + + NoControl + + + 6, 17 + + + 14, 13 + + + 15 + + + P + + + label52 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox8 + + + 7 + + + 4, 1 + + + 195, 108 + + + 11 + + + Servo Roll Pid + + + groupBox8 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAPM2 + + + 11 + + + 4, 22 + + + 0, 0, 0, 0 + + + 722, 434 + + + 0 + + + APM 2.x + + + TabAPM2 + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + ConfigTabs + + + 0 + + + 80, 63 + + + 78, 20 + + + 11 + + + THR_RATE_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox5 + + + 0 + + + NoControl + + + 6, 66 + + + 65, 13 + + + 12 + + + IMAX + + + label14 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox5 + + + 1 + + + 80, 37 + + + 78, 20 + + + 7 + + + THR_RATE_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox5 + + + 2 + + + NoControl + + + 6, 40 + + + 10, 13 + + + 14 + + + I + + + label20 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox5 + + + 3 + + + 80, 13 + + + 78, 20 + + + 5 + + + THR_RATE_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox5 + + + 4 + + + NoControl + + + 6, 16 + + + 14, 13 + + + 15 + + + P + + + label25 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox5 + + + 5 + + + 6, 237 + + + 170, 110 + + + 16 + + + Throttle Rate + + + groupBox5 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAC2 + + + 0 + + + True + + + 3, 198 + + + 154, 17 + + + 13 + + + Lock Pitch and Roll Values + + + CHK_lockrollpitch + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAC2 + + + 1 + + + 80, 86 + + + 78, 20 + + + 16 + + + WP_SPEED_MAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 0 + + + NoControl + + + 6, 89 + + + 54, 13 + + + 17 + + + m/s + + + label9 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 1 + + + 80, 63 + + + 78, 20 + + + 11 + + + NAV_LAT_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 2 + + + NoControl + + + 6, 66 + + + 65, 13 + + + 12 + + + IMAX + + + label13 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 3 + + + 80, 37 + + + 78, 20 + + + 7 + + + NAV_LAT_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 4 + + + NoControl + + + 6, 40 + + + 10, 13 + + + 14 + + + I + + + label15 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 5 + + + 80, 13 + + + 78, 20 + + + 5 + + + NAV_LAT_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 6 + + + NoControl + + + 6, 16 + + + 14, 13 + + + 15 + + + P + + + label16 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 7 + + + 534, 107 + + + 170, 108 + + + 0 + + + Nav WP + + + groupBox4 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAC2 + + + 2 + + + 80, 86 + + + 78, 20 + + + 18 + + + XTRK_ANGLE_CD1 + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox6 + + + 0 + + + NoControl + + + 6, 89 + + + 82, 13 + + + 19 + + + Error Max + + + label10 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox6 + + + 1 + + + 80, 63 + + + 78, 20 + + + 11 + + + XTRACK_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox6 + + + 2 + + + NoControl + + + 6, 66 + + + 65, 13 + + + 12 + + + IMAX + + + label11 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox6 + + + 3 + + + 80, 37 + + + 78, 20 + + + 7 + + + XTRACK_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox6 + + + 4 + + + NoControl + + + 6, 40 + + + 10, 13 + + + 14 + + + I + + + label17 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox6 + + + 5 + + + 80, 13 + + + 78, 20 + + + 5 + + + XTRACK_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox6 + + + 6 + + + NoControl + + + 6, 16 + + + 14, 13 + + + 15 + + + P + + + label18 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox6 + + + 7 + + + 358, 237 + + + 170, 110 + + + 2 + + + Crosstrack Correction + + + groupBox6 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAC2 + + + 3 + + + 80, 63 + + + 78, 20 + + + 11 + + + THR_ALT_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox7 + + + 0 + + + NoControl + + + 6, 66 + + + 65, 13 + + + 12 + + + IMAX + + + label19 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox7 + + + 1 + + + 80, 37 + + + 78, 20 + + + 7 + + + THR_ALT_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox7 + + + 2 + + + NoControl + + + 6, 40 + + + 10, 13 + + + 14 + + + I + + + label21 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox7 + + + 3 + + + 80, 13 + + + 78, 20 + + + 5 + + + THR_ALT_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox7 + + + 4 + + + NoControl + + + 6, 16 + + + 14, 13 + + + 15 + + + P + + + label22 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox7 + + + 5 + + + 182, 237 + + + 170, 110 + + + 3 + + + Altitude Hold + groupBox7 - - 28 + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + + TabAC2 + + + 4 + + + 80, 61 + + + 78, 20 + + + 11 + + + HLD_LAT_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox19 + + + 0 + + + NoControl + + + 6, 64 + + + 65, 13 + + + 12 + + + IMAX + + + label28 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox19 + + + 1 + + + 80, 37 + + + 78, 20 + + + 7 + + + HLD_LAT_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox19 + + + 2 + + + NoControl + + + 6, 40 + + + 10, 13 + + + 14 + + + I + + + label30 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox19 + + + 3 + + 80, 13 - + + 78, 20 + + + 5 + + + HLD_LAT_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox19 + + + 4 + + + NoControl + + + 6, 16 + + + 14, 13 + + + 15 + + + P + + + label31 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox19 + + + 5 + + + 531, 6 + + + 170, 95 + + + 6 + + + Loiter + + + groupBox19 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAC2 + + + 5 + + + 80, 63 + + + 78, 20 + + + 11 + + + STB_YAW_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox20 + + + 0 + + + NoControl + + + 6, 66 + + + 65, 13 + + + 12 + + + IMAX + + + label32 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox20 + + + 1 + + + 80, 37 + + + 78, 20 + + + 7 + + + STB_YAW_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox20 + + + 2 + + + NoControl + + + 6, 40 + + + 10, 13 + + + 14 + + + I + + + label34 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox20 + + + 3 + + + 80, 13 + + + 78, 20 + + + 5 + + + STB_YAW_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox20 + + + 4 + + + NoControl + + + 6, 16 + + + 14, 13 + + + 15 + + + P + + + label35 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox20 + + + 5 + + + 358, 6 + + + 170, 95 + + + 7 + + + Stabilize Yaw + + + groupBox20 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAC2 + + + 6 + + + 80, 63 + + + 78, 20 + + + 11 + + + STB_PIT_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox21 + + + 0 + + + NoControl + + + 6, 66 + + + 65, 13 + + + 12 + + + IMAX + + + label36 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox21 + + + 1 + + + 80, 37 + + + 78, 20 + + + 7 + + + STB_PIT_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox21 + + + 2 + + + NoControl + + + 6, 40 + + + 10, 13 + + + 14 + + + I + + + label41 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox21 + + + 3 + + + 80, 13 + + + 78, 20 + + + 5 + + + STB_PIT_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox21 + + + 4 + + + NoControl + + + 6, 16 + + + 14, 13 + + + 15 + + + P + + + label42 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox21 + + + 5 + + + 182, 6 + + + 170, 95 + + + 8 + + + Stabilize Pitch + + + groupBox21 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAC2 + + + 7 + + + 80, 63 + + + 78, 20 + + + 11 + + + STB_RLL_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox22 + + + 0 + + + NoControl + + + 6, 66 + + + 65, 13 + + + 12 + + + IMAX + + + label43 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox22 + + + 1 + + + 80, 37 + + + 78, 20 + + + 7 + + + STB_RLL_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox22 + + + 2 + + + NoControl + + + 6, 40 + + + 10, 13 + + + 14 + + + I + + + label45 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox22 + + + 3 + + + 80, 13 + + + 78, 20 + + + 5 + + + STB_RLL_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox22 + + + 4 + + + NoControl + + + 6, 16 + + + 14, 13 + + + 15 + + + P + + + label46 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 groupBox22 - - 11 + + 5 - - mavScale + + 6, 6 - - label90 - - - - - - NoControl - - - Servo Pitch Pid - - - TabPlanner - - - - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 13 + + 170, 95 9 - - Bottom, Left + + Stabilize Roll - - 1 + + groupBox22 - + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAC2 + + + 8 + + + 80, 63 + + 78, 20 - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 0 - - PTCH2SRV_D + + RATE_YAW_IMAX - - m/s - - - 7 - - - 195, 108 - - - P - - - Telemetry Rates - - - label45 - - - I - - - groupBox15 - - - 111, 82 - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - - - - 78, 20 - - - - - - 1 - - + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + groupBox23 - + + 0 + + NoControl - - groupBox4 - - - 18 - - - 78, 20 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 30, 176 - - - 65, 13 - - - HDNG2RLL_IMAX - - + 6, 66 - + + 65, 13 + + + 1 + + + IMAX + + + label47 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox23 + + + 1 + + + 80, 37 + + + 78, 20 + + + 4 + + + RATE_YAW_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox23 + + + 2 + + NoControl - - 78, 20 + + 6, 40 10, 13 - - + + 5 - - Nav Roll Pid + + I - + + label77 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox23 + + 3 - + + 80, 13 + + + 78, 20 + + + 6 + + + RATE_YAW_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox23 + + + 4 + + + NoControl + + + 6, 16 + + + 14, 13 + + + 7 + + + P + + + label82 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + groupBox23 + + + 5 + + + 358, 107 + + + 170, 91 + + + 10 + + + Rate Yaw + + + groupBox23 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAC2 + + + 9 + + + 80, 63 + + + 78, 20 + + + 0 + + + RATE_PIT_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox24 + + + 0 + + + NoControl + + + 6, 66 + + + 65, 13 + + + 1 + IMAX - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + label84 - - STB_PIT_IMAX + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 5 + + groupBox24 - - 30, 94 + + 1 - + + 80, 37 + + + 78, 20 + + + 4 + + + RATE_PIT_I + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - label97 + + groupBox24 + + + 2 + + + NoControl + + + 6, 40 10, 13 - - 23 + + 5 - + + I + + + label86 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox24 + + + 3 + + + 80, 13 + + + 78, 20 + + + 6 + + + RATE_PIT_P + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - Stabilize Pitch + + groupBox24 - - 6, 86 + + 4 - - ENRGY2THR_IMAX + + NoControl - - 4, 1 + + 6, 16 - - 29 + + 14, 13 + + + 7 + + + P + + + label87 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox24 + + + 5 + + + 182, 107 + + + 170, 91 + + + 11 + + + Rate Pitch + + + groupBox24 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAC2 + + + 10 + + + 80, 63 + + + 78, 20 + + + 0 + + + RATE_RLL_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox25 + + + 0 + + + NoControl + + + 6, 66 + + + 68, 13 + + + 1 + + + IMAX + + + label88 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox25 + + + 1 + + + 80, 37 + + + 78, 20 + + + 4 + + + RATE_RLL_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox25 + + + 2 + + + NoControl + + + 6, 40 + + + 10, 13 + + + 5 + + + I + + + label90 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox25 + + + 3 + + + 80, 13 + + + 78, 20 + + + 6 + + + RATE_RLL_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox25 + + + 4 + + + NoControl + + + 6, 16 + + + 14, 13 + + + 7 + + + P + + + label91 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox25 + + + 5 + + + 6, 107 + + + 170, 91 + + + 12 + + + Rate Roll + + + groupBox25 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAC2 + + + 11 + + + 4, 22 + + + 3, 3, 3, 3 + + + 722, 434 + + + 1 + + + AC2 + + + TabAC2 + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + ConfigTabs + + + 1 + + + NoControl + + + 30, 300 + + + 61, 13 + + + 39 + + + HUD + + + label12 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 0 + + + NoControl + + + 139, 299 + + + 177, 17 + + + 40 + + + GDI+ (old type) + + + 17, 17 + + + OpenGL = Disabled +GDI+ = Enabled + + + CHK_GDIPlus + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 1 + + + NoControl + + + 30, 277 + + + 61, 13 + + + 37 + + + Waypoints + + + label24 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 2 + + + NoControl + + + 139, 276 + + + 177, 17 + + + 38 + + + Load Waypoints on connect? + + + CHK_loadwponconnect + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 3 + + + NoControl + + + 30, 252 + + + 103, 18 + + + 36 + + + Track Length + + + label23 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 4 + + + 139, 250 + + + 67, 20 + + + 35 + + + On the Flight Data Tab + + + NUM_tracklength + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 5 + + + NoControl + + + 579, 67 + + + 102, 17 + + + 34 + + + Alt Warning + + + CHK_speechaltwarning + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 6 + + + NoControl + + + 30, 228 + + + 61, 13 + + + 0 + + + APM Reset + + + label108 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 TabPlanner - - groupBox4 + + 7 - - groupBox20 + + NoControl + + + 139, 227 + + + 163, 17 + + + 1 + + + Reset APM on USB Connect + + + CHK_resetapmonconnect + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 8 + + + Bottom, Left + + + NoControl + + + 33, 411 + + + 144, 17 + + + 2 + + + Mavlink Message Debug + + + CHK_mavdebug + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 9 + + + NoControl + + + 590, 203 + + + 22, 13 + + + 3 + + + RC + + + label107 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 10 + + + 0 + + + 1 + + + 3 + + + 10 + + + 621, 200 + + + 80, 21 + + + 4 + + + CMB_raterc + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 11 + + + NoControl + + + 425, 203 + + + 69, 13 + + + 5 + + + Mode/Status + + + label104 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 12 + + + NoControl + + + 280, 203 + + + 44, 13 + + + 6 + + + Position + + + label103 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 13 + + + NoControl + + + 136, 203 + + + 43, 13 + + + 7 + + + Attitude + + + label102 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 14 + + + NoControl + + + 27, 203 + + + 84, 13 + + + 8 + + + Telemetry Rates + + + label101 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 15 + + + 0 + + + 1 3 @@ -2664,3865 +5074,957 @@ 10 - - 4 - - - 4 - - - 13 - - - groupBox7 - - - 23 - - - groupBox2 - - - groupBox1 - - - NoControl - - - 3, 3 - - - groupBox6 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - P - - - TabAC2 - - - groupBox6 - - - - - - - - - - - - NoControl - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 16 - - - HUD - - - 0 - - - - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 40 - - - TabAC2 - - - 10, 13 - - - 7 - - - 0 - - - 0 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 7 - - - NoControl - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NAV_LAT_IMAX - - - 54, 13 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 52, 13 - - - I - - - 111, 59 - - - 50, 13 - - - 4, 217 - - - 80, 37 - - - TabAC2 - - - INT_MAX - - - - - - 14 - - - Bottom, Left - - - 78, 20 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 1 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox8 - - - label47 - - - NoControl - - - 195, 108 - - - Save - - - - - - ALT2PTCH_D - - - 6, 63 - - - TabPlanner - - - 3 - - - 9 - - - Bottom, Left - - - 14, 13 - - - Airspeed m/s - - - 102, 17 - - - label98 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 0, 0, 0, 0 - - - - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 86 - - - 6 - - - 3 - - - 78, 20 - - - 10 - - - 6 - - - 6, 16 - - - 2 - - - NoControl - - - Navigation Angles - - - groupBox24 - - - 5 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 1 - - - groupBox7 - - - False - - - CHK_speechcustom - - - groupBox20 - - - 16 - - - 78, 20 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - XTRK_ANGLE_CD - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 7 - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - 6 - - - NoControl - - - 17 - - - P - - - label42 - - - groupBox19 - - - D - - - 3 - - - CHK_loadwponconnect - - - 2 - - - Loiter - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - Throttle 0-100% - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - 15 - - - groupBox1 - - - 2 - - - 205, 325 - - - Start - - - NoControl - - - Nav WP - - - label43 - - - 78, 20 - - - 78, 20 - - - 65, 13 - - - 11 - - - - - - 78, 20 - - - 0 - - - 111, 82 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 36, 13 - - - 78, 20 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 78, 20 - - - 5 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - label108 - - - ConfigTabs - - - 12 - - - - - - 111, 36 - - - 78, 20 - - - 31 - - - groupBox14 - - - label49 - - - groupBox10 - - - Crosstrack Correction - - - 35 - - - - - - - - - - - - P - - - 30, 47 - - - THR_HOLD_I - - - groupBox19 - - - NoControl - - - ALT2PTCH_IMAX - - - - - - - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox2 - - - 15 - - - 8 - - - 26 - - - Altitude Hold - - - 57, 13 - - - groupBox1 - - - 12 - - - 6, 63 - - - 17 - - - groupBox19 - - - TabPlanner - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox4 - - - Lock Pitch and Roll Values - - - - - - 103, 18 - - - 13 - - - NoControl - - - NoControl - - - groupBox24 - - - 38 - - - 80, 63 - - - 71, 17 - - - 0 - - - 2 - - - 111, 82 - - - groupBox21 - - - 6, 86 - - - 0 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 37 - - - NoControl - - - groupBox13 - - - 11 - - - 3 - - - groupBox6 - - - 1 - - - NoControl - - - groupBox2 - - - 78, 20 - - - 80, 13 - - - groupBox11 - - - INT_MAX - - - 54, 13 - - - 30, 71 - - - 4, 22 - - - 4 - - - 6, 40 - - - 0 - - - NoControl - - - Value - - - NoControl - - - ARSPD_FBW_MIN - - - 14 - - - 7 - - - - - - 0 - - - 78, 20 - - - 14 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - Reset APM on USB Connect - - - 5 - - - 170, 91 - - - groupBox24 - - - TabPlanner - - - 78, 20 - - - 1 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - - - - 11 - - - 1 - - - 78, 20 - - - YW2SRV_P - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 59 - - - 10 - - - groupBox8 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 0 - - - 31, 438 - - - 78, 20 - - - ARSPD_FBW_MAX - - - Compare Params - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - label41 - - - groupBox25 - - - groupBox20 - - - CMB_speedunits - - - 722, 434 - - - - - - 20 - - - groupBox23 - - - groupBox3 - - - - - - - - - - - - 5 - - - 2 - - - 111, 59 - - - 15, 13 - - - 13 - - - 4, 325 - - - 11 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox23 - - - 78, 20 - - - - - - 78, 20 - - - - - - NoControl - - - 26 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 5 - - - 144, 17 - - - 78, 20 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox10 - - - 182, 241 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 78, 20 - - - groupBox2 - - - 78, 20 - - - - - - STB_YAW_P - 499, 200 - - - - - - - - TabPlanner - - - 111, 13 - - - System.Windows.Forms.TabControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 78, 20 - - - 7 - - - D - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 621, 200 - - - 322, 67 - - - groupBox2 - - - groupBox11 - - - 2 - - - NoControl - - - groupBox2 - - - - - - 80, 13 - - - 4 - - - 6, 86 - - - 0 - - - 7 - - - 6, 17 - - - XTRACK_I - - - 7 - - - - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 2 - - - 30 - - - NoControl - - - 0, 0 - - - 169, 441 - - - 14 - - - 6 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 7 - - - NoControl - - - 15 - - - 54, 13 - - - 9 - - - 80, 37 - - - groupBox12 - - - 7 - - - groupBox24 - - - KFF_PTCH2THR - - - PTCH2SRV_IMAX - - - Bottom, Left - - - groupBox19 - - - Top, Bottom, Left - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 8 - - - $this - - - 25 - - - KFF_PTCHCOMP - - - 9 - - - 17 - - - I - - - 4 - - - 78, 20 - - - NoControl - - - 1 - - - 14 - - - On the Flight Data Tab - - - - - - 6, 107 - - - 45, 13 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 78, 20 - - - 138, 21 - - - groupBox3 - - - 9 - - - groupBox20 - - - NoControl - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - THR_HOLD_IMAX - - - 4 - - - 4 - - - 0 - - - Gain (cm) - - - 6 - - - NoControl - - - RATE_PIT_P - - - groupBox4 - - - - - - 5 - - - 7 - - - 4 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 6, 40 - - - - - - 170, 95 - - - - - - Rate Pitch - - - 4 - - - LIM_PITCH_MIN - - - TabPlanner - - - - 80, 21 - - APM Reset + + 9 - + + CMB_ratestatus + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 16 + + + 0 + + 1 - + 3 - - 7 - - - groupBox9 - - - 63 - - + 10 - - 13 + + 334, 200 - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 80, 21 - - CHK_enablespeech + + 10 - - 7 + + CMB_rateposition - - 21 + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - groupBox22 - - - - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 5 - - - 5 - - - groupBox2 - - + TabPlanner - - System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 17 - - 67, 20 + + 0 - - 14, 13 - - - TabPlanner - - - False - - - 75, 19 - - + 1 - - 30, 252 - - - 3, 3, 3, 3 - - - TabAC2 - - - 111, 13 - - - TabPlanner - - - 38 - - - NoControl - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 15 - - - 80, 63 - - - 1 - - - 4 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - + 3 10 - - 40 + + 188, 200 - - NoControl - - - 2 - - - 15, 13 - - - 111, 13 - - - 3 - - - - - - 5 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 0 - - - NoControl - - - 14, 13 - - - System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 1 - - - 5 - - - Cruise - - - 1 - - - 0 - - - 1 - - - 78, 20 - - - 78, 20 - - - TabPlanner - - - 5 - - - I - - - NoControl - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - Mode/Status - - - 2 - - - 9 - - - 80, 37 - - - 6 - - - NoControl - - - TabAC2 - - - 87, 17 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - label84 - - - 1 - - - 7 - - - - - - - - - label73 - - - 53, 13 - - - Servo Yaw Pid - - - 78, 20 - - - P - - - - - - Pitch Max - - - TabAPM2 - - - D - - - NoControl - - - label103 - - - 6 - - - groupBox14 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 1 - - - 11 - - - 36 - - - - - - 6 - - - 3 - - - 78, 20 - - - Stabilize Yaw - - - 3 - - - groupBox20 - - - label34 - - - NoControl - - - 14, 13 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - groupBox15 - - - BUT_videostart - - - 5 - - - IMAX - - - - - - 33 - - - 3 - - - NoControl - - - 10, 13 - - - groupBox4 - - - 6 - - - 32, 13 - - - 5 - - - 1 - - - STB_RLL_P - - - label35 - - - TabPlanner - - - $this - - - 406, 109 - - - I - - - label62 - - - 4 - - - 1 - - - STB_YAW_IMAX - - - 177, 17 - - - NoControl - - - - - - 5 - - - TabPlanner - - - CMB_osdcolor - - - 3 - - - 0 - - - - - - - - - 78, 20 - - - CMB_ratestatus - - - 7 - - - 182, 107 - - - TabPlanner - - - label80 - - - - - - TabPlanner - - - THR_HOLD_P - - - 6, 63 - - - groupBox4 - - - 7 - - - 78, 20 - - - groupBox16 - - - NoControl - - - 5 - - - groupBox14 - - - 5 - - - 11 - - - - - - Speed Units - - - NoControl - - - label81 - - - 1 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 86 - - - - - - - - - BUT_save - - - 3 - - - groupBox20 - - - 14 - - - P - - - CHK_speechbattery - - - I - - - 24 - - - label30 - - - RawValue - - - label17 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - False - - - $this - - - Configuration - - - 40 - - - groupBox11 - - - HLD_LAT_IMAX - - - groupBox1 - - - 21 - - - groupBox13 - - - label31 - - - THR_MAX - - - 61, 13 - - - 14, 13 - - - TabPlanner - - - Alt Warning - - - 54, 13 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 36, 13 - - - STB_RLL_IMAX - - - 80, 13 - - - label87 - - - 6, 40 - - - 75, 19 - - - 6, 89 - - - 1 - - - KFF_RDDRMIX - - - groupBox14 - - - 4 - - - TabPlanner - - - label36 - - - TabPlanner - - - ARSP2PTCH_IMAX - - - groupBox9 - - - 78, 20 - - - groupBox25 - - - 4 - - - Time Interval - - - Other Mix's - - - - - - Mode - - - groupBox23 - - - - - - 405, 217 - - - RATE_YAW_I - - - 7 - - - 80, 13 - - - label12 - - - 0 - - - label37 - - - 5 - - - TabPlanner - - - 5 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - I - - - Attitude - - - P - - - 1 - - - RC - - - 6, 86 - - - 3 - - - NoControl - - - label82 - - - TabPlanner - - - 34 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 54, 13 - - - 1 - - - CMB_rateposition - - - groupBox21 - - - Speech - - - - - - 0 - - - 9 - - - - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 14, 13 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 3 - - - 5 - - - 1008, 461 - - - - - - TabAPM2 - - - Error Max - - - label83 - - - 3 - - - 0 - - - 0 - - - NoControl - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 195, 108 - - - 6 - - - 6 - - - 6, 40 - - - 7 - - - 6 - - - 111, 59 - - - label32 - - - groupBox13 - - - 1 - - - label88 - - - 78, 20 - - - groupBox22 - - - NoControl - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - NoControl - - - 2 - - - 170, 95 - - - 163, 17 - - - groupBox3 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 3 - - - 170, 91 - - - groupBox14 - - - label15 - - - groupBox4 - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 86 - - - RATE_RLL_P - - - 3 - - - 195, 108 - - - 3 - - - 19 - - - groupBox9 - - - 534, 107 - - - TabPlanner - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - 64 - - - 4 - - - 13 - - - label38 - - - groupBox1 - - - $this - - - 111, 59 - - - groupBox16 - - - 12 - - - 1 - - - TabPlanner - - - 82, 13 - - - groupBox6 - - - 0 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - 100, 23 - - - XTRACK_IMAX - - - label39 - - - 6, 16 - - - 78, 20 - - - RawValue - - - 12 - - - 6 - - - groupBox15 - - - 14 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - groupBox4 - - - - - - 1 - - - TabPlanner - - - - - - Default - - - 12 - - - TabAPM2 - - - LIM_PITCH_MAX - - - label10 - - - 0 - - - groupBox8 - - - 3 - - - - - - - - - 378, 67 - - - - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 99, 23 - - - 80, 63 - - - - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 14 - - - groupBox8 - - - TabPlanner - - - 6 - - - label11 - - - 6, 17 - - - 15 - - - 14 - - - - - - - - - 6, 16 - - - label1 - - - - - - 6, 66 - - - 111, 82 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - label16 - - - - - - 6, 66 - - + 80, 21 - - ConfigTabs - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 241 - - - 0 - - - - - - 7 - - - 4 - - - INT_MAX - - - 65, 13 - - - 30, 300 - - - D - - - 9 - - - 12 - - - 6 - - - NoControl - - - label5 - - - groupBox14 - - - 111, 59 - - - 6, 17 - - - NoControl - - - 170, 95 - - - 10, 13 - - - - - - TabAPM2 - - - - - - 4 - - - 6, 40 - - - NoControl - - - 6, 40 - - - 14, 13 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - Refresh Params - - - CHK_lockrollpitch - - - HDNG2RLL_I - - - 12 - - - - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 6, 16 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 10, 13 - - - 19 - - - CMB_language - - - label9 - - - NoControl - - - NoControl - - - 7 - - - 471, 11 - - - groupBox12 - - - groupBox3 - - - - - - TabPlanner - - - 1 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 10 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 40 - - - IMAX - - - NoControl - - - 6, 17 - - - - - - NoControl - - - - - - 2 - - - XTRACK_P - - - 14 - - - NoControl - - - 4 - - - TabPlanner - - - - - - 4 - - - I - - - 425, 203 - - - Value - - - 139, 250 - - - 6, 16 - - - 36 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - - - - TabAPM2 - - - label13 - - - mavScale - - - groupBox16 - - - TabAC2 - - - 80, 86 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabSetup - - - NoControl - - - 4 - - - I - - - P - - - 2 - - - I - - - 111, 13 - - - label18 - - - 0 - - - 14, 13 - - - groupBox3 - - - 0 - - - - - - 5 - - - 6, 66 - - - 80, 61 - - - Waypoints - - - - - - 15 - - - 138, 21 - - - $this - - - label19 - - - - - - groupBox22 - - - 78, 20 - - - 78, 20 - - - 6, 17 - - - 1 - - - TabAC2 - - - 39 - - - Command - - - - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - 10 - - - 170, 108 - - - 27 - - - 2 - - - groupBox11 - - - 6, 40 - - - 2 - - - Pitch Comp - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 19 - - - 5 - - - FBW min - - - NoControl - - - D - - - 51, 13 - - - I - - - 6, 66 - - - + + 11 CMB_rateattitude - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - HLD_LAT_I - - - 6, 40 - - - 6, 40 - - - I - - - groupBox12 - - - 12 - - - 2 - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 103, 19 - - - 111, 13 - - - - - + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - groupBox10 - - - 6, 63 - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - 82, 416 - - - - - - 5 - - - 78, 20 - - - Bank Max - - - AC2 - - - groupBox9 - - - 78, 20 - - - - - - 78, 20 - - - 4 - - - 103, 19 - - - groupBox14 - - - groupBox13 - - - - - - 6, 16 - - - 2 - - - 1 - - - - - - 80, 63 - - - 54, 13 - - - 6 - - - 0 - - - - - - 69, 13 - - - 6, 63 - - - Rate Yaw - - - 13 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - TabAC2 - - - FS Value - - - 5 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - + TabPlanner - - 10, 13 - - - 12 - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - groupBox16 - - - 111, 36 - - - - - - 7 - - - 15 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 7 - - - - - - BUT_videostop - - - CHK_resetapmonconnect - - - - - - 14, 13 - - - 245, 21 - - - 15 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 11 - - - NoControl - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 1 - - - 3 - - - 2 - - - System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 55, 13 - - - ARSPD_RATIO - - - Params - - - groupBox19 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 35 - - - 0 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox1 - - - 0 - - - 4 - - - 7 - - - - - - TabPlanner - - - TabPlanner - - - NoControl - - - 6, 89 - - - groupBox25 - - - - - - NoControl - - - IMAX - - - - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - Pitch Min - - - 269, 409 - - - 358, 107 - - - groupBox23 - - - NoControl - - - NAV_LAT_P - - - TabAPM2 - - - NoControl - - - 7 - - - 0, 0, 0, 0 - - - - - - 78, 20 - - - NoControl - - - Stop - - + 18 - - 169, 416 - - - 111, 59 - - - groupBox11 - - - 111, 13 - - - 78, 20 - - - 2 - - - 4 - - - label74 - - - 78, 20 - - - RATE_RLL_I - - + NoControl - - 7 + + 283, 168 - - 6, 66 + + 402, 13 - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 54, 13 - - - CMB_videosources - - - groupBox12 - - - TabPlanner - - - groupBox13 - - - label75 - - - - - - 3 - - - NoControl - - - 5 - - - 6, 40 - - - - - - 139, 173 - - - 6, 63 - - - 2 - - - 2 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabPlanner - - - 33, 411 - - - 6, 17 - - - 7 - - - - - + 12 - - 16 - - - 10, 13 - - - - - - CHK_speechmode - - - 111, 59 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 2 - - - Entry Angle - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - NOTE: The Configuration Tab will NOT display these units, as those are raw values. - - + + label99 - - 2 - - - - - - 84, 13 - - - 2 - - - 4 - - - $this - - - - - - 8 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - Position - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 80, 63 - - - - - - 5 - - - 0 - - + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 6 - - - LIM_ROLL_CD - - - groupBox10 - - - label66 - - - label70 - - - groupBox13 - - - - - - - - - 6, 40 - - - System.Windows.Forms.DataGridView, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - OpenGL = Disabled -GDI+ = Enabled - - - 6 - - - 54, 13 - - - 8 - - - 111, 82 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 3 - - - NoControl - - - Xtrack Pids - - - NoControl - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - + TabPlanner - - 24, 13 + + 19 - - label71 - - - 39 - - - 552, 15 - - - groupBox11 - - - BUT_compare - - - 139, 67 - - + NoControl - - Planner + + 30, 176 - - 6, 63 + + 65, 13 - - TabPlanner - - - I - - - 0 - - - CMB_raterc - - - groupBox21 - - - OSD Color - - - - - - Rate Roll - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 80, 37 - - - label76 - - - 6, 86 - - - 406, 1 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - 37 - - - NoControl - - - 6, 6 - - - 111, 36 - - - - - - 64, 13 - - - 111, 36 - - - 11 - - - Mavlink Message Debug - - - 6, 63 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox12 - - - 111, 13 - - - BUT_load - - - label77 - - - 9 - - - 3 - - - 280, 203 - - - 9 - - - 0 - - - NoControl - - - NoControl - - - 5 - - - 195, 108 - - - - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - Bottom, Left - - - - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6 - - - RLL2SRV_D - - - 32 - - - - - - 9 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 3 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - 15, 13 - - - 8 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - label92 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - label63 - - - TRIM_ARSPD_CM - - - - - - 111, 36 - - - 7 - - - - - - 10, 13 - - - NoControl - - - label21 - - + 13 - - groupBox9 + + Speed Units - - label72 + + label98 - - label54 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 20 + + + NoControl + + + 30, 149 + + + 52, 13 + + + 14 + + + Dist Units + + + label97 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 21 + + + 139, 173 + + + 138, 21 + + + 15 + + + CMB_speedunits + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 22 + + + 139, 146 + + + 138, 21 + + + 16 + + + CMB_distunits + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 23 + + + NoControl + + + 30, 122 + + + 45, 13 + + + 17 + + + Joystick + + + label96 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 24 + + + NoControl + + + 30, 71 + + + 44, 13 + + + 18 + + + Speech + + + label95 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 25 + + + NoControl 471, 67 - - 10 + + 102, 17 - - 2 + + 19 - - + + Battery Warning - - groupBox11 + + CHK_speechbattery - - groupBox11 - - - 99, 17 - - - groupBox6 - - - TabPlanner - - - PTCH2SRV_I - - - groupBox24 - - - 139, 227 - - - Load Waypoints on connect? - - - STB_RLL_I - - - label55 - - - 14 - - - 78, 20 - - - 32 - - - 78, 20 - - - 14, 13 - - - groupBox8 - - - - - - 62 - - - - - - 5 - - - - - - groupBox25 - - + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + + TabPlanner + + + 26 + + NoControl - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 378, 67 + + + 87, 17 + + + 20 + + + Time Interval + + + CHK_speechcustom + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 27 + + + NoControl + + + 322, 67 + + + 56, 17 + + + 21 + + + Mode + + + CHK_speechmode + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 28 + + + NoControl + + + 245, 67 + + + 71, 17 + + + 22 + + + Waypoint + + + CHK_speechwaypoint + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 29 + + + NoControl + + + 30, 47 + + + 57, 13 + + + 23 + + + OSD Color + + + label94 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 30 + + + 139, 40 138, 21 - + + 24 + + + CMB_osdcolor + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 31 + + + 139, 90 + + + 138, 21 + + + 25 + + + CMB_language + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 32 + + + NoControl + + + 30, 94 + + + 69, 13 + + + 26 + + + UI Language + + + label93 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 54, 13 + + TabPlanner - - STB_YAW_I + + 33 - - 61, 13 + + NoControl - - label104 + + 139, 67 - - label99 + + 99, 17 - + + 27 + + + Enable Speech + + + CHK_enablespeech + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 34 + + + NoControl + + + 552, 15 + + + 125, 17 + + + 28 + + + Enable HUD Overlay + + + CHK_hudshow + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 35 + + + NoControl + + + 30, 16 + + + 100, 23 + + + 29 + + + Video Device + + + label92 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - groupBox25 + + TabPlanner - - + + 36 139, 13 - - 80, 13 + + 245, 21 - - 80, 63 + + 30 - - 9 + + CMB_videosources - - label79 + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - groupBox3 + + TabPlanner - - TabAC2 + + 37 - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + NoControl - - groupBox3 + + 139, 117 - - + + 99, 23 - - ALT2PTCH_P + + 31 - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + Joystick Setup - - 15 + + BUT_Joystick - - 0, 0, 0, 0 + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + TabPlanner - - 10, 13 + + 38 - - 8 + + NoControl - - groupBox13 + + 471, 11 - - Write changed params to device + + 75, 23 - - groupBox22 + + 32 + + + Stop + + + BUT_videostop + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + TabPlanner + + + 39 + + + NoControl + + + 390, 11 + + + 75, 23 + + + 33 + + + Start + + + BUT_videostart + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + TabPlanner + + + 40 + + + 4, 22 + + + 3, 3, 3, 3 + + + 722, 434 + + + 2 + + + Planner + + + TabPlanner + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + ConfigTabs + + + 2 + + + 4, 22 + + + 722, 434 + + + 3 + + + Setup + + + TabSetup + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + ConfigTabs + + + 3 52, 18 - - True + + 278, 0 + + + 0, 0, 0, 0 + + + 0, 0 + + + 730, 460 + + + 62 + + + ConfigTabs + + + System.Windows.Forms.TabControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 2 + + + Bottom, Left + + + NoControl + + + 169, 441 + + + 103, 19 + + + 0 + + + Refresh Params + + + Reload params from device + + + BUT_rerequestparams + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + $this + + + 1 + + + Bottom, Left + + + NoControl + + + 169, 416 + + + 103, 19 + + + 63 + + + Write Params + + + Write changed params to device + + + BUT_writePIDS + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + $this + + + 3 + + + Bottom, Left + + + NoControl + + + 82, 416 + + + 0, 0, 0, 0 + + + 75, 19 + + + 64 + + + Save + + + Save params to file + + + BUT_save + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + $this + + + 4 + + + Bottom, Left + + + NoControl + + + 3, 416 + + + 0, 0, 0, 0 + + + 75, 19 + + + 65 + + + Load + + + Load param's from file + + + BUT_load + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + $this + + + 5 + + + Bottom, Left + + + NoControl + + + 31, 438 + + + 103, 19 + + + 66 + + + Compare Params + + + BUT_compare + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + $this + + + 0 True - - 17, 17 + + 6, 13 - - True + + 1008, 461 - - True + + Command - - True + + System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Value + + + System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Default + + + System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + mavScale + + + System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + RawValue + + + System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + toolTip1 + + + System.Windows.Forms.ToolTip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Configuration + + + System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c ..\Resources\MAVParam.txt;System.String, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089;Windows-1252 diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/Resources/MAVCmd.txt b/Tools/ArdupilotMegaPlanner/bin/Release/Resources/MAVCmd.txt new file mode 100644 index 0000000000..51caf769b8 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/bin/Release/Resources/MAVCmd.txt @@ -0,0 +1,19 @@ +WAYPOINT;WAYPOINT;Delay;Alt;Lat;Long +LOITER_UNLIM;LOITER_UNLIM;N/A;Alt;Lat;Long +LOITER_TURNS;LOITER_TURNS;Turns;Alt;Lat;Long +LOITER_TIME;LOITER_TIME;Time s*10;Alt;Lat;Long +RETURN_TO_LAUNCH;RETURN_TO_LAUNCH;N/A;Alt;Lat;Long +LAND;LAND;N/A;Alt;Lat;Long +TAKEOFF;TAKEOFF;Angle;Alt;N/A;N/A +CONDITION_DELAY;CONDITION_DELAY;N/A;N/A;Time (sec);N/A +CONDITION_CHANGE_ALT;CONDITION_CHANGE_ALT;N/A;Alt;Rate (cm/sec);N/A +CONDITION_DISTANCE;CONDITION_DISTANCE;N/A;N/A;Dist (m);N/A +CONDITION_YAW;CONDITION_YAW;Angle;Speed(deg/sec);Direction (1/-1);Relateiv(1)/Absolute(0) +DO_JUMP;DO_JUMP;WP #;N/A;Repeat Count;N/A +DO_CHANGE_SPEED;DO_CHANGE_SPEED;Type (0=as 1=gs);Speed (m/s);Throttle(%);N/A +DO_SET_HOME;DO_SET_HOME;Current(1)/Spec(0);Alt (m);Lat;Long +DO_SET_PARAMETER;DO_SET_PARAMETER;Param Number;Param Value;N/A;N/A +DO_REPEAT_RELAY;DO_REPEAT_RELAY;N/A;Repeat#;Delay (sec);N/A +DO_SET_RELAY;DO_SET_RELAY;Off(0)/On(1);N/A;N/A;N/A +DO_SET_SERVO;DO_SET_SERVO;Servo No;PWM;N/A;N/A +DO_REPEAT_SERVO;DO_REPEAT_SERVO;Servo No;PWM;Repeat#;Delay (sec) \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/Resources/MAVParam.txt b/Tools/ArdupilotMegaPlanner/bin/Release/Resources/MAVParam.txt new file mode 100644 index 0000000000..9a19416a3b --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/bin/Release/Resources/MAVParam.txt @@ -0,0 +1,221 @@ +== MAVLink Parameters == (this is a copy fo the wiki page FYI) + +This is a list of all the user-modifiable MAVLink parameters and what they do. You can modify them via the MAVLink parameters window in any compatible GCS, such as the Mission Planner, HK GCS or !QGroundControl. + +It includes both fixed wing (APM) and rotary wing (!ArduCopter) parameters. Some may only be relevant for one platform or another. + +|| *EEPROM variable name* || *Min* || *Max* || *Default* || *Multiplier* || *Enabled (0 = no, 1 = yes)* || *Comment* || +||MAH|| || ||1|| || || || +||CURRENT_ENABLE|| || ||1|| || || || +||AOA|| || ||1|| || || || +||MAG_ENABLE|| || ||1|| || || || +||HDNG2RLL_P||0||5||0.7||1||1||NAV_ROLL_P - Navigation control gains. Tuning values for the navigation control PID loops. The P term is the primary tuning value. This determines how the control deflection varies in proportion to the required correction.|| +||HDNG2RLL_I||0||1||0.01||1||1||NAV_ROLL_I - Navigation control gains. Tuning values for the navigation control PID loops. The I term is used to control drift.|| +||HDNG2RLL_D||0||1||0.02||1||1||NAV_ROLL_D - Navigation control gains. Tuning values for the navigation control PID loops. The D term is used to control overshoot. Avoid adjusting this term if you are not familiar with tuning PID loops.|| +||HDNG2RLL_IMAX||0||3000||500||100||1||NAV_ROLL_INT_MAX_CENTIDEGREE - In Degrees - Maximum control offset due to the integral. This prevents the control output from being overdriven due to a persistent offset (e.g. native flight AoA). If you find this value is insufficient consider adjusting the AOA parameter.|| +||RLL2SRV_P||0||5||0.4||1||1||SERVO_ROLL_P - Attitude control gains - Tuning values for the attitude control PID loops. The P term is the primary tuning value. This determines how the control deflection varies in proportion to the required correction.|| +||RLL2SRV_I||0||1||0||1||1||SERVO_ROLL_I - Attitude control gains - Tuning values for the attitude control PID loops. The I term is used to help control surfaces settle. This value should normally be kept low.|| +||RLL2SRV_D||0||1||0||1||1||SERVO_ROLL_D - Attitude control gains - Tuning values for the attitude control PID loops. The D term is used to control overshoot. Avoid using or adjusting this term if you are not familiar with tuning PID loops. It should normally be zero for most aircraft.|| +||RLL2SRV_IMAX||0||3000||500||100||1||SERVO_ROLL_INT_MAX_DEGREE - In Degrees - Maximum control offset due to the integral. This prevents the control output from being overdriven due to a persistent offset (e.g. crosstracking). Default is 5 degrees.|| +||PTCH2SRV_P||0||5||0.6||1||1||SERVO_PITCH_P - Attitude control gains - Tuning values for the attitude control PID loops. The P term is the primary tuning value. This determines how the control deflection varies in proportion to the required correction.|| +||PTCH2SRV_I||0||1||0||1||1||SERVO_PITCH_I - Attitude control gains - Tuning values for the attitude control PID loops. The I term is used to help control surfaces settle. This value should normally be kept low.|| +||PTCH2SRV_D||0||1||0||1||1||SERVO_PITCH_D - Attitude control gains - Tuning values for the attitude control PID loops. The D term is used to control overshoot. Avoid using or adjusting this term if you are not familiar with tuning PID loops. It should normally be zero for most aircraft.|| +||PTCH2SRV_IMAX||0||3000||500||100||1||SERVO_PITCH_INT_MAX_DEGREE - In Degrees - Maximum control offset due to the integral. This prevents the control output from being overdriven due to a persistent offset (e.g. crosstracking). Default is 5 degrees.|| +||ARSPD2PTCH_P||0||5||0.65||1||1||NAV_PITCH_ASP_P - P. I and D terms for pitch adjustments made to maintain airspeed.|| +||ARSPD2PTCH_I||0||1||0||1||1||NAV_PITCH_ASP_I - P. I and D terms for pitch adjustments made to maintain airspeed.|| +||ARSPD2PTCH_D||0||1||0||1||1||NAV_PITCH_ASP_D - P. I and D terms for pitch adjustments made to maintain airspeed.|| +||ARSPD2PTCH_IMA||0||3000||500||100||1||NAV_PITCH_ASP_INT_MAX - In Degrees - Maximum pitch offset due to the integral. This limits the control output from being overdriven due to a persistent offset (eg. inability to maintain the programmed airspeed).|| +||YW2SRV_P||0||5||0||1||1||SERVO_YAW_P - P. I and D terms for the YAW control. Note units of this control loop are unusual. PID input is in m/s**2|| +||YW2SRV_I||0||1||0||1||1||SERVO_YAW_I - P. I and D terms for the YAW control. Note units of this control loop are unusual. PID input is in m/s**2|| +||YW2SRV_D||0||1||0||1||1||SERVO_YAW_D - P. I and D terms for the YAW control. Note units of this control loop are unusual. PID input is in m/s**2|| +||YW2SRV_IMAX||0||3000||0||100||1||SERVO_YAW_INT_MAX - Maximum control offset due to the integral. This prevents the control output from being overdriven due to a persistent offset (e.g. crosstracking).|| +||ENRGY2THR_P||0||5||0.5||1||1||THROTTLE_TE_P - P. I and D terms for throttle adjustments made to control altitude.|| +||ENRGY2THR_I||0||1||0||1||1||THROTTLE_TE_I - P. I and D terms for throttle adjustments made to control altitude.|| +||ENRGY2THR_D||0||1||0||1||1||THROTTLE_TE_D - P. I and D terms for throttle adjustments made to control altitude.|| +||ENRGY2THR_IMAX||0||100||20||1||1||THROTTLE_TE_INT_MAX - In Percent - Maximum throttle input due to the integral term. This limits the throttle from being overdriven due to a persistent offset (e.g. inability to maintain the programmed altitude).|| +||ALT2PTCH_P||0||5||0.65||1||1||NAV_PITCH_ALT_P - P. I and D terms for pitch adjustments made to maintain altitude.|| +||ALT2PTCH_I||0||1||0||1||1||NAV_PITCH_ALT_I - P. I and D terms for pitch adjustments made to maintain altitude.|| +||ALT2PTCH_D||0||1||0||1||1||NAV_PITCH_ALT_D - P. I and D terms for pitch adjustments made to maintain altitude.|| +||ALT2PTCH_IMAX||0||3000||500||100||1||NAV_PITCH_ALT_INT_MAX - In Meters - Maximum pitch offset due to the integral. This limits the control output from being overdriven due to a persistent offset (eg. inability to maintain the programmed altitude).|| +||KFF_PTCHCOMP||-3||3||0.2||0.01||1||PITCH_COMP - In Percent - Adds pitch input to compensate for the loss of lift due to roll control.|| +||KFF_RDDRMIX||-3||3||0.5||0.01||1||RUDDER_MIX - Roll to yaw mixing. This allows for co-ordinated turns.|| +||KFF_PTCH2THR||-3||3||0||1||1||P_TO_T - Pitch to throttle feed-forward gain.|| +||KFF_THR2PTCH||-3||3||0||1||1||T_TO_P - Throttle to pitch feed-forward gain.|| +||XTRK_GAIN_SC||0||100||100||100||1||XTRACK_GAIN_SCALED - Default value is 1.0 degrees per metre. Values lower than 0.001 will disable crosstrack compensation.|| +||ALT_MIX||0||1||1||0.01||1||ALTITUDE_MIX - In Percent - Configures the blend between GPS and pressure altitude. 0 = GPS altitude, 1 = Press alt, 0.5 = half and half, etc.|| +||ARSPD_RATIO||0||5||1.9936||1||1||AIRSPEED_RATIO - Adjust AIRSPEED_RATIO in small increments to calibrate the airspeed sensor relative to your GPS. The calculation and default value are optimized for speeds around 12 m/s|| +||WP_RADIUS||0||200||30||1||1||WP_RADIUS_DEFAULT - When the user performs a factory reset on the APM, sets the waypoint radius (the radius from a target waypoint within which the APM will consider itself to have arrived at the waypoint) to this value in meters. This is mainly intended to allow users to start using the APM without programming a mission first.|| +||WP_LOITER_RAD||0||200||60||1||1||LOITER_RADIUS_DEFAULT - When the user performs a factory reset on the APM, sets the loiter radius (the distance the APM will attempt to maintain from a waypoint while loitering) to this value in meters. This is mainly intended to allow users to start using the APM without programming a mission first.|| +||ARSPD_FBW_MIN||5||50||6||1||1||AIRSPEED_FBW_MIN - In m/s - Airspeed corresponding to minimum and maximum throttle in Fly By Wire B mode.|| +||ARSPD_FBW_MAX||5||50||22||1||1||AIRSPEED_FBW_MAX - In m/s - Airspeed corresponding to minimum and maximum throttle in Fly By Wire B mode. AIRSPEED_FBW_MAX also sets the maximum airspeed that the cruise airspeed can be ""nudged"" to in AUTO mode when ENABLE_STICK_MIXING is set. In AUTO the cruise airspeed can be increased between AIRSPEED_CRUISE and AIRSPEED_FBW_MAX by positioning the throttle stick in the top 1/2 of its range. Throttle stick in the bottom 1/2 provide regular AUTO control.|| +||THR_MIN||0||100||0||1||1||THROTTLE_MIN - The minimum throttle setting to which the autopilot will reduce the throttle while descending. The default is zero, which is suitable for aircraft with a steady power-off glide. Increase this value if your aircraft needs throttle to maintain a stable descent in level flight.|| +||THR_MAX||0||100||75||1||1||THROTTLE_MAX - The maximum throttle setting the autopilot will apply. The default is 75%. Reduce this value if your aicraft is overpowered or has complex flight characteristics at high throttle settings.|| +||THR_FAILSAFE||0||0||1|| || ||THROTTLE_FAILSAFE - The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel (channel 3). This can be used to achieve a failsafe override on loss of radio control without having to sacrifice one of your FLIGHT_MODE settings as the throttle failsafe overrides the switch-selected mode. Throttle failsafe is enabled by setting THROTTLE_FAILSAFE to 1.|| +||THR_FS_ACTION||0||2||1||1|| ||THROTTLE_FAILSAFE_ACTION - The FAILSAFE_ACTION setting determines what APM will do when throttle failsafe mode is entered while flying in AUTO mode. This is important in order to avoid accidental failsafe behaviour when flying waypoints that take the aircraft temporarily out of radio range. If FAILSAFE_ACTION is 1 when failsafe is entered in AUTO or LOITER modes the aircraft will head for home in RTL mode. If the throttle channel moves back up it will return to AUTO or LOITER mode. The default behavior is to ignore throttle failsafe in AUTO and LOITER modes.|| +||TRIM_THROTTLE||0||90||45||1||1||THROTTLE_CRUISE - In Percent - The approximate throttle setting to achieve AIRSPEED_CRUISE in level flight. The default is 45% which is reasonable for a modestly powered aircraft.|| +||TRIM_AUTO||0||1||1||1||1||AUTO_TRIM - !ArduPilot Mega can update its trim settings by looking at the radio inputs when switching out of MANUAL mode. This allows you to manually trim your aircraft before switching to an assisted mode but it also means that you should avoid switching out of MANUAL while you have any control stick deflection.|| +||FLTMODE_CH||5||8||8||1||1||FLIGHT_MODE_CHANNEL - Flight modes assigned to the control channel, and the input channel that is read for the control mode. Use a servo tester or the !ArduPilotMega_demo test program to check your switch settings. ATTENTION: Some !ArduPilot Mega boards have radio channels marked 0-7 and others have them marked the standard 1-8. The FLIGHT_MODE_CHANNEL option uses channel numbers 1-8 (and defaults to 8). If you only have a three-position switch or just want three modes set your switch to produce 1165, 1425, and 1815 microseconds and configure FLIGHT_MODE 1 & 2, 3 & 4 and 5 & 6 to be the same. This is the default. If you have FLIGHT_MODE_CHANNEL set to 8 (the default) and your control channel connected to input channel 8, the hardware failsafe mode will activate for any control input over 1750ms.|| +||FLIGHT_MODE_1||0||14||11||1|| ||FLIGHT_MODE_1 - The following standard flight modes are available: MANUAL = Full manual control via the hardware multiplexer. STABILIZE = Tries to maintain level flight but can be overridden with radio control inputs. FLY_BY_WIRE_A = Autopilot style control via user input with manual throttle. FLY_BY_WIRE_B = Autopilot style control via user input, aispeed controlled with throttle. RTL = Returns to the Home location and then LOITERs at a safe altitude. AUTO = Autonomous flight based on programmed waypoints.|| +||FLIGHT_MODE_2||0||14||11||1|| ||FLIGHT_MODE_2|| +||FLIGHT_MODE_3||0||14||5||1|| ||FLIGHT_MODE_3|| +||FLIGHT_MODE_4||0||14||5||1|| ||FLIGHT_MODE_4|| +||FLIGHT_MODE_5||0||14||0||1|| ||FLIGHT_MODE_5|| +||FLIGHT_MODE_6||0||14||0||1|| ||FLIGHT_MODE_6|| +||RC1_MIN||900||2100||1500||1||1||PWM_RC1_MIN - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit|| +||RC1_MAX||900||2100||1500||1||1||PWM_RC1_MAX - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit|| +||RC1_TRIM||900||2100||1200||1||1||PWM_RC1_TRIM - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit|| +||RC2_MIN||900||2100||1500||1||1||PWM_RC2_MIN - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit|| +||RC2_MAX||900||2100||1500||1||1||PWM_RC2_MAX - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit|| +||RC2_TRIM||900||2100||1200||1||1||PWM_RC2_TRIM - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit|| +||RC3_MIN||900||2100||1500||1||1||PWM_RC3_MIN - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit|| +||RC3_MAX||900||2100||1500||1||1||PWM_RC3_MAX - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC3_TRIM||900||2100||1500||1||1||PWM_RC3_TRIM - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC4_MIN||900||2100||1500||1||1||PWM_RC4_MIN - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC4_MAX||900||2100||1500||1||1||PWM_RC4_MAX - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC4_TRIM||900||2100||1200||1||1||PWM_RC4_TRIM - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC5_MIN||900||2100||1500||1||1||PWM_CH5_MIN - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC5_MAX||900||2100||1500||1||1||PWM_CH5_MAX - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC5_MAX||900||2100||1500||1||1||PWM_CH5_MAX - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC5_TRIM||900||2100||1500||1||1||PWM_CH5_TRIM - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC6_MIN||900||2100||1500||1||1||PWM_CH6_MIN - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC6_MAX||900||2100||1500||1||1||PWM_CH6_MAX - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC6_TRIM||900||2100||1500||1||1||PWM_CH6_TRIM - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC7_MIN||900||2100||1500||1||1||PWM_CH7_MIN - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC7_MAX||900||2100||1500||1||1||PWM_CH7_MAX - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC7_TRIM||900||2100||1500||1||1||PWM_CH7_TRIM - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC8_MIN||900||2100||1500||1||1||PWM_CH8_MIN - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC8_MAX||900||2100||1500||1||1||PWM_CH8_MAX - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC8_TRIM||900||2100||1500||1||1||PWM_CH8_TRIM - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||IMU_OFFSET_0||0||0||0|| || ||IMU_OFFSET_0 - IMU Calibration|| +||IMU_OFFSET_1||0||0||0|| || ||IMU_OFFSET_1 - IMU Calibration|| +||IMU_OFFSET_2||0||0||0|| || ||IMU_OFFSET_2 - IMU Calibration|| +||IMU_OFFSET_3||0||0||0|| || ||IMU_OFFSET_3 - IMU Calibration|| +||IMU_OFFSET_4||0||0||0|| || ||IMU_OFFSET_4 - IMU Calibration|| +||IMU_OFFSET_5||0||0||0|| || ||IMU_OFFSET_5 - IMU Calibration|| +||YAW_MODE|| || ||0|| || ||YAW_MODE|| +||WP_MODE|| || ||0|| || ||WP_MODE|| +||WP_TOTAL||0||255|| ||0|| ||WP_TOTAL|| +||WP_INDEX||0||255|| ||0|| ||WP_INDEX|| +||CONFIG|| || ||1|| || ||CONFIG_OPTIONS|| +||SWITCH_ENABLE||0||1||1||1||1||REVERS_SWITCH_ENABLE - 0 = Off, 1 = On, Enables/Disables physical reverse switches on APM board|| +||FIRMWARE_VER|| || ||0|| || ||FIRMWARE_VER|| +||LOG_BITMASK||0||65535||334||1||1||LOG_BITMASK|| +||TRIM_ELEVON||900||2100||1500||1||1||TRIM_ELEVON|| +||THR_FS_VALUE||850||1000||950||1||1||THROTTLE_FS_VALUE - If the throttle failsafe is enabled, THROTTLE_FS_VALUE sets the channel value below which the failsafe engages. The default is 975ms, which is a very low throttle setting. Most transmitters will let you trim the manual throttle position up so that you cannot engage the failsafe with a regular stick movement. Configure your receiver's failsafe setting for the throttle channel to the absolute minimum, and use the !ArduPilotMega_demo program to check that you cannot reach that value with the throttle control. Leave a margin of at least 50 microseconds between the lowest throttle setting and THROTTLE_FS_VALUE.|| +||TRIM_ARSPD_CM||500||5000||1200||100||1||AIRSPEED_CRUISE_CM - The speed in metres per second to maintain during cruise. The default is 10m/s, which is a conservative value suitable for relatively small, light aircraft.|| +||GND_TEMP||-10||50||28||1||1||GND_TEMP - Ground Temperature|| +||AP_OFFSET|| || ||0|| || ||AP_OFFSET|| +||TRIM_PITCH_CD|| || ||0|| || ||TRIM_PITCH_CD|| +||ALT_HOLD_RTL||0||20000||10000||100||1||ALT_HOLD_HOME_CM - When the user performs a factory reset on the APM. Sets the flag for weather the current altitude or ALT_HOLD_HOME altitude should be used for Return To Launch. Also sets the value of USE_CURRENT_ALT in meters. This is mainly intended to allow users to start using the APM without programming a mission first.|| +||XTRK_ANGLE_CD||0||6000||3000||100||1||XTRACK_ENTRY_ANGLE_DEGREE - Maximum angle used to correct for track following.|| +||ROLL_SRV_MAX||0||100||4500||100||0||ROLL_SERVO_MAX_DEGREE|| +||PITCH_SRV_MAX||0||100||4500||100||0||PITCH_SERVO_MAX_DEGREE|| +||RUDER_SRV_MAX||0||100||4500||100||0||RUDDER_SERVO_MAX_DEGREE|| +||LIM_ROLL_CD||0||6000||4500||100||1||HEAD_MAX_DEGREE - The maximum commanded bank angle in either direction. The default is 45 degrees. Decrease this value if your aircraft is not stable or has difficulty maintaining altitude in a steep bank.|| +||LIM_PITCH_MAX||0||6000||1500||100||1||PITCH_MAX_DEGREE - The maximum commanded pitch up angle. The default is 15 degrees. Care should be taken not to set this value too large, as the aircraft may stall|| +||LIM_PITCH_MIN||-6000||0||-2500||100||1||PITCH_MIN_DEGREE - The maximum commanded pitch down angle. Note that this value must be negative. The default is -25 degrees. Care should be taken not to set this value too large as it may result in overspeeding the aircraft.|| +||GND_ALT_CM||0||500000||0||100||1||GND_ALT_CM|| +||GND_ABS_PRESS|| || ||0|| || ||GND_ABS_PRESS|| +||COMPASS_DEC||-1.57075||1.57075||0||1|| ||COMPASS_DEC - Compass Declination|| +||SR0_EXT_STAT||0||50||3||1||1||TELEMETRY_ENABLE Port 0 - Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS|| +||SR0_EXTRA1||0||50||10||1||1||TELEMETRY_ENABLE Port 0 - Enable MSG_ATTITUDE|| +||SR0_EXTRA2||0||50||3||1||1||TELEMETRY_ENABLE Port 0 - Enable MSG_VFR_HUD|| +||SR0_EXTRA3||0||50||3||1||1||TELEMETRY_ENABLE Port 0 - Not currently used|| +||SR0_POSITION||0||50||3||1||1||TELEMETRY_ENABLE Port 0 - Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages|| +||SR0_RAW_CTRL||0||50||3||1||1||TELEMETRY_ENABLE Port 0 - Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT|| +||SR0_RAW_SENS||0||50||3||1||1||TELEMETRY_ENABLE Port 0 - Enable IMU_RAW, GPS_RAW, GPS_STATUS packets|| +||SR0_RC_CHAN||0||50||3||1||1||TELEMETRY_ENABLE Port 0 - Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW|| +||SR3_EXT_STAT||0||50||0||1||1||TELEMETRY_ENABLE Port 3 - Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS|| +||SR3_EXTRA1||0||50||0||1||1||TELEMETRY_ENABLE Port 3 - Enable MSG_ATTITUDE|| +||SR3_EXTRA2||0||50||0||1||1||TELEMETRY_ENABLE Port 3 - Enable MSG_VFR_HUD|| +||SR3_EXTRA3||0||50||0||1||1||TELEMETRY_ENABLE Port 3 - Not currently used|| +||SR3_POSITION||0||50||0||1||1||TELEMETRY_ENABLE Port 3 - Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages|| +||SR3_RAW_CTRL||0||50||0||1||1||TELEMETRY_ENABLE Port 3 - Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT|| +||SR3_RAW_SENS||0||50||0||1||1||TELEMETRY_ENABLE Port 3 - Enable IMU_RAW, GPS_RAW, GPS_STATUS packets|| +||SR3_RC_CHAN||0||50||0||1||1||TELEMETRY_ENABLE Port 3 - Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW|| +||MAG_ENABLE||0||1||0||1||1||MAG_ENABLE - 0 = Off, 1 = On, Magnetometer Enable|| +||ARSPD_ENABLE||0||1||0||1||1||AIRSPEED_ENABLE - 0 = Off, 1 = On, Airspeed Sensor Enable|| +||BATT_CAPACITY||0||10000||1760||1||1||BATTERY_MAH - Battery capacity in mAh|| +||BATT_MONITOR||0||4||0||1||1||BATTERY_MONITOR - The value should be set to 0 to disable battery monitoring, 1 to measure cell voltages for a 3 cell lipo, 2 to measure cell voltages for a 4 cell lipo, 3 to measure the total battery voltage (only) on input 1, or 4 to measure total battery voltage on input 1 and current on input 2. || +||FS_GCS_ENABL||0||1||0||1||1||FS_GCS_ENABLE - 0 = Off, 1 = On, If the GCS heartbeat is lost for 20 seconds, the plane will Return to Launch|| +||FS_LONG_ACTN||0||1||0||1||1||FS_LONG_ACTION - 0 = Off, 1 = On, If heartbeat is lost for 20 srconds, the plane will Return to Launch|| +||FS_SHORT_ACTN||0||1||0||1||1||FS_SHORT_ACTION - 0 = Off, 1 = On, If heartbeat is lost for 1.5 seconds, the plane will circle until heartbeat is found again or 20 seconds has passed|| +||SYSID_MYGCS||0||255||255||1||1||SYSID_MYGCS - The system ID of the GCS|| +||SYSID_THISMAV||0||255||1||1||1||SYSID_THISMAV - The system ID of the MAVlink vehicle|| +||AOA|| || ||0|| || +||ACR_PIT_D|| || ||1|| || ||Description coming soon|| +||ACR_PIT_I|| || ||1|| || ||Description coming soon|| +||ACR_PIT_IMAX|| || ||1|| || ||Description coming soon|| +||ACR_PIT_P|| || ||1|| || ||Description coming soon|| +||ACR_RLL_D|| || ||1|| || ||Description coming soon|| +||ACR_RLL_I|| || ||1|| || ||Description coming soon|| +||ACR_RLL_IMAX|| || ||1|| || ||Description coming soon|| +||ACR_RLL_P|| || ||1|| || ||Description coming soon|| +||ACR_YAW_D|| || ||1|| || ||Description coming soon|| +||ACR_YAW_I|| || ||1|| || ||Description coming soon|| +||ACR_YAW_IMAX|| || ||1|| || ||Description coming soon|| +||ACR_YAW_P|| || ||1|| || ||Description coming soon|| +||ESC|| || ||1|| || ||ESC_CALIBRATE_MODE|| +||FRAME|| || ||1|| || ||FRAME_ORIENTATION || +||LOITER_RADIUS|| || ||1|| || ||Description coming soon|| +||NAV_LAT_D|| || ||1|| || ||Description coming soon|| +||NAV_LAT_I|| || ||1|| || ||Description coming soon|| +||NAV_LAT_IMAX|| || ||1|| || ||Description coming soon|| +||NAV_LAT_P|| || ||1|| || ||Description coming soon|| +||NAV_LON_D|| || ||1|| || ||Description coming soon|| +||NAV_LON_I|| || ||1|| || ||Description coming soon|| +||NAV_LON_IMAX|| || ||1|| || ||Description coming soon|| +||NAV_LON_P|| || ||1|| || ||Description coming soon|| +||NAV_WP_D|| || ||1|| || ||Description coming soon|| +||NAV_WP_I|| || ||1|| || ||Description coming soon|| +||NAV_WP_IMAX|| || ||1|| || ||Description coming soon|| +||NAV_WP_P|| || ||1|| || ||Description coming soon|| +||PITCH_MAX|| || ||1|| || ||Description coming soon|| +||SONAR_ENABLE||0||1||0||1||1||SONAR_ENABLE - 0 = Off, 1 = On, Sonar Enable|| +||STB_PIT_D|| || ||1|| || ||Description coming soon|| +||STB_PIT_I|| || ||1|| || ||Description coming soon|| +||STB_PIT_IMAX|| || ||1|| || ||Description coming soon|| +||STB_PIT_P|| || ||1|| || ||Description coming soon|| +||STB_RLL_D|| || ||1|| || ||Description coming soon|| +||STB_RLL_I|| || ||1|| || ||Description coming soon|| +||STB_RLL_IMAX|| || ||1|| || ||Description coming soon|| +||STB_RLL_P|| || ||1|| || ||Description coming soon|| +||STB_YAW_D|| || ||1|| || ||Description coming soon|| +||STB_YAW_I|| || ||1|| || ||Description coming soon|| +||STB_YAW_IMAX|| || ||1|| || ||Description coming soon|| +||STB_YAW_P|| || ||1|| || ||Description coming soon|| +||THR_BAR_D|| || ||1|| || ||Description coming soon|| +||THR_BAR_I|| || ||1|| || ||Description coming soon|| +||THR_BAR_IMAX|| || ||1|| || ||Description coming soon|| +||THR_BAR_P|| || ||1|| || ||Description coming soo|| +||THR_SON_D|| || ||1|| || ||Description coming soon|| +||THR_SON_I|| || ||1|| || ||Description coming soon|| +||THR_SON_IMAX|| || ||1|| || ||Description coming soon|| +||THR_SON_P|| || ||1|| || ||Description coming soon|| +||WP_MODE|| || ||1|| || ||Description coming soon|| +||WP_MUST_INDEX|| || ||1|| || ||Description coming soon|| +||XTRACK_ANGLE|| || ||1|| || ||Description coming soon|| +||XTRK_GAIN|| || ||1|| || ||Description coming soon|| +||ARSPD_OFFSET|| || ||0|| || ||Description coming soon|| +||ELEVON_CH1_REV||0||1||0||1||1||ELEVON_CHANNEL1_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches|| +||ELEVON_CH2_REV||0||1||0||1||1||ELEVON_CHANNEL2_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches|| +||ELEVON_MIXING||0||1||0||1||1||ELEVON_MIXING - 0 = Disabled, 1 = Enabled|| +||ELEVON_REVERSE||0||1||0||1||1||ELEVON_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches|| +||INVERTEDFLT_CH||0||8||0||1||1||INVERTED_FLIGHT_CHANNEL - Channel to select inverted flight mode, 0 = Disabled|| +||RC1_REV||0||1||1||1||1||RC_CHANNEL1_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches|| +||RC2_REV||0||1||1||1||1||RC_CHANNEL2_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches|| +||RC3_REV||0||1||1||1||1||RC_CHANNEL3_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches|| +||RC4_REV||0||1||1||1||1||RC_CHANNEL4_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches|| +||RC5_REV||0||1||1||1||1||RC_CHANNEL5_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches|| +||RC6_REV||0||1||1||1||1||RC_CHANNEL6_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches|| +||RC7_REV||0||1||1||1||1||RC_CHANNEL7_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches|| +||RC8_REV||0||1||1||1||1||RC_CHANNEL8_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches|| +||SYSID_SW_MREV|| || ||0|| || ||Description coming soon|| +||SYSID_SW_TYPE|| || ||0|| || ||Description coming soon|| +||THR_SLEWRATE||0||100||0||1||1||THROTTLE_SLEW_RATE - 0 = Disabled, otherwise it limits throttle movement rate. Units are % per second. This is a test feature and may go away.|| +||FLTMODE1||0||20||1||1|| ||FLIGHT_MODE_1 - Mode switch setting 1 - APM: 0 = Manual, 2 = Stabilize, 5 - Fly-By-Wire-A, 6 = Fly-By-Wire-B, 7 = Fly-By-Wire-C, 10 = Auto - Mission, 11 = RTL, 12 = Loiter, 13 = Take-off, 14 = Land, 15= Guided; ACM2: 0 = Stabilize, 1 = Acro, 2 = Alt Hold, 3 = Auto, 4 = Guided, 5 = Loiter, 6 = RTL|| +||FLTMODE2||0||20||1||1|| ||FLIGHT_MODE_2 - Mode switch setting 2 - APM: 0 = Manual, 2 = Stabilize, 5 - Fly-By-Wire-A, 6 = Fly-By-Wire-B, 7 = Fly-By-Wire-C, 10 = Auto - Mission, 11 = RTL, 12 = Loiter, 13 = Take-off, 14 = Land, 15= Guided; ACM2: 0 = Stabilize, 1 = Acro, 2 = Alt Hold, 3 = Auto, 4 = Guided, 5 = Loiter, 6 = RTL|| +||FLTMODE3||0||20||1||1|| ||FLIGHT_MODE_3 - Mode switch setting 3 - APM: 0 = Manual, 2 = Stabilize, 5 - Fly-By-Wire-A, 6 = Fly-By-Wire-B, 7 = Fly-By-Wire-C, 10 = Auto - Mission, 11 = RTL, 12 = Loiter, 13 = Take-off, 14 = Land, 15= Guided; ACM2: 0 = Stabilize, 1 = Acro, 2 = Alt Hold, 3 = Auto, 4 = Guided, 5 = Loiter, 6 = RTL|| +||FLTMODE4||0||20||1||1|| ||FLIGHT_MODE_4 - Mode switch setting 4 - APM: 0 = Manual, 2 = Stabilize, 5 - Fly-By-Wire-A, 6 = Fly-By-Wire-B, 7 = Fly-By-Wire-C, 10 = Auto - Mission, 11 = RTL, 12 = Loiter, 13 = Take-off, 14 = Land, 15= Guided; ACM2: 0 = Stabilize, 1 = Acro, 2 = Alt Hold, 3 = Auto, 4 = Guided, 5 = Loiter, 6 = RTL|| +||FLTMODE5||0||20||1||1|| ||FLIGHT_MODE_5 - Mode switch setting 5 - APM: 0 = Manual, 2 = Stabilize, 5 - Fly-By-Wire-A, 6 = Fly-By-Wire-B, 7 = Fly-By-Wire-C, 10 = Auto - Mission, 11 = RTL, 12 = Loiter, 13 = Take-off, 14 = Land, 15= Guided; ACM2: 0 = Stabilize, 1 = Acro, 2 = Alt Hold, 3 = Auto, 4 = Guided, 5 = Loiter, 6 = RTL|| +||FLTMODE6||0||20||1||1|| ||FLIGHT_MODE_6 - Mode switch setting 6 - APM: 0 = Manual, 2 = Stabilize, 5 - Fly-By-Wire-A, 6 = Fly-By-Wire-B, 7 = Fly-By-Wire-C, 10 = Auto - Mission, 11 = RTL, 12 = Loiter, 13 = Take-off, 14 = Land, 15= Guided; ACM2: 0 = Stabilize, 1 = Acro, 2 = Alt Hold, 3 = Auto, 4 = Guided, 5 = Loiter, 6 = RTL|| \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/Resources/Welcome_to_Michael_Oborne.rtf b/Tools/ArdupilotMegaPlanner/bin/Release/Resources/Welcome_to_Michael_Oborne.rtf new file mode 100644 index 0000000000..c537652c1f Binary files /dev/null and b/Tools/ArdupilotMegaPlanner/bin/Release/Resources/Welcome_to_Michael_Oborne.rtf differ diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/Setup/Setup.resx b/Tools/ArdupilotMegaPlanner/bin/Release/Setup/Setup.resx new file mode 100644 index 0000000000..6deb0ac7f6 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/bin/Release/Setup/Setup.resx @@ -0,0 +1,3304 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + text/microsoft-resx + + + 2.0 + + + System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + NoControl + + + + 214, 161 + + + 195, 23 + + + + 0 + + + Reset APM Hardware to Default + + + BUT_reset + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + tabReset + + + 0 + + + 4, 22 + + + 666, 393 + + + 4 + + + Reset + + + tabReset + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabControl1 + + + 0 + + + True + + + NoControl + + + 287, 158 + + + 66, 17 + + + 106 + + + Reverse + + + CHK_revch3 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabRadioIn + + + 0 + + + True + + + NoControl + + + 315, 310 + + + 66, 17 + + + 105 + + + Reverse + + + CHK_revch4 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabRadioIn + + + 1 + + + True + + + NoControl + + + 71, 158 + + + 66, 17 + + + 104 + + + Reverse + + + CHK_revch2 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabRadioIn + + + 2 + + + True + + + NoControl + + + 315, 12 + + + 66, 17 + + + 103 + + + Reverse + + + CHK_revch1 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabRadioIn + + + 3 + + + NoControl + + + 482, 340 + + + 134, 23 + + + 102 + + + Calibrate Radio + + + BUT_Calibrateradio + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + tabRadioIn + + + 4 + + + 17, 17 + + + 446, 240 + + + 170, 25 + + + 101 + + + BAR8 + + + ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + tabRadioIn + + + 5 + + + 446, 185 + + + 170, 25 + + + 100 + + + BAR7 + + + ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + tabRadioIn + + + 6 + + + 446, 130 + + + 170, 25 + + + 99 + + + BAR6 + + + ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + tabRadioIn + + + 7 + + + 446, 75 + + + 170, 25 + + + 98 + + + BAR5 + + + ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + tabRadioIn + + + 8 + + + 143, 61 + + + 47, 211 + + + 96 + + + BARpitch + + + ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + tabRadioIn + + + 9 + + + 359, 61 + + + 47, 211 + + + 95 + + + BARthrottle + + + ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + tabRadioIn + + + 10 + + + 21, 304 + + + 288, 23 + + + 94 + + + BARyaw + + + ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + tabRadioIn + + + 11 + + + 21, 6 + + + 288, 23 + + + 93 + + + BARroll + + + ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + tabRadioIn + + + 12 + + + 4, 22 + + + 3, 3, 3, 3 + + + 666, 393 + + + 0 + + + Radio Input + + + tabRadioIn + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabControl1 + + + 1 + + + True + + + NoControl + + + 380, 235 + + + 2, 2, 2, 2 + + + 87, 17 + + + 119 + + + Simple Mode + + + CB_simple6 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 0 + + + True + + + NoControl + + + 380, 208 + + + 2, 2, 2, 2 + + + 87, 17 + + + 118 + + + Simple Mode + + + CB_simple5 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 1 + + + True + + + NoControl + + + 380, 181 + + + 2, 2, 2, 2 + + + 87, 17 + + + 117 + + + Simple Mode + + + CB_simple4 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 2 + + + True + + + NoControl + + + 380, 154 + + + 2, 2, 2, 2 + + + 87, 17 + + + 116 + + + Simple Mode + + + CB_simple3 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 3 + + + True + + + NoControl + + + 380, 127 + + + 2, 2, 2, 2 + + + 87, 17 + + + 115 + + + Simple Mode + + + CB_simple2 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 4 + + + True + + + 380, 100 + + + 2, 2, 2, 2 + + + 87, 17 + + + 114 + + + Simple Mode + + + CB_simple1 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 5 + + + True + + + NoControl + + + 242, 67 + + + 74, 13 + + + 113 + + + Current PWM: + + + label14 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 6 + + + True + + + NoControl + + + 322, 67 + + + 13, 13 + + + 112 + + + 0 + + + LBL_flightmodepwm + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 7 + + + True + + + NoControl + + + 242, 50 + + + 74, 13 + + + 111 + + + Current Mode: + + + label13 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 8 + + + True + + + NoControl + + + 322, 50 + + + 42, 13 + + + 110 + + + Manual + + + lbl_currentmode + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 9 + + + True + + + NoControl + + + 506, 101 + + + 76, 13 + + + 109 + + + PWM 0 - 1230 + + + False + + + label12 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 10 + + + True + + + NoControl + + + 506, 236 + + + 70, 13 + + + 108 + + + PWM 1750 + + + + False + + + label11 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 11 + + + True + + + NoControl + + + 506, 209 + + + 94, 13 + + + 107 + + + PWM 1621 - 1749 + + + False + + + label10 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 12 + + + True + + + NoControl + + + 506, 182 + + + 94, 13 + + + 106 + + + PWM 1491 - 1620 + + + False + + + label9 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 13 + + + True + + + NoControl + + + 506, 155 + + + 94, 13 + + + 105 + + + PWM 1361 - 1490 + + + False + + + label8 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 14 + + + True + + + NoControl + + + 506, 128 + + + 94, 13 + + + 104 + + + PWM 1231 - 1360 + + + False + + + label7 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 15 + + + True + + + NoControl + + + 168, 236 + + + 71, 13 + + + 11 + + + Flight Mode 6 + + + label6 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 16 + + + 245, 233 + + + 121, 21 + + + 10 + + + CMB_fmode6 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 17 + + + True + + + NoControl + + + 168, 209 + + + 71, 13 + + + 9 + + + Flight Mode 5 + + + label5 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 18 + + + 245, 206 + + + 121, 21 + + + 8 + + + CMB_fmode5 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 19 + + + True + + + NoControl + + + 168, 182 + + + 71, 13 + + + 7 + + + Flight Mode 4 + + + label4 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 20 + + + 245, 179 + + + 121, 21 + + + 6 + + + CMB_fmode4 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 21 + + + True + + + NoControl + + + 168, 155 + + + 71, 13 + + + 5 + + + Flight Mode 3 + + + label3 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 22 + + + 245, 152 + + + 121, 21 + + + 4 + + + CMB_fmode3 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 23 + + + True + + + NoControl + + + 168, 128 + + + 71, 13 + + + 3 + + + Flight Mode 2 + + + label2 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 24 + + + 245, 125 + + + 121, 21 + + + 2 + + + CMB_fmode2 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 25 + + + True + + + NoControl + + + 168, 101 + + + 71, 13 + + + 1 + + + Flight Mode 1 + + + label1 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 26 + + + 245, 98 + + + 121, 21 + + + 0 + + + CMB_fmode1 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 27 + + + NoControl + + + 245, 260 + + + 121, 23 + + + 103 + + + Save Modes + + + BUT_SaveModes + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + tabModes + + + 28 + + + 4, 22 + + + 666, 393 + + + 3 + + + Modes + + + tabModes + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabControl1 + + + 2 + + + True + + + NoControl + + + 390, 80 + + + 104, 13 + + + 28 + + + Declination WebSite + + + linkLabelmagdec + + + System.Windows.Forms.LinkLabel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 0 + + + NoControl + + + 310, 57 + + + 60, 13 + + + 23 + + + Declination + + + label100 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 1 + + + 383, 57 + + + 121, 20 + + + 20 + + + 214, 17 + + + Magnetic Declination (-20.0 to 20.0) eg 2° 3' W is -2.3 + + + TXT_declination + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 2 + + + NoControl + + + 162, 214 + + + 103, 17 + + + 24 + + + Enable Airspeed + + + CHK_enableairspeed + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 3 + + + NoControl + + + 159, 136 + + + 90, 17 + + + 25 + + + Enable Sonar + + + CHK_enablesonar + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 4 + + + NoControl + + + 162, 56 + + + 105, 17 + + + 27 + + + Enable Compass + + + CHK_enablecompass + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 5 + + + Zoom + + + NoControl + + + 78, 188 + + + 75, 75 + + + 3 + + + pictureBox4 + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 6 + + + Zoom + + + NoControl + + + 78, 106 + + + 75, 75 + + + 2 + + + pictureBox3 + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 7 + + + Zoom + + + + + + NoControl + + + + + + 78, 25 + + + 75, 75 + + + 0 + + + pictureBox1 + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 8 + + + 4, 22 + + + 3, 3, 3, 3 + + + 666, 393 + + + 1 + + + Hardware + + + tabHardware + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabControl1 + + + 3 + + + 162, 267 + + + 2, 2, 2, 2 + + + 76, 20 + + + 38 + + + TXT_ampspervolt + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 0 + + + 162, 245 + + + 2, 2, 2, 2 + + + 76, 20 + + + 37 + + + TXT_divider + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 1 + + + 162, 224 + + + 2, 2, 2, 2 + + + 76, 20 + + + 36 + + + TXT_voltage + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 2 + + + 162, 202 + + + 2, 2, 2, 2 + + + 76, 20 + + + 35 + + + TXT_measuredvoltage + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 3 + + + 162, 180 + + + 2, 2, 2, 2 + + + 76, 20 + + + 34 + + + TXT_inputvoltage + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 4 + + + True + + + NoControl + + + 29, 270 + + + 2, 0, 2, 0 + + + 89, 13 + + + 33 + + + Amperes per volt: + + + label35 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 5 + + + True + + + NoControl + + + 28, 248 + + + 2, 0, 2, 0 + + + 80, 13 + + + 32 + + + Voltage divider: + + + label34 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 6 + + + True + + + NoControl + + + 28, 227 + + + 2, 0, 2, 0 + + + 81, 13 + + + 31 + + + Battery voltage: + + + label33 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 7 + + + True + + + NoControl + + + 28, 205 + + + 2, 0, 2, 0 + + + 130, 13 + + + 30 + + + Measured battery voltage: + + + label32 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 8 + + + True + + + NoControl + + + 28, 183 + + + 2, 0, 2, 0 + + + 72, 13 + + + 29 + + + Input voltage: + + + label31 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 9 + + + 31, 110 + + + 2, 2, 2, 2 + + + True + + + 428, 62 + + + 28 + + + Voltage sensor calibration: +1. Measure APM input voltage and enter it to the box below +2. Measure battery voltage and enter it to the box below +3. From current sensor datasheet, enter amperes per volt value to the box below + + + textBox3 + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 10 + + + True + + + NoControl + + + 305, 50 + + + 48, 13 + + + 23 + + + Capacity + + + label29 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 11 + + + NoControl + + + 123, 50 + + + 42, 13 + + + 24 + + + Monitor + + + label30 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 12 + + + 366, 47 + + + 83, 20 + + + 25 + + + TXT_battcapacity + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 13 + + + 0: Disabled + + + 1: 3 Cell + + + 2: 4 Cell + + + 3: Battery Volts + + + 4: Volts & Current + + + 177, 46 + + + 121, 21 + + + 26 + + + CMB_batmontype + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 14 + + + Zoom + + + NoControl + + + 31, 21 + + + 75, 75 + + + 2 + + + pictureBox5 + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 15 + + + 4, 22 + + + 2, 2, 2, 2 + + + 666, 393 + + + 6 + + + Battery + + + tabBattery + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabControl1 + + + 4 + + + True + + + NoControl + + + 217, 38 + + + 210, 13 + + + 9 + + + Level your quad to set default accel offsets + + + label28 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabArducopter + + + 0 + + + True + + + NoControl + + + 217, 333 + + + 192, 26 + + + 7 + + + NOTE: images are for presentation only +will work with hexa's etc + + + label16 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabArducopter + + + 1 + + + True + + + NoControl + + + 260, 124 + + + 102, 13 + + + 6 + + + Frame Setup (+ or x) + + + label15 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabArducopter + + + 2 + + + NoControl + + + 319, 140 + + + 190, 190 + + + Zoom + + + 5 + + + pictureBoxQuadX + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabArducopter + + + 3 + + + NoControl + + + 112, 140 + + + 190, 190 + + + Zoom + + + 4 + + + pictureBoxQuad + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabArducopter + + + 4 + + + NoControl + + + 274, 67 + + + 75, 23 + + + 8 + + + Level + + + BUT_levelac2 + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + tabArducopter + + + 5 + + + 4, 22 + + + 666, 393 + + + 2 + + + ArduCopter2 + + + tabArducopter + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabControl1 + + + 5 + + + True + + + NoControl + + + 552, 222 + + + 54, 13 + + + 120 + + + Gyro Gain + + + label27 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 0 + + + 555, 238 + + + 47, 20 + + + 119 + + + 1000 + + + GYR_GAIN_ + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 1 + + + True + + + NoControl + + + 540, 202 + + + 84, 17 + + + 118 + + + Gyro Enable + + + GYR_ENABLE_ + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 2 + + + True + + + NoControl + + + 563, 94 + + + 54, 13 + + + 117 + + + Pitch Max + + + label26 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 3 + + + 564, 110 + + + 47, 20 + + + 116 + + + 4500 + + + PIT_MAX_ + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 4 + + + True + + + NoControl + + + 563, 50 + + + 48, 13 + + + 115 + + + Roll Max + + + label25 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 5 + + + 564, 69 + + + 47, 20 + + + 114 + + + 4500 + + + ROL_MAX_ + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 6 + + + True + + + NoControl + + + 537, 170 + + + 65, 13 + + + 113 + + + 0 Collective: + + + label24 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 7 + + + True + + + NoControl + + + 603, 170 + + + 31, 13 + + + 112 + + + 1500 + + + COL_MID_ + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 8 + + + True + + + NoControl + + + 440, 23 + + + 68, 13 + + + 109 + + + Servo Travel + + + label23 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 9 + + + True + + + NoControl + + + 290, 23 + + + 97, 13 + + + 101 + + + Level Swash - Trim + + + label22 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 10 + + + True + + + NoControl + + + 178, 23 + + + 78, 13 + + + 99 + + + Servo Reverse + + + label21 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 11 + + + True + + + NoControl + + + 181, 148 + + + 75, 17 + + + 98 + + + Reverse 4 + + + HS4_REV + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 12 + + + True + + + NoControl + + + 13, 258 + + + 44, 13 + + + 97 + + + Servo 3 + + + label20 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 13 + + + True + + + NoControl + + + 13, 232 + + + 44, 13 + + + 96 + + + Servo 2 + + + label19 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 14 + + + True + + + NoControl + + + 13, 206 + + + 44, 13 + + + 95 + + + Servo 1 + + + label18 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 15 + + + 66, 255 + + + 100, 20 + + + 94 + + + 180 + + + SV3_POS_ + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 16 + + + 66, 229 + + + 100, 20 + + + 93 + + + 60 + + + SV2_POS_ + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 17 + + + 66, 203 + + + 100, 20 + + + 92 + + + -60 + + + SV1_POS_ + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 18 + + + True + + + NoControl + + + 181, 125 + + + 75, 17 + + + 91 + + + Reverse 3 + + + HS3_REV + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 19 + + + True + + + NoControl + + + 181, 102 + + + 75, 17 + + + 90 + + + Reverse 2 + + + HS2_REV + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 20 + + + True + + + NoControl + + + 181, 79 + + + 75, 17 + + + 89 + + + Reverse 1 + + + HS1_REV + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 21 + + + True + + + NoControl + + + 38, 23 + + + 109, 13 + + + 82 + + + Swash-Servo position + + + label17 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 22 + + + NoControl + + + 430, 307 + + + 90, 23 + + + 111 + + + Save Travel + + + BUT_saveheliconfig + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + tabHeli + + + 23 + + + NoControl + + + 540, 144 + + + 90, 23 + + + 110 + + + Set 0 Collective + + + BUT_0collective + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + tabHeli + + + 24 + + + 478, 50 + + + 42, 213 + + + 108 + + + HS4 + + + ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + tabHeli + + + 25 + + + 430, 50 + + + 42, 213 + + + 107 + + + HS3 + + + ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + tabHeli + + + 26 + + + NoControl + + + 276, 203 + + + 128, 45 + + + 104 + + + HS4_TRIM + + + ArdupilotMega.MyTrackBar, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + tabHeli + + + 27 + + + NoControl + + + 276, 152 + + + 128, 45 + + + 103 + + + HS3_TRIM + + + ArdupilotMega.MyTrackBar, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + tabHeli + + + 28 + + + NoControl + + + 276, 101 + + + 128, 45 + + + 102 + + + HS2_TRIM + + + ArdupilotMega.MyTrackBar, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + tabHeli + + + 29 + + + NoControl + + + 276, 50 + + + 128, 45 + + + 100 + + + HS1_TRIM + + + ArdupilotMega.MyTrackBar, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + tabHeli + + + 30 + + + Zoom + + + Microsoft Sans Serif, 9pt + + + 16, 50 + + + 0, 0, 0, 0 + + + 150, 150 + + + 81 + + + Gservoloc + + + AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + tabHeli + + + 31 + + + 4, 22 + + + 666, 393 + + + 5 + + + AC2 Heli - BETA + + + tabHeli + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabControl1 + + + 6 + + + Fill + + + 0, 0 + + + 674, 419 + + + 93 + + + tabControl1 + + + System.Windows.Forms.TabControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 0 + + + True + + + 6, 13 + + + 674, 419 + + + APMSetup + + + currentStateBindingSource + + + System.Windows.Forms.BindingSource, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + toolTip1 + + + System.Windows.Forms.ToolTip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Setup + + + System.Windows.Forms.Form, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/hud.html b/Tools/ArdupilotMegaPlanner/bin/Release/hud.html new file mode 100644 index 0000000000..ce9253d9e8 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/bin/Release/hud.html @@ -0,0 +1,225 @@ + + + + + + + +

This example requires a browser that supports the + HTML5 + <canvas> feature.

+
+ + diff --git a/Tools/ArdupilotMegaPlanner/hud.html b/Tools/ArdupilotMegaPlanner/hud.html new file mode 100644 index 0000000000..ce9253d9e8 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/hud.html @@ -0,0 +1,225 @@ + + + + + + + +

This example requires a browser that supports the + HTML5 + <canvas> feature.

+
+ + diff --git a/Tools/ArdupilotMegaPlanner/mavlinklist.pl b/Tools/ArdupilotMegaPlanner/mavlinklist.pl index 6686745a1e..43b0b6219e 100644 --- a/Tools/ArdupilotMegaPlanner/mavlinklist.pl +++ b/Tools/ArdupilotMegaPlanner/mavlinklist.pl @@ -75,6 +75,8 @@ foreach $file (@files) { $line =~ s/MAV_CMD_NAV_//; $line =~ s/MAV_CMD_//; + + $line =~ s/\/\/\/"); + foreach (DataGridViewRow row in dataGridView1.Rows) { - if (row.Cells[colFile.Index].Value.ToString() != fname) + try { - if (writer !=null) - writer.Close(); - writer = new ResXResourceWriter("translation/" + row.Cells[colFile.Index].Value.ToString().Replace(".resx", "." + ci + ".resx")); + if (row.Cells[colFile.Index].Value.ToString() != fname) + { + if (writer != null) + writer.Close(); + writer = new ResXResourceWriter("translation/" + row.Cells[colFile.Index].Value.ToString().Replace(".resx", "." + ci + ".resx")); + } + + writer.AddResource(row.Cells[colInternal.Index].Value.ToString(), row.Cells[colOtherLang.Index].Value.ToString()); + + fname = row.Cells[colFile.Index].Value.ToString(); } - - writer.AddResource(row.Cells[colInternal.Index].Value.ToString(),row.Cells[colOtherLang.Index].Value.ToString()); - - fname = row.Cells[colFile.Index].Value.ToString(); + catch { } + try + { + sw.Write(""); + } + catch (Exception ex) { try { MessageBox.Show("Failed to save " + row.Cells[colOtherLang.Index].Value.ToString() + " " + ex.ToString()); } catch { } } } if (writer != null) writer.Close(); + sw.Write("
" + row.Cells[colFile.Index].Value.ToString() + "" + row.Cells[colInternal.Index].Value.ToString() + "" + row.Cells[colOtherLang.Index].Value.ToString() + "
"); + sw.Close(); + } + + private void button3_Click(object sender, EventArgs e) + { + StreamReader sr1 = new StreamReader("translation/output.txt"); + + StreamReader sr2 = new StreamReader("translation/output.ru.txt", Encoding.Unicode); + + while (!sr1.EndOfStream) + { + string line1 = sr1.ReadLine(); + string line1a = sr2.ReadLine(); + + int index1 = line1.IndexOf(' ', line1.IndexOf(' ') + 1) + 1; + + int index1a = line1a.IndexOf(' ',line1a.IndexOf(' ')+1)+1; + + foreach (DataGridViewRow row in dataGridView1.Rows) + { + if (line1.Contains(row.Cells[colFile.Index].Value.ToString()) && line1.Contains(row.Cells[colInternal.Index].Value.ToString())) + { + row.Cells[colOtherLang.Index].Value = line1a.Substring(index1a); + } + } + } + + sr1.Close(); + sr2.Close(); } } } diff --git a/Tools/ArdupilotMegaPlanner/resedit/resedit.csproj b/Tools/ArdupilotMegaPlanner/resedit/resedit.csproj index 0fe03178e4..4cbe9044ce 100644 --- a/Tools/ArdupilotMegaPlanner/resedit/resedit.csproj +++ b/Tools/ArdupilotMegaPlanner/resedit/resedit.csproj @@ -24,15 +24,17 @@ DEBUG;TRACE prompt 4 + 2048 x86 pdbonly true ..\bin\Release\ - TRACE + DEBUG;TRACE prompt 4 + 2048 diff --git a/Tools/ArdupilotMegaPlanner/srtm.cs b/Tools/ArdupilotMegaPlanner/srtm.cs index 4b75ee5c52..1bc8ca401f 100644 --- a/Tools/ArdupilotMegaPlanner/srtm.cs +++ b/Tools/ArdupilotMegaPlanner/srtm.cs @@ -12,7 +12,7 @@ namespace ArdupilotMega public static int getAltitude(double lat, double lng) { - short alt = -32768; + short alt = 0; lat += 0.00083333333333333; //lng += 0.0008; diff --git a/Tools/ArdupilotMegaPlanner/temp.cs b/Tools/ArdupilotMegaPlanner/temp.cs index 043c87e25f..b794b748c2 100644 --- a/Tools/ArdupilotMegaPlanner/temp.cs +++ b/Tools/ArdupilotMegaPlanner/temp.cs @@ -789,7 +789,11 @@ namespace ArdupilotMega FolderBrowserDialog fbd = new FolderBrowserDialog(); - fbd.SelectedPath = @"C:\Users\hog\Documents\albany 2011\New folder"; + try + { + fbd.SelectedPath = @"C:\Users\hog\Documents\albany 2011\New folder"; + } + catch { } fbd.ShowDialog(); diff --git a/Tools/PPMEncoder/ap_ppm_encoder.c b/Tools/PPMEncoder/ap_ppm_encoder.c index 6e03261eb8..ea707c6d91 100644 --- a/Tools/PPMEncoder/ap_ppm_encoder.c +++ b/Tools/PPMEncoder/ap_ppm_encoder.c @@ -30,7 +30,6 @@ /********************************************************************************************************/ - #define RC_SERVO_PORT D /* The port for the servo pulse input. */ #define RC_LED_PORT B /* The port for the PPM waveform and the led. */ diff --git a/apo/.cproject b/apo/.cproject new file mode 100644 index 0000000000..00f2f875be --- /dev/null +++ b/apo/.cproject @@ -0,0 +1,46 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/apo/.gitignore b/apo/.gitignore new file mode 100644 index 0000000000..e31d5d5b64 --- /dev/null +++ b/apo/.gitignore @@ -0,0 +1 @@ +apo.cpp diff --git a/apo/.project b/apo/.project new file mode 100644 index 0000000000..4152e256c1 --- /dev/null +++ b/apo/.project @@ -0,0 +1,79 @@ + + + apo + + + + + + org.eclipse.cdt.managedbuilder.core.genmakebuilder + clean,full,incremental, + + + ?name? + + + + org.eclipse.cdt.make.core.append_environment + true + + + org.eclipse.cdt.make.core.autoBuildTarget + all + + + org.eclipse.cdt.make.core.buildArguments + + + + org.eclipse.cdt.make.core.buildCommand + make + + + org.eclipse.cdt.make.core.cleanBuildTarget + clean + + + org.eclipse.cdt.make.core.contents + org.eclipse.cdt.make.core.activeConfigSettings + + + org.eclipse.cdt.make.core.enableAutoBuild + false + + + org.eclipse.cdt.make.core.enableCleanBuild + true + + + org.eclipse.cdt.make.core.enableFullBuild + true + + + org.eclipse.cdt.make.core.fullBuildTarget + all + + + org.eclipse.cdt.make.core.stopOnError + true + + + org.eclipse.cdt.make.core.useDefaultBuildCmd + true + + + + + org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder + full,incremental, + + + + + + org.eclipse.cdt.core.cnature + org.eclipse.cdt.core.ccnature + org.eclipse.cdt.managedbuilder.core.managedBuildNature + org.eclipse.cdt.managedbuilder.core.ScannerConfigNature + + diff --git a/apo/ControllerPlane.h b/apo/ControllerPlane.h new file mode 100644 index 0000000000..408cb04491 --- /dev/null +++ b/apo/ControllerPlane.h @@ -0,0 +1,215 @@ +/* + * ControllerPlane.h + * + * Created on: Jun 30, 2011 + * Author: jgoppert + */ + +#ifndef CONTROLLERPLANE_H_ +#define CONTROLLERPLANE_H_ + +#include "../APO/AP_Controller.h" + +namespace apo { + +class ControllerPlane: public AP_Controller { +private: + AP_Var_group _group; + AP_Var_group _trimGroup; + AP_Uint8 _mode; + AP_Uint8 _rdrAilMix; + bool _needsTrim; + AP_Float _ailTrim; + AP_Float _elvTrim; + AP_Float _rdrTrim; + AP_Float _thrTrim; + enum { + ch_mode = 0, ch_roll, ch_pitch, ch_thr, ch_yaw + }; + enum { + k_chMode = k_radioChannelsStart, + k_chRoll, + k_chPitch, + k_chYaw, + k_chThr, + + k_pidBnkRll = k_controllersStart, + k_pidSpdPit, + k_pidPitPit, + k_pidYwrYaw, + k_pidHdgBnk, + k_pidAltThr, + + k_trim = k_customStart + }; + BlockPID pidBnkRll; // bank error to roll servo deflection + BlockPID pidSpdPit; // speed error to pitch command + BlockPID pidPitPit; // pitch error to pitch servo deflection + BlockPID pidYwrYaw; // yaw rate error to yaw servo deflection + BlockPID pidHdgBnk; // heading error to bank command + BlockPID pidAltThr; // altitude error to throttle deflection + bool requireRadio; + +public: + ControllerPlane(AP_Navigator * nav, AP_Guide * guide, + AP_HardwareAbstractionLayer * hal) : + AP_Controller(nav, guide, hal), + _group(k_cntrl, PSTR("cntrl_")), + _trimGroup(k_trim, PSTR("trim_")), + _mode(&_group, 1, MAV_MODE_UNINIT, PSTR("mode")), + _rdrAilMix(&_group, 2, rdrAilMix, PSTR("rdrAilMix")), + _needsTrim(false), + _ailTrim(&_trimGroup, 1, ailTrim, PSTR("ail")), + _elvTrim(&_trimGroup, 2, elvTrim, PSTR("elv")), + _rdrTrim(&_trimGroup, 3, rdrTrim, PSTR("rdr")), + _thrTrim(&_trimGroup, 4, thrTrim, PSTR("thr")), + pidBnkRll(new AP_Var_group(k_pidBnkRll, PSTR("bnkRll_")), 1, + pidBnkRllP, pidBnkRllI, pidBnkRllD, pidBnkRllAwu, + pidBnkRllLim, pidBnkRllDFCut), + pidPitPit(new AP_Var_group(k_pidPitPit, PSTR("pitPit_")), 1, + pidPitPitP, pidPitPitI, pidPitPitD, pidPitPitAwu, + pidPitPitLim, pidPitPitDFCut), + pidSpdPit(new AP_Var_group(k_pidSpdPit, PSTR("spdPit_")), 1, + pidSpdPitP, pidSpdPitI, pidSpdPitD, pidSpdPitAwu, + pidSpdPitLim, pidSpdPitDFCut), + pidYwrYaw(new AP_Var_group(k_pidYwrYaw, PSTR("ywrYaw_")), 1, + pidYwrYawP, pidYwrYawI, pidYwrYawD, pidYwrYawAwu, + pidYwrYawLim, pidYwrYawDFCut), + pidHdgBnk(new AP_Var_group(k_pidHdgBnk, PSTR("hdgBnk_")), 1, + pidHdgBnkP, pidHdgBnkI, pidHdgBnkD, pidHdgBnkAwu, + pidHdgBnkLim, pidHdgBnkDFCut), + pidAltThr(new AP_Var_group(k_pidAltThr, PSTR("altThr_")), 1, + pidAltThrP, pidAltThrI, pidAltThrD, pidAltThrAwu, + pidAltThrLim, pidAltThrDFCut), + requireRadio(false) { + + _hal->debug->println_P(PSTR("initializing plane controller")); + + _hal->rc.push_back( + new AP_RcChannel(k_chMode, PSTR("mode_"), APM_RC, 5, 1100, + 1500, 1900, RC_MODE_IN, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chRoll, PSTR("roll_"), APM_RC, 0, 1200, + 1500, 1800, RC_MODE_INOUT, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chPitch, PSTR("pitch_"), APM_RC, 1, 1200, + 1500, 1800, RC_MODE_INOUT, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chThr, PSTR("thr_"), APM_RC, 2, 1100, 1100, + 1900, RC_MODE_INOUT, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chYaw, PSTR("yaw_"), APM_RC, 3, 1200, 1500, + 1800, RC_MODE_INOUT, false)); + } + 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 the value of the throttle is less than 5% cut motor power + } else if (requireRadio && _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(); + + // force auto to read new manual trim + if (_needsTrim == false) + _needsTrim = true; + //_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; + + float aileron = pidBnkRll.update( + pidHdgBnk.update(headingError, dt) - _nav->getRoll(), dt); + float elevator = pidPitPit.update( + -pidSpdPit.update( + _guide->getAirSpeedCommand() - _nav->getAirSpeed(), + dt) - _nav->getPitch(), dt); + float rudder = pidYwrYaw.update(-_nav->getYawRate(), dt); + // desired yaw rate is zero, needs washout + float throttle = pidAltThr.update( + _guide->getAltitudeCommand() - _nav->getAlt(), dt); + + // if needs trim + if (_needsTrim) { + // need to subtract current controller deflections so control + // surfaces are actually at the same position as manual flight + _ailTrim = _hal->rc[ch_roll]->getRadioPosition() - aileron; + _elvTrim = _hal->rc[ch_pitch]->getRadioPosition() - elevator; + _rdrTrim = _hal->rc[ch_yaw]->getRadioPosition() - rudder; + _thrTrim = _hal->rc[ch_thr]->getRadioPosition() - throttle; + _needsTrim = false; + } + + // actuator mixing/ output + _hal->rc[ch_roll]->setPosition( + aileron + _rdrAilMix * rudder + _ailTrim); + _hal->rc[ch_yaw]->setPosition(rudder + _rdrTrim); + _hal->rc[ch_pitch]->setPosition(elevator + _elvTrim); + _hal->rc[ch_thr]->setPosition(throttle + _thrTrim); + + //_hal->debug->println("automode"); + + + // heading debug +// Serial.print("heading command: "); Serial.println(_guide->getHeadingCommand()); +// Serial.print("heading: "); Serial.println(_nav->getYaw()); +// Serial.print("heading error: "); Serial.println(headingError); + + // alt debug +// Serial.print("alt command: "); Serial.println(_guide->getAltitudeCommand()); +// Serial.print("alt: "); Serial.println(_nav->getAlt()); +// Serial.print("alt error: "); Serial.println(_guide->getAltitudeCommand() - _nav->getAlt()); + 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 /* CONTROLLERPLANE_H_ */ diff --git a/apo/ControllerQuad.h b/apo/ControllerQuad.h new file mode 100644 index 0000000000..9e12bbe0b0 --- /dev/null +++ b/apo/ControllerQuad.h @@ -0,0 +1,250 @@ +/* + * ControllerQuad.h + * + * Created on: Jun 30, 2011 + * Author: jgoppert + */ + +#ifndef CONTROLLERQUAD_H_ +#define CONTROLLERQUAD_H_ + +#include "../APO/AP_Controller.h" + +namespace apo { + +class ControllerQuad: public AP_Controller { +public: + + /** + * note that these are not the controller radio channel numbers, they are just + * unique keys so they can be reaccessed from the hal rc vector + */ + enum { + CH_MODE = 0, // note scicoslab channels set mode, left, right, front, back order + CH_LEFT, // this enum must match this + CH_RIGHT, + CH_FRONT, + CH_BACK, + CH_ROLL, + CH_PITCH, + CH_YAW, + CH_THRUST + }; + + enum { + k_chMode = k_radioChannelsStart, + k_chLeft, + k_chRight, + k_chFront, + k_chBack, + k_chRoll, + k_chPitch, + k_chYaw, + k_chThr + }; + + enum { + k_pidGroundSpeed2Throttle = k_controllersStart, + k_pidStr, + k_pidPN, + k_pidPE, + k_pidPD, + k_pidRoll, + k_pidPitch, + k_pidYawRate, + k_pidYaw, + }; + + ControllerQuad(AP_Navigator * nav, AP_Guide * guide, + AP_HardwareAbstractionLayer * hal) : + AP_Controller(nav, guide, hal), + pidRoll(new AP_Var_group(k_pidRoll, PSTR("ROLL_")), 1, + PID_ATT_P, PID_ATT_I, PID_ATT_D, PID_ATT_AWU, + PID_ATT_LIM), + pidPitch(new AP_Var_group(k_pidPitch, PSTR("PITCH_")), 1, + PID_ATT_P, PID_ATT_I, PID_ATT_D, PID_ATT_AWU, + PID_ATT_LIM), + pidYaw(new AP_Var_group(k_pidYaw, PSTR("YAW_")), 1, + PID_YAWPOS_P, PID_YAWPOS_I, PID_YAWPOS_D, + PID_YAWPOS_AWU, PID_YAWPOS_LIM), + pidYawRate(new AP_Var_group(k_pidYawRate, PSTR("YAWRT_")), 1, + PID_YAWSPEED_P, PID_YAWSPEED_I, PID_YAWSPEED_D, + PID_YAWSPEED_AWU, PID_YAWSPEED_LIM, PID_YAWSPEED_DFCUT), + pidPN(new AP_Var_group(k_pidPN, PSTR("NORTH_")), 1, PID_POS_P, + PID_POS_I, PID_POS_D, PID_POS_AWU, PID_POS_LIM), + pidPE(new AP_Var_group(k_pidPE, PSTR("EAST_")), 1, PID_POS_P, + PID_POS_I, PID_POS_D, PID_POS_AWU, PID_POS_LIM), + pidPD(new AP_Var_group(k_pidPD, PSTR("DOWN_")), 1, PID_POS_Z_P, + PID_POS_Z_I, PID_POS_Z_D, PID_POS_Z_AWU, PID_POS_Z_LIM) { + /* + * allocate radio channels + * the order of the channels has to match the enumeration above + */ + _hal->rc.push_back( + new AP_RcChannel(k_chMode, PSTR("MODE_"), APM_RC, 5, 1100, + 1500, 1900, RC_MODE_IN, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chLeft, PSTR("LEFT_"), APM_RC, 0, 1100, + 1100, 1900, RC_MODE_OUT, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chRight, PSTR("RIGHT_"), APM_RC, 1, 1100, + 1100, 1900, RC_MODE_OUT, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chFront, PSTR("FRONT_"), APM_RC, 2, 1100, + 1100, 1900, RC_MODE_OUT, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chBack, PSTR("BACK_"), APM_RC, 3, 1100, + 1100, 1900, RC_MODE_OUT, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chRoll, PSTR("ROLL_"), APM_RC, 0, 1100, + 1500, 1900, RC_MODE_IN, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chPitch, PSTR("PITCH_"), APM_RC, 1, 1100, + 1500, 1900, RC_MODE_IN, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chYaw, PSTR("YAW_"), APM_RC, 2, 1100, 1500, + 1900, RC_MODE_IN, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chThr, PSTR("THRUST_"), APM_RC, 3, 1100, + 1100, 1900, RC_MODE_IN, false)); + } + + 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_THRUST]->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); + } + + // manual mode + float mixRemoteWeight = 0; + if (_hal->rc[CH_MODE]->getRadioPosition() > 0) { + mixRemoteWeight = 1; + _mode = MAV_MODE_MANUAL; + } else { + _mode = MAV_MODE_AUTO; + } + + // commands for inner loop + float cmdRoll = 0; + float cmdPitch = 0; + float cmdYawRate = 0; + float thrustMix = 0; + + switch(_mode) { + + case MAV_MODE_MANUAL: { + setAllRadioChannelsManually(); + // "mix manual" + cmdRoll = 0.5 * _hal->rc[CH_ROLL]->getPosition() + * mixRemoteWeight; + cmdPitch = 0.5 * _hal->rc[CH_PITCH]->getPosition() + * mixRemoteWeight; + cmdYawRate = 0.5 * _hal->rc[CH_YAW]->getPosition() + * mixRemoteWeight; + thrustMix = _hal->rc[CH_THRUST]->getPosition() * mixRemoteWeight; + break; + } + + case MAV_MODE_AUTO: { + + // XXX kills all commands, + // auto not currently implemented + + // position loop + /* + float cmdNorthTilt = pidPN.update(_nav->getPN(),_nav->getVN(),dt); + float cmdEastTilt = pidPE.update(_nav->getPE(),_nav->getVE(),dt); + float cmdDown = pidPD.update(_nav->getPD(),_nav->getVD(),dt); + + // "transform-to-body" + { + float trigSin = sin(-yaw); + float trigCos = cos(-yaw); + _cmdPitch = _cmdEastTilt * trigCos + - _cmdNorthTilt * trigSin; + _cmdRoll = -_cmdEastTilt * trigSin + + _cmdNorthTilt * trigCos; + // note that the north tilt is negative of the pitch + } + + //thrustMix += THRUST_HOVER_OFFSET; + + // "thrust-trim-adjust" + if (fabs(_cmdRoll) > 0.5) { + _thrustMix *= 1.13949393; + } else { + _thrustMix /= cos(_cmdRoll); + } + if (fabs(_cmdPitch) > 0.5) { + _thrustMix *= 1.13949393; + } else { + _thrustMix /= cos(_cmdPitch); + } + */ + } + + } + + // attitude loop + // XXX negative sign added to nav roll, not sure why this is necessary + // XXX negative sign added to nav roll rate, not sure why this is necessary + float rollMix = pidRoll.update(cmdRoll + _nav->getRoll(), + -_nav->getRollRate(), dt); + // XXX negative sign added to cmdPitch, not sure why this is necessary + float pitchMix = pidPitch.update(-cmdPitch - _nav->getPitch(), + _nav->getPitchRate(), dt); + // XXX negative sign added to cmdYawRate, not sure why this is necessary + float yawMix = pidYawRate.update(-cmdYawRate - _nav->getYawRate(), dt); + + _hal->rc[CH_LEFT]->setPosition(thrustMix + rollMix + yawMix); + _hal->rc[CH_RIGHT]->setPosition(thrustMix - rollMix + yawMix); + _hal->rc[CH_FRONT]->setPosition(thrustMix + pitchMix - yawMix); + _hal->rc[CH_BACK]->setPosition(thrustMix - pitchMix - yawMix); + + // _hal->debug->printf("L: %f\t R: %f\t F: %f\t B: %f\n", + // _hal->rc[CH_LEFT]->getPosition(), + // _hal->rc[CH_RIGHT]->getPosition(), + // _hal->rc[CH_FRONT]->getPosition(), + // _hal->rc[CH_BACK]->getPosition()); + + _hal->debug->printf( + "rollMix: %f\t pitchMix: %f\t yawMix: %f\t thrustMix: %f\n", + rollMix, pitchMix, yawMix, thrustMix); + + // _hal->debug->printf("roll pwm: %d\t pitch pwm: %d\t yaw pwm: %d\t thrust pwm: %d\n", + // _hal->rc[CH_ROLL]->readRadio(), + // _hal->rc[CH_PITCH]->readRadio(), + // _hal->rc[CH_YAW]->readRadio(), + // _hal->rc[CH_THRUST]->readRadio()); + } + virtual MAV_MODE getMode() { + return (MAV_MODE) _mode.get(); + } +private: + AP_Uint8 _mode; + BlockPIDDfb pidRoll, pidPitch, pidYaw; + BlockPID pidYawRate; + BlockPIDDfb pidPN, pidPE, pidPD; + +}; + +} // namespace apo + +#endif /* CONTROLLERQUAD_H_ */ diff --git a/apo/Makefile b/apo/Makefile new file mode 100644 index 0000000000..1d9b6a022d --- /dev/null +++ b/apo/Makefile @@ -0,0 +1 @@ +include ../libraries/AP_Common/Arduino.mk diff --git a/apo/PlaneEasystar.h b/apo/PlaneEasystar.h new file mode 100644 index 0000000000..812c4ad449 --- /dev/null +++ b/apo/PlaneEasystar.h @@ -0,0 +1,113 @@ +/* + * PlaneEasystar.h + * + * Created on: May 1, 2011 + * Author: jgoppert + */ + +#ifndef PLANEEASYSTAR_H_ +#define PLANEEASYSTAR_H_ + + +// vehicle options +static const apo::vehicle_t vehicle = apo::VEHICLE_PLANE; +//static const apo::halMode_t halMode = apo::MODE_LIVE; // live mode, actual flight +static const apo::halMode_t halMode = apo::MODE_HIL_CNTL; // hardware in the loop, control level +static const apo::board_t board = apo::BOARD_ARDUPILOTMEGA_1280; +static const uint8_t heartBeatTimeout = 3; + +// algorithm selection +#define CONTROLLER_CLASS ControllerPlane +#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 rdrAilMix = 1.0; // since there are no ailerons + +// bank error to roll servo +static const float pidBnkRllP = -1; +static const float pidBnkRllI = 0.0; +static const float pidBnkRllD = 0.0; +static const float pidBnkRllAwu = 0.0; +static const float pidBnkRllLim = 1.0; +static const float pidBnkRllDFCut = 0.0; + +// pitch error to pitch servo +static const float pidPitPitP = -1; +static const float pidPitPitI = 0.0; +static const float pidPitPitD = 0.0; +static const float pidPitPitAwu = 0.0; +static const float pidPitPitLim = 1.0; +static const float pidPitPitDFCut = 0.0; + +// speed error to pitch command +static const float pidSpdPitP = 0.1; +static const float pidSpdPitI = 0.0; +static const float pidSpdPitD = 0.0; +static const float pidSpdPitAwu = 0.0; +static const float pidSpdPitLim = 1.0; +static const float pidSpdPitDFCut = 0.0; + +// yaw rate error to yaw servo +static const float pidYwrYawP = -0.1; +static const float pidYwrYawI = 0.0; +static const float pidYwrYawD = 0.0; +static const float pidYwrYawAwu = 0.0; +static const float pidYwrYawLim = 1.0; +static const float pidYwrYawDFCut = 0.0; + +// heading error to bank angle command +static const float pidHdgBnkP = 1.0; +static const float pidHdgBnkI = 0.0; +static const float pidHdgBnkD = 0.0; +static const float pidHdgBnkAwu = 0.0; +static const float pidHdgBnkLim = 0.5; +static const float pidHdgBnkDFCut = 0.0; + +// altitude error to throttle command +static const float pidAltThrP = .01; +static const float pidAltThrI = 0.0; +static const float pidAltThrD = 0.0; +static const float pidAltThrAwu = 0.0; +static const float pidAltThrLim = 1; +static const float pidAltThrDFCut = 0.0; + +// trim control positions (-1,1) +static const float ailTrim = 0.0; +static const float elvTrim = 0.0; +static const float rdrTrim = 0.0; +static const float thrTrim = 0.5; + +#include "ControllerPlane.h" + +#endif /* PLANEEASYSTAR_H_ */ diff --git a/apo/QuadArducopter.h b/apo/QuadArducopter.h new file mode 100644 index 0000000000..5151b224fe --- /dev/null +++ b/apo/QuadArducopter.h @@ -0,0 +1,98 @@ +/* + * QuadArducopter.h + * + * Created on: May 1, 2011 + * Author: jgoppert + */ + +#ifndef QUADARDUCOPTER_H_ +#define QUADARDUCOPTER_H_ + +// vehicle options +static const apo::vehicle_t vehicle = apo::VEHICLE_QUAD; +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 ControllerQuad +#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; + +//motor parameters +static const float MOTOR_MAX = 1; +static const float MOTOR_MIN = 0.1; + +// position control loop +static const float PID_POS_INTERVAL = 1 / 100; // 5 hz +static const float PID_POS_P = 0; +static const float PID_POS_I = 0; +static const float PID_POS_D = 0; +static const float PID_POS_LIM = 0; // about 5 deg +static const float PID_POS_AWU = 0; // about 5 deg +static const float PID_POS_Z_P = 0; +static const float PID_POS_Z_I = 0; +static const float PID_POS_Z_D = 0; +static const float PID_POS_Z_LIM = 0; +static const float PID_POS_Z_AWU = 0; + +// attitude control loop +static const float PID_ATT_INTERVAL = 1 / 100; // 100 hz +static const float PID_ATT_P = 0.1; // 0.1 +static const float PID_ATT_I = 0; // 0.0 +static const float PID_ATT_D = 0.1; // 0.1 +static const float PID_ATT_LIM = 1; // 0.01 // 10 % #define MOTORs +static const float PID_ATT_AWU = 0; // 0.0 +static const float PID_YAWPOS_P = 0; +static const float PID_YAWPOS_I = 0; +static const float PID_YAWPOS_D = 0; +static const float PID_YAWPOS_LIM = 0; // 1 rad/s +static const float PID_YAWPOS_AWU = 0; // 1 rad/s +static const float PID_YAWSPEED_P = .2; +static const float PID_YAWSPEED_I = 0; +static const float PID_YAWSPEED_D = 0; +static const float PID_YAWSPEED_LIM = .3; // 0.01 // 10 % MOTORs +static const float PID_YAWSPEED_AWU = 0.0; +static const float PID_YAWSPEED_DFCUT = 3.0; // 3 Radians, about 1 Hz + +// mixing +static const float MIX_REMOTE_WEIGHT = 1; +static const float MIX_POSITION_WEIGHT = 1; +static const float MIX_POSITION_Z_WEIGHT = 1; +static const float MIX_POSITION_YAW_WEIGHT = 1; + +static const float THRUST_HOVER_OFFSET = 0.475; + +#include "ControllerQuad.h" + +#endif /* QUADARDUCOPTER_H_ */ diff --git a/apo/QuadMikrokopter.h b/apo/QuadMikrokopter.h new file mode 100644 index 0000000000..7aeeacd5e6 --- /dev/null +++ b/apo/QuadMikrokopter.h @@ -0,0 +1,98 @@ +/* + * QuadMikrokopter + * + * Created on: May 1, 2011 + * Author: jgoppert + */ + +#ifndef QUADMIKROKOPTER_H_ +#define QUADMIKROKOPTER_H_ + +// vehicle options +static const apo::vehicle_t vehicle = apo::VEHICLE_QUAD; +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 ControllerQuad +#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; + +//motor parameters +static const float MOTOR_MAX = 1; +static const float MOTOR_MIN = 0.1; + +// position control loop +static const float PID_POS_INTERVAL = 1 / 100; // 5 hz +static const float PID_POS_P = 0; +static const float PID_POS_I = 0; +static const float PID_POS_D = 0; +static const float PID_POS_LIM = 0; // about 5 deg +static const float PID_POS_AWU = 0; // about 5 deg +static const float PID_POS_Z_P = 0; +static const float PID_POS_Z_I = 0; +static const float PID_POS_Z_D = 0; +static const float PID_POS_Z_LIM = 0; +static const float PID_POS_Z_AWU = 0; + +// attitude control loop +static const float PID_ATT_INTERVAL = 1 / 100; // 100 hz +static const float PID_ATT_P = 0.1; // 0.1 +static const float PID_ATT_I = 0; // 0.0 +static const float PID_ATT_D = 0.1; // 0.1 +static const float PID_ATT_LIM = 1; // 0.01 // 10 % #define MOTORs +static const float PID_ATT_AWU = 0; // 0.0 +static const float PID_YAWPOS_P = 0; +static const float PID_YAWPOS_I = 0; +static const float PID_YAWPOS_D = 0; +static const float PID_YAWPOS_LIM = 0; // 1 rad/s +static const float PID_YAWPOS_AWU = 0; // 1 rad/s +static const float PID_YAWSPEED_P = .2; +static const float PID_YAWSPEED_I = 0; +static const float PID_YAWSPEED_D = 0; +static const float PID_YAWSPEED_LIM = .3; // 0.01 // 10 % MOTORs +static const float PID_YAWSPEED_AWU = 0.0; +static const float PID_YAWSPEED_DFCUT = 3.0; // 3 Radians, about 1 Hz + +// mixing +static const float MIX_REMOTE_WEIGHT = 1; +static const float MIX_POSITION_WEIGHT = 1; +static const float MIX_POSITION_Z_WEIGHT = 1; +static const float MIX_POSITION_YAW_WEIGHT = 1; + +static const float THRUST_HOVER_OFFSET = 0.475; + +#include "ControllerQuad.h" + +#endif /* QUADMIKROKOPTER_H_ */ diff --git a/apo/apo.pde b/apo/apo.pde new file mode 100644 index 0000000000..5148713899 --- /dev/null +++ b/apo/apo.pde @@ -0,0 +1,23 @@ +// Libraries +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +// Vehicle Configuration +#include "PlaneEasystar.h" + +// ArduPilotOne Default Setup +#include "APO_DefaultSetup.h" diff --git a/cmake/PdeP.jar b/cmake/PdeP.jar deleted file mode 100644 index ae76f9b762..0000000000 Binary files a/cmake/PdeP.jar and /dev/null differ diff --git a/cmake/modules/FindArduino.cmake b/cmake/modules/FindArduino.cmake index 7faadeba15..e53873e9ad 100644 --- a/cmake/modules/FindArduino.cmake +++ b/cmake/modules/FindArduino.cmake @@ -188,31 +188,23 @@ function(GENERATE_ARDUINO_FIRMWARE TARGET_NAME) endif() message(STATUS "Generating ${TARGET_NAME}") - message(STATUS "Sketches ${INPUT_SKETCHES}") - + set(ALL_LIBS) - set(ALL_SRCS ${INPUT_SKETCHES} ${INPUT_SRCS} ${INPUT_HDRS} ) - #set(ALL_SRCS ${INPUT_SRCS} ${INPUT_HDRS} ) - - #set compile flags and file properties for pde files - #SET_SOURCE_FILES_PROPERTIES(${INPUT_SKETCHES} PROPERTIES LANGUAGE CXX) - #SET_SOURCE_FILES_PROPERTIES(${INPUT_SKETCHES} PROPERTIES COMPILE_FLAGS "-x c++" ) - - setup_arduino_compiler(${INPUT_BOARD}) + set(ALL_SRCS ${INPUT_SRCS} ${INPUT_HDRS}) + + setup_arduino_compiler(${INPUT_BOARD}) setup_arduino_core(CORE_LIB ${INPUT_BOARD}) #setup_arduino_sketch(SKETCH_SRCS ${INPUT_SKETCHES}) if(INPUT_AUTOLIBS) - setup_arduino_libraries(ALL_LIBS ${INPUT_BOARD} "${ALL_SRCS}") + setup_arduino_libraries(ALL_LIBS ${INPUT_BOARD} "${ALL_SRCS}") endif() list(APPEND ALL_LIBS ${CORE_LIB} ${INPUT_LIBS}) - + setup_arduino_target(${TARGET_NAME} "${ALL_SRCS}" "${ALL_LIBS}") - #SET_TARGET_PROPERTIES(${TARGET_NAME} PROPERTIES LINKER_LANGUAGE CXX) - #setup_arduino_target(${TARGET_NAME} "${INPUT_SKETCHES}" ${INPUT_HDRS} "${ALL_LIBS}") if(INPUT_PORT) setup_arduino_upload(${INPUT_BOARD} ${TARGET_NAME} ${INPUT_PORT}) @@ -287,7 +279,8 @@ function(setup_arduino_core VAR_NAME BOARD_ID) set(BOARD_CORE ${${BOARD_ID}.build.core}) if(BOARD_CORE AND NOT TARGET ${CORE_LIB_NAME}) set(BOARD_CORE_PATH ${ARDUINO_CORES_PATH}/${BOARD_CORE}) - find_sources(CORE_SRCS ${BOARD_CORE_PATH}) + find_sources(CORE_SRCS ${BOARD_CORE_PATH} True) + list(REMOVE_ITEM CORE_SRCS "${BOARD_CORE_PATH}/main.cxx") add_library(${CORE_LIB_NAME} ${CORE_SRCS}) set(${VAR_NAME} ${CORE_LIB_NAME} PARENT_SCOPE) endif() @@ -321,8 +314,11 @@ function(find_arduino_libraries VAR_NAME SRCS) foreach(SRC_LINE ${SRC_CONTENTS}) if("${SRC_LINE}" MATCHES "^ *#include *[<\"](.*)[>\"]") get_filename_component(INCLUDE_NAME ${CMAKE_MATCH_1} NAME_WE) - foreach(LIB_SEARCH_PATH ${ARDUINO_LIBRARIES_PATH} ${CMAKE_CURRENT_SOURCE_DIR}) - if(EXISTS ${LIB_SEARCH_PATH}/${INCLUDE_NAME}/${CMAKE_MATCH_1}) + get_property(LIBRARY_SEARCH_PATH + DIRECTORY # Property Scope + PROPERTY LINK_DIRECTORIES) + foreach(LIB_SEARCH_PATH ${LIBRARY_SEARCH_PATH} ${ARDUINO_LIBRARIES_PATH} ${CMAKE_CURRENT_SOURCE_DIR} ${CMAKE_CURRENT_SOURCE_DIR}/libraries) + if(EXISTS ${LIB_SEARCH_PATH}/${INCLUDE_NAME}/${CMAKE_MATCH_1}) list(APPEND ARDUINO_LIBS ${LIB_SEARCH_PATH}/${INCLUDE_NAME}) break() endif() @@ -344,12 +340,23 @@ endfunction() # # Creates an Arduino library, with all it's library dependencies. # +# "LIB_NAME"_RECURSE controls if the library will recurse +# when looking for source files +# + +# For known libraries can list recurse here +set(Wire_RECURSE True) function(setup_arduino_library VAR_NAME BOARD_ID LIB_PATH) set(LIB_TARGETS) get_filename_component(LIB_NAME ${LIB_PATH} NAME) set(TARGET_LIB_NAME ${BOARD_ID}_${LIB_NAME}) if(NOT TARGET ${TARGET_LIB_NAME}) - find_sources(LIB_SRCS ${LIB_PATH}) + string(REGEX REPLACE ".*/" "" LIB_SHORT_NAME ${LIB_NAME}) + #message(STATUS "short name: ${LIB_SHORT_NAME} recures: ${${LIB_SHORT_NAME}_RECURSE}") + if (NOT DEFINED ${LIB_SHORT_NAME}_RECURSE) + set(${LIB_SHORT_NAME}_RECURSE False) + endif() + find_sources(LIB_SRCS ${LIB_PATH} ${${LIB_SHORT_NAME}_RECURSE}) if(LIB_SRCS) message(STATUS "Generating Arduino ${LIB_NAME} library") @@ -452,21 +459,29 @@ function(setup_arduino_upload BOARD_ID TARGET_NAME PORT) add_dependencies(upload ${TARGET_NAME}-upload) endfunction() -# find_sources(VAR_NAME LIB_PATH) +# find_sources(VAR_NAME LIB_PATH RECURSE) # # VAR_NAME - Variable name that will hold the detected sources # LIB_PATH - The base path +# RECURSE - Whether or not to recurse # # Finds all C/C++ sources located at the specified path. # -function(find_sources VAR_NAME LIB_PATH) - file(GLOB_RECURSE LIB_FILES ${LIB_PATH}/*.cpp - ${LIB_PATH}/*.c - ${LIB_PATH}/*.cc - ${LIB_PATH}/*.cxx - ${LIB_PATH}/*.h - ${LIB_PATH}/*.hh - ${LIB_PATH}/*.hxx) +function(find_sources VAR_NAME LIB_PATH RECURSE) + set(FILE_SEARCH_LIST + ${LIB_PATH}/*.cpp + ${LIB_PATH}/*.c + ${LIB_PATH}/*.cc + ${LIB_PATH}/*.cxx + ${LIB_PATH}/*.h + ${LIB_PATH}/*.hh + ${LIB_PATH}/*.hxx) + if (RECURSE) + file(GLOB_RECURSE LIB_FILES ${FILE_SEARCH_LIST}) + else() + file(GLOB LIB_FILES ${FILE_SEARCH_LIST}) + endif() + #message(STATUS "${LIB_PATH} recurse: ${RECURSE}") if(LIB_FILES) set(${VAR_NAME} ${LIB_FILES} PARENT_SCOPE) endif() diff --git a/cmake/modules/MacroEnsureOutOfSourceBuild.cmake b/cmake/modules/MacroEnsureOutOfSourceBuild.cmake new file mode 100644 index 0000000000..3ff891b512 --- /dev/null +++ b/cmake/modules/MacroEnsureOutOfSourceBuild.cmake @@ -0,0 +1,19 @@ +# - MACRO_ENSURE_OUT_OF_SOURCE_BUILD() +# MACRO_ENSURE_OUT_OF_SOURCE_BUILD() + +# Copyright (c) 2006, Alexander Neundorf, +# +# Redistribution and use is allowed according to the terms of the BSD license. +# For details see the accompanying COPYING-CMAKE-SCRIPTS file. + +macro (MACRO_ENSURE_OUT_OF_SOURCE_BUILD _errorMessage) + + string(COMPARE EQUAL "${CMAKE_SOURCE_DIR}" "${CMAKE_BINARY_DIR}" _insource) + if (_insource) + file(REMOVE [CMakeCache.txt CMakeFiles]) + message(FATAL_ERROR "${_errorMessage}") + endif (_insource) + +endmacro (MACRO_ENSURE_OUT_OF_SOURCE_BUILD) + +# vim:ts=4:sw=4:expandtab diff --git a/cmake/toolchains/Arduino.cmake b/cmake/toolchains/Arduino.cmake index 616c7b9160..68c58a72e9 100644 --- a/cmake/toolchains/Arduino.cmake +++ b/cmake/toolchains/Arduino.cmake @@ -6,27 +6,33 @@ set(CMAKE_CXX_COMPILER avr-g++) #=============================================================================# # C Flags # #=============================================================================# -set(ARDUINO_C_FLAGS "-ffunction-sections -fdata-sections") +if (NOT DEFINED ARDUINO_C_FLAGS) + set(ARDUINO_C_FLAGS "-ffunction-sections -fdata-sections") +endif() set(CMAKE_C_FLAGS "-g -Os ${ARDUINO_C_FLAGS}" CACHE STRING "") set(CMAKE_C_FLAGS_DEBUG "-g ${ARDUINO_C_FLAGS}" CACHE STRING "") set(CMAKE_C_FLAGS_MINSIZEREL "-Os -DNDEBUG ${ARDUINO_C_FLAGS}" CACHE STRING "") -set(CMAKE_C_FLAGS_RELEASE "-Os -DNDEBUG -w ${ARDUINO_C_FLAGS}" CACHE STRING "") -set(CMAKE_C_FLAGS_RELWITHDEBINFO "-Os -g -w ${ARDUINO_C_FLAGS}" CACHE STRING "") +set(CMAKE_C_FLAGS_RELEASE "-0s -DNDEBUG -w ${ARDUINO_C_FLAGS}" CACHE STRING "") +set(CMAKE_C_FLAGS_RELWITHDEBINFO "-0s -g -w ${ARDUINO_C_FLAGS}" CACHE STRING "") #=============================================================================# # C++ Flags # #=============================================================================# -set(ARDUINO_CXX_FLAGS "${ARDUINO_C_FLAGS} -fno-exceptions") +if (NOT DEFINED ARDUINO_CXX_FLAGS) + set(ARDUINO_CXX_FLAGS "${ARDUINO_C_FLAGS} -fno-exceptions") +endif() set(CMAKE_CXX_FLAGS "-g -Os ${ARDUINO_CXX_FLAGS}" CACHE STRING "") -set(CMAKE_CXX_FLAGS_DEBUG "-g -Os ${ARDUINO_CXX_FLAGS}" CACHE STRING "") +set(CMAKE_CXX_FLAGS_DEBUG "-g ${ARDUINO_CXX_FLAGS}" CACHE STRING "") set(CMAKE_CXX_FLAGS_MINSIZEREL "-Os -DNDEBUG ${ARDUINO_CXX_FLAGS}" CACHE STRING "") -set(CMAKE_CXX_FLAGS_RELEASE "-Os -DNDEBUG ${ARDUINO_CXX_FLAGS}" CACHE STRING "") -set(CMAKE_CXX_FLAGS_RELWITHDEBINFO "-Os -g ${ARDUINO_CXX_FLAGS}" CACHE STRING "") +set(CMAKE_CXX_FLAGS_RELEASE "-0s -DNDEBUG ${ARDUINO_CXX_FLAGS}" CACHE STRING "") +set(CMAKE_CXX_FLAGS_RELWITHDEBINFO "-0s -g ${ARDUINO_CXX_FLAGS}" CACHE STRING "") #=============================================================================# # Executable Linker Flags # #=============================================================================# -set(ARDUINO_LINKER_FLAGS "-Wl,--gc-sections -lc -lm") +if (NOT DEFINED ARDUINO_LINKER_FLAGS) + set(ARDUINO_LINKER_FLAGS "-Wl,--gc-sections") +endif() set(CMAKE_EXE_LINKER_FLAGS "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") set(CMAKE_EXE_LINKER_FLAGS_DEBUG "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") set(CMAKE_EXE_LINKER_FLAGS_MINSIZEREL "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") diff --git a/cmake/updated-arduino-cmake.sh b/cmake/updated-arduino-cmake.sh new file mode 100755 index 0000000000..3c86d4b728 --- /dev/null +++ b/cmake/updated-arduino-cmake.sh @@ -0,0 +1,5 @@ +#!/bin/bash +git clone git@github.com:jgoppert/arduino-cmake.git tmp +cp -rf tmp/cmake/modules/* modules +cp -rf tmp/cmake/toolchains/* toolchains +rm -rf tmp diff --git a/libraries/APM_BMP085/CMakeLists.txt b/libraries/APM_BMP085/CMakeLists.txt deleted file mode 100644 index 342fe4668f..0000000000 --- a/libraries/APM_BMP085/CMakeLists.txt +++ /dev/null @@ -1,22 +0,0 @@ -set(LIB_NAME APM_BMP085) - -set(${LIB_NAME}_SRCS - APM_BMP085.cpp - ) # Firmware sources - -set(${LIB_NAME}_HDRS - APM_BMP085.h - ) - -include_directories( - - - - #${CMAKE_SOURCE_DIR}/libraries/AP_Math - #${CMAKE_SOURCE_DIR}/libraries/AP_Common - #${CMAKE_SOURCE_DIR}/libraries/FastSerial -# - ) - -set(${LIB_NAME}_BOARD mega2560) - -generate_arduino_library(${LIB_NAME}) diff --git a/libraries/APM_PI/APM_PI.cpp b/libraries/APM_PI/APM_PI.cpp index 33954289a7..6fd710a32a 100644 --- a/libraries/APM_PI/APM_PI.cpp +++ b/libraries/APM_PI/APM_PI.cpp @@ -10,23 +10,11 @@ long APM_PI::get_pi(int32_t error, float dt) { - float output = 0; - //float delta_time = (float)dt / 1000.0; + _integrator += ((float)error * _ki) * dt; + _integrator = min(_integrator, (float)_imax); + _integrator = max(_integrator, (float)-_imax); - // Compute proportional component - output += error * _kp; - - // Compute integral component if time has elapsed - _integrator += (error * _ki) * dt; - - if (_integrator < -_imax) { - _integrator = -_imax; - } else if (_integrator > _imax) { - _integrator = _imax; - } - - output += _integrator; - return output; + return (float)error * _kp + _integrator; } void diff --git a/libraries/APM_PI/CMakeLists.txt b/libraries/APM_PI/CMakeLists.txt deleted file mode 100644 index e65e76f6a4..0000000000 --- a/libraries/APM_PI/CMakeLists.txt +++ /dev/null @@ -1,24 +0,0 @@ -set(LIB_NAME APM_PI) - -set(${LIB_NAME}_SRCS - APM_PI.cpp - #AP_OpticalFlow_ADNS3080.cpp - ) # Firmware sources - -set(${LIB_NAME}_HDRS - APM_PI.h - #AP_OpticalFlow_ADNS3080.h - ) - -include_directories( - - - - #${CMAKE_SOURCE_DIR}/libraries/AP_Math - ${CMAKE_SOURCE_DIR}/libraries/AP_Common - #${CMAKE_SOURCE_DIR}/libraries/FastSerial -# - ) - -set(${LIB_NAME}_BOARD mega2560) - -generate_arduino_library(${LIB_NAME}) diff --git a/libraries/APM_RC/APM_RC.cpp b/libraries/APM_RC/APM_RC.cpp index 27de25875d..db81cd1852 100644 --- a/libraries/APM_RC/APM_RC.cpp +++ b/libraries/APM_RC/APM_RC.cpp @@ -28,34 +28,42 @@ #else // Variable definition for Input Capture interrupt -volatile unsigned int ICR4_old; -volatile unsigned char PPM_Counter=0; -volatile uint16_t PWM_RAW[8] = {2400,2400,2400,2400,2400,2400,2400,2400}; -volatile unsigned char radio_status=0; +//volatile uint16_t ICR4_old; +//volatile uint8_t PPM_Counter=0; +volatile uint16_t PWM_RAW[NUM_CHANNELS] = {2400,2400,2400,2400,2400,2400,2400,2400}; +volatile uint8_t radio_status=0; /**************************************************** Input Capture Interrupt ICP4 => PPM signal read ****************************************************/ ISR(TIMER4_CAPT_vect) { - unsigned int Pulse; - unsigned int Pulse_Width; + static uint16_t ICR4_old; + static uint8_t PPM_Counter=0; + uint16_t Pulse; + uint16_t Pulse_Width; + Pulse=ICR4; - if (Pulse8000) // SYNC pulse? + if (Pulse8000) { // SYNC pulse? PPM_Counter=0; - else - { - if (PPM_Counter < (sizeof(PWM_RAW) / sizeof(PWM_RAW[0]))) { - PWM_RAW[PPM_Counter++]=Pulse_Width; //Saving pulse. - if (PPM_Counter >= NUM_CHANNELS) - radio_status = 1; + } + else { + if (PPM_Counter < NUM_CHANNELS) { // Valid pulse channel? + PWM_RAW[PPM_Counter++]=Pulse_Width; // Saving pulse. + + if (PPM_Counter >= NUM_CHANNELS) { + radio_status = 1; } } + } ICR4_old = Pulse; } @@ -124,7 +132,7 @@ void APM_RC_Class::Init(void) TIMSK4 |= (1<>1; // Because timer runs at 0.5us we need to do value/2 - result2 = PWM_RAW[ch]>>1; - if (result != result2) - result = PWM_RAW[ch]>>1; // if the results are different we make a third reading (this should be fine) - + result = PWM_RAW[ch]; + if (result != PWM_RAW[ch]) { + result = PWM_RAW[ch]; // if the results are different we make a third reading (this should be fine) + } + result >>= 1; // Because timer runs at 0.5us we need to do value/2 + // Limit values to a valid range result = constrain(result,MIN_PULSEWIDTH,MAX_PULSEWIDTH); radio_status=0; // Radio channel read return(result); } -unsigned char APM_RC_Class::GetState(void) +uint8_t APM_RC_Class::GetState(void) { return(radio_status); } @@ -198,7 +206,7 @@ void APM_RC_Class::Force_Out6_Out7(void) bool APM_RC_Class::setHIL(int16_t v[NUM_CHANNELS]) { uint8_t sum = 0; - for (unsigned char i=0; idebug = &Serial; + hal->debug->println_P(PSTR("initializing debug line")); + + /* + * Sensor initialization + */ + if (hal->getMode() == MODE_LIVE) { + + hal->debug->println_P(PSTR("initializing adc")); + hal->adc = new ADC_CLASS; + hal->adc->Init(); + + if (gpsEnabled) { + Serial1.begin(GPS_BAUD, 128, 16); // gps + hal->debug->println_P(PSTR("initializing gps")); + AP_GPS_Auto gpsDriver(&Serial1, &(hal->gps)); + hal->gps = &gpsDriver; + hal->gps->init(); + } + + if (baroEnabled) { + hal->debug->println_P(PSTR("initializing baro")); + hal->baro = new BARO_CLASS; + hal->baro->Init(); + } + + if (compassEnabled) { + hal->debug->println_P(PSTR("initializing compass")); + hal->compass = new COMPASS_CLASS; + hal->compass->set_orientation(AP_COMPASS_COMPONENTS_UP_PINS_FORWARD); + hal->compass->init(); + } + + /** + * Initialize ultrasonic sensors. If sensors are not plugged in, the navigator will not + * initialize them and NULL will be assigned to those corresponding pointers. + * On detecting NULL assigned to any ultrasonic sensor, its corresponding block of code + * will not be executed by the navigator. + * The coordinate system is assigned by the right hand rule with the thumb pointing down. + * In set_orientation, it is defined as (front/back,left/right,down,up) + */ + + if (rangeFinderFrontEnabled) { + hal->debug->println_P(PSTR("initializing front range finder")); + RangeFinder * rangeFinder = new RANGE_FINDER_CLASS(hal->adc,new ModeFilter); + rangeFinder->set_analog_port(1); + rangeFinder->set_orientation(1, 0, 0); + hal->rangeFinders.push_back(rangeFinder); + } + + if (rangeFinderBackEnabled) { + hal->debug->println_P(PSTR("initializing back range finder")); + RangeFinder * rangeFinder = new RANGE_FINDER_CLASS(hal->adc,new ModeFilter); + rangeFinder->set_analog_port(2); + rangeFinder->set_orientation(-1, 0, 0); + hal->rangeFinders.push_back(rangeFinder); + } + + if (rangeFinderLeftEnabled) { + hal->debug->println_P(PSTR("initializing left range finder")); + RangeFinder * rangeFinder = new RANGE_FINDER_CLASS(hal->adc,new ModeFilter); + rangeFinder->set_analog_port(3); + rangeFinder->set_orientation(0, -1, 0); + hal->rangeFinders.push_back(rangeFinder); + } + + if (rangeFinderRightEnabled) { + hal->debug->println_P(PSTR("initializing right range finder")); + RangeFinder * rangeFinder = new RANGE_FINDER_CLASS(hal->adc,new ModeFilter); + rangeFinder->set_analog_port(4); + rangeFinder->set_orientation(0, 1, 0); + hal->rangeFinders.push_back(rangeFinder); + } + + if (rangeFinderUpEnabled) { + hal->debug->println_P(PSTR("initializing up range finder")); + RangeFinder * rangeFinder = new RANGE_FINDER_CLASS(hal->adc,new ModeFilter); + rangeFinder->set_analog_port(5); + rangeFinder->set_orientation(0, 0, -1); + hal->rangeFinders.push_back(rangeFinder); + } + + if (rangeFinderDownEnabled) { + hal->debug->println_P(PSTR("initializing down range finder")); + RangeFinder * rangeFinder = new RANGE_FINDER_CLASS(hal->adc,new ModeFilter); + rangeFinder->set_analog_port(6); + rangeFinder->set_orientation(0, 0, 1); + hal->rangeFinders.push_back(rangeFinder); + } + + } else + + /* + * Select guidance, navigation, control algorithms + */ + navigator = new NAVIGATOR_CLASS(hal); + guide = new GUIDE_CLASS(navigator, hal); + controller = new CONTROLLER_CLASS(navigator, guide, hal); + + /* + * CommLinks + */ + if (board==BOARD_ARDUPILOTMEGA_2) + { + Serial2.begin(TELEM_BAUD, 128, 128); // gcs + hal->gcs = new COMMLINK_CLASS(&Serial2, navigator, guide, controller, hal); + } + else + { + Serial3.begin(TELEM_BAUD, 128, 128); // gcs + hal->gcs = new COMMLINK_CLASS(&Serial3, navigator, guide, controller, hal); + } + + /* + * Hardware in the Loop + */ + if (hal->getMode() == MODE_HIL_CNTL) { + Serial.println("HIL line setting up"); + Serial1.begin(HIL_BAUD, 128, 128); + hal->hil = new COMMLINK_CLASS(&Serial1, navigator, guide, controller, hal); + } + + + /* + * Start the autopilot + */ + hal->debug->printf_P(PSTR("initializing arduplane\n")); + hal->debug->printf_P(PSTR("free ram: %d bytes\n"),freeMemory()); + + autoPilot = new apo::AP_Autopilot(navigator, guide, controller, hal, + loop0Rate, loop1Rate, loop2Rate, loop3Rate); +} + +void loop() { + autoPilot->update(); +} + +#endif //_APO_COMMON_H diff --git a/libraries/APO/AP_Autopilot.cpp b/libraries/APO/AP_Autopilot.cpp new file mode 100644 index 0000000000..55251c720d --- /dev/null +++ b/libraries/APO/AP_Autopilot.cpp @@ -0,0 +1,246 @@ +/* + * AP_Autopilot.cpp + * + * Created on: Apr 30, 2011 + * Author: jgoppert + */ + +#include "AP_Autopilot.h" + +namespace apo { + +class AP_HardwareAbstractionLayer; + +AP_Autopilot::AP_Autopilot(AP_Navigator * navigator, AP_Guide * guide, + AP_Controller * controller, AP_HardwareAbstractionLayer * hal, + float loop0Rate, float loop1Rate, float loop2Rate, float loop3Rate) : + Loop(loop0Rate, callback0, this), _navigator(navigator), _guide(guide), + _controller(controller), _hal(hal), _loop0Rate(loop0Rate), + _loop1Rate(loop1Rate), _loop2Rate(loop2Rate), _loop3Rate(loop3Rate), + _loop4Rate(loop3Rate) { + + hal->setState(MAV_STATE_BOOT); + hal->gcs->sendMessage(MAVLINK_MSG_ID_HEARTBEAT); + hal->gcs->sendMessage(MAVLINK_MSG_ID_SYS_STATUS); + + /* + * Calibration + */ + hal->setState(MAV_STATE_CALIBRATING); + hal->gcs->sendMessage(MAVLINK_MSG_ID_HEARTBEAT); + hal->gcs->sendMessage(MAVLINK_MSG_ID_SYS_STATUS); + + if (navigator) navigator->calibrate(); + + /* + * Look for valid initial state + */ + while (_navigator) { + // letc gcs known we are alive + hal->gcs->sendMessage(MAVLINK_MSG_ID_HEARTBEAT); + hal->gcs->sendMessage(MAVLINK_MSG_ID_SYS_STATUS); + if (hal->getMode() == MODE_LIVE) { + _navigator->updateSlow(0); + if (hal->gps) { + if (hal->gps->fix) { + break; + } else { + hal->gcs->sendText(SEVERITY_LOW, + PSTR("waiting for gps lock\n")); + hal->debug->printf_P(PSTR("waiting for gps lock\n")); + } + } else { // no gps, can skip + break; + } + } else if (hal->getMode() == MODE_HIL_CNTL) { // hil + hal->hil->sendMessage(MAVLINK_MSG_ID_HEARTBEAT); + hal->hil->receive(); + Serial.println("HIL Receive Called"); + if (_navigator->getTimeStamp() != 0) { + // give hil a chance to send some packets + for (int i = 0; i < 5; i++) { + hal->debug->println_P(PSTR("reading initial hil packets")); + hal->gcs->sendText(SEVERITY_LOW, + PSTR("reading initial hil packets")); + delay(1000); + } + break; + } + hal->debug->println_P(PSTR("waiting for hil packet")); + delay(1000); + } + } + + AP_MavlinkCommand::home.setAlt(_navigator->getAlt()); + AP_MavlinkCommand::home.setLat(_navigator->getLat()); + AP_MavlinkCommand::home.setLon(_navigator->getLon()); + AP_MavlinkCommand::home.setCommand(MAV_CMD_NAV_WAYPOINT); + AP_MavlinkCommand::home.save(); + _hal->debug->printf_P(PSTR("\nhome before load lat: %f deg, lon: %f deg, cmd: %d\n"), + AP_MavlinkCommand::home.getLat()*rad2Deg, + AP_MavlinkCommand::home.getLon()*rad2Deg, + AP_MavlinkCommand::home.getCommand()); + AP_MavlinkCommand::home.load(); + _hal->debug->printf_P(PSTR("\nhome after load lat: %f deg, lon: %f deg, cmd: %d\n"), + AP_MavlinkCommand::home.getLat()*rad2Deg, + AP_MavlinkCommand::home.getLon()*rad2Deg, + AP_MavlinkCommand::home.getCommand()); + + /* + * Attach loops + */ + hal->debug->println_P(PSTR("attaching loops")); + subLoops().push_back(new Loop(getLoopRate(1), callback1, this)); + subLoops().push_back(new Loop(getLoopRate(2), callback2, this)); + subLoops().push_back(new Loop(getLoopRate(3), callback3, this)); + subLoops().push_back(new Loop(getLoopRate(4), callback4, this)); + + hal->debug->println_P(PSTR("running")); + hal->gcs->sendText(SEVERITY_LOW, PSTR("running")); + + if (hal->getMode() == MODE_LIVE) { + hal->setState(MAV_STATE_ACTIVE); + } else { + hal->setState(MAV_STATE_HILSIM); + } + + /* + * Radio setup + */ + hal->debug->println_P(PSTR("initializing radio")); + APM_RC.Init(); // APM Radio initialization, + // start this after control loop is running +} + +void AP_Autopilot::callback0(void * data) { + AP_Autopilot * apo = (AP_Autopilot *) data; + //apo->hal()->debug->println_P(PSTR("callback 0")); + + /* + * ahrs update + */ + if (apo->getNavigator()) + apo->getNavigator()->updateFast(1.0 / apo->getLoopRate(0)); +} + +void AP_Autopilot::callback1(void * data) { + AP_Autopilot * apo = (AP_Autopilot *) data; + //apo->getHal()->debug->println_P(PSTR("callback 1")); + + /* + * hardware in the loop + */ + if (apo->getHal()->hil && apo->getHal()->getMode() != MODE_LIVE) { + apo->getHal()->hil->receive(); + apo->getHal()->hil->sendMessage(MAVLINK_MSG_ID_RC_CHANNELS_SCALED); + } + + /* + * update control laws + */ + if (apo->getController()) { + //apo->getHal()->debug->println_P(PSTR("updating controller")); + apo->getController()->update(1. / apo->getLoopRate(1)); + } + /* + char msg[50]; + sprintf(msg, "c_hdg: %f, c_thr: %f", apo->guide()->headingCommand, apo->guide()->groundSpeedCommand); + apo->hal()->gcs->sendText(AP_CommLink::SEVERITY_LOW, msg); + */ +} + +void AP_Autopilot::callback2(void * data) { + AP_Autopilot * apo = (AP_Autopilot *) data; + //apo->getHal()->debug->println_P(PSTR("callback 2")); + + /* + * update guidance laws + */ + if (apo->getGuide()) + { + //apo->getHal()->debug->println_P(PSTR("updating guide")); + apo->getGuide()->update(); + } + + /* + * send telemetry + */ + if (apo->getHal()->gcs) { + // send messages + apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_GPS_RAW); + apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_ATTITUDE); + //apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_RC_CHANNELS_SCALED); + //apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_GLOBAL_POSITION); + apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_RC_CHANNELS_RAW); + //apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_SCALED_IMU); + } + + /* + * slow navigation loop update + */ + if (apo->getNavigator()) { + apo->getNavigator()->updateSlow(1.0 / apo->getLoopRate(2)); + } + + /* + * handle ground control station communication + */ + if (apo->getHal()->gcs) { + // send messages + apo->getHal()->gcs->requestCmds(); + apo->getHal()->gcs->sendParameters(); + + // receive messages + apo->getHal()->gcs->receive(); + } + + /* + * navigator debug + */ + /* + if (apo->navigator()) { + apo->getHal()->debug->printf_P(PSTR("roll: %f deg\tpitch: %f deg\tyaw: %f deg\n"), + apo->navigator()->getRoll()*rad2Deg, + apo->navigator()->getPitch()*rad2Deg, + apo->navigator()->getYaw()*rad2Deg); + apo->getHal()->debug->printf_P(PSTR("lat: %f deg\tlon: %f deg\talt: %f m\n"), + apo->navigator()->getLat()*rad2Deg, + apo->navigator()->getLon()*rad2Deg, + apo->navigator()->getAlt()); + } + */ +} + +void AP_Autopilot::callback3(void * data) { + AP_Autopilot * apo = (AP_Autopilot *) data; + //apo->getHal()->debug->println_P(PSTR("callback 3")); + + /* + * send heartbeat + */ + apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_HEARTBEAT); + + /* + * load/loop rate/ram debug + */ + apo->getHal()->load = apo->load(); + apo->getHal()->debug->printf_P(PSTR("load: %d%%\trate: %f Hz\tfree ram: %d bytes\n"), + apo->load(),1.0/apo->dt(),freeMemory()); + + apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_SYS_STATUS); + + /* + * adc debug + */ + //apo->getDebug().printf_P(PSTR("adc: %d %d %d %d %d %d %d %d\n"), + //apo->adc()->Ch(0), apo->adc()->Ch(1), apo->adc()->Ch(2), + //apo->adc()->Ch(3), apo->adc()->Ch(4), apo->adc()->Ch(5), + //apo->adc()->Ch(6), apo->adc()->Ch(7), apo->adc()->Ch(8)); +} + +void AP_Autopilot::callback4(void * data) { + //AP_Autopilot * apo = (AP_Autopilot *) data; + //apo->getHal()->debug->println_P(PSTR("callback 4")); +} + +} // apo diff --git a/libraries/APO/AP_Autopilot.h b/libraries/APO/AP_Autopilot.h new file mode 100644 index 0000000000..08daf19f57 --- /dev/null +++ b/libraries/APO/AP_Autopilot.h @@ -0,0 +1,165 @@ +/* + * AP_Autopilot.h + * + * Created on: Apr 30, 2011 + * Author: jgoppert + */ + +#ifndef AP_AUTOPILOT_H_ +#define AP_AUTOPILOT_H_ + +/* + * AVR runtime + */ +#include +#include +#include +#include +/* + * Libraries + */ +#include "../AP_Common/AP_Common.h" +#include "../FastSerial/FastSerial.h" +#include "../AP_GPS/GPS.h" +#include "../APM_RC/APM_RC.h" +#include "../AP_ADC/AP_ADC.h" +#include "../APM_BMP085/APM_BMP085.h" +#include "../AP_Compass/AP_Compass.h" +#include "../AP_Math/AP_Math.h" +#include "../AP_IMU/AP_IMU.h" +#include "../AP_DCM/AP_DCM.h" +#include "../AP_Common/AP_Loop.h" +#include "../GCS_MAVLink/GCS_MAVLink.h" +#include "../AP_RangeFinder/AP_RangeFinder.h" +/* + * Local Modules + */ +#include "AP_HardwareAbstractionLayer.h" +#include "AP_RcChannel.h" +#include "AP_Controller.h" +#include "AP_Navigator.h" +#include "AP_Guide.h" +#include "AP_CommLink.h" + +/** + * ArduPilotOne namespace to protect variables + * from overlap with avr and libraries etc. + * ArduPilotOne does not use any global + * variables. + */ +namespace apo { + +// forward declarations +class AP_CommLink; + +/** + * This class encapsulates the entire autopilot system + * The constructor takes guide, navigator, and controller + * as well as the hardware abstraction layer. + * + * It inherits from loop to manage + * the sub-loops and sets the overall + * frequency for the autopilot. + * + + */ +class AP_Autopilot: public Loop { +public: + /** + * Default constructor + */ + AP_Autopilot(AP_Navigator * navigator, AP_Guide * guide, + AP_Controller * controller, AP_HardwareAbstractionLayer * hal, + float loop0Rate, float loop1Rate, float loop2Rate, float loop3Rate); + + /** + * Accessors + */ + AP_Navigator * getNavigator() { + return _navigator; + } + AP_Guide * getGuide() { + return _guide; + } + AP_Controller * getController() { + return _controller; + } + AP_HardwareAbstractionLayer * getHal() { + return _hal; + } + + float getLoopRate(uint8_t i) { + switch(i) { + case 0: return _loop0Rate; + case 1: return _loop1Rate; + case 2: return _loop2Rate; + case 3: return _loop3Rate; + case 4: return _loop4Rate; + default: return 0; + } + } + +private: + + /** + * Loop 0 Callbacks (fastest) + * - inertial navigation + * @param data A void pointer used to pass the apo class + * so that the apo public interface may be accessed. + */ + static void callback0(void * data); + float _loop0Rate; + + /** + * Loop 1 Callbacks + * - control + * - compass reading + * @see callback0 + */ + static void callback1(void * data); + float _loop1Rate; + + /** + * Loop 2 Callbacks + * - gps sensor fusion + * - compass sensor fusion + * @see callback0 + */ + static void callback2(void * data); + float _loop2Rate; + + /** + * Loop 3 Callbacks + * - slow messages + * @see callback0 + */ + static void callback3(void * data); + float _loop3Rate; + + /** + * Loop 4 Callbacks + * - super slow messages + * - log writing + * @see callback0 + */ + static void callback4(void * data); + float _loop4Rate; + + /** + * Components + */ + AP_Navigator * _navigator; + AP_Guide * _guide; + AP_Controller * _controller; + AP_HardwareAbstractionLayer * _hal; + + /** + * Constants + */ + static const float deg2rad = M_PI / 180; + static const float rad2deg = 180 / M_PI; +}; + +} // namespace apo + +#endif /* AP_AUTOPILOT_H_ */ diff --git a/libraries/APO/AP_CommLink.cpp b/libraries/APO/AP_CommLink.cpp new file mode 100644 index 0000000000..92b9d0fdde --- /dev/null +++ b/libraries/APO/AP_CommLink.cpp @@ -0,0 +1,15 @@ +/* + * AP_CommLink.cpp + * + * Created on: Apr 30, 2011 + * Author: jgoppert + */ + +#include "AP_CommLink.h" + +namespace apo { + +uint8_t MavlinkComm::_nChannels = 0; +uint8_t MavlinkComm::_paramNameLengthMax = 13; + +} // apo diff --git a/libraries/APO/AP_CommLink.h b/libraries/APO/AP_CommLink.h new file mode 100644 index 0000000000..b40641b143 --- /dev/null +++ b/libraries/APO/AP_CommLink.h @@ -0,0 +1,789 @@ +/* + * AP_CommLink.h + * Copyright (C) James Goppert 2010 + * + * This file 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 file 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 . + */ + +#ifndef AP_CommLink_H +#define AP_CommLink_H + +#include "AP_HardwareAbstractionLayer.h" +#include "AP_MavlinkCommand.h" +#include "AP_Controller.h" + +namespace apo { + +class AP_Controller; +class AP_Navigator; +class AP_Guide; +class AP_HardwareAbstractionLayer; + +enum { + SEVERITY_LOW, SEVERITY_MED, SEVERITY_HIGH +}; + +// forward declarations +//class ArduPilotOne; +//class AP_Controller; + +/// CommLink class +class AP_CommLink { +public: + + AP_CommLink(FastSerial * link, AP_Navigator * navigator, AP_Guide * guide, + AP_Controller * controller, AP_HardwareAbstractionLayer * hal) : + _link(link), _navigator(navigator), _guide(guide), + _controller(controller), _hal(hal) { + } + virtual void send() = 0; + virtual void receive() = 0; + virtual void sendMessage(uint8_t id, uint32_t param = 0) = 0; + virtual void sendText(uint8_t severity, const char *str) = 0; + virtual void sendText(uint8_t severity, const prog_char_t *str) = 0; + virtual void acknowledge(uint8_t id, uint8_t sum1, uint8_t sum2) = 0; + virtual void sendParameters() = 0; + virtual void requestCmds() = 0; + +protected: + FastSerial * _link; + AP_Navigator * _navigator; + AP_Guide * _guide; + AP_Controller * _controller; + AP_HardwareAbstractionLayer * _hal; +}; + +class MavlinkComm: public AP_CommLink { +public: + MavlinkComm(FastSerial * link, AP_Navigator * nav, AP_Guide * guide, + AP_Controller * controller, AP_HardwareAbstractionLayer * hal) : + AP_CommLink(link, nav, guide, controller, hal), + + // options + _useRelativeAlt(true), + + // commands + _sendingCmds(false), _receivingCmds(false), + _cmdTimeLastSent(millis()), _cmdTimeLastReceived(millis()), + _cmdDestSysId(0), _cmdDestCompId(0), _cmdRequestIndex(0), + _cmdMax(30), _cmdNumberRequested(0), + + // parameters + _parameterCount(0), _queuedParameter(NULL), + _queuedParameterIndex(0) { + + switch (_nChannels) { + case 0: + mavlink_comm_0_port = link; + _channel = MAVLINK_COMM_0; + _nChannels++; + break; + case 1: + mavlink_comm_1_port = link; + _channel = MAVLINK_COMM_1; + _nChannels++; + break; + default: + // signal that number of channels exceeded + _channel = MAVLINK_COMM_3; + break; + } + } + + virtual void send() { + // if number of channels exceeded return + if (_channel == MAVLINK_COMM_3) + return; + } + + void sendMessage(uint8_t id, uint32_t param = 0) { + //_hal->debug->printf_P(PSTR("send message\n")); + + // if number of channels exceeded return + if (_channel == MAVLINK_COMM_3) + return; + + uint64_t timeStamp = micros(); + + switch (id) { + + case MAVLINK_MSG_ID_HEARTBEAT: { + mavlink_msg_heartbeat_send(_channel, mavlink_system.type, + MAV_AUTOPILOT_ARDUPILOTMEGA); + break; + } + + case MAVLINK_MSG_ID_ATTITUDE: { + mavlink_msg_attitude_send(_channel, timeStamp, + _navigator->getRoll(), _navigator->getPitch(), + _navigator->getYaw(), _navigator->getRollRate(), + _navigator->getPitchRate(), _navigator->getYawRate()); + break; + } + + case MAVLINK_MSG_ID_GLOBAL_POSITION: { + mavlink_msg_global_position_send(_channel, timeStamp, + _navigator->getLat() * rad2Deg, + _navigator->getLon() * rad2Deg, _navigator->getAlt(), + _navigator->getVN(), _navigator->getVE(), + _navigator->getVD()); + break; + } + + case MAVLINK_MSG_ID_GPS_RAW: { + mavlink_msg_gps_raw_send(_channel, timeStamp, _hal->gps->status(), + _navigator->getLat() * rad2Deg, + _navigator->getLon() * rad2Deg, _navigator->getAlt(), 0, 0, + _navigator->getGroundSpeed(), + _navigator->getYaw() * rad2Deg); + break; + } + + /* + case MAVLINK_MSG_ID_GPS_RAW_INT: { + mavlink_msg_gps_raw_int_send(_channel,timeStamp,_hal->gps->status(), + _navigator->getLat_degInt(), _navigator->getLon_degInt(),_navigator->getAlt_intM(), 0,0, + _navigator->getGroundSpeed(),_navigator->getYaw()*rad2Deg); + break; + } + */ + + case MAVLINK_MSG_ID_SCALED_IMU: { + /* + * accel/gyro debug + */ + /* + Vector3f accel = _hal->imu->get_accel(); + Vector3f gyro = _hal->imu->get_gyro(); + Serial.printf_P(PSTR("accel: %f %f %f gyro: %f %f %f\n"), + accel.x,accel.y,accel.z,gyro.x,gyro.y,gyro.z); + */ + Vector3f accel = _hal->imu->get_accel(); + Vector3f gyro = _hal->imu->get_gyro(); + mavlink_msg_raw_imu_send(_channel, timeStamp, 1000 * accel.x, + 1000 * accel.y, 1000 * accel.z, 1000 * gyro.x, + 1000 * gyro.y, 1000 * gyro.z, _hal->compass->mag_x, + _hal->compass->mag_y, _hal->compass->mag_z); // XXX THIS IS NOT SCALED FOR MAG + } + + case MAVLINK_MSG_ID_RC_CHANNELS_SCALED: { + int16_t ch[8]; + for (int i = 0; i < 8; i++) + ch[i] = 0; + for (uint8_t i = 0; i < 8 && i < _hal->rc.getSize(); i++) { + ch[i] = 10000 * _hal->rc[i]->getPosition(); + //_hal->debug->printf_P(PSTR("ch: %d position: %d\n"),i,ch[i]); + } + mavlink_msg_rc_channels_scaled_send(_channel, ch[0], ch[1], ch[2], + ch[3], ch[4], ch[5], ch[6], ch[7], 255); + break; + } + + case MAVLINK_MSG_ID_RC_CHANNELS_RAW: { + int16_t ch[8]; + for (int i = 0; i < 8; i++) + ch[i] = 0; + for (uint8_t i = 0; i < 8 && i < _hal->rc.getSize(); i++) + ch[i] = _hal->rc[i]->getPwm(); + mavlink_msg_rc_channels_raw_send(_channel, ch[0], ch[1], ch[2], + ch[3], ch[4], ch[5], ch[6], ch[7], 255); + break; + } + + case MAVLINK_MSG_ID_SYS_STATUS: { + + float batteryVoltage, temp; + temp = analogRead(0); + batteryVoltage = ((temp * 5 / 1023) / 0.28); + + mavlink_msg_sys_status_send(_channel, _controller->getMode(), + _guide->getMode(), _hal->getState(), _hal->load * 10, + batteryVoltage * 1000, + (batteryVoltage - 3.3) / (4.2 - 3.3) * 1000, _packetDrops); + break; + } + + case MAVLINK_MSG_ID_WAYPOINT_ACK: { + sendText(SEVERITY_LOW, PSTR("waypoint ack")); + //mavlink_waypoint_ack_t packet; + uint8_t type = 0; // ok (0), error(1) + mavlink_msg_waypoint_ack_send(_channel, _cmdDestSysId, + _cmdDestCompId, type); + + // turn off waypoint send + _receivingCmds = false; + break; + } + + case MAVLINK_MSG_ID_WAYPOINT_CURRENT: { + mavlink_msg_waypoint_current_send(_channel, + _guide->getCurrentIndex()); + break; + } + + default: { + char msg[50]; + sprintf(msg, "autopilot sending unknown command with id: %d", id); + sendText(SEVERITY_HIGH, msg); + } + + } // switch + } // send message + + virtual void receive() { + //_hal->debug->printf_P(PSTR("receive\n")); + // if number of channels exceeded return + // + if (_channel == MAVLINK_COMM_3) + return; + + // receive new packets + mavlink_message_t msg; + mavlink_status_t status; + + // process received bytes + while (comm_get_available(_channel)) { + uint8_t c = comm_receive_ch(_channel); + + // Try to get a new message + if (mavlink_parse_char(_channel, c, &msg, &status)) + _handleMessage(&msg); + } + + // Update packet drops counter + _packetDrops += status.packet_rx_drop_count; + } + + void sendText(uint8_t severity, const char *str) { + mavlink_msg_statustext_send(_channel, severity, (const int8_t*) str); + } + + void sendText(uint8_t severity, const prog_char_t *str) { + mavlink_statustext_t m; + uint8_t i; + for (i = 0; i < sizeof(m.text); i++) { + m.text[i] = pgm_read_byte((const prog_char *) (str++)); + } + if (i < sizeof(m.text)) + m.text[i] = 0; + sendText(severity, (const char *) m.text); + } + + void acknowledge(uint8_t id, uint8_t sum1, uint8_t sum2) { + } + + /** + * sends parameters one at a time + */ + void sendParameters() { + //_hal->debug->printf_P(PSTR("send parameters\n")); + // Check to see if we are sending parameters + while (NULL != _queuedParameter) { + AP_Var *vp; + float value; + + // copy the current parameter and prepare to move to the next + vp = _queuedParameter; + _queuedParameter = _queuedParameter->next(); + + // if the parameter can be cast to float, report it here and break out of the loop + value = vp->cast_to_float(); + if (!isnan(value)) { + + char paramName[_paramNameLengthMax]; + vp->copy_name(paramName, sizeof(paramName)); + + mavlink_msg_param_value_send(_channel, (int8_t*) paramName, + value, _countParameters(), _queuedParameterIndex); + + _queuedParameterIndex++; + break; + } + } + + } + + /** + * request commands one at a time + */ + void requestCmds() { + //_hal->debug->printf_P(PSTR("requesting commands\n")); + // request cmds one by one + if (_receivingCmds && _cmdRequestIndex <= _cmdNumberRequested) { + mavlink_msg_waypoint_request_send(_channel, _cmdDestSysId, + _cmdDestCompId, _cmdRequestIndex); + } + } + +private: + + // options + bool _useRelativeAlt; + + // commands + bool _sendingCmds; + bool _receivingCmds; + uint16_t _cmdTimeLastSent; + uint16_t _cmdTimeLastReceived; + uint16_t _cmdDestSysId; + uint16_t _cmdDestCompId; + uint16_t _cmdRequestIndex; + uint16_t _cmdNumberRequested; + uint16_t _cmdMax; + Vector _cmdList; + + // parameters + static uint8_t _paramNameLengthMax; + uint16_t _parameterCount; + AP_Var * _queuedParameter; + uint16_t _queuedParameterIndex; + + // channel + mavlink_channel_t _channel; + uint16_t _packetDrops; + static uint8_t _nChannels; + + void _handleMessage(mavlink_message_t * msg) { + + uint32_t timeStamp = micros(); + + switch (msg->msgid) { + _hal->debug->printf_P(PSTR("message received: %d"), msg->msgid); + + case MAVLINK_MSG_ID_HEARTBEAT: { + mavlink_heartbeat_t packet; + mavlink_msg_heartbeat_decode(msg, &packet); + _hal->lastHeartBeat = micros(); + break; + } + + case MAVLINK_MSG_ID_GPS_RAW: { + // decode + mavlink_gps_raw_t packet; + mavlink_msg_gps_raw_decode(msg, &packet); + + _navigator->setTimeStamp(timeStamp); + _navigator->setLat(packet.lat * deg2Rad); + _navigator->setLon(packet.lon * deg2Rad); + _navigator->setAlt(packet.alt); + _navigator->setYaw(packet.hdg * deg2Rad); + _navigator->setGroundSpeed(packet.v); + _navigator->setAirSpeed(packet.v); + //_hal->debug->printf_P(PSTR("received hil gps raw packet\n")); + /* + _hal->debug->printf_P(PSTR("received lat: %f deg\tlon: %f deg\talt: %f m\n"), + packet.lat, + packet.lon, + packet.alt); + */ + break; + } + + case MAVLINK_MSG_ID_ATTITUDE: { + // decode + mavlink_attitude_t packet; + mavlink_msg_attitude_decode(msg, &packet); + + // set dcm hil sensor + _navigator->setTimeStamp(timeStamp); + _navigator->setRoll(packet.roll); + _navigator->setPitch(packet.pitch); + _navigator->setYaw(packet.yaw); + _navigator->setRollRate(packet.rollspeed); + _navigator->setPitchRate(packet.pitchspeed); + _navigator->setYawRate(packet.yawspeed); + //_hal->debug->printf_P(PSTR("received hil attitude packet\n")); + break; + } + + case MAVLINK_MSG_ID_ACTION: { + // decode + mavlink_action_t packet; + mavlink_msg_action_decode(msg, &packet); + if (_checkTarget(packet.target, packet.target_component)) + break; + + // do action + sendText(SEVERITY_LOW, PSTR("action received")); + switch (packet.action) { + + case MAV_ACTION_STORAGE_READ: + AP_Var::load_all(); + break; + + case MAV_ACTION_STORAGE_WRITE: + AP_Var::save_all(); + break; + + case MAV_ACTION_CALIBRATE_RC: + case MAV_ACTION_CALIBRATE_GYRO: + case MAV_ACTION_CALIBRATE_MAG: + case MAV_ACTION_CALIBRATE_ACC: + case MAV_ACTION_CALIBRATE_PRESSURE: + case MAV_ACTION_REBOOT: + case MAV_ACTION_REC_START: + case MAV_ACTION_REC_PAUSE: + case MAV_ACTION_REC_STOP: + case MAV_ACTION_TAKEOFF: + case MAV_ACTION_LAND: + case MAV_ACTION_NAVIGATE: + case MAV_ACTION_LOITER: + case MAV_ACTION_MOTORS_START: + case MAV_ACTION_CONFIRM_KILL: + case MAV_ACTION_EMCY_KILL: + case MAV_ACTION_MOTORS_STOP: + case MAV_ACTION_SHUTDOWN: + case MAV_ACTION_CONTINUE: + case MAV_ACTION_SET_MANUAL: + case MAV_ACTION_SET_AUTO: + case MAV_ACTION_LAUNCH: + case MAV_ACTION_RETURN: + case MAV_ACTION_EMCY_LAND: + case MAV_ACTION_HALT: + sendText(SEVERITY_LOW, PSTR("action not implemented")); + break; + default: + sendText(SEVERITY_LOW, PSTR("unknown action")); + break; + } + break; + } + + case MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST: { + sendText(SEVERITY_LOW, PSTR("waypoint request list")); + + // decode + mavlink_waypoint_request_list_t packet; + mavlink_msg_waypoint_request_list_decode(msg, &packet); + if (_checkTarget(packet.target_system, packet.target_component)) + break; + + // Start sending waypoints + mavlink_msg_waypoint_count_send(_channel, msg->sysid, msg->compid, + _guide->getNumberOfCommands()); + + _cmdTimeLastSent = millis(); + _cmdTimeLastReceived = millis(); + _sendingCmds = true; + _receivingCmds = false; + _cmdDestSysId = msg->sysid; + _cmdDestCompId = msg->compid; + break; + } + + case MAVLINK_MSG_ID_WAYPOINT_REQUEST: { + sendText(SEVERITY_LOW, PSTR("waypoint request")); + + // Check if sending waypiont + if (!_sendingCmds) + break; + + // decode + mavlink_waypoint_request_t packet; + mavlink_msg_waypoint_request_decode(msg, &packet); + if (_checkTarget(packet.target_system, packet.target_component)) + break; + + _hal->debug->printf_P(PSTR("sequence: %d\n"),packet.seq); + AP_MavlinkCommand cmd(packet.seq); + + mavlink_waypoint_t wp = cmd.convert(_guide->getCurrentIndex()); + mavlink_msg_waypoint_send(_channel, _cmdDestSysId, _cmdDestCompId, + wp.seq, wp.frame, wp.command, wp.current, wp.autocontinue, + wp.param1, wp.param2, wp.param3, wp.param4, wp.x, wp.y, + wp.z); + + // update last waypoint comm stamp + _cmdTimeLastSent = millis(); + break; + } + + case MAVLINK_MSG_ID_WAYPOINT_ACK: { + sendText(SEVERITY_LOW, PSTR("waypoint ack")); + + // decode + mavlink_waypoint_ack_t packet; + mavlink_msg_waypoint_ack_decode(msg, &packet); + if (_checkTarget(packet.target_system, packet.target_component)) + break; + + // check for error + //uint8_t type = packet.type; // ok (0), error(1) + + // turn off waypoint send + _sendingCmds = false; + break; + } + + case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: { + sendText(SEVERITY_LOW, PSTR("param request list")); + + // decode + mavlink_param_request_list_t packet; + mavlink_msg_param_request_list_decode(msg, &packet); + if (_checkTarget(packet.target_system, packet.target_component)) + break; + + // Start sending parameters - next call to ::update will kick the first one out + + _queuedParameter = AP_Var::first(); + _queuedParameterIndex = 0; + break; + } + + case MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL: { + sendText(SEVERITY_LOW, PSTR("waypoint clear all")); + + // decode + mavlink_waypoint_clear_all_t packet; + mavlink_msg_waypoint_clear_all_decode(msg, &packet); + if (_checkTarget(packet.target_system, packet.target_component)) + break; + + // clear all waypoints + uint8_t type = 0; // ok (0), error(1) + _guide->setNumberOfCommands(1); + _guide->setCurrentIndex(0); + + // send acknowledgement 3 times to makes sure it is received + for (int i = 0; i < 3; i++) + mavlink_msg_waypoint_ack_send(_channel, msg->sysid, + msg->compid, type); + + break; + } + + case MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT: { + sendText(SEVERITY_LOW, PSTR("waypoint set current")); + + // decode + mavlink_waypoint_set_current_t packet; + mavlink_msg_waypoint_set_current_decode(msg, &packet); + Serial.print("Packet Sequence:"); + Serial.println(packet.seq); + if (_checkTarget(packet.target_system, packet.target_component)) + break; + + // set current waypoint + Serial.print("Current Index:"); + Serial.println(_guide->getCurrentIndex()); + Serial.flush(); + _guide->setCurrentIndex(packet.seq); + mavlink_msg_waypoint_current_send(_channel, + _guide->getCurrentIndex()); + break; + } + + case MAVLINK_MSG_ID_WAYPOINT_COUNT: { + sendText(SEVERITY_LOW, PSTR("waypoint count")); + + // decode + mavlink_waypoint_count_t packet; + mavlink_msg_waypoint_count_decode(msg, &packet); + if (_checkTarget(packet.target_system, packet.target_component)) + break; + + // start waypoint receiving + if (packet.count > _cmdMax) { + packet.count = _cmdMax; + } + _cmdNumberRequested = packet.count; + _cmdTimeLastReceived = millis(); + _receivingCmds = true; + _sendingCmds = false; + _cmdRequestIndex = 0; + break; + } + + case MAVLINK_MSG_ID_WAYPOINT: { + sendText(SEVERITY_LOW, PSTR("waypoint")); + + // Check if receiving waypiont + if (!_receivingCmds) { + //sendText(SEVERITY_HIGH, PSTR("not receiving commands")); + break; + } + + // decode + mavlink_waypoint_t packet; + mavlink_msg_waypoint_decode(msg, &packet); + if (_checkTarget(packet.target_system, packet.target_component)) + break; + + // check if this is the requested waypoint + if (packet.seq != _cmdRequestIndex) { + char warningMsg[50]; + sprintf(warningMsg, + "waypoint request out of sequence: (packet) %d / %d (ap)", + packet.seq, _cmdRequestIndex); + sendText(SEVERITY_HIGH, warningMsg); + break; + } + + _hal->debug->printf_P(PSTR("received waypoint x: %f\ty: %f\tz: %f\n"), + packet.x, + packet.y, + packet.z); + + // store waypoint + AP_MavlinkCommand command(packet); + //sendText(SEVERITY_HIGH, PSTR("waypoint stored")); + _cmdRequestIndex++; + if (_cmdRequestIndex == _cmdNumberRequested) { + sendMessage(MAVLINK_MSG_ID_WAYPOINT_ACK); + _receivingCmds = false; + _guide->setNumberOfCommands(_cmdNumberRequested); + //sendText(SEVERITY_LOW, PSTR("waypoint ack sent")); + } else if (_cmdRequestIndex > _cmdNumberRequested) { + _receivingCmds = false; + } + _cmdTimeLastReceived = millis(); + break; + } + + case MAVLINK_MSG_ID_PARAM_SET: { + sendText(SEVERITY_LOW, PSTR("param set")); + AP_Var *vp; + AP_Meta_class::Type_id var_type; + + // decode + mavlink_param_set_t packet; + mavlink_msg_param_set_decode(msg, &packet); + if (_checkTarget(packet.target_system, packet.target_component)) + break; + + // set parameter + + char key[_paramNameLengthMax + 1]; + strncpy(key, (char *) packet.param_id, _paramNameLengthMax); + key[_paramNameLengthMax] = 0; + + // find the requested parameter + vp = AP_Var::find(key); + if ((NULL != vp) && // exists + !isnan(packet.param_value) && // not nan + !isinf(packet.param_value)) { // not inf + + // add a small amount before casting parameter values + // from float to integer to avoid truncating to the + // next lower integer value. + const float rounding_addition = 0.01; + + // fetch the variable type ID + var_type = vp->meta_type_id(); + + // handle variables with standard type IDs + if (var_type == AP_Var::k_typeid_float) { + ((AP_Float *) vp)->set_and_save(packet.param_value); + + } else if (var_type == AP_Var::k_typeid_float16) { + ((AP_Float16 *) vp)->set_and_save(packet.param_value); + + } else if (var_type == AP_Var::k_typeid_int32) { + ((AP_Int32 *) vp)->set_and_save( + packet.param_value + rounding_addition); + + } else if (var_type == AP_Var::k_typeid_int16) { + ((AP_Int16 *) vp)->set_and_save( + packet.param_value + rounding_addition); + + } else if (var_type == AP_Var::k_typeid_int8) { + ((AP_Int8 *) vp)->set_and_save( + packet.param_value + rounding_addition); + } else { + // we don't support mavlink set on this parameter + break; + } + + // Report back the new value if we accepted the change + // we send the value we actually set, which could be + // different from the value sent, in case someone sent + // a fractional value to an integer type + mavlink_msg_param_value_send(_channel, (int8_t *) key, + vp->cast_to_float(), _countParameters(), -1); // XXX we don't actually know what its index is... + } + + break; + } // end case + + + } + } + + uint16_t _countParameters() { + // if we haven't cached the parameter count yet... + if (0 == _parameterCount) { + AP_Var *vp; + + vp = AP_Var::first(); + do { + // if a parameter responds to cast_to_float then we are going to be able to report it + if (!isnan(vp->cast_to_float())) { + _parameterCount++; + } + } while (NULL != (vp = vp->next())); + } + return _parameterCount; + } + + AP_Var * _findParameter(uint16_t index) { + AP_Var *vp; + + vp = AP_Var::first(); + while (NULL != vp) { + + // if the parameter is reportable + if (!(isnan(vp->cast_to_float()))) { + // if we have counted down to the index we want + if (0 == index) { + // return the parameter + return vp; + } + // count off this parameter, as it is reportable but not + // the one we want + index--; + } + // and move to the next parameter + vp = vp->next(); + } + return NULL; + } + + // check the target + uint8_t _checkTarget(uint8_t sysid, uint8_t compid) { + /* + char msg[50]; + sprintf(msg, "target = %d / %d\tcomp = %d / %d", sysid, + mavlink_system.sysid, compid, mavlink_system.compid); + sendText(SEVERITY_LOW, msg); + */ + if (sysid != mavlink_system.sysid) { + //sendText(SEVERITY_LOW, PSTR("system id mismatch")); + return 1; + + } else if (compid != mavlink_system.compid) { + //sendText(SEVERITY_LOW, PSTR("component id mismatch")); + return 0; // XXX currently not receiving correct compid from gcs + + } else { + return 0; // no error + } + } + +}; + +} // namespace apo + +#endif // AP_CommLink_H +// vim:ts=4:sw=4:tw=78:expandtab diff --git a/libraries/APO/AP_Controller.cpp b/libraries/APO/AP_Controller.cpp new file mode 100644 index 0000000000..ebbd5ed524 --- /dev/null +++ b/libraries/APO/AP_Controller.cpp @@ -0,0 +1,8 @@ +/* + * AP_Controller.cpp + * + * Created on: Apr 30, 2011 + * Author: jgoppert + */ + +#include "AP_Controller.h" diff --git a/libraries/APO/AP_Controller.h b/libraries/APO/AP_Controller.h new file mode 100644 index 0000000000..d7dac0c60c --- /dev/null +++ b/libraries/APO/AP_Controller.h @@ -0,0 +1,304 @@ +/* + * AP_Controller.h + * Copyright (C) James Goppert 2010 + * + * This file 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 file 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 . + */ + +#ifndef AP_Controller_H +#define AP_Controller_H + +#include "AP_Navigator.h" +#include "AP_Guide.h" +#include "AP_HardwareAbstractionLayer.h" +#include "../AP_Common/AP_Vector.h" +#include "../AP_Common/AP_Var.h" + +namespace apo { + +/// Controller class +class AP_Controller { +public: + AP_Controller(AP_Navigator * nav, AP_Guide * guide, + AP_HardwareAbstractionLayer * hal) : + _nav(nav), _guide(guide), _hal(hal) { + } + + virtual void update(const float & dt) = 0; + + virtual MAV_MODE getMode() = 0; + + void setAllRadioChannelsToNeutral() { + for (uint8_t i = 0; i < _hal->rc.getSize(); i++) { + _hal->rc[i]->setPosition(0.0); + } + } + + void setAllRadioChannelsManually() { + for (uint8_t i = 0; i < _hal->rc.getSize(); i++) { + _hal->rc[i]->setUsingRadio(); + } + } + +protected: + AP_Navigator * _nav; + AP_Guide * _guide; + AP_HardwareAbstractionLayer * _hal; +}; + +class AP_ControllerBlock { +public: + AP_ControllerBlock(AP_Var_group * group, uint8_t groupStart, + uint8_t groupLength) : + _group(group), _groupStart(groupStart), + _groupEnd(groupStart + groupLength) { + } + uint8_t getGroupEnd() { + return _groupEnd; + } +protected: + AP_Var_group * _group; /// helps with parameter management + uint8_t _groupStart; + uint8_t _groupEnd; +}; + +class BlockLowPass: public AP_ControllerBlock { +public: + BlockLowPass(AP_Var_group * group, uint8_t groupStart, float fCut, + const prog_char_t * fCutLabel = NULL) : + AP_ControllerBlock(group, groupStart, 1), + _fCut(group, groupStart, fCut, fCutLabel ? : PSTR("fCut")), + _y(0) { + } + float update(const float & input, const float & dt) { + float RC = 1 / (2 * M_PI * _fCut); // low pass filter + _y = _y + (input - _y) * (dt / (dt + RC)); + return _y; + } +protected: + AP_Float _fCut; + float _y; +}; + +class BlockSaturation: public AP_ControllerBlock { +public: + BlockSaturation(AP_Var_group * group, uint8_t groupStart, float yMax, + const prog_char_t * yMaxLabel = NULL) : + AP_ControllerBlock(group, groupStart, 1), + _yMax(group, groupStart, yMax, yMaxLabel ? : PSTR("yMax")) { + } + float update(const float & input) { + + // pid sum + float y = input; + + // saturation + if (y > _yMax) + y = _yMax; + if (y < -_yMax) + y = -_yMax; + return y; + } +protected: + AP_Float _yMax; /// output saturation +}; + +class BlockDerivative { +public: + BlockDerivative() : + _lastInput(0), firstRun(true) { + } + float update(const float & input, const float & dt) { + float derivative = (input - _lastInput) / dt; + _lastInput = input; + if (firstRun) { + firstRun = false; + return 0; + } else + return derivative; + } +protected: + float _lastInput; /// last input + bool firstRun; +}; + +class BlockIntegral { +public: + BlockIntegral() : + _i(0) { + } + float update(const float & input, const float & dt) { + _i += input * dt; + return _i; + } +protected: + float _i; /// integral +}; + +class BlockP: public AP_ControllerBlock { +public: + BlockP(AP_Var_group * group, uint8_t groupStart, float kP, + const prog_char_t * kPLabel = NULL) : + AP_ControllerBlock(group, groupStart, 1), + _kP(group, groupStart, kP, kPLabel ? : PSTR("p")) { + } + + float update(const float & input) { + return _kP * input; + } +protected: + AP_Float _kP; /// proportional gain +}; + +class BlockI: public AP_ControllerBlock { +public: + BlockI(AP_Var_group * group, uint8_t groupStart, float kI, float iMax, + const prog_char_t * kILabel = NULL, + const prog_char_t * iMaxLabel = NULL) : + AP_ControllerBlock(group, groupStart, 2), + _kI(group, groupStart, kI, kILabel ? : PSTR("i")), + _blockSaturation(group, groupStart + 1, iMax, iMaxLabel ? : PSTR("iMax")), + _eI(0) { + } + + float update(const float & input, const float & dt) { + // integral + _eI += input * dt; + _eI = _blockSaturation.update(_eI); + return _kI * _eI; + } +protected: + AP_Float _kI; /// integral gain + BlockSaturation _blockSaturation; /// integrator saturation + float _eI; /// integral of input +}; + +class BlockD: public AP_ControllerBlock { +public: + BlockD(AP_Var_group * group, uint8_t groupStart, float kD, uint8_t dFCut, + const prog_char_t * kDLabel = NULL, + const prog_char_t * dFCutLabel = NULL) : + AP_ControllerBlock(group, groupStart, 2), + _blockLowPass(group, groupStart, dFCut, + dFCutLabel ? : PSTR("dFCut")), + _kD(group, _blockLowPass.getGroupEnd(), kD, + kDLabel ? : PSTR("d")), _eP(0) { + } + float update(const float & input, const float & dt) { + // derivative with low pass + float _eD = _blockLowPass.update((_eP - input) / dt, dt); + // proportional, note must come after derivative + // because derivatve uses _eP as previous value + _eP = input; + return _kD * _eD; + } +protected: + BlockLowPass _blockLowPass; + AP_Float _kD; /// derivative gain + float _eP; /// input +}; + +class BlockPID: public AP_ControllerBlock { +public: + BlockPID(AP_Var_group * group, uint8_t groupStart, float kP, float kI, + float kD, float iMax, float yMax, uint8_t dFcut) : + AP_ControllerBlock(group, groupStart, 6), + _blockP(group, groupStart, kP), + _blockI(group, _blockP.getGroupEnd(), kI, iMax), + _blockD(group, _blockI.getGroupEnd(), kD, dFcut), + _blockSaturation(group, _blockD.getGroupEnd(), yMax) { + } + + float update(const float & input, const float & dt) { + return _blockSaturation.update( + _blockP.update(input) + _blockI.update(input, dt) + + _blockD.update(input, dt)); + } +protected: + BlockP _blockP; + BlockI _blockI; + BlockD _blockD; + BlockSaturation _blockSaturation; +}; + +class BlockPI: public AP_ControllerBlock { +public: + BlockPI(AP_Var_group * group, uint8_t groupStart, float kP, float kI, + float iMax, float yMax) : + AP_ControllerBlock(group, groupStart, 4), + _blockP(group, groupStart, kP), + _blockI(group, _blockP.getGroupEnd(), kI, iMax), + _blockSaturation(group, _blockI.getGroupEnd(), yMax) { + } + + float update(const float & input, const float & dt) { + + float y = _blockP.update(input) + _blockI.update(input, dt); + return _blockSaturation.update(y); + } +protected: + BlockP _blockP; + BlockI _blockI; + BlockSaturation _blockSaturation; +}; + +class BlockPD: public AP_ControllerBlock { +public: + BlockPD(AP_Var_group * group, uint8_t groupStart, float kP, float kI, + float kD, float iMax, float yMax, uint8_t dFcut) : + AP_ControllerBlock(group, groupStart, 4), + _blockP(group, groupStart, kP), + _blockD(group, _blockP.getGroupEnd(), kD, dFcut), + _blockSaturation(group, _blockD.getGroupEnd(), yMax) { + } + + float update(const float & input, const float & dt) { + + float y = _blockP.update(input) + _blockD.update(input, dt); + return _blockSaturation.update(y); + } +protected: + BlockP _blockP; + BlockD _blockD; + BlockSaturation _blockSaturation; +}; + +/// PID with derivative feedback (ignores reference derivative) +class BlockPIDDfb: public AP_ControllerBlock { +public: + BlockPIDDfb(AP_Var_group * group, uint8_t groupStart, float kP, float kI, + float kD, float iMax, float yMax, const prog_char_t * dLabel = NULL) : + AP_ControllerBlock(group, groupStart, 5), + _blockP(group, groupStart, kP), + _blockI(group, _blockP.getGroupEnd(), kI, iMax), + _blockSaturation(group, _blockI.getGroupEnd(), yMax), + _kD(group, _blockSaturation.getGroupEnd(), kD, dLabel ? : PSTR("d")) { + } + float update(const float & input, const float & derivative, + const float & dt) { + float y = _blockP.update(input) + _blockI.update(input, dt) - _kD + * derivative; + return _blockSaturation.update(y); + } +protected: + BlockP _blockP; + BlockI _blockI; + BlockSaturation _blockSaturation; + AP_Float _kD; /// derivative gain +}; + +} // apo + +#endif // AP_Controller_H +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/AP_Guide.cpp b/libraries/APO/AP_Guide.cpp new file mode 100644 index 0000000000..488b746610 --- /dev/null +++ b/libraries/APO/AP_Guide.cpp @@ -0,0 +1,8 @@ +/* + * AP_Guide.cpp + * + * Created on: Apr 30, 2011 + * Author: jgoppert + */ + +#include "AP_Guide.h" diff --git a/libraries/APO/AP_Guide.h b/libraries/APO/AP_Guide.h new file mode 100644 index 0000000000..8f5b61929b --- /dev/null +++ b/libraries/APO/AP_Guide.h @@ -0,0 +1,357 @@ +/* + * AP_Guide.h + * Copyright (C) James Goppert 2010 + * + * This file 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 file 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 . + */ + +#ifndef AP_Guide_H +#define AP_Guide_H + +#include "../GCS_MAVLink/GCS_MAVLink.h" +#include "AP_HardwareAbstractionLayer.h" +#include "AP_Navigator.h" +#include "../AP_Common/AP_Common.h" +#include "../AP_Common/AP_Vector.h" +#include "AP_MavlinkCommand.h" +#include "constants.h" + +//#include "AP_CommLink.h" + +namespace apo { + +/// Guide class +class AP_Guide { +public: + + /** + * This is the constructor, which requires a link to the navigator. + * @param navigator This is the navigator pointer. + */ + AP_Guide(AP_Navigator * navigator, AP_HardwareAbstractionLayer * hal) : + _navigator(navigator), _hal(hal), _command(AP_MavlinkCommand::home), + _previousCommand(AP_MavlinkCommand::home), + _headingCommand(0), _airSpeedCommand(0), + _groundSpeedCommand(0), _altitudeCommand(0), _pNCmd(0), + _pECmd(0), _pDCmd(0), _mode(MAV_NAV_LOST), + _numberOfCommands(1), _cmdIndex(0), _nextCommandCalls(0), + _nextCommandTimer(0) { + } + + virtual void update() = 0; + + virtual void nextCommand() = 0; + + MAV_NAV getMode() const { + return _mode; + } + uint8_t getCurrentIndex() { + return _cmdIndex; + } + + void setCurrentIndex(uint8_t val) { + _cmdIndex.set_and_save(val); + _command = AP_MavlinkCommand(getCurrentIndex()); + _previousCommand = AP_MavlinkCommand(getPreviousIndex()); + //_hal->gcs->sendMessage(MAVLINK_MSG_ID_WAYPOINT_CURRENT); + } + + uint8_t getNumberOfCommands() { + return _numberOfCommands; + } + + void setNumberOfCommands(uint8_t val) { + _numberOfCommands.set_and_save(val); + } + + uint8_t getPreviousIndex() { + // find previous waypoint, TODO, handle non-nav commands + int16_t prevIndex = int16_t(getCurrentIndex()) - 1; + if (prevIndex < 0) + prevIndex = getNumberOfCommands() - 1; + return (uint8_t) prevIndex; + } + + uint8_t getNextIndex() { + // find previous waypoint, TODO, handle non-nav commands + int16_t nextIndex = int16_t(getCurrentIndex()) + 1; + if (nextIndex > (getNumberOfCommands() - 1)) + nextIndex = 0; + return nextIndex; + } + + float getHeadingCommand() { + return _headingCommand; + } + float getAirSpeedCommand() { + return _airSpeedCommand; + } + float getGroundSpeedCommand() { + return _groundSpeedCommand; + } + float getAltitudeCommand() { + return _altitudeCommand; + } + float getPNCmd() { + return _pNCmd; + } + float getPECmd() { + return _pECmd; + } + float getPDCmd() { + return _pDCmd; + } + MAV_NAV getMode() { + return _mode; + } + uint8_t getCommandIndex() { + return _cmdIndex; + } + +protected: + AP_Navigator * _navigator; + AP_HardwareAbstractionLayer * _hal; + AP_MavlinkCommand _command, _previousCommand; + float _headingCommand; + float _airSpeedCommand; + float _groundSpeedCommand; + float _altitudeCommand; + float _pNCmd; + float _pECmd; + float _pDCmd; + MAV_NAV _mode; + AP_Uint8 _numberOfCommands; + AP_Uint8 _cmdIndex; + uint16_t _nextCommandCalls; + uint16_t _nextCommandTimer; +}; + +class MavlinkGuide: public AP_Guide { +public: + MavlinkGuide(AP_Navigator * navigator, + AP_HardwareAbstractionLayer * hal) : + AP_Guide(navigator, hal), _rangeFinderFront(), _rangeFinderBack(), + _rangeFinderLeft(), _rangeFinderRight(), + _group(k_guide, PSTR("guide_")), + _velocityCommand(&_group, 1, 1, PSTR("velCmd")), + _crossTrackGain(&_group, 2, 1, PSTR("xt")), + _crossTrackLim(&_group, 3, 90, PSTR("xtLim")) { + + for (uint8_t i = 0; i < _hal->rangeFinders.getSize(); i++) { + RangeFinder * rF = _hal->rangeFinders[i]; + if (rF == NULL) + continue; + if (rF->orientation_x == 1 && rF->orientation_y == 0 + && rF->orientation_z == 0) + _rangeFinderFront = rF; + else if (rF->orientation_x == -1 && rF->orientation_y == 0 + && rF->orientation_z == 0) + _rangeFinderBack = rF; + else if (rF->orientation_x == 0 && rF->orientation_y == 1 + && rF->orientation_z == 0) + _rangeFinderRight = rF; + else if (rF->orientation_x == 0 && rF->orientation_y == -1 + && rF->orientation_z == 0) + _rangeFinderLeft = rF; + + } + } + + virtual void update() { + // process mavlink commands + handleCommand(); + + // obstacle avoidance overrides + // stop if your going to drive into something in front of you + for (uint8_t i = 0; i < _hal->rangeFinders.getSize(); i++) + _hal->rangeFinders[i]->read(); + float frontDistance = _rangeFinderFront->distance / 200.0; //convert for other adc + if (_rangeFinderFront && frontDistance < 2) { + _mode = MAV_NAV_VECTOR; + + //airSpeedCommand = 0; + //groundSpeedCommand = 0; +// _headingCommand -= 45 * deg2Rad; +// _hal->debug->print("Obstacle Distance (m): "); +// _hal->debug->println(frontDistance); +// _hal->debug->print("Obstacle avoidance Heading Command: "); +// _hal->debug->println(headingCommand); +// _hal->debug->printf_P( +// PSTR("Front Distance, %f\n"), +// frontDistance); + } + if (_rangeFinderBack && _rangeFinderBack->distance < 5) { + _airSpeedCommand = 0; + _groundSpeedCommand = 0; + + } + + if (_rangeFinderLeft && _rangeFinderLeft->distance < 5) { + _airSpeedCommand = 0; + _groundSpeedCommand = 0; + } + + if (_rangeFinderRight && _rangeFinderRight->distance < 5) { + _airSpeedCommand = 0; + _groundSpeedCommand = 0; + } + } + + void nextCommand() { + // within 1 seconds, check if more than 5 calls to next command occur + // if they do, go to home waypoint + if (millis() - _nextCommandTimer < 1000) { + if (_nextCommandCalls > 5) { + Serial.println("commands loading too fast, returning home"); + setCurrentIndex(0); + setNumberOfCommands(1); + _nextCommandCalls = 0; + _nextCommandTimer = millis(); + return; + } + _nextCommandCalls++; + } else { + _nextCommandTimer = millis(); + _nextCommandCalls = 0; + } + + _cmdIndex = getNextIndex(); + //Serial.print("cmd : "); Serial.println(int(_cmdIndex)); + //Serial.print("cmd prev : "); Serial.println(int(getPreviousIndex())); + //Serial.print("cmd num : "); Serial.println(int(getNumberOfCommands())); + _command = AP_MavlinkCommand(getCurrentIndex()); + _previousCommand = AP_MavlinkCommand(getPreviousIndex()); + } + + void handleCommand() { + + // TODO handle more commands + switch (_command.getCommand()) { + + case MAV_CMD_NAV_WAYPOINT: { + + // if we don't have enough waypoint for cross track calcs + // go home + if (_numberOfCommands == 1) { + _mode = MAV_NAV_RETURNING; + _altitudeCommand = AP_MavlinkCommand::home.getAlt(); + _headingCommand = AP_MavlinkCommand::home.bearingTo( + _navigator->getLat_degInt(), _navigator->getLon_degInt()) + + 180 * deg2Rad; + if (_headingCommand > 360 * deg2Rad) + _headingCommand -= 360 * deg2Rad; + + //_hal->debug->printf_P(PSTR("going home: bearing: %f distance: %f\n"), + //headingCommand,AP_MavlinkCommand::home.distanceTo(_navigator->getLat_degInt(),_navigator->getLon_degInt())); + + // if we have 2 or more waypoints do x track navigation + } else { + _mode = MAV_NAV_WAYPOINT; + float alongTrack = _command.alongTrack(_previousCommand, + _navigator->getLat_degInt(), + _navigator->getLon_degInt()); + float distanceToNext = _command.distanceTo( + _navigator->getLat_degInt(), _navigator->getLon_degInt()); + float segmentLength = _previousCommand.distanceTo(_command); + if (distanceToNext < _command.getRadius() || alongTrack + > segmentLength) + { + Serial.println("waypoint reached"); + nextCommand(); + } + _altitudeCommand = _command.getAlt(); + float dXt = _command.crossTrack(_previousCommand, + _navigator->getLat_degInt(), + _navigator->getLon_degInt()); + float temp = dXt * _crossTrackGain * deg2Rad; // crosstrack gain, rad/m + if (temp > _crossTrackLim * deg2Rad) + temp = _crossTrackLim * deg2Rad; + if (temp < -_crossTrackLim * deg2Rad) + temp = -_crossTrackLim * deg2Rad; + float bearing = _previousCommand.bearingTo(_command); + _headingCommand = bearing - temp; + //_hal->debug->printf_P( + //PSTR("nav: bCurrent2Dest: %f\tdXt: %f\tcmdHeading: %f\tnextWpDistance: %f\talongTrack: %f\n"), + //bearing * rad2Deg, dXt, _headingCommand * rad2Deg, distanceToNext, alongTrack); + } + + _groundSpeedCommand = _velocityCommand; + + // calculate pN,pE,pD from home and gps coordinates + _pNCmd = _command.getPN(_navigator->getLat_degInt(), + _navigator->getLon_degInt()); + _pECmd = _command.getPE(_navigator->getLat_degInt(), + _navigator->getLon_degInt()); + _pDCmd = _command.getPD(_navigator->getAlt_intM()); + + // debug + //_hal->debug->printf_P( + //PSTR("guide loop, number: %d, current index: %d, previous index: %d\n"), + //getNumberOfCommands(), + //getCurrentIndex(), + //getPreviousIndex()); + + break; + } +// case MAV_CMD_CONDITION_CHANGE_ALT: +// case MAV_CMD_CONDITION_DELAY: +// case MAV_CMD_CONDITION_DISTANCE: +// case MAV_CMD_CONDITION_LAST: +// case MAV_CMD_CONDITION_YAW: +// case MAV_CMD_DO_CHANGE_SPEED: +// case MAV_CMD_DO_CONTROL_VIDEO: +// case MAV_CMD_DO_JUMP: +// case MAV_CMD_DO_LAST: +// case MAV_CMD_DO_LAST: +// case MAV_CMD_DO_REPEAT_RELAY: +// case MAV_CMD_DO_REPEAT_SERVO: +// case MAV_CMD_DO_SET_HOME: +// case MAV_CMD_DO_SET_MODE: +// case MAV_CMD_DO_SET_PARAMETER: +// case MAV_CMD_DO_SET_RELAY: +// case MAV_CMD_DO_SET_SERVO: +// case MAV_CMD_PREFLIGHT_CALIBRATION: +// case MAV_CMD_PREFLIGHT_STORAGE: +// case MAV_CMD_NAV_LAND: +// case MAV_CMD_NAV_LAST: +// case MAV_CMD_NAV_LOITER_TIME: +// case MAV_CMD_NAV_LOITER_TURNS: +// case MAV_CMD_NAV_LOITER_UNLIM: +// case MAV_CMD_NAV_ORIENTATION_TARGET: +// case MAV_CMD_NAV_PATHPLANNING: +// case MAV_CMD_NAV_RETURN_TO_LAUNCH: +// case MAV_CMD_NAV_TAKEOFF: + default: + // unhandled command, skip + Serial.println("unhandled command"); + nextCommand(); + break; + } + } +private: + RangeFinder * _rangeFinderFront; + RangeFinder * _rangeFinderBack; + RangeFinder * _rangeFinderLeft; + RangeFinder * _rangeFinderRight; + AP_Var_group _group; + AP_Float _velocityCommand; + AP_Float _crossTrackGain; + AP_Float _crossTrackLim; +}; + +} // namespace apo + +#endif // AP_Guide_H + +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/AP_HardwareAbstractionLayer.cpp b/libraries/APO/AP_HardwareAbstractionLayer.cpp new file mode 100644 index 0000000000..afa06769ab --- /dev/null +++ b/libraries/APO/AP_HardwareAbstractionLayer.cpp @@ -0,0 +1,8 @@ +/* + * AP_HardwareAbstractionLayer.cpp + * + * Created on: Apr 30, 2011 + * Author: jgoppert + */ + +#include "AP_HardwareAbstractionLayer.h" diff --git a/libraries/APO/AP_HardwareAbstractionLayer.h b/libraries/APO/AP_HardwareAbstractionLayer.h new file mode 100644 index 0000000000..45e7daaf75 --- /dev/null +++ b/libraries/APO/AP_HardwareAbstractionLayer.h @@ -0,0 +1,166 @@ +/* + * AP_HardwareAbstractionLayer.h + * + * Created on: Apr 4, 2011 + * + */ + +#ifndef AP_HARDWAREABSTRACTIONLAYER_H_ +#define AP_HARDWAREABSTRACTIONLAYER_H_ + +#include "../AP_Common/AP_Common.h" +#include "../FastSerial/FastSerial.h" +#include "../AP_Common/AP_Vector.h" +#include "../GCS_MAVLink/GCS_MAVLink.h" + +#include "../AP_ADC/AP_ADC.h" +#include "../AP_IMU/AP_IMU.h" +#include "../AP_GPS/GPS.h" +#include "../APM_BMP085/APM_BMP085.h" +#include "../AP_Compass/AP_Compass.h" +#include "AP_RcChannel.h" +#include "../AP_RangeFinder/AP_RangeFinder.h" +#include "../GCS_MAVLink/GCS_MAVLink.h" + +class AP_ADC; +class IMU; +class GPS; +class APM_BMP085_Class; +class Compass; +class BetterStream; +class RangeFinder; + +namespace apo { + +class AP_RcChannel; +class AP_CommLink; + +// enumerations +enum halMode_t { + MODE_LIVE, MODE_HIL_CNTL, +/*MODE_HIL_NAV*/}; +enum board_t { + BOARD_ARDUPILOTMEGA_1280, BOARD_ARDUPILOTMEGA_2560, BOARD_ARDUPILOTMEGA_2 +}; +enum vehicle_t { + VEHICLE_CAR, VEHICLE_QUAD, VEHICLE_PLANE, VEHICLE_BOAT, VEHICLE_TANK +}; + +class AP_HardwareAbstractionLayer { + +public: + + AP_HardwareAbstractionLayer(halMode_t mode, board_t board, + vehicle_t vehicle, uint8_t heartBeatTimeout) : + adc(), gps(), baro(), compass(), rangeFinders(), imu(), rc(), gcs(), + hil(), debug(), load(), lastHeartBeat(), + _heartBeatTimeout(heartBeatTimeout), _mode(mode), + _board(board), _vehicle(vehicle), _state(MAV_STATE_UNINIT) { + + /* + * Board specific hardware initialization + */ + if (board == BOARD_ARDUPILOTMEGA_1280) { + slideSwitchPin = 40; + pushButtonPin = 41; + aLedPin = 37; + bLedPin = 36; + cLedPin = 35; + eepromMaxAddr = 1024; + pinMode(aLedPin, OUTPUT); // extra led + pinMode(bLedPin, OUTPUT); // imu ledclass AP_CommLink; + pinMode(cLedPin, OUTPUT); // gps led + pinMode(slideSwitchPin, INPUT); + pinMode(pushButtonPin, INPUT); + DDRL |= B00000100; // set port L, pint 2 to output for the relay + } else if (board == BOARD_ARDUPILOTMEGA_2560) { + slideSwitchPin = 40; + pushButtonPin = 41; + aLedPin = 37; + bLedPin = 36; + cLedPin = 35; + eepromMaxAddr = 2048; + pinMode(aLedPin, OUTPUT); // extra led + pinMode(bLedPin, OUTPUT); // imu ledclass AP_CommLink; + pinMode(cLedPin, OUTPUT); // gps led + pinMode(slideSwitchPin, INPUT); + pinMode(pushButtonPin, INPUT); + DDRL |= B00000100; // set port L, pint 2 to output for the relay + } + } + + /** + * Sensors + */ + AP_ADC * adc; + GPS * gps; + APM_BMP085_Class * baro; + Compass * compass; + Vector rangeFinders; + IMU * imu; + + /** + * Radio Channels + */ + Vector rc; + + /** + * Communication Channels + */ + AP_CommLink * gcs; + AP_CommLink * hil; + FastSerial * debug; + + /** + * data + */ + uint8_t load; + uint32_t lastHeartBeat; + + /** + * settings + */ + uint8_t slideSwitchPin; + uint8_t pushButtonPin; + uint8_t aLedPin; + uint8_t bLedPin; + uint8_t cLedPin; + uint16_t eepromMaxAddr; + + // accessors + halMode_t getMode() { + return _mode; + } + board_t getBoard() { + return _board; + } + vehicle_t getVehicle() { + return _vehicle; + } + MAV_STATE getState() { + return _state; + } + void setState(MAV_STATE state) { + _state = state; + } + + bool heartBeatLost() { + if (_heartBeatTimeout == 0) + return false; + else + return ((micros() - lastHeartBeat) / 1e6) > _heartBeatTimeout; + } + +private: + + // enumerations + uint8_t _heartBeatTimeout; + halMode_t _mode; + board_t _board; + vehicle_t _vehicle; + MAV_STATE _state; +}; + +} + +#endif /* AP_HARDWAREABSTRACTIONLAYER_H_ */ diff --git a/libraries/APO/AP_MavlinkCommand.cpp b/libraries/APO/AP_MavlinkCommand.cpp new file mode 100644 index 0000000000..987e2c0dbe --- /dev/null +++ b/libraries/APO/AP_MavlinkCommand.cpp @@ -0,0 +1,187 @@ +/* + * AP_MavlinkCommand.cpp + * + * Created on: Apr 30, 2011 + * Author: jgoppert + */ + +#include "AP_MavlinkCommand.h" + +namespace apo { + +AP_MavlinkCommand::AP_MavlinkCommand(const AP_MavlinkCommand & v) : + _data(v._data), _seq(v._seq) { + //if (FastSerial::getInitialized(0)) Serial.println("copy ctor"); +} + +AP_MavlinkCommand::AP_MavlinkCommand(uint16_t index, bool doLoad) : + _data(k_commands + index), _seq(index) { + + if (FastSerial::getInitialized(0)) { + Serial.println("index ctor"); + Serial.println("++"); + Serial.print("index: "); Serial.println(index); + Serial.print("key: "); Serial.println(k_commands + index); + Serial.println("++"); + } + + // default values for structure + _data.get().command = MAV_CMD_NAV_WAYPOINT; + _data.get().autocontinue = true; + _data.get().frame = MAV_FRAME_GLOBAL; + _data.get().param1 = 0; + _data.get().param2 = 10; // radius of 10 meters + _data.get().param3 = 0; + _data.get().param4 = 0; + _data.get().x = 0; + _data.get().y = 0; + _data.get().z = 1000; + + // This is a failsafe measure to stop trying to load a command if it can't load + if (doLoad && !load()) { + Serial.println("load failed, reverting to home waypoint"); + _data = AP_MavlinkCommand::home._data; + _seq = AP_MavlinkCommand::home._seq; + } +} + +AP_MavlinkCommand::AP_MavlinkCommand(const mavlink_waypoint_t & cmd) : + _data(k_commands + cmd.seq), _seq(cmd.seq) { + setCommand(MAV_CMD(cmd.command)); + setAutocontinue(cmd.autocontinue); + setFrame(MAV_FRAME(cmd.frame)); + setParam1(cmd.param1); + setParam2(cmd.param2); + setParam3(cmd.param3); + setParam4(cmd.param4); + setX(cmd.x); + setY(cmd.y); + setZ(cmd.z); + save(); + + // reload home if sent + if (cmd.seq == 0) home.load(); + + Serial.println("============================================================"); + Serial.println("storing new command from mavlink_waypoint_t"); + Serial.print("key: "); Serial.println(_data.key(),DEC); + Serial.print("number: "); Serial.println(cmd.seq,DEC); + Serial.print("command: "); Serial.println(getCommand()); + Serial.print("autocontinue: "); Serial.println(getAutocontinue(),DEC); + Serial.print("frame: "); Serial.println(getFrame(),DEC); + Serial.print("1000*param1: "); Serial.println(int(1000*getParam1()),DEC); + Serial.print("1000*param2: "); Serial.println(int(1000*getParam2()),DEC); + Serial.print("1000*param3: "); Serial.println(int(1000*getParam3()),DEC); + Serial.print("1000*param4: "); Serial.println(int(1000*getParam4()),DEC); + Serial.print("1000*x0: "); Serial.println(int(1000*cmd.x),DEC); + Serial.print("1000*y0: "); Serial.println(int(1000*cmd.y),DEC); + Serial.print("1000*z0: "); Serial.println(int(1000*cmd.z),DEC); + Serial.print("1000*x: "); Serial.println(int(1000*getX()),DEC); + Serial.print("1000*y: "); Serial.println(int(1000*getY()),DEC); + Serial.print("1000*z: "); Serial.println(int(1000*getZ()),DEC); + + load(); + + Serial.print("1000*x1: "); Serial.println(int(1000*getX()),DEC); + Serial.print("1000*y1: "); Serial.println(int(1000*getY()),DEC); + Serial.print("1000*z1: "); Serial.println(int(1000*getZ()),DEC); + Serial.println("============================================================"); + Serial.flush(); +} + +mavlink_waypoint_t AP_MavlinkCommand::convert(uint8_t current) const { + mavlink_waypoint_t mavCmd; + mavCmd.seq = getSeq(); + mavCmd.command = getCommand(); + mavCmd.frame = getFrame(); + mavCmd.param1 = getParam1(); + mavCmd.param2 = getParam2(); + mavCmd.param3 = getParam3(); + mavCmd.param4 = getParam4(); + mavCmd.x = getX(); + mavCmd.y = getY(); + mavCmd.z = getZ(); + mavCmd.autocontinue = getAutocontinue(); + mavCmd.current = (getSeq() == current); + mavCmd.target_component = mavlink_system.compid; + mavCmd.target_system = mavlink_system.sysid; + return mavCmd; +} + +float AP_MavlinkCommand::bearingTo(const AP_MavlinkCommand & next) const { + float deltaLon = next.getLon() - getLon(); + /* + Serial.print("Lon: "); Serial.println(getLon()); + Serial.print("nextLon: "); Serial.println(next.getLon()); + Serial.print("deltaLonDeg * 1e7: "); Serial.println(deltaLon*rad2DegInt); + */ + float bearing = atan2( + sin(deltaLon) * cos(next.getLat()), + cos(getLat()) * sin(next.getLat()) - sin(getLat()) * cos( + next.getLat()) * cos(deltaLon)); + return bearing; +} + +float AP_MavlinkCommand::bearingTo(int32_t latDegInt, int32_t lonDegInt) const { + // have to be careful to maintain the precision of the gps coordinate + float deltaLon = (lonDegInt - getLon_degInt()) * degInt2Rad; + float nextLat = latDegInt * degInt2Rad; + float bearing = atan2( + sin(deltaLon) * cos(nextLat), + cos(getLat()) * sin(nextLat) - sin(getLat()) * cos(nextLat) + * cos(deltaLon)); + if (bearing < 0) + bearing += 2 * M_PI; + return bearing; +} + +float AP_MavlinkCommand::distanceTo(const AP_MavlinkCommand & next) const { + float sinDeltaLat2 = sin((getLat() - next.getLat()) / 2); + float sinDeltaLon2 = sin((getLon() - next.getLon()) / 2); + float a = sinDeltaLat2 * sinDeltaLat2 + cos(getLat()) * cos( + next.getLat()) * sinDeltaLon2 * sinDeltaLon2; + float c = 2 * atan2(sqrt(a), sqrt(1 - a)); + return rEarth * c; +} + +float AP_MavlinkCommand::distanceTo(int32_t lat_degInt, int32_t lon_degInt) const { + float sinDeltaLat2 = sin( + (lat_degInt - getLat_degInt()) * degInt2Rad / 2); + float sinDeltaLon2 = sin( + (lon_degInt - getLon_degInt()) * degInt2Rad / 2); + float a = sinDeltaLat2 * sinDeltaLat2 + cos(getLat()) * cos( + lat_degInt * degInt2Rad) * sinDeltaLon2 * sinDeltaLon2; + float c = 2 * atan2(sqrt(a), sqrt(1 - a)); + /* + Serial.print("wp lat_degInt: "); Serial.println(getLat_degInt()); + Serial.print("wp lon_degInt: "); Serial.println(getLon_degInt()); + Serial.print("lat_degInt: "); Serial.println(lat_degInt); + Serial.print("lon_degInt: "); Serial.println(lon_degInt); + Serial.print("sinDeltaLat2: "); Serial.println(sinDeltaLat2); + Serial.print("sinDeltaLon2: "); Serial.println(sinDeltaLon2); + */ + return rEarth * c; +} + +//calculates cross track of a current location +float AP_MavlinkCommand::crossTrack(const AP_MavlinkCommand & previous, + int32_t lat_degInt, int32_t lon_degInt) const { + float d = previous.distanceTo(lat_degInt, lon_degInt); + float bCurrent = previous.bearingTo(lat_degInt, lon_degInt); + float bNext = previous.bearingTo(*this); + return asin(sin(d / rEarth) * sin(bCurrent - bNext)) * rEarth; +} + +// calculates along track distance of a current location +float AP_MavlinkCommand::alongTrack(const AP_MavlinkCommand & previous, + int32_t lat_degInt, int32_t lon_degInt) const { + // ignores lat/lon since single prec. + float dXt = this->crossTrack(previous,lat_degInt, lon_degInt); + float d = previous.distanceTo(lat_degInt, lon_degInt); + return dXt / tan(asin(dXt / d)); +} + + +AP_MavlinkCommand AP_MavlinkCommand::home = AP_MavlinkCommand(0,false); + +} diff --git a/libraries/APO/AP_MavlinkCommand.h b/libraries/APO/AP_MavlinkCommand.h new file mode 100644 index 0000000000..a50002cb95 --- /dev/null +++ b/libraries/APO/AP_MavlinkCommand.h @@ -0,0 +1,375 @@ +/* + * AP_MavlinkCommand.h + * + * Created on: Apr 4, 2011 + * Author: jgoppert + */ + +#ifndef AP_MAVLINKCOMMAND_H_ +#define AP_MAVLINKCOMMAND_H_ + +#include "../GCS_MAVLink/GCS_MAVLink.h" +#include "../AP_Common/AP_Common.h" +#include "AP_Var_keys.h" +#include "constants.h" +#include "../FastSerial/FastSerial.h" + +namespace apo { + +class AP_MavlinkCommand { +private: + struct CommandStorage { + MAV_CMD command; + bool autocontinue; + MAV_FRAME frame; + float param1; + float param2; + float param3; + float param4; + float x; + float y; + float z; + }; + AP_VarS _data; + uint16_t _seq; +public: + static AP_MavlinkCommand home; + + /** + * Copy Constructor + */ + AP_MavlinkCommand(const AP_MavlinkCommand & v); + + /** + * Basic Constructor + * @param index Start at zero. + */ + AP_MavlinkCommand(uint16_t index, bool doLoad = true); + + /** + * Constructor for copying/ saving from a mavlink waypoint. + * @param cmd The mavlink_waopint_t structure for the command. + */ + AP_MavlinkCommand(const mavlink_waypoint_t & cmd); + + bool save() { + return _data.save(); + } + bool load() { + return _data.load(); + } + uint8_t getSeq() const { + return _seq; + } + bool getAutocontinue() const { + return _data.get().autocontinue; + } + void setAutocontinue( bool val) { + _data.get().autocontinue = val; + } + void setSeq(uint8_t val) { + _seq = val; + } + MAV_CMD getCommand() const { + return _data.get().command; + } + void setCommand(MAV_CMD val) { + _data.get().command = val; + } + MAV_FRAME getFrame() const { + return _data.get().frame; + } + void setFrame(MAV_FRAME val) { + _data.get().frame = val; + } + float getParam1() const { + return _data.get().param1; + } + void setParam1(float val) { + _data.get().param1 = val; + } + float getParam2() const { + return _data.get().param2; + } + void setParam2(float val) { + _data.get().param2 = val; + } + float getParam3() const { + return _data.get().param3; + } + void setParam3(float val) { + _data.get().param3 = val; + } + float getParam4() const { + return _data.get().param4; + } + void setParam4(float val) { + _data.get().param4 = val; + } + float getX() const { + return _data.get().x; + } + void setX(float val) { + _data.get().x = val; + } + float getY() const { + return _data.get().y; + } + void setY(float val) { + _data.get().y = val; + } + float getZ() const { + return _data.get().z; + } + void setZ(float val) { + _data.get().z = val; + } + float getLatDeg() const { + switch (getFrame()) { + case MAV_FRAME_GLOBAL: + case MAV_FRAME_GLOBAL_RELATIVE_ALT: + return getX(); + break; + case MAV_FRAME_LOCAL: + case MAV_FRAME_LOCAL_ENU: + case MAV_FRAME_MISSION: + default: + return 0; + break; + } + } + void setLatDeg(float val) { + switch (getFrame()) { + case MAV_FRAME_GLOBAL: + case MAV_FRAME_GLOBAL_RELATIVE_ALT: + setX(val); + break; + case MAV_FRAME_LOCAL: + case MAV_FRAME_LOCAL_ENU: + case MAV_FRAME_MISSION: + default: + break; + } + } + float getLonDeg() const { + switch (getFrame()) { + case MAV_FRAME_GLOBAL: + case MAV_FRAME_GLOBAL_RELATIVE_ALT: + return getY(); + break; + case MAV_FRAME_LOCAL: + case MAV_FRAME_LOCAL_ENU: + case MAV_FRAME_MISSION: + default: + return 0; + break; + } + } + void setLonDeg(float val) { + switch (getFrame()) { + case MAV_FRAME_GLOBAL: + case MAV_FRAME_GLOBAL_RELATIVE_ALT: + setY(val); + break; + case MAV_FRAME_LOCAL: + case MAV_FRAME_LOCAL_ENU: + case MAV_FRAME_MISSION: + default: + break; + } + } + void setLon(float val) { + setLonDeg(val * rad2Deg); + } + void setLon_degInt(int32_t val) { + setLonDeg(val / 1.0e7); + } + void setLat_degInt(int32_t val) { + setLatDeg(val / 1.0e7); + } + int32_t getLon_degInt() const { + return getLonDeg() * 1e7; + } + int32_t getLat_degInt() const { + return getLatDeg() * 1e7; + } + float getLon() const { + return getLonDeg() * deg2Rad; + } + float getLat() const { + return getLatDeg() * deg2Rad; + } + void setLat(float val) { + setLatDeg(val * rad2Deg); + } + float getAlt() const { + switch (getFrame()) { + case MAV_FRAME_GLOBAL: + return getZ(); + break; + case MAV_FRAME_GLOBAL_RELATIVE_ALT: + case MAV_FRAME_LOCAL: + return -getZ() + home.getAlt(); + break; + case MAV_FRAME_LOCAL_ENU: + return getZ() + home.getAlt(); + break; + case MAV_FRAME_MISSION: + default: + return 0; + break; + } + } + /** + * set the altitude in meters + */ + void setAlt(float val) { + switch (getFrame()) { + case MAV_FRAME_GLOBAL: + case MAV_FRAME_GLOBAL_RELATIVE_ALT: + setZ(val); + break; + case MAV_FRAME_LOCAL: + setZ(home.getLonDeg() - val); + break; + case MAV_FRAME_LOCAL_ENU: + setZ(val - home.getLonDeg()); + break; + case MAV_FRAME_MISSION: + default: + break; + } + } + /** + * Get the relative altitude to home + * @return relative altitude in meters + */ + float getRelAlt() const { + switch (getFrame()) { + case MAV_FRAME_GLOBAL: + return getZ() - home.getAlt(); + break; + case MAV_FRAME_GLOBAL_RELATIVE_ALT: + case MAV_FRAME_LOCAL: + return -getZ(); + break; + case MAV_FRAME_LOCAL_ENU: + return getZ(); + break; + case MAV_FRAME_MISSION: + default: + return 0; + break; + } + } + /** + * set the relative altitude in meters from home (up) + */ + void setRelAlt(float val) { + switch (getFrame()) { + case MAV_FRAME_GLOBAL: + setZ(val + home.getAlt()); + break; + case MAV_FRAME_GLOBAL_RELATIVE_ALT: + case MAV_FRAME_LOCAL: + setZ(-val); + break; + case MAV_FRAME_LOCAL_ENU: + setZ(val); + break; + case MAV_FRAME_MISSION: + break; + } + } + + float getRadius() const { + return getParam2(); + } + + void setRadius(float val) { + setParam2(val); + } + + /** + * conversion for outbound packets to ground station + * @return output the mavlink_waypoint_t packet + */ + mavlink_waypoint_t convert(uint8_t current) const; + + /** + * Calculate the bearing from this command to the next command + * @param next The command to calculate the bearing to. + * @return the bearing + */ + float bearingTo(const AP_MavlinkCommand & next) const; + + /** + * Bearing form this command to a gps coordinate in integer units + * @param latDegInt latitude in degrees E-7 + * @param lonDegInt longitude in degrees E-7 + * @return + */ + float bearingTo(int32_t latDegInt, int32_t lonDegInt) const; + + /** + * Distance to another command + * @param next The command to measure to. + * @return The distance in meters. + */ + float distanceTo(const AP_MavlinkCommand & next) const; + + /** + * Distance to a gps coordinate in integer units + * @param latDegInt latitude in degrees E-7 + * @param lonDegInt longitude in degrees E-7 + * @return The distance in meters. + */ + float distanceTo(int32_t lat_degInt, int32_t lon_degInt) const; + + float getPN(int32_t lat_degInt, int32_t lon_degInt) const { + // local tangent approximation at this waypoint + float deltaLat = (lat_degInt - getLat_degInt()) * degInt2Rad; + return deltaLat * rEarth; + } + + float getPE(int32_t lat_degInt, int32_t lon_degInt) const { + // local tangent approximation at this waypoint + float deltaLon = (lon_degInt - getLon_degInt()) * degInt2Rad; + return cos(getLat()) * deltaLon * rEarth; + } + + float getPD(int32_t alt_intM) const { + return -(alt_intM / scale_m - getAlt()); + } + + float getLat(float pN) const { + + return pN / rEarth + getLat(); + } + + float getLon(float pE) const { + + return pE / rEarth / cos(getLat()) + getLon(); + } + + /** + * Gets altitude in meters + * @param pD alt in meters + * @return + */ + float getAlt(float pD) const { + + return getAlt() - pD; + } + + //calculates cross track of a current location + float crossTrack(const AP_MavlinkCommand & previous, int32_t lat_degInt, int32_t lon_degInt) const; + + // calculates along track distance of a current location + float alongTrack(const AP_MavlinkCommand & previous, int32_t lat_degInt, int32_t lon_degInt) const; +}; + +} // namespace apo + + +#endif /* AP_MAVLINKCOMMAND_H_ */ diff --git a/libraries/APO/AP_Navigator.cpp b/libraries/APO/AP_Navigator.cpp new file mode 100644 index 0000000000..ff33e8ed2c --- /dev/null +++ b/libraries/APO/AP_Navigator.cpp @@ -0,0 +1,8 @@ +/* + * AP_Navigator.cpp + * + * Created on: Apr 30, 2011 + * Author: jgoppert + */ + +#include "AP_Navigator.h" diff --git a/libraries/APO/AP_Navigator.h b/libraries/APO/AP_Navigator.h new file mode 100644 index 0000000000..8170aa826a --- /dev/null +++ b/libraries/APO/AP_Navigator.h @@ -0,0 +1,387 @@ +/* + * AP_Navigator.h + * Copyright (C) James Goppert 2010 + * + * This file 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 file 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 . + */ + +#ifndef AP_Navigator_H +#define AP_Navigator_H + +#include "AP_HardwareAbstractionLayer.h" +#include "../AP_DCM/AP_DCM.h" +#include "../AP_Math/AP_Math.h" +#include "../AP_Compass/AP_Compass.h" +#include "AP_MavlinkCommand.h" +#include "constants.h" +#include "AP_Var_keys.h" +#include "../AP_RangeFinder/AP_RangeFinder.h" +#include "../AP_IMU/AP_IMU.h" + +namespace apo { + +/// Navigator class +class AP_Navigator { +public: + AP_Navigator(AP_HardwareAbstractionLayer * hal) : + _hal(hal), _timeStamp(0), _roll(0), _rollRate(0), _pitch(0), + _pitchRate(0), _yaw(0), _yawRate(0), _airSpeed(0), + _groundSpeed(0), _vD(0), _lat_degInt(0), + _lon_degInt(0), _alt_intM(0) { + } + virtual void calibrate() { + } + virtual void updateFast(float dt) = 0; + virtual void updateSlow(float dt) = 0; + float getPD() const { + return AP_MavlinkCommand::home.getPD(getAlt_intM()); + } + + float getPE() const { + return AP_MavlinkCommand::home.getPE(getLat_degInt(), getLon_degInt()); + } + + float getPN() const { + return AP_MavlinkCommand::home.getPN(getLat_degInt(), getLon_degInt()); + } + + void setPD(float _pD) { + setAlt(AP_MavlinkCommand::home.getAlt(_pD)); + } + + void setPE(float _pE) { + setLat(AP_MavlinkCommand::home.getLat(_pE)); + } + + void setPN(float _pN) { + setLon(AP_MavlinkCommand::home.getLon(_pN)); + } + + float getAirSpeed() const { + return _airSpeed; + } + + int32_t getAlt_intM() const { + return _alt_intM; + } + + float getAlt() const { + return _alt_intM / scale_m; + } + + void setAlt(float _alt) { + this->_alt_intM = _alt * scale_m; + } + + float getLat() const { + //Serial.print("getLatfirst"); + //Serial.println(_lat_degInt * degInt2Rad); + return _lat_degInt * degInt2Rad; + } + + void setLat(float _lat) { + //Serial.print("setLatfirst"); + //Serial.println(_lat * rad2DegInt); + setLat_degInt(_lat*rad2DegInt); + } + + float getLon() const { + return _lon_degInt * degInt2Rad; + } + + void setLon(float _lon) { + this->_lon_degInt = _lon * rad2DegInt; + } + + float getVD() const { + return _vD; + } + + float getVE() const { + return sin(getYaw()) * getGroundSpeed(); + } + + float getGroundSpeed() const { + return _groundSpeed; + } + + int32_t getLat_degInt() const { + //Serial.print("getLat_degInt"); + //Serial.println(_lat_degInt); + return _lat_degInt; + + } + + int32_t getLon_degInt() const { + return _lon_degInt; + } + + float getVN() const { + return cos(getYaw()) * getGroundSpeed(); + } + + float getPitch() const { + return _pitch; + } + + float getPitchRate() const { + return _pitchRate; + } + + float getRoll() const { + return _roll; + } + + float getRollRate() const { + return _rollRate; + } + + float getYaw() const { + return _yaw; + } + + float getYawRate() const { + return _yawRate; + } + + void setAirSpeed(float airSpeed) { + _airSpeed = airSpeed; + } + + void setAlt_intM(int32_t alt_intM) { + _alt_intM = alt_intM; + } + + void setVD(float vD) { + _vD = vD; + } + + void setGroundSpeed(float groundSpeed) { + _groundSpeed = groundSpeed; + } + + void setLat_degInt(int32_t lat_degInt) { + _lat_degInt = lat_degInt; + //Serial.print("setLat_degInt"); + //Serial.println(_lat_degInt); + } + + void setLon_degInt(int32_t lon_degInt) { + _lon_degInt = lon_degInt; + } + + void setPitch(float pitch) { + _pitch = pitch; + } + + void setPitchRate(float pitchRate) { + _pitchRate = pitchRate; + } + + void setRoll(float roll) { + _roll = roll; + } + + void setRollRate(float rollRate) { + _rollRate = rollRate; + } + + void setYaw(float yaw) { + _yaw = yaw; + } + + void setYawRate(float yawRate) { + _yawRate = yawRate; + } + void setTimeStamp(int32_t timeStamp) { + _timeStamp = timeStamp; + } + int32_t getTimeStamp() const { + return _timeStamp; + } + +protected: + AP_HardwareAbstractionLayer * _hal; +private: + int32_t _timeStamp; // micros clock + float _roll; // rad + float _rollRate; //rad/s + float _pitch; // rad + float _pitchRate; // rad/s + float _yaw; // rad + float _yawRate; // rad/s + float _airSpeed; // m/s + float _groundSpeed; // m/s + float _vD; // m/s + int32_t _lat_degInt; // deg / 1e7 + int32_t _lon_degInt; // deg / 1e7 + int32_t _alt_intM; // meters / 1e3 +}; + +class DcmNavigator: public AP_Navigator { +private: + /** + * Sensors + */ + + RangeFinder * _rangeFinderDown; + AP_DCM * _dcm; + IMU * _imu; + uint16_t _imuOffsetAddress; + +public: + DcmNavigator(AP_HardwareAbstractionLayer * hal) : + AP_Navigator(hal), _dcm(), _imuOffsetAddress(0) { + + // if orientation equal to front, store as front + /** + * rangeFinder is assigned values based on orientation which + * is specified in ArduPilotOne.pde. + */ + for (uint8_t i = 0; i < _hal-> rangeFinders.getSize(); i++) { + if (_hal->rangeFinders[i] == NULL) + continue; + if (_hal->rangeFinders[i]->orientation_x == 0 + && _hal->rangeFinders[i]->orientation_y == 0 + && _hal->rangeFinders[i]->orientation_z == 1) + _rangeFinderDown = _hal->rangeFinders[i]; + } + + if (_hal->getMode() == MODE_LIVE) { + if (_hal->adc) + _hal->imu = new AP_IMU_Oilpan(_hal->adc, k_sensorCalib); + if (_hal->imu) + _dcm = new AP_DCM(_hal->imu, _hal->gps, _hal->compass); + if (_hal->compass) { + _dcm->set_compass(_hal->compass); + + } + } + } + virtual void calibrate() { + + AP_Navigator::calibrate(); + + // TODO: handle cold/warm restart + if (_hal->imu) { + _hal->imu->init(IMU::COLD_START,delay); + } + } + virtual void updateFast(float dt) { + if (_hal->getMode() != MODE_LIVE) + return; + + setTimeStamp(micros()); // if running in live mode, record new time stamp + + + //_hal->debug->println_P(PSTR("nav loop")); + + /** + * The altitued is read off the barometer by implementing the following formula: + * altitude (in m) = 44330*(1-(p/po)^(1/5.255)), + * where, po is pressure in Pa at sea level (101325 Pa). + * See http://www.sparkfun.com/tutorials/253 or type this formula + * in a search engine for more information. + * altInt contains the altitude in meters. + */ + if (_hal->baro) { + + if (_rangeFinderDown != NULL && _rangeFinderDown->distance <= 695) + setAlt(_rangeFinderDown->distance); + + else { + float tmp = (_hal->baro->Press / 101325.0); + tmp = pow(tmp, 0.190295); + //setAlt(44330 * (1.0 - tmp)); //sets the altitude in meters XXX wrong, baro reads 0 press + setAlt(0.0); + } + } + + // dcm class for attitude + if (_dcm) { + _dcm->update_DCM(); + setRoll(_dcm->roll); + setPitch(_dcm->pitch); + setYaw(_dcm->yaw); + setRollRate(_dcm->get_gyro().x); + setPitchRate(_dcm->get_gyro().y); + setYawRate(_dcm->get_gyro().z); + + /* + * accel/gyro debug + */ + /* + Vector3f accel = _hal->imu->get_accel(); + Vector3f gyro = _hal->imu->get_gyro(); + Serial.printf_P(PSTR("accel: %f %f %f gyro: %f %f %f\n"), + accel.x,accel.y,accel.z,gyro.x,gyro.y,gyro.z); + */ + } + } + virtual void updateSlow(float dt) { + if (_hal->getMode() != MODE_LIVE) + return; + + setTimeStamp(micros()); // if running in live mode, record new time stamp + + if (_hal->gps) { + _hal->gps->update(); + updateGpsLight(); + if (_hal->gps->fix && _hal->gps->new_data) { + setLat_degInt(_hal->gps->latitude); + setLon_degInt(_hal->gps->longitude); + setAlt_intM(_hal->gps->altitude * 10); // gps in cm, intM in mm + setGroundSpeed(_hal->gps->ground_speed / 100.0); // gps is in cm/s + } + } + + if (_hal->compass) { + _hal->compass->read(); + _hal->compass->calculate(getRoll(), getPitch()); + _hal->compass->null_offsets(_dcm->get_dcm_matrix()); + } + } + void updateGpsLight(void) { + // GPS LED on if we have a fix or Blink GPS LED if we are receiving data + // --------------------------------------------------------------------- + static bool GPS_light = false; + switch (_hal->gps->status()) { + case (2): + //digitalWrite(C_LED_PIN, HIGH); //Turn LED C on when gps has valid fix. + break; + + case (1): + if (_hal->gps->valid_read == true) { + GPS_light = !GPS_light; // Toggle light on and off to indicate gps messages being received, but no GPS fix lock + if (GPS_light) { + digitalWrite(_hal->cLedPin, LOW); + } else { + digitalWrite(_hal->cLedPin, HIGH); + } + _hal->gps->valid_read = false; + } + break; + + default: + digitalWrite(_hal->cLedPin, LOW); + break; + } + } + +}; + +} // namespace apo + +#endif // AP_Navigator_H +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/AP_RcChannel.cpp b/libraries/APO/AP_RcChannel.cpp new file mode 100644 index 0000000000..1c1f823482 --- /dev/null +++ b/libraries/APO/AP_RcChannel.cpp @@ -0,0 +1,102 @@ +/* + AP_RcChannel.cpp - Radio library for Arduino + Code by Jason Short, James Goppert. DIYDrones.com + + This library is free software; you can redistribute it and / or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + */ + +#include +#include +#include "AP_RcChannel.h" +#include "../AP_Common/AP_Common.h" +#include + +namespace apo { + +AP_RcChannel::AP_RcChannel(AP_Var::Key keyValue, const prog_char_t * name, + APM_RC_Class & rc, const uint8_t & ch, const uint16_t & pwmMin, + const uint16_t & pwmNeutral, const uint16_t & pwmMax, + const rcMode_t & rcMode, const bool & reverse, const float & scale) : + AP_Var_group(keyValue, name), _ch(this, 1, ch, PSTR("ch")), + _pwmMin(this, 2, pwmMin, PSTR("pMin")), + _pwmNeutral(this, 3, pwmNeutral, PSTR("pNtrl")), + _pwmMax(this, 4, pwmMax, PSTR("pMax")), + _reverse(this, 5, reverse, PSTR("rev")), + _scale(scale == 0 ? AP_Float(0) : AP_Float(this,6,reverse,PSTR("scale"))), + _rcMode(rcMode), _rc(rc), _pwm(pwmNeutral) { + //Serial.print("pwm after ctor: "); Serial.println(pwmNeutral); + if (rcMode == RC_MODE_IN) + return; + //Serial.print("pwm set for ch: "); Serial.println(int(ch)); + rc.OutputCh(ch, pwmNeutral); + +} + +uint16_t AP_RcChannel::getRadioPwm() { + if (_rcMode == RC_MODE_OUT) { + Serial.print("tryng to read from output channel: "); + Serial.println(int(_ch)); + return _pwmNeutral; // if this happens give a safe value of neutral + } + return _rc.InputCh(_ch); +} + +void AP_RcChannel::setPwm(uint16_t pwm) { + //Serial.printf("pwm in setPwm: %d\n", pwm); + //Serial.printf("reverse: %s\n", (reverse)?"true":"false"); + + // apply reverse + if (_reverse) + pwm = int16_t(_pwmNeutral - pwm) + _pwmNeutral; + //Serial.printf("pwm after reverse: %d\n", pwm); + + // apply saturation + if (_pwm > uint8_t(_pwmMax)) + _pwm = _pwmMax; + if (_pwm < uint8_t(_pwmMin)) + _pwm = _pwmMin; + _pwm = pwm; + + //Serial.print("ch: "); Serial.print(ch); Serial.print(" pwm: "); Serial.println(pwm); + if (_rcMode == RC_MODE_IN) + return; + _rc.OutputCh(_ch, _pwm); +} + +uint16_t AP_RcChannel::_positionToPwm(const float & position) { + uint16_t pwm; + //Serial.printf("position: %f\n", position); + if (position < 0) + pwm = position * int16_t(_pwmNeutral - _pwmMin) + _pwmNeutral; + else + pwm = position * int16_t(_pwmMax - _pwmNeutral) + _pwmNeutral; + + if (pwm > uint16_t(_pwmMax)) + pwm = _pwmMax; + if (pwm < uint16_t(_pwmMin)) + pwm = _pwmMin; + return pwm; +} + +float AP_RcChannel::_pwmToPosition(const uint16_t & pwm) { + float position; + // note a piece-wise linear mapping occurs if the pwm ranges + // are not symmetric about pwmNeutral + if (pwm < uint8_t(_pwmNeutral)) + position = 1.0 * int16_t(pwm - _pwmNeutral) / int16_t( + _pwmNeutral - _pwmMin); + else + position = 1.0 * int16_t(pwm - _pwmNeutral) / int16_t( + _pwmMax - _pwmNeutral); + if (position > 1) + position = 1; + if (position < -1) + position = -1; + return position; +} + +} // namespace apo diff --git a/libraries/APO/AP_RcChannel.h b/libraries/APO/AP_RcChannel.h new file mode 100644 index 0000000000..5a9076e92f --- /dev/null +++ b/libraries/APO/AP_RcChannel.h @@ -0,0 +1,84 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- + +/// @file AP_RcChannel.h +/// @brief AP_RcChannel manager + +#ifndef AP_RCCHANNEL_H +#define AP_RCCHANNEL_H + +#include +#include "../APM_RC/APM_RC.h" +#include "../AP_Common/AP_Common.h" +#include "../AP_Common/AP_Var.h" + +namespace apo { + +enum rcMode_t { + RC_MODE_IN, RC_MODE_OUT, RC_MODE_INOUT +}; + +/// @class AP_RcChannel +/// @brief Object managing one RC channel +class AP_RcChannel: public AP_Var_group { + +public: + + /// Constructor + AP_RcChannel(AP_Var::Key keyValue, const prog_char_t * name, APM_RC_Class & rc, + const uint8_t & ch, const uint16_t & pwmMin, + const uint16_t & pwmNeutral, const uint16_t & pwmMax, + const rcMode_t & rcMode, + const bool & reverse, const float & scale = 0); + + // configuration + AP_Uint8 _ch; + AP_Uint16 _pwmMin; + AP_Uint16 _pwmNeutral; + AP_Uint16 _pwmMax; + rcMode_t _rcMode; + AP_Bool _reverse; + AP_Float _scale; + + // get + uint16_t getPwm() { + return _pwm; + } + uint16_t getRadioPwm(); + float getPosition() { + return _pwmToPosition(getPwm()); + } + float getRadioPosition() { + return _pwmToPosition(getRadioPwm()); + } + float getScaled() { + return _scale*getPwm(); + } + + // set + void setUsingRadio() { + setPwm(getRadioPwm()); + } + void setPwm(uint16_t pwm); + void setPosition(float position) { + setPwm(_positionToPwm(position)); + } + void setScaled(float val) { + setPwm(val/_scale); + } + +protected: + + // configuration + APM_RC_Class & _rc; + + // internal states + uint16_t _pwm; // this is the internal state, position is just created when needed + + // private methods + uint16_t _positionToPwm(const float & position); + float _pwmToPosition(const uint16_t & pwm); +}; + +} // apo + +#endif // AP_RCCHANNEL_H diff --git a/libraries/APO/AP_Var_keys.h b/libraries/APO/AP_Var_keys.h new file mode 100644 index 0000000000..58a715b591 --- /dev/null +++ b/libraries/APO/AP_Var_keys.h @@ -0,0 +1,24 @@ +#ifndef AP_Var_keys_H +#define AP_Var_keys_H + +enum keys { + + // general + k_config = 0, + k_cntrl, + k_guide, + k_sensorCalib, + + k_radioChannelsStart=10, + + k_controllersStart=30, + + k_customStart=100, + + // 200-256 reserved for commands + k_commands = 200 +}; + +// max 256 keys + +#endif diff --git a/libraries/APO/constants.h b/libraries/APO/constants.h new file mode 100644 index 0000000000..2a4316bcb3 --- /dev/null +++ b/libraries/APO/constants.h @@ -0,0 +1,23 @@ +/* + * constants.h + * + * Created on: Apr 7, 2011 + * Author: nkgentry + */ + +#ifndef CONSTANTS_H_ +#define CONSTANTS_H_ + +#include "math.h" + +const float scale_deg = 1e7; // scale of integer degrees/ degree +const float scale_m = 1e3; // scale of integer meters/ meter +const float rEarth = 6371000; // radius of earth, meters +const float rad2Deg = 180 / M_PI; // radians to degrees +const float deg2Rad = M_PI / 180; // degrees to radians +const float rad2DegInt = rad2Deg * scale_deg; // radians to degrees x 1e7 +const float degInt2Rad = deg2Rad / scale_deg; // degrees x 1e7 to radians + +#define MAV_MODE_FAILSAFE MAV_MODE_TEST3 + +#endif /* CONSTANTS_H_ */ diff --git a/libraries/APO/examples/MavlinkTest/Makefile b/libraries/APO/examples/MavlinkTest/Makefile new file mode 100644 index 0000000000..85b4d8856b --- /dev/null +++ b/libraries/APO/examples/MavlinkTest/Makefile @@ -0,0 +1,2 @@ +BOARD = mega +include ../../../AP_Common/Arduino.mk diff --git a/libraries/APO/examples/MavlinkTest/MavlinkTest.pde b/libraries/APO/examples/MavlinkTest/MavlinkTest.pde new file mode 100644 index 0000000000..d64be33822 --- /dev/null +++ b/libraries/APO/examples/MavlinkTest/MavlinkTest.pde @@ -0,0 +1,49 @@ +/* + AnalogReadSerial + Reads an analog input on pin 0, prints the result to the serial monitor + + This example code is in the public domain. + */ + +#include + +int packetDrops = 0; + +void handleMessage(mavlink_message_t * msg) { + Serial.print(", received mavlink message: "); + Serial.print(msg->msgid, DEC); +} + +void setup() { + Serial.begin(57600); + Serial3.begin(57600); + mavlink_comm_0_port = &Serial3; + packetDrops = 0; +} + +void loop() { + mavlink_msg_heartbeat_send(MAVLINK_COMM_0, mavlink_system.type, + MAV_AUTOPILOT_ARDUPILOTMEGA); + Serial.print("heartbeat sent"); + + // receive new packets + mavlink_message_t msg; + mavlink_status_t status; + + Serial.print(", bytes available: "); + Serial.print(comm_get_available(MAVLINK_COMM_0)); + while (comm_get_available( MAVLINK_COMM_0)) { + uint8_t c = comm_receive_ch(MAVLINK_COMM_0); + + // Try to get a new message + if (mavlink_parse_char(MAVLINK_COMM_0, c, &msg, &status)) + handleMessage(&msg); + } + + // Update packet drops counter + packetDrops += status.packet_rx_drop_count; + + Serial.print(", dropped packets: "); + Serial.println(packetDrops); + delay(1000); +} diff --git a/libraries/APO/examples/ServoManual/Makefile b/libraries/APO/examples/ServoManual/Makefile new file mode 100644 index 0000000000..85b4d8856b --- /dev/null +++ b/libraries/APO/examples/ServoManual/Makefile @@ -0,0 +1,2 @@ +BOARD = mega +include ../../../AP_Common/Arduino.mk diff --git a/libraries/APO/examples/ServoManual/ServoManual.pde b/libraries/APO/examples/ServoManual/ServoManual.pde new file mode 100644 index 0000000000..8be346f18a --- /dev/null +++ b/libraries/APO/examples/ServoManual/ServoManual.pde @@ -0,0 +1,109 @@ +/* + Example of RC_Channel library. + Code by James Goppert/ Jason Short. 2010 + DIYDrones.com + + */ +#include +#include +#include +#include // ArduPilot Mega RC Library +#include +#include +FastSerialPort0(Serial) +; // make sure this proceeds variable declarations + +// test settings + +using namespace apo; + +class RadioTest { +private: + float testPosition; + int8_t testSign; + enum { + version, + rollKey, + pitchKey, + thrKey, + yawKey, + ch5Key, + ch6Key, + ch7Key, + ch8Key + }; + Vector ch; +public: + RadioTest() : + testPosition(2), testSign(1) { + ch.push_back( + new AP_RcChannel(rollKey, PSTR("ROLL"), APM_RC, 0, 1100, 1500, + 1900)); + ch.push_back( + new AP_RcChannel(pitchKey, PSTR("PITCH"), APM_RC, 1, 1100, + 1500, 1900)); + ch.push_back( + new AP_RcChannel(thrKey, PSTR("THR"), APM_RC, 2, 1100, 1500, + 1900)); + ch.push_back( + new AP_RcChannel(yawKey, PSTR("YAW"), APM_RC, 3, 1100, 1500, + 1900)); + ch.push_back( + new AP_RcChannel(ch5Key, PSTR("CH5"), APM_RC, 4, 1100, 1500, + 1900)); + ch.push_back( + new AP_RcChannel(ch6Key, PSTR("CH6"), APM_RC, 5, 1100, 1500, + 1900)); + ch.push_back( + new AP_RcChannel(ch7Key, PSTR("CH7"), APM_RC, 6, 1100, 1500, + 1900)); + ch.push_back( + new AP_RcChannel(ch8Key, PSTR("CH8"), APM_RC, 7, 1100, 1500, + 1900)); + + Serial.begin(115200); + delay(2000); + Serial.println("ArduPilot RC Channel test"); + APM_RC.Init(); // APM Radio initialization + delay(2000); + } + + void update() { + // read the radio + for (uint8_t i = 0; i < ch.getSize(); i++) + ch[i]->setUsingRadio(); + + // print channel names + Serial.print("\t\t"); + static char name[7]; + for (uint8_t i = 0; i < ch.getSize(); i++) { + ch[i]->copy_name(name, 7); + Serial.printf("%7s\t", name); + } + Serial.println(); + + // print pwm + Serial.printf("pwm :\t"); + for (uint8_t i = 0; i < ch.getSize(); i++) + Serial.printf("%7d\t", ch[i]->getPwm()); + Serial.println(); + + // print position + Serial.printf("position :\t"); + for (uint8_t i = 0; i < ch.getSize(); i++) + Serial.printf("%7.2f\t", ch[i]->getPosition()); + Serial.println(); + + delay(500); + } +}; + +RadioTest * test; + +void setup() { + test = new RadioTest; +} + +void loop() { + test->update(); +} diff --git a/libraries/APO/examples/ServoSweep/Makefile b/libraries/APO/examples/ServoSweep/Makefile new file mode 100644 index 0000000000..85b4d8856b --- /dev/null +++ b/libraries/APO/examples/ServoSweep/Makefile @@ -0,0 +1,2 @@ +BOARD = mega +include ../../../AP_Common/Arduino.mk diff --git a/libraries/APO/examples/ServoSweep/ServoSweep.pde b/libraries/APO/examples/ServoSweep/ServoSweep.pde new file mode 100644 index 0000000000..75827d4f09 --- /dev/null +++ b/libraries/APO/examples/ServoSweep/ServoSweep.pde @@ -0,0 +1,125 @@ +/* + Example of RC_Channel library. + Code by James Goppert/ Jason Short. 2010 + DIYDrones.com + + */ +#include +#include +#include +#include // ArduPilot Mega RC Library +#include +#include +FastSerialPort0(Serial) +; // make sure this proceeds variable declarations + +// test settings + +using namespace apo; + +class RadioTest { +private: + float testPosition; + int8_t testSign; + enum { + version, + rollKey, + pitchKey, + thrKey, + yawKey, + ch5Key, + ch6Key, + ch7Key, + ch8Key + }; + Vector ch; +public: + RadioTest() : + testPosition(2), testSign(1) { + ch.push_back( + new AP_RcChannel(rollKey, PSTR("ROLL"), APM_RC, 0, 1100, 1500, + 1900)); + ch.push_back( + new AP_RcChannel(pitchKey, PSTR("PITCH"), APM_RC, 1, 1100, + 1500, 1900)); + ch.push_back( + new AP_RcChannel(thrKey, PSTR("THR"), APM_RC, 2, 1100, 1500, + 1900)); + ch.push_back( + new AP_RcChannel(yawKey, PSTR("YAW"), APM_RC, 3, 1100, 1500, + 1900)); + ch.push_back( + new AP_RcChannel(ch5Key, PSTR("CH5"), APM_RC, 4, 1100, 1500, + 1900)); + ch.push_back( + new AP_RcChannel(ch6Key, PSTR("CH6"), APM_RC, 5, 1100, 1500, + 1900)); + ch.push_back( + new AP_RcChannel(ch7Key, PSTR("CH7"), APM_RC, 6, 1100, 1500, + 1900)); + ch.push_back( + new AP_RcChannel(ch8Key, PSTR("CH8"), APM_RC, 7, 1100, 1500, + 1900)); + + Serial.begin(115200); + delay(2000); + Serial.println("ArduPilot RC Channel test"); + APM_RC.Init(); // APM Radio initialization + delay(2000); + } + + void update() { + // update test value + testPosition += testSign * .1; + if (testPosition > 1) { + //eepromRegistry.print(Serial); // show eeprom map + testPosition = 1; + testSign = -1; + } else if (testPosition < -1) { + testPosition = -1; + testSign = 1; + } + + // set channel positions + for (uint8_t i = 0; i < ch.getSize(); i++) + ch[i]->setPosition(testPosition); + + // print test position + Serial.printf("\nnormalized position (%f)\n", testPosition); + + // print channel names + Serial.print("\t\t"); + static char name[7]; + for (uint8_t i = 0; i < ch.getSize(); i++) { + ch[i]->copy_name(name, 7); + Serial.printf("%7s\t", name); + } + Serial.println(); + + // print pwm + Serial.printf("pwm :\t"); + for (uint8_t i = 0; i < ch.getSize(); i++) + Serial.printf("%7d\t", ch[i]->getRadioPwm()); + Serial.println(); + + // print position + Serial.printf("position :\t"); + for (uint8_t i = 0; i < ch.getSize(); i++) + Serial.printf("%7.2f\t", ch[i]->getRadioPosition()); + Serial.println(); + + delay(500); + } +}; + +RadioTest * test; + +void setup() { + test = new RadioTest; +} + +void loop() { + test->update(); +} + +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/template.h b/libraries/APO/template.h new file mode 100644 index 0000000000..0ebf3dd191 --- /dev/null +++ b/libraries/APO/template.h @@ -0,0 +1,32 @@ +/* + * Class.h + * Copyright (C) Author 2011 + * + * This file 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 file 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 . + */ + +#ifndef Class_H +#define Class_H + +namespace apo { + +/// Class description +class Class { +public: +} + +} // namespace apo + +#endif // Class_H +// vim:ts=4:sw=4:expandtab diff --git a/libraries/AP_ADC/AP_ADC_ADS7844.cpp b/libraries/AP_ADC/AP_ADC_ADS7844.cpp index b3ef6cbb76..8e14e2c7b6 100644 --- a/libraries/AP_ADC/AP_ADC_ADS7844.cpp +++ b/libraries/AP_ADC/AP_ADC_ADS7844.cpp @@ -1,232 +1,274 @@ -/* - AP_ADC_ADS7844.cpp - ADC ADS7844 Library for Ardupilot Mega - Code by Jordi Mu�oz and Jose Julio. DIYDrones.com - - Modified by John Ihlein 6 / 19 / 2010 to: - 1)Prevent overflow of adc_counter when more than 8 samples collected between reads. Probably - only an issue on initial read of ADC at program start. - 2)Reorder analog read order as follows: - p, q, r, ax, ay, az - - This library is free software; you can redistribute it and / or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - External ADC ADS7844 is connected via Serial port 2 (in SPI mode) - TXD2 = MOSI = pin PH1 - RXD2 = MISO = pin PH0 - XCK2 = SCK = pin PH2 - Chip Select pin is PC4 (33) [PH6 (9)] - We are using the 16 clocks per conversion timming to increase efficiency (fast) - - The sampling frequency is 1kHz (Timer2 overflow interrupt) - - So if our loop is at 50Hz, our needed sampling freq should be 100Hz, so - we have an 10x oversampling and averaging. - - Methods: - Init() : Initialization of interrupts an Timers (Timer2 overflow interrupt) - Ch(ch_num) : Return the ADC channel value - - // HJI - Input definitions. USB connector assumed to be on the left, Rx and servo - // connector pins to the rear. IMU shield components facing up. These are board - // referenced sensor inputs, not device referenced. - On Ardupilot Mega Hardware, oriented as described above: - Chennel 0 : yaw rate, r - Channel 1 : roll rate, p - Channel 2 : pitch rate, q - Channel 3 : x / y gyro temperature - Channel 4 : x acceleration, aX - Channel 5 : y acceleration, aY - Channel 6 : z acceleration, aZ - Channel 7 : Differential pressure sensor port - -*/ -extern "C" { - // AVR LibC Includes - #include - #include - #include - #include "WConstants.h" -} - -#include "AP_ADC_ADS7844.h" - - -// Commands for reading ADC channels on ADS7844 -static const unsigned char adc_cmd[9] = { 0x87, 0xC7, 0x97, 0xD7, 0xA7, 0xE7, 0xB7, 0xF7, 0x00 }; - -// the sum of the values since last read -static volatile uint32_t _sum[8]; - -// how many values we've accumulated since last read -static volatile uint16_t _count[8]; - -static uint32_t last_ch6_micros; - -// TCNT2 values for various interrupt rates, -// assuming 256 prescaler. Note that these values -// assume a zero-time ISR. The actual rate will be a -// bit lower than this -#define TCNT2_781_HZ (256-80) -#define TCNT2_1008_HZ (256-62) -#define TCNT2_1302_HZ (256-48) - -static inline unsigned char ADC_SPI_transfer(unsigned char data) -{ - /* Put data into buffer, sends the data */ - UDR2 = data; - /* Wait for data to be received */ - while ( !(UCSR2A & (1 << RXC2)) ); - /* Get and return received data from buffer */ - return UDR2; -} - - -ISR (TIMER2_OVF_vect) -{ - uint8_t ch; - static uint8_t timer_offset; - - bit_clear(PORTC, 4); // Enable Chip Select (PIN PC4) - ADC_SPI_transfer(adc_cmd[0]); // Command to read the first channel - - for (ch = 0; ch < 8; ch++) { - uint16_t v; - - v = ADC_SPI_transfer(0) << 8; // Read first byte - v |= ADC_SPI_transfer(adc_cmd[ch + 1]); // Read second byte and send next command - - if (v & 0x8007) { - // this is a 12-bit ADC, shifted by 3 bits. - // if we get other bits set then the value is - // bogus and should be ignored - continue; - } - - if (++_count[ch] == 0) { - // overflow ... shouldn't happen too often - // unless we're just not using the - // channel. Notice that we overflow the count - // to 1 here, not zero, as otherwise the - // reader below could get a division by zero - _sum[ch] = 0; - _count[ch] = 1; - last_ch6_micros = micros(); - } - _sum[ch] += (v >> 3); - } - - bit_set(PORTC, 4); // Disable Chip Select (PIN PC4) - - // this gives us a sample rate between 781Hz and 1302Hz. We - // randomise it to try to minimise aliasing effects - timer_offset = (timer_offset + 49) % 32; - TCNT2 = TCNT2_781_HZ + timer_offset; -} - - -// Constructors //////////////////////////////////////////////////////////////// -AP_ADC_ADS7844::AP_ADC_ADS7844() -{ -} - -// Public Methods ////////////////////////////////////////////////////////////// -void AP_ADC_ADS7844::Init(void) -{ - pinMode(ADC_CHIP_SELECT, OUTPUT); - - digitalWrite(ADC_CHIP_SELECT, HIGH); // Disable device (Chip select is active low) - - // Setup Serial Port2 in SPI mode - UBRR2 = 0; - DDRH |= (1 << PH2); // SPI clock XCK2 (PH2) as output. This enable SPI Master mode - // Set MSPI mode of operation and SPI data mode 0. - UCSR2C = (1 << UMSEL21) | (1 << UMSEL20); // |(0 << UCPHA2) | (0 << UCPOL2); - // Enable receiver and transmitter. - UCSR2B = (1 << RXEN2) | (1 << TXEN2); - // Set Baud rate - UBRR2 = 2; // SPI clock running at 2.6MHz - - // get an initial value for each channel. This ensures - // _count[] is never zero - for (uint8_t i=0; i<8; i++) { - uint16_t adc_tmp; - adc_tmp = ADC_SPI_transfer(0) << 8; - adc_tmp |= ADC_SPI_transfer(adc_cmd[i + 1]); - _count[i] = 1; - _sum[i] = adc_tmp; - } - - last_ch6_micros = micros(); - - // Enable Timer2 Overflow interrupt to capture ADC data - TIMSK2 = 0; // Disable interrupts - TCCR2A = 0; // normal counting mode - TCCR2B = _BV(CS21) | _BV(CS22); // Set prescaler of clk/256 - TCNT2 = 0; - TIFR2 = _BV(TOV2); // clear pending interrupts; - TIMSK2 = _BV(TOIE2); // enable the overflow interrupt -} - -// Read one channel value -uint16_t AP_ADC_ADS7844::Ch(uint8_t ch_num) -{ - uint16_t count; - uint32_t sum; - - // ensure we have at least one value - while (_count[ch_num] == 0) /* noop */ ; - - // grab the value with interrupts disabled, and clear the count - cli(); - count = _count[ch_num]; - sum = _sum[ch_num]; - _count[ch_num] = 0; - _sum[ch_num] = 0; - sei(); - - return sum/count; -} - -// Read 6 channel values -// this assumes that the counts for all of the 6 channels are -// equal. This will only be true if we always consistently access a -// sensor by either Ch6() or Ch() and never mix them. If you mix them -// then you will get very strange results -uint32_t AP_ADC_ADS7844::Ch6(const uint8_t *channel_numbers, uint16_t *result) -{ - uint16_t count[6]; - uint32_t sum[6]; - uint8_t i; - - // ensure we have at least one value - for (i=0; i<6; i++) { - while (_count[channel_numbers[i]] == 0) /* noop */; - } - - // grab the values with interrupts disabled, and clear the counts - cli(); - for (i=0; i<6; i++) { - count[i] = _count[channel_numbers[i]]; - sum[i] = _sum[channel_numbers[i]]; - _count[channel_numbers[i]] = 0; - _sum[channel_numbers[i]] = 0; - } - sei(); - - // calculate averages. We keep this out of the cli region - // to prevent us stalling the ISR while doing the - // division. That costs us 36 bytes of stack, but I think its - // worth it. - for (i=0; i<6; i++) { - result[i] = sum[i] / count[i]; - } - - // return number of microseconds since last call - uint32_t us = micros(); - uint32_t ret = us - last_ch6_micros; - last_ch6_micros = us; - return ret; -} +/* + AP_ADC_ADS7844.cpp - ADC ADS7844 Library for Ardupilot Mega + Code by Jordi Mu�oz and Jose Julio. DIYDrones.com + + Modified by John Ihlein 6 / 19 / 2010 to: + 1)Prevent overflow of adc_counter when more than 8 samples collected between reads. Probably + only an issue on initial read of ADC at program start. + 2)Reorder analog read order as follows: + p, q, r, ax, ay, az + + This library is free software; you can redistribute it and / or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + External ADC ADS7844 is connected via Serial port 2 (in SPI mode) + TXD2 = MOSI = pin PH1 + RXD2 = MISO = pin PH0 + XCK2 = SCK = pin PH2 + Chip Select pin is PC4 (33) [PH6 (9)] + We are using the 16 clocks per conversion timming to increase efficiency (fast) + + The sampling frequency is 1kHz (Timer2 overflow interrupt) + + So if our loop is at 50Hz, our needed sampling freq should be 100Hz, so + we have an 10x oversampling and averaging. + + Methods: + Init() : Initialization of interrupts an Timers (Timer2 overflow interrupt) + Ch(ch_num) : Return the ADC channel value + + // HJI - Input definitions. USB connector assumed to be on the left, Rx and servo + // connector pins to the rear. IMU shield components facing up. These are board + // referenced sensor inputs, not device referenced. + On Ardupilot Mega Hardware, oriented as described above: + Chennel 0 : yaw rate, r + Channel 1 : roll rate, p + Channel 2 : pitch rate, q + Channel 3 : x / y gyro temperature + Channel 4 : x acceleration, aX + Channel 5 : y acceleration, aY + Channel 6 : z acceleration, aZ + Channel 7 : Differential pressure sensor port + +*/ +extern "C" { + // AVR LibC Includes + #include + #include + #include + #include "WConstants.h" +} + +#include "AP_ADC_ADS7844.h" + +// Commands for reading ADC channels on ADS7844 +static const unsigned char adc_cmd[9] = { 0x87, 0xC7, 0x97, 0xD7, 0xA7, 0xE7, 0xB7, 0xF7, 0x00 }; + +// the sum of the values since last read +static volatile uint32_t _sum[8]; + +// how many values we've accumulated since last read +static volatile uint16_t _count[8]; + +static uint32_t last_ch6_micros; + +// TCNT2 values for various interrupt rates, +// assuming 256 prescaler. Note that these values +// assume a zero-time ISR. The actual rate will be a +// bit lower than this +#define TCNT2_781_HZ (256-80) +#define TCNT2_1008_HZ (256-62) +#define TCNT2_1302_HZ (256-48) + +static inline unsigned char ADC_SPI_transfer(unsigned char data) +{ + /* Put data into buffer, sends the data */ + UDR2 = data; + /* Wait for data to be received */ + while ( !(UCSR2A & (1 << RXC2)) ); + /* Get and return received data from buffer */ + return UDR2; +} + + +ISR (TIMER2_OVF_vect) +{ + uint8_t ch; + static uint8_t timer_offset; + + bit_clear(PORTC, 4); // Enable Chip Select (PIN PC4) + ADC_SPI_transfer(adc_cmd[0]); // Command to read the first channel + + for (ch = 0; ch < 8; ch++) { + uint16_t v; + + v = ADC_SPI_transfer(0) << 8; // Read first byte + v |= ADC_SPI_transfer(adc_cmd[ch + 1]); // Read second byte and send next command + + if (v & 0x8007) { + // this is a 12-bit ADC, shifted by 3 bits. + // if we get other bits set then the value is + // bogus and should be ignored + continue; + } + + if (++_count[ch] == 0) { + // overflow ... shouldn't happen too often + // unless we're just not using the + // channel. Notice that we overflow the count + // to 1 here, not zero, as otherwise the + // reader below could get a division by zero + _sum[ch] = 0; + _count[ch] = 1; + last_ch6_micros = micros(); + } + _sum[ch] += (v >> 3); + } + + bit_set(PORTC, 4); // Disable Chip Select (PIN PC4) + + // this gives us a sample rate between 781Hz and 1302Hz. We + // randomise it to try to minimise aliasing effects + timer_offset = (timer_offset + 49) % 32; + TCNT2 = TCNT2_781_HZ + timer_offset; +} + + +// Constructors //////////////////////////////////////////////////////////////// +AP_ADC_ADS7844::AP_ADC_ADS7844() : + _filter_index_accel(0), + filter_result(false) +{ +} + +// Public Methods ////////////////////////////////////////////////////////////// +void AP_ADC_ADS7844::Init(void) +{ + pinMode(ADC_CHIP_SELECT, OUTPUT); + + digitalWrite(ADC_CHIP_SELECT, HIGH); // Disable device (Chip select is active low) + + // Setup Serial Port2 in SPI mode + UBRR2 = 0; + DDRH |= (1 << PH2); // SPI clock XCK2 (PH2) as output. This enable SPI Master mode + // Set MSPI mode of operation and SPI data mode 0. + UCSR2C = (1 << UMSEL21) | (1 << UMSEL20); // |(0 << UCPHA2) | (0 << UCPOL2); + // Enable receiver and transmitter. + UCSR2B = (1 << RXEN2) | (1 << TXEN2); + // Set Baud rate + UBRR2 = 2; // SPI clock running at 2.6MHz + + // get an initial value for each channel. This ensures + // _count[] is never zero + for (uint8_t i=0; i<8; i++) { + uint16_t adc_tmp; + adc_tmp = ADC_SPI_transfer(0) << 8; + adc_tmp |= ADC_SPI_transfer(adc_cmd[i + 1]); + _count[i] = 1; + _sum[i] = adc_tmp; + } + + last_ch6_micros = micros(); + + // Enable Timer2 Overflow interrupt to capture ADC data + TIMSK2 = 0; // Disable interrupts + TCCR2A = 0; // normal counting mode + TCCR2B = _BV(CS21) | _BV(CS22); // Set prescaler of clk/256 + TCNT2 = 0; + TIFR2 = _BV(TOV2); // clear pending interrupts; + TIMSK2 = _BV(TOIE2); // enable the overflow interrupt +} + +// Read one channel value +uint16_t AP_ADC_ADS7844::Ch(uint8_t ch_num) +{ + uint16_t count; + uint32_t sum; + + // ensure we have at least one value + while (_count[ch_num] == 0) /* noop */ ; + + // grab the value with interrupts disabled, and clear the count + cli(); + count = _count[ch_num]; + sum = _sum[ch_num]; + _count[ch_num] = 0; + _sum[ch_num] = 0; + sei(); + + return sum/count; +} + +// Read 6 channel values +// this assumes that the counts for all of the 6 channels are +// equal. This will only be true if we always consistently access a +// sensor by either Ch6() or Ch() and never mix them. If you mix them +// then you will get very strange results +uint32_t AP_ADC_ADS7844::Ch6(const uint8_t *channel_numbers, uint16_t *result) +{ + uint16_t count[6]; + uint32_t sum[6]; + uint8_t i; + + // ensure we have at least one value + for (i=0; i<6; i++) { + while (_count[channel_numbers[i]] == 0) /* noop */; + } + + // grab the values with interrupts disabled, and clear the counts + cli(); + for (i=0; i<6; i++) { + count[i] = _count[channel_numbers[i]]; + sum[i] = _sum[channel_numbers[i]]; + _count[channel_numbers[i]] = 0; + _sum[channel_numbers[i]] = 0; + } + sei(); + + // calculate averages. We keep this out of the cli region + // to prevent us stalling the ISR while doing the + // division. That costs us 36 bytes of stack, but I think its + // worth it. + for (i = 0; i < 6; i++) { + result[i] = sum[i] / count[i]; + } + + + if(filter_result){ + uint32_t _sum_accel; + + // simple Gyro Filter + for (i = 0; i < 3; i++) { + // add prev filtered value to new raw value, divide by 2 + result[i] = (_prev_gyro[i] + result[i]) >> 1; + + // remember the filtered value + _prev_gyro[i] = result[i]; + } + + // Accel filter + for (i = 0; i < 3; i++) { + // move most recent result into filter + _filter_accel[i][_filter_index_accel] = result[i+3]; + + // clear the sum + _sum_accel = 0; + + // sum the filter + for (uint8_t n = 0; n < ADC_ACCEL_FILTER_SIZE; n++) { + _sum_accel += _filter_accel[i][n]; + } + + // filter does a moving average on last 8 reads, sums half with half of last filtered value + // save old result + _prev_accel[i] = result[i+3] = (_sum_accel >> 4) + (_prev_accel[i] >> 1); // divide by 16, divide by 2 + + } + + // increment filter index + _filter_index_accel++; + + // loop our filter + if(_filter_index_accel == ADC_ACCEL_FILTER_SIZE) + _filter_index_accel = 0; + } + + + // return number of microseconds since last call + uint32_t us = micros(); + uint32_t ret = us - last_ch6_micros; + last_ch6_micros = us; + return ret; +} diff --git a/libraries/AP_ADC/AP_ADC_ADS7844.h b/libraries/AP_ADC/AP_ADC_ADS7844.h index 2b1314ea1c..d5e36c93dd 100644 --- a/libraries/AP_ADC/AP_ADC_ADS7844.h +++ b/libraries/AP_ADC/AP_ADC_ADS7844.h @@ -1,32 +1,40 @@ -#ifndef AP_ADC_ADS7844_H -#define AP_ADC_ADS7844_H - -#define bit_set(p,m) ((p) |= ( 1< - -class AP_ADC_ADS7844 : public AP_ADC -{ - public: - AP_ADC_ADS7844(); // Constructor - void Init(); - - // Read 1 sensor value - uint16_t Ch(unsigned char ch_num); - - // Read 6 sensors at once - uint32_t Ch6(const uint8_t *channel_numbers, uint16_t *result); - - private: -}; - -#endif +#ifndef AP_ADC_ADS7844_H +#define AP_ADC_ADS7844_H + +#define bit_set(p,m) ((p) |= ( 1< + +class AP_ADC_ADS7844 : public AP_ADC +{ + public: + AP_ADC_ADS7844(); // Constructor + void Init(); + + // Read 1 sensor value + uint16_t Ch(unsigned char ch_num); + + // Read 6 sensors at once + uint32_t Ch6(const uint8_t *channel_numbers, uint16_t *result); + bool filter_result; + + private: + uint16_t _filter_accel[3][ADC_ACCEL_FILTER_SIZE]; + uint16_t _prev_gyro[3]; + uint16_t _prev_accel[3]; + uint8_t _filter_index_accel; + +}; + +#endif diff --git a/libraries/AP_ADC/CMakeLists.txt b/libraries/AP_ADC/CMakeLists.txt deleted file mode 100644 index df85645fb2..0000000000 --- a/libraries/AP_ADC/CMakeLists.txt +++ /dev/null @@ -1,26 +0,0 @@ -set(LIB_NAME AP_ADC) - -set(${LIB_NAME}_SRCS - AP_ADC_HIL.cpp - AP_ADC_ADS7844.cpp - AP_ADC.cpp - ) # Firmware sources - -set(${LIB_NAME}_HDRS - AP_ADC_HIL.h - AP_ADC_ADS7844.h - AP_ADC.h - ) - -include_directories( - - - - #${CMAKE_SOURCE_DIR}/libraries/AP_Math - #${CMAKE_SOURCE_DIR}/libraries/AP_Common - #${CMAKE_SOURCE_DIR}/libraries/FastSerial -# - ) - -set(${LIB_NAME}_BOARD mega2560) - -generate_arduino_library(${LIB_NAME}) diff --git a/libraries/AP_Common/AP_Var.cpp b/libraries/AP_Common/AP_Var.cpp index 956f527a3a..474dcb8541 100644 --- a/libraries/AP_Common/AP_Var.cpp +++ b/libraries/AP_Common/AP_Var.cpp @@ -9,19 +9,21 @@ /// @file AP_Var.cpp /// @brief The AP variable store. -#if 0 -# include -extern "C" { extern void delay(unsigned long); } -# define debug(fmt, args...) do {Serial.printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__ , ##args); delay(100); } while(0) -#else -# define debug(fmt, args...) -#endif #include #include #include +//#define ENABLE_FASTSERIAL_DEBUG + +#ifdef ENABLE_FASTSERIAL_DEBUG +# include +# define serialDebug(fmt, args...) if (FastSerial::getInitialized(0)) do {Serial.printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__ , ##args); delay(0); } while(0) +#else +# define serialDebug(fmt, args...) +#endif + // Global constants exported for general use. // AP_Float AP_Float_unity ( 1.0, AP_Var::k_key_none, NULL, AP_Var::k_flag_unlisted); @@ -71,7 +73,11 @@ AP_Var::AP_Var(AP_Var_group *pGroup, Key index, const prog_char_t *name, Flags f // to the pointer to the node that we are considering inserting in front of. // vp = &_grouped_variables; + size_t loopCount = 0; while (*vp != NULL) { + + if (loopCount++>k_num_max) return; + if ((*vp)->_key >= _key) { break; } @@ -98,12 +104,19 @@ AP_Var::~AP_Var(void) } // Scan the list and remove this if we find it - while (*vp) { - if (*vp == this) { - *vp = _link; - break; - } - vp = &((*vp)->_link); + + { + size_t loopCount = 0; + while (*vp) { + + if (loopCount++>k_num_max) return; + + if (*vp == this) { + *vp = _link; + break; + } + vp = &((*vp)->_link); + } } // If we are destroying a group, remove all its variables from the list @@ -112,8 +125,12 @@ AP_Var::~AP_Var(void) // Scan the list and remove any variable that has this as its group vp = &_grouped_variables; + size_t loopCount = 0; + while (*vp) { + if (loopCount++>k_num_max) return; + // Does the variable claim us as its group? if ((*vp)->_group == this) { *vp = (*vp)->_link; @@ -145,7 +162,12 @@ AP_Var::find(const char *name) { AP_Var *vp; + size_t loopCount = 0; + for (vp = first(); vp; vp = vp->next()) { + + if (loopCount++>k_num_max) return NULL; + char name_buffer[32]; // copy the variable's name into our scratch buffer @@ -165,9 +187,9 @@ AP_Var * AP_Var::find(Key key) { AP_Var *vp; - + size_t loopCount = 0; for (vp = first(); vp; vp = vp->next()) { - + if (loopCount++>k_num_max) return NULL; if (key == vp->key()) { return vp; } @@ -188,11 +210,11 @@ bool AP_Var::save(void) return _group->save(); } - debug("save: %S", _name ? _name : PSTR("??")); + serialDebug("save: %S", _name ? _name : PSTR("??")); // locate the variable in EEPROM, allocating space as required if (!_EEPROM_locate(true)) { - debug("locate failed"); + serialDebug("locate failed"); return false; } @@ -200,13 +222,13 @@ bool AP_Var::save(void) size = serialize(vbuf, sizeof(vbuf)); if (0 == size) { // variable cannot be serialised into the buffer - debug("cannot save (too big or not supported)"); + serialDebug("cannot save (too big or not supported)"); return false; } // if it fit in the buffer, save it to EEPROM if (size <= sizeof(vbuf)) { - debug("saving %u to %u", size, _key); + serialDebug("saving %u to %u", size, _key); // XXX this should use eeprom_update_block if/when Arduino moves to // avr-libc >= 1.7 uint8_t *ep = (uint8_t *)_key; @@ -219,7 +241,7 @@ bool AP_Var::save(void) // now read it back newv = eeprom_read_byte(ep); if (newv != vbuf[i]) { - debug("readback failed at offset %p: got %u, expected %u", + serialDebug("readback failed at offset %p: got %u, expected %u", ep, newv, vbuf[i]); return false; } @@ -241,11 +263,11 @@ bool AP_Var::load(void) return _group->load(); } - debug("load: %S", _name ? _name : PSTR("??")); + serialDebug("load: %S", _name ? _name : PSTR("??")); // locate the variable in EEPROM, but do not allocate space if (!_EEPROM_locate(false)) { - debug("locate failed"); + serialDebug("locate failed"); return false; } @@ -255,7 +277,7 @@ bool AP_Var::load(void) // size = serialize(NULL, 0); if (0 == size) { - debug("cannot load (too big or not supported)"); + serialDebug("cannot load (too big or not supported)"); return false; } @@ -263,7 +285,7 @@ bool AP_Var::load(void) // has converted _key into an EEPROM address. // if (size <= sizeof(vbuf)) { - debug("loading %u from %u", size, _key); + serialDebug("loading %u from %u", size, _key); eeprom_read_block(vbuf, (void *)_key, size); return unserialize(vbuf, size); } @@ -278,7 +300,12 @@ bool AP_Var::save_all(void) bool result = true; AP_Var *vp = _variables; + size_t loopCount = 0; + while (vp) { + + if (loopCount++>k_num_max) return false; + if (!vp->has_flags(k_flag_no_auto_load) && // not opted out of autosave (vp->_key != k_key_none)) { // has a key @@ -298,7 +325,12 @@ bool AP_Var::load_all(void) bool result = true; AP_Var *vp = _variables; + size_t loopCount = 0; + while (vp) { + + if (loopCount++>k_num_max) return false; + if (!vp->has_flags(k_flag_no_auto_load) && // not opted out of autoload (vp->_key != k_key_none)) { // has a key @@ -322,13 +354,19 @@ AP_Var::erase_all() AP_Var *vp; uint16_t i; - debug("erase EEPROM"); + serialDebug("erase EEPROM"); // Scan the list of variables/groups, fetching their key values and // reverting them to their not-located state. // vp = _variables; + + size_t loopCount = 0; + while (vp) { + + if (loopCount++>k_num_max) return; + vp->_key = vp->key() | k_key_not_located; vp = vp->_link; } @@ -405,9 +443,15 @@ AP_Var::first_member(AP_Var_group *group) vp = &_grouped_variables; - debug("seeking %p", group); + serialDebug("seeking %p", group); + + size_t loopCount = 0; + while (*vp) { - debug("consider %p with %p", *vp, (*vp)->_group); + + if (loopCount++>k_num_max) return NULL; + + serialDebug("consider %p with %p", *vp, (*vp)->_group); if ((*vp)->_group == group) { return *vp; } @@ -423,7 +467,12 @@ AP_Var::next_member() AP_Var *vp; vp = _link; + size_t loopCount = 0; + while (vp) { + + if (loopCount++>k_num_max) return NULL; + if (vp->_group == _group) { return vp; } @@ -451,7 +500,7 @@ bool AP_Var::_EEPROM_scan(void) if ((ee_header.magic != k_EEPROM_magic) || (ee_header.revision != k_EEPROM_revision)) { - debug("no header, magic 0x%x revision %u", ee_header.magic, ee_header.revision); + serialDebug("no header, magic 0x%x revision %u", ee_header.magic, ee_header.revision); return false; } @@ -460,17 +509,22 @@ bool AP_Var::_EEPROM_scan(void) // Avoid trying to read a header when there isn't enough space left. // eeprom_address = sizeof(ee_header); + + size_t loopCount = 0; + while (eeprom_address < (k_EEPROM_size - sizeof(var_header) - 1)) { + if (loopCount++>k_num_max) return NULL; + // Read a variable header // - debug("reading header from %u", eeprom_address); + serialDebug("reading header from %u", eeprom_address); eeprom_read_block(&var_header, (void *)eeprom_address, sizeof(var_header)); // If the header is for the sentinel, scanning is complete // if (var_header.key == k_key_sentinel) { - debug("found tail sentinel"); + serialDebug("found tail sentinel"); break; } @@ -482,23 +536,25 @@ bool AP_Var::_EEPROM_scan(void) var_header.size + 1 + // data for this variable sizeof(var_header))) { // header for sentinel - debug("header overruns EEPROM"); + serialDebug("header overruns EEPROM"); return false; } // look for a variable with this key vp = _variables; - while (vp) { + size_t loopCount2 = 0; + while(vp) { + if (loopCount2++>k_num_max) return false; if (vp->key() == var_header.key) { // adjust the variable's key to point to this entry vp->_key = eeprom_address + sizeof(var_header); - debug("update %p with key %u -> %u", vp, var_header.key, vp->_key); + serialDebug("update %p with key %u -> %u", vp, var_header.key, vp->_key); break; } vp = vp->_link; } if (!vp) { - debug("key %u not claimed (already scanned or unknown)", var_header.key); + serialDebug("key %u not claimed (already scanned or unknown)", var_header.key); } // move to the next variable header @@ -514,16 +570,18 @@ bool AP_Var::_EEPROM_scan(void) // mark all the rest as not allocated. // vp = _variables; - while (vp) { + size_t loopCount3 = 0; + while(vp) { + if (loopCount3++>k_num_max) return false; if (vp->_key & k_key_not_located) { vp->_key |= k_key_not_allocated; - debug("key %u not allocated", vp->key()); + serialDebug("key %u not allocated", vp->key()); } vp = vp->_link; } // Scanning is complete - debug("scan done"); + serialDebug("scan done"); _tail_sentinel = eeprom_address; return true; } @@ -539,7 +597,7 @@ bool AP_Var::_EEPROM_locate(bool allocate) // Is it a group member, or does it have a no-location key? // if (_group || (_key == k_key_none)) { - debug("not addressable"); + serialDebug("not addressable"); return false; // it is/does, and thus it has no location } @@ -554,7 +612,7 @@ bool AP_Var::_EEPROM_locate(bool allocate) // try scanning to see if we can locate it. // if (!(_key & k_key_not_allocated)) { - debug("need scan"); + serialDebug("need scan"); _EEPROM_scan(); // Has the variable now been located? @@ -569,7 +627,7 @@ bool AP_Var::_EEPROM_locate(bool allocate) if (!allocate) { return false; } - debug("needs allocation"); + serialDebug("needs allocation"); // Ask the serializer for the size of the thing we are allocating, and fail // if it is too large or if it has no size, as we will not be able to allocate @@ -577,7 +635,7 @@ bool AP_Var::_EEPROM_locate(bool allocate) // size = serialize(NULL, 0); if ((size == 0) || (size > k_size_max)) { - debug("size %u out of bounds", size); + serialDebug("size %u out of bounds", size); return false; } @@ -585,7 +643,7 @@ bool AP_Var::_EEPROM_locate(bool allocate) // header and the new tail sentinel. // if ((_tail_sentinel + size + sizeof(Var_header) * 2) > k_EEPROM_size) { - debug("no space in EEPROM"); + serialDebug("no space in EEPROM"); return false; } @@ -595,7 +653,7 @@ bool AP_Var::_EEPROM_locate(bool allocate) if (0 == _tail_sentinel) { uint8_t pad_size; - debug("writing header"); + serialDebug("writing header"); EEPROM_header ee_header; ee_header.magic = k_EEPROM_magic; @@ -621,7 +679,7 @@ bool AP_Var::_EEPROM_locate(bool allocate) // new_location = _tail_sentinel; _tail_sentinel += sizeof(var_header) + size; - debug("allocated %u/%u for key %u new sentinel %u", new_location, size, key(), _tail_sentinel); + serialDebug("allocated %u/%u for key %u new sentinel %u", new_location, size, key(), _tail_sentinel); // Write the new sentinel first. If we are interrupted during this operation // the old sentinel will still correctly terminate the EEPROM image. @@ -670,17 +728,22 @@ AP_Var_group::_serialize_unserialize(void *buf, size_t buf_size, bool do_seriali // Traverse the list of group members, serializing each in order // vp = first_member(this); - debug("starting with %p", vp); + serialDebug("starting with %p", vp); total_size = 0; + + size_t loopCount = 0; + while (vp) { + if (loopCount++>k_num_max) return false; + // (un)serialise the group member if (do_serialize) { size = vp->serialize(buf, buf_size); - debug("serialize %p -> %u", vp, size); + serialDebug("serialize %p -> %u", vp, size); } else { size = vp->unserialize(buf, buf_size); - debug("unserialize %p -> %u", vp, size); + serialDebug("unserialize %p -> %u", vp, size); } // Unserialize will return zero if the buffer is too small @@ -688,7 +751,7 @@ AP_Var_group::_serialize_unserialize(void *buf, size_t buf_size, bool do_seriali // Either case is fatal for any operation we might be trying. // if (0 == size) { - debug("group (un)serialize failed, buffer too small or not supported"); + serialDebug("group (un)serialize failed, buffer too small or not supported"); return 0; } @@ -704,7 +767,7 @@ AP_Var_group::_serialize_unserialize(void *buf, size_t buf_size, bool do_seriali // and the calling function will have to treat it as an error. // total_size += size; - debug("used %u", total_size); + serialDebug("used %u", total_size); if (size <= buf_size) { // there was space for this one, account for it buf_size -= size; diff --git a/libraries/AP_Common/AP_Var.h b/libraries/AP_Common/AP_Var.h index 6ed680d7ab..4fd5dc1d49 100644 --- a/libraries/AP_Common/AP_Var.h +++ b/libraries/AP_Common/AP_Var.h @@ -128,6 +128,10 @@ public: /// static const size_t k_size_max = 64; + /// The maximum number of keys + /// + static const size_t k_num_max = 255; + /// Optional flags affecting the behavior and usage of the variable. /// typedef uint8_t Flags; diff --git a/libraries/AP_Common/Arduino.mk b/libraries/AP_Common/Arduino.mk index 8d34a6fd54..9850b11475 100644 --- a/libraries/AP_Common/Arduino.mk +++ b/libraries/AP_Common/Arduino.mk @@ -43,12 +43,11 @@ SRCROOT := $(realpath $(dir $(firstword $(MAKEFILE_LIST)))) ifneq ($(findstring CYGWIN, $(SYSTYPE)),) # Workaround a $(realpath ) bug on cygwin ifeq ($(SRCROOT),) - SRCROOT := $(subst /cygdrive/c,c:,$(CURDIR)) + SRCROOT := $(shell cygpath -m ${CURDIR}) $(warning your realpath function is not working) $(warning > setting SRCROOT to $(SRCROOT)) endif # Correct the directory backslashes on cygwin - SKETCHBOOK := $(subst \,/,$(SKETCHBOOK)) ARDUINO := $(subst \,/,$(ARDUINO)) endif @@ -77,6 +76,11 @@ else $(warning WARNING: sketchbook directory $(SKETCHBOOK) contains no libraries) endif endif +ifneq ($(findstring CYGWIN, $(SYSTYPE)),) + # Convert cygwin path into a windows normal path + SKETCHBOOK := $(shell cygpath -d ${SKETCHBOOK}) + SKETCHBOOK := $(subst \,/,$(SKETCHBOOK)) +endif # # Work out the sketch name from the name of the source directory. @@ -142,14 +146,29 @@ ifeq ($(ARDUINO),) ARDUINOS := $(wildcard $(ARDUINO_SEARCHPATH)) endif + ifneq ($(findstring CYGWIN, $(SYSTYPE)),) + # Most of the following commands are simply to deal with whitespaces in the path + # Read the "Program Files" system directory from the windows registry + PROGRAM_FILES := $(shell cat /proc/registry/HKEY_LOCAL_MACHINE/SOFTWARE/Microsoft/Windows/CurrentVersion/ProgramFilesDir) + # Convert the path delimiters to / + PROGRAM_FILES := $(shell cygpath -m ${PROGRAM_FILES}) + # Escape the space with a backslash + PROGRAM_FILES := $(shell echo $(PROGRAM_FILES) | sed s/\ /\\\\\ / ) + # Use DOS paths because they do not contain spaces + PROGRAM_FILES := $(shell cygpath -d ${PROGRAM_FILES}) + # Convert the path delimiters to / + PROGRAM_FILES := $(subst \,/,$(PROGRAM_FILES)) + # Search for an Arduino instalation in a couple of paths + ARDUINO_SEARCHPATH := c:/arduino* $(PROGRAM_FILES)/arduino* + ARDUINOS := $(wildcard $(ARDUINO_SEARCHPATH)) + endif + # # Pick the first option if more than one candidate is found. # - # XXX this is bad if any of the paths (c:\Program Files\ anyone?) has a space in its name... - # ARDUINO := $(firstword $(ARDUINOS)) ifeq ($(ARDUINO),) - $(error ERROR: Cannot find Arduino on this system, please specify on the commandline with ARDUINO=) + $(error ERROR: Cannot find Arduino on this system, please specify on the commandline with ARDUINO= or on the config.mk file) endif ifneq ($(words $(ARDUINOS)),1) @@ -189,6 +208,9 @@ CC := $(call FIND_TOOL,avr-gcc) AS := $(call FIND_TOOL,avr-gcc) AR := $(call FIND_TOOL,avr-ar) LD := $(call FIND_TOOL,avr-gcc) +GDB := $(call FIND_TOOL,avr-gdb) +AVRDUDE := $(call FIND_TOOL,avrdude) +AVARICE := $(call FIND_TOOL,avarice) OBJCOPY := $(call FIND_TOOL,avr-objcopy) ifeq ($(CXX),) $(error ERROR: cannot find the compiler tools anywhere on the path $(TOOLPATH)) @@ -305,7 +327,14 @@ LIBOBJS := $(SKETCHLIBOBJS) $(ARDUINOLIBOBJS) # Pull the Arduino version from the revisions.txt file # # XXX can we count on this? If not, what? -ARDUINO_VERS := $(shell expr `head -1 $(ARDUINO)/revisions.txt | cut -d ' ' -f 2`) +ARDUINO_VERS := $(shell expr `head -1 $(ARDUINO)/revisions.txt | cut -d ' ' -f 2`) +# If the version is not a number, try it again, using another file +ifneq ($(ARDUINO_VERS),$(shell echo $(ARDUINO_VERS) | sed 's/[^0-9]*//g')) + ARDUINO_VERS := $(shell expr `head -1 $(ARDUINO)/lib/version.txt | cut -d ' ' -f 2`) +endif +ifneq ($(ARDUINO_VERS),$(shell echo $(ARDUINO_VERS) | sed 's/[^0-9]*//g')) + $(warning Could not determine Arduino version) +endif # Find the hardware directory to use HARDWARE_DIR := $(firstword $(wildcard $(SKETCHBOOK)/hardware/$(HARDWARE) \ @@ -327,7 +356,13 @@ HARDWARE_CORE := $(shell grep $(BOARD).build.core $(BOARDFILE) | cut -d = -f 2) UPLOAD_SPEED := $(shell grep $(BOARD).upload.speed $(BOARDFILE) | cut -d = -f 2) ifeq ($(UPLOAD_PROTOCOL),) -UPLOAD_PROTOCOL := $(shell grep $(BOARD).upload.protocol $(BOARDFILE) | cut -d = -f 2) + UPLOAD_PROTOCOL := $(shell grep $(BOARD).upload.protocol $(BOARDFILE) | cut -d = -f 2) +endif + +# Adding override for mega since boards.txt uses stk500 instead of +# arduino on 22 release +ifeq ($(BOARD),mega) + UPLOAD_PROTOCOL := arduino endif ifeq ($(MCU),) @@ -380,21 +415,31 @@ all: $(SKETCHELF) $(SKETCHEEP) $(SKETCHHEX) .PHONY: upload upload: $(SKETCHHEX) - avrdude -c $(UPLOAD_PROTOCOL) -p $(MCU) -P $(PORT) -b$(UPLOAD_SPEED) -U $(SKETCHHEX) + $(AVRDUDE) -c $(UPLOAD_PROTOCOL) -p $(MCU) -P $(PORT) -b$(UPLOAD_SPEED) -U $(SKETCHHEX) configure: $(warning WARNING - A $(SKETCHBOOK)/config.mk file has been written) $(warning Please edit the file to match your system configuration, if you use a different board or port) - @echo BOARD=mega > $(SKETCHBOOK)/config.mk - @echo PORT=/dev/null >> $(SKETCHBOOK)/config.mk + @echo \# Select \'mega\' for the original APM, or \'mega2560\' for the V2 APM. > $(SKETCHBOOK)/config.mk + @echo BOARD=mega >> $(SKETCHBOOK)/config.mk + @echo \# The communication port used to communicate with the APM. >> $(SKETCHBOOK)/config.mk +ifneq ($(findstring CYGWIN, $(SYSTYPE)),) + @echo PORT=com3 >> $(SKETCHBOOK)/config.mk +else + @echo PORT=/dev/ttyUSB0 >> $(SKETCHBOOK)/config.mk +endif debug: - avarice --mkII --capture --jtag usb :4242 & \ - gnome-terminal -x avr-gdb $(SKETCHELF) & \ + $(AVARICE) --mkII --capture --jtag usb :4242 & \ + gnome-terminal -x $(GDB) $(SKETCHELF) & \ echo -e '\n\nat the gdb prompt type "target remote localhost:4242"' clean: +ifneq ($(findstring CYGWIN, $(SYSTYPE)),) + @del /S $(BUILDROOT) +else @rm -fr $(BUILDROOT) +endif ################################################################################ # Rules diff --git a/libraries/AP_Common/CMakeLists.txt b/libraries/AP_Common/CMakeLists.txt deleted file mode 100644 index 7d89ba1e40..0000000000 --- a/libraries/AP_Common/CMakeLists.txt +++ /dev/null @@ -1,33 +0,0 @@ -set(LIB_NAME AP_Common) - -set(${LIB_NAME}_SRCS - AP_Common.cpp - AP_Loop.cpp - AP_MetaClass.cpp - AP_Var.cpp - AP_Var_menufuncs.cpp - c++.cpp - menu.cpp - ) # Firmware sources - -set(${LIB_NAME}_HDRS - AP_Common.h - AP_Loop.h - AP_MetaClass.h - AP_Var.h - AP_Test.h - c++.h - AP_Vector.h -) - -include_directories( - - - - ${CMAKE_SOURCE_DIR}/libraries/AP_Common - ${CMAKE_SOURCE_DIR}/libraries/FastSerial -# - ) - -set(${LIB_NAME}_BOARD mega2560) - -generate_arduino_library(${LIB_NAME}) diff --git a/libraries/AP_Compass/CMakeLists.txt b/libraries/AP_Compass/CMakeLists.txt deleted file mode 100644 index 613b751ef4..0000000000 --- a/libraries/AP_Compass/CMakeLists.txt +++ /dev/null @@ -1,27 +0,0 @@ -set(LIB_NAME AP_Compass) - -set(${LIB_NAME}_SRCS - AP_Compass_HIL.cpp - AP_Compass_HMC5843.cpp - Compass.cpp - ) # Firmware sources - -set(${LIB_NAME}_HDRS - Compass.h - AP_Compass_HIL.h - AP_Compass_HMC5843.h - AP_Compass.h - ) - - - -include_directories( - - - - ${ARDUINO_LIBRARIES_PATH}/Wire - #${CMAKE_SOURCE_DIR}/libraries/FastSerial - # -) -set(${LIB_NAME}_BOARD mega2560) - -generate_arduino_library(${LIB_NAME}) diff --git a/libraries/AP_DCM/CMakeLists.txt b/libraries/AP_DCM/CMakeLists.txt deleted file mode 100644 index 0131eeb495..0000000000 --- a/libraries/AP_DCM/CMakeLists.txt +++ /dev/null @@ -1,25 +0,0 @@ -set(LIB_NAME AP_DCM) - -set(${LIB_NAME}_SRCS - AP_DCM.cpp - AP_DCM_HIL.cpp - #AP_OpticalFlow_ADNS3080.cpp - ) # Firmware sources - -set(${LIB_NAME}_HDRS - AP_DCM.h - AP_DCM_HIL.h - ) - -include_directories( - - - - ${CMAKE_SOURCE_DIR}/libraries/AP_DCM - #${CMAKE_SOURCE_DIR}/libraries/AP_Common - #${CMAKE_SOURCE_DIR}/libraries/FastSerial -# - ) - -set(${LIB_NAME}_BOARD mega2560) - -generate_arduino_library(${LIB_NAME}) diff --git a/libraries/AP_GPS/CMakeLists.txt b/libraries/AP_GPS/CMakeLists.txt deleted file mode 100644 index 57409c6d24..0000000000 --- a/libraries/AP_GPS/CMakeLists.txt +++ /dev/null @@ -1,44 +0,0 @@ -set(LIB_NAME AP_GPS) - -set(${LIB_NAME}_SRCS - AP_GPS_406.cpp - AP_GPS_Auto.cpp - AP_GPS_HIL.cpp - AP_GPS_IMU.cpp - AP_GPS_MTK.cpp - AP_GPS_MTK16.cpp - AP_GPS_NMEA.cpp - AP_GPS_SIRF.cpp - AP_GPS_UBLOX.cpp - GPS.cpp - ) # Firmware sources - -set(${LIB_NAME}_HDRS - AP_GPS_406.h - AP_GPS_Auto.h - AP_GPS_HIL.h - AP_GPS_IMU.h - AP_GPS_MTK.h - AP_GPS_MTK_Common.h - AP_GPS_MTK16.h - AP_GPS_NMEA.h - AP_GPS_None.h - AP_GPS_Shim.h - AP_GPS_SIRF.h - AP_GPS_UBLOX.h - AP_GPS.h - GPS.h - ) - -include_directories( - - - - #${CMAKE_SOURCE_DIR}/libraries/AP_Math - ${CMAKE_SOURCE_DIR}/libraries/AP_Common - ${CMAKE_SOURCE_DIR}/libraries/FastSerial -# - ) - -set(${LIB_NAME}_BOARD mega2560) - -generate_arduino_library(${LIB_NAME}) diff --git a/libraries/AP_IMU/AP_IMU_Oilpan.cpp b/libraries/AP_IMU/AP_IMU_Oilpan.cpp index 73cef75e4e..a150648b56 100644 --- a/libraries/AP_IMU/AP_IMU_Oilpan.cpp +++ b/libraries/AP_IMU/AP_IMU_Oilpan.cpp @@ -293,9 +293,9 @@ AP_IMU_Oilpan::update(void) _accel.y = _accel_scale * _sensor_in(4, adc_values[4], tc_temp); _accel.z = _accel_scale * _sensor_in(5, adc_values[5], tc_temp); - _accel_filtered.x = _accel_filtered.x * .98 + _accel.x * .02; - _accel_filtered.y = _accel_filtered.y * .98 + _accel.y * .02; - _accel_filtered.z = _accel_filtered.z * .98 + _accel.z * .02; + _accel_filtered.x = _accel_filtered.x / 2 + _accel.x / 2; + _accel_filtered.y = _accel_filtered.y / 2 + _accel.y / 2; + _accel_filtered.z = _accel_filtered.z / 2 + _accel.z / 2; // always updated return true; diff --git a/libraries/AP_IMU/CMakeLists.txt b/libraries/AP_IMU/CMakeLists.txt deleted file mode 100644 index 2447a078c4..0000000000 --- a/libraries/AP_IMU/CMakeLists.txt +++ /dev/null @@ -1,25 +0,0 @@ -set(LIB_NAME AP_IMU) - -set(${LIB_NAME}_SRCS - AP_IMU_Oilpan.cpp - ) # Firmware sources - -set(${LIB_NAME}_HDRS - AP_IMU.h - AP_IMU_Shim.h - AP_IMU_Oilpan.h - IMU.h - ) - -include_directories( - - - - #${CMAKE_SOURCE_DIR}/libraries/AP_Math - ${CMAKE_SOURCE_DIR}/libraries/AP_Common - ${CMAKE_SOURCE_DIR}/libraries/FastSerial -# - ) - -set(${LIB_NAME}_BOARD mega2560) - -generate_arduino_library(${LIB_NAME}) diff --git a/libraries/AP_Math/CMakeLists.txt b/libraries/AP_Math/CMakeLists.txt deleted file mode 100644 index f4a83b3102..0000000000 --- a/libraries/AP_Math/CMakeLists.txt +++ /dev/null @@ -1,24 +0,0 @@ -set(LIB_NAME AP_Math) - -set(${LIB_NAME}_SRCS - - ) # Firmware sources - -set(${LIB_NAME}_HDRS - AP_Math.h - matrix3.h - vector2.h - vector3.h - ) - -include_directories( - - - -# ${CMAKE_SOURCE_DIR}/libraries/AP_Common - #${CMAKE_SOURCE_DIR}/libraries/FastSerial -# - ) - -set(${LIB_NAME}_BOARD mega2560) - -generate_arduino_library(${LIB_NAME}) diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp index da47395701..25dbec3fec 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp @@ -97,9 +97,9 @@ AP_OpticalFlow::update_position(float roll, float pitch, float cos_yaw_x, float x_cm = -change_x * avg_altitude * conv_factor; // perhaps this altitude should actually be the distance to the ground? i.e. if we are very rolled over it should be longer? y_cm = -change_y * avg_altitude * conv_factor; // for example if you are leaned over at 45 deg the ground will appear farther away and motion from opt flow sensor will be less - - vlon = x_cm * sin_yaw_y - y_cm * cos_yaw_x; - vlat = y_cm * sin_yaw_y - x_cm * cos_yaw_x; + // convert x/y movements into lon/lat movement + vlon = x_cm * sin_yaw_y + y_cm * cos_yaw_x; + vlat = y_cm * sin_yaw_y - x_cm * cos_yaw_x; } _last_altitude = altitude; diff --git a/libraries/AP_OpticalFlow/CMakeLists.txt b/libraries/AP_OpticalFlow/CMakeLists.txt deleted file mode 100644 index 74d7457ac4..0000000000 --- a/libraries/AP_OpticalFlow/CMakeLists.txt +++ /dev/null @@ -1,24 +0,0 @@ -set(LIB_NAME AP_OpticalFlow) - -set(${LIB_NAME}_SRCS - AP_OpticalFlow.cpp - #AP_OpticalFlow_ADNS3080.cpp - ) # Firmware sources - -set(${LIB_NAME}_HDRS - AP_OpticalFlow.h - #AP_OpticalFlow_ADNS3080.h - ) - -include_directories( - - - - ${CMAKE_SOURCE_DIR}/libraries/AP_Math - #${CMAKE_SOURCE_DIR}/libraries/AP_Common - #${CMAKE_SOURCE_DIR}/libraries/FastSerial -# - ) - -set(${LIB_NAME}_BOARD mega2560) - -generate_arduino_library(${LIB_NAME}) diff --git a/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.pde b/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.pde index 057e9d5353..ef8c604a2c 100644 --- a/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.pde +++ b/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.pde @@ -3,10 +3,23 @@ Code by Randy Mackay. DIYDrones.com */ +#include +#include #include // ArduPilot Mega Vector/Matrix math Library -#include // Arduino SPI library +#include // Arduino SPI library +#include // ArduCopter DCM Library #include "AP_OpticalFlow.h" // ArduCopter OpticalFlow Library +//////////////////////////////////////////////////////////////////////////////// +// Serial ports +//////////////////////////////////////////////////////////////////////////////// +// +// Note that FastSerial port buffers are allocated at ::begin time, +// so there is not much of a penalty to defining ports that we don't +// use. +// +FastSerialPort0(Serial); // FTDI/console + AP_OpticalFlow_ADNS3080 flowSensor; void setup() @@ -297,7 +310,7 @@ void display_motion() while( !Serial.available() ) { flowSensor.read(); - flowSensor.get_position(0,0,0,100); + flowSensor.update_position(0,0,0,1,100); // x,y,squal //if( flowSensor.motion() || first_time ) { diff --git a/libraries/AP_PID/CMakeLists.txt b/libraries/AP_PID/CMakeLists.txt deleted file mode 100644 index 14e9782e51..0000000000 --- a/libraries/AP_PID/CMakeLists.txt +++ /dev/null @@ -1,24 +0,0 @@ -set(LIB_NAME AP_PID) - -set(${LIB_NAME}_SRCS - AP_PID.cpp - #AP_OpticalFlow_ADNS3080.cpp - ) # Firmware sources - -set(${LIB_NAME}_HDRS - AP_PID.h - #AP_OpticalFlow_ADNS3080.h - ) - -include_directories( - - - - #${CMAKE_SOURCE_DIR}/libraries/AP_Math - #${CMAKE_SOURCE_DIR}/libraries/AP_Common - #${CMAKE_SOURCE_DIR}/libraries/FastSerial -# - ) - -set(${LIB_NAME}_BOARD mega2560) - -generate_arduino_library(${LIB_NAME}) diff --git a/libraries/AP_RangeFinder/CMakeLists.txt b/libraries/AP_RangeFinder/CMakeLists.txt deleted file mode 100644 index add2e2928e..0000000000 --- a/libraries/AP_RangeFinder/CMakeLists.txt +++ /dev/null @@ -1,27 +0,0 @@ -set(LIB_NAME AP_RangeFinder) - -set(${LIB_NAME}_SRCS - AP_RangeFinder_MaxsonarXL.cpp - AP_RangeFinder_SharpGP2Y.cpp - RangeFinder.cpp - ) # Firmware sources - -set(${LIB_NAME}_HDRS - AP_RangeFinder.h - AP_RangeFinder_MaxsonarXL.h - AP_RangeFinder_SharpGP2Y.h - RangeFinder.h - ) - -include_directories( - - - - #${CMAKE_SOURCE_DIR}/libraries/AP_Math - #${CMAKE_SOURCE_DIR}/libraries/AP_Common - #${CMAKE_SOURCE_DIR}/libraries/FastSerial -# - ) - -set(${LIB_NAME}_BOARD mega2560) - -generate_arduino_library(${LIB_NAME}) diff --git a/libraries/AP_Relay/AP_Relay.cpp b/libraries/AP_Relay/AP_Relay.cpp new file mode 100644 index 0000000000..0c62abb449 --- /dev/null +++ b/libraries/AP_Relay/AP_Relay.cpp @@ -0,0 +1,45 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- + +/* + * AP_Relay.cpp + * + * Created on: Oct 2, 2011 + * Author: Amilcar Lucas + */ + +#include +#include "wiring.h" + +#include "AP_Relay.h" + +void AP_Relay::on() +{ + PORTL |= B00000100; +} + + +void AP_Relay::off() +{ + PORTL &= ~B00000100; +} + + +void AP_Relay::toggle() +{ + PORTL ^= B00000100; +} + + +void AP_Relay::set(bool status) +{ + if (status) + on(); + else + off(); +} + + +bool AP_Relay::get() +{ + return PORTL & B00000100; +} diff --git a/libraries/AP_Relay/AP_Relay.h b/libraries/AP_Relay/AP_Relay.h new file mode 100644 index 0000000000..a69c10edcf --- /dev/null +++ b/libraries/AP_Relay/AP_Relay.h @@ -0,0 +1,37 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- + +/* + * AP_Relay.h + * + * Created on: Oct 2, 2011 + * Author: Amilcar Lucas + */ + +/// @file AP_Relay.h +/// @brief APM relay control class + +#ifndef AP_RELAY_H_ +#define AP_RELAY_H_ + +/// @class AP_Relay +/// @brief Class to manage the APM relay +class AP_Relay{ +public: + // activate the relay + void on(); + + // de-activate the relay + void off(); + + // toggle the relay status + void toggle(); + + // set the relay status (on/off) + void set(bool status); + + // get the relay status (on/off) + bool get(); +}; + + +#endif /* AP_RELAY_H_ */ diff --git a/libraries/CMakeLists.txt b/libraries/CMakeLists.txt deleted file mode 100644 index ed27448a23..0000000000 --- a/libraries/CMakeLists.txt +++ /dev/null @@ -1,24 +0,0 @@ -add_subdirectory(DataFlash) -add_subdirectory(AP_Math) -add_subdirectory(PID) -add_subdirectory(AP_Common) -add_subdirectory(RC_Channel) -add_subdirectory(AP_OpticalFlow) -add_subdirectory(ModeFilter) -add_subdirectory(memcheck) -add_subdirectory(APM_PI) -add_subdirectory(AP_GPS) -add_subdirectory(AP_DCM) -add_subdirectory(AP_Compass) -add_subdirectory(AP_ADC) -add_subdirectory(AP_IMU) -add_subdirectory(AP_RangeFinder) - -add_subdirectory(APM_RC) -add_subdirectory(APM_BMP085) - -#add_subdirectory(APO) -add_subdirectory(FastSerial) -add_subdirectory(GCS_MAVLink) - -#add_subdirectory(playgroundlib) diff --git a/libraries/DataFlash/CMakeLists.txt b/libraries/DataFlash/CMakeLists.txt deleted file mode 100644 index 2e13294932..0000000000 --- a/libraries/DataFlash/CMakeLists.txt +++ /dev/null @@ -1,21 +0,0 @@ -set(LIB_NAME DataFlash) - -set(${LIB_NAME}_SRCS - DataFlash.cpp - ) # Firmware sources - -set(${LIB_NAME}_HDRS - DataFlash.h - ) - -include_directories( - - - -# ${CMAKE_SOURCE_DIR}/libraries/AP_Common - #${CMAKE_SOURCE_DIR}/libraries/FastSerial -# - ) - -set(${LIB_NAME}_BOARD mega2560) - -generate_arduino_library(${LIB_NAME}) diff --git a/libraries/FastSerial/CMakeLists.txt b/libraries/FastSerial/CMakeLists.txt deleted file mode 100644 index 78e94e9023..0000000000 --- a/libraries/FastSerial/CMakeLists.txt +++ /dev/null @@ -1,28 +0,0 @@ -set(LIB_NAME FastSerial) - -set(${LIB_NAME}_SRCS - BetterStream.cpp - FastSerial.cpp - vprintf.cpp - ) # Firmware sources - -set(${LIB_NAME}_HDRS - BetterStream.h - FastSerial.h - ftoa_engine.h - ntz.h - xtoa_fast.h - ) - -include_directories( - - - - #${CMAKE_SOURCE_DIR}/libraries/AP_Math - #${CMAKE_SOURCE_DIR}/libraries/AP_Common - #${CMAKE_SOURCE_DIR}/libraries/FastSerial -# - ) - -set(${LIB_NAME}_BOARD mega2560) - -generate_arduino_library(${LIB_NAME}) diff --git a/libraries/FastSerial/FastSerial.cpp b/libraries/FastSerial/FastSerial.cpp index 5ee8ad3ee8..5312f3d6bf 100644 --- a/libraries/FastSerial/FastSerial.cpp +++ b/libraries/FastSerial/FastSerial.cpp @@ -45,6 +45,7 @@ FastSerial::Buffer __FastSerial__rxBuffer[FS_MAX_PORTS]; FastSerial::Buffer __FastSerial__txBuffer[FS_MAX_PORTS]; +uint8_t FastSerial::_serialInitialized = 0; // Constructor ///////////////////////////////////////////////////////////////// @@ -61,6 +62,8 @@ FastSerial::FastSerial(const uint8_t portNumber, volatile uint8_t *ubrrh, volati _rxBuffer(&__FastSerial__rxBuffer[portNumber]), _txBuffer(&__FastSerial__txBuffer[portNumber]) { + setInitialized(portNumber); + begin(57600); } // Public Methods ////////////////////////////////////////////////////////////// diff --git a/libraries/FastSerial/FastSerial.h b/libraries/FastSerial/FastSerial.h index 920554555f..bc0417a7c0 100644 --- a/libraries/FastSerial/FastSerial.h +++ b/libraries/FastSerial/FastSerial.h @@ -55,6 +55,7 @@ #include "BetterStream.h" + /// @file FastSerial.h /// @brief An enhanced version of the Arduino HardwareSerial class /// implementing interrupt-driven transmission and flexible @@ -101,6 +102,7 @@ extern class FastSerial Serial3; /// class FastSerial: public BetterStream { public: + /// Constructor FastSerial(const uint8_t portNumber, volatile uint8_t *ubrrh, volatile uint8_t *ubrrl, volatile uint8_t *ucsra, volatile uint8_t *ucsrb, const uint8_t u2x, const uint8_t portEnableBits, const uint8_t portTxBits); @@ -149,7 +151,21 @@ public: uint8_t *bytes; ///< pointer to allocated buffer }; + /// Tell if the serial port has been initialized + static bool getInitialized(uint8_t port) { + return (1<>1); +} + void RC_Channel::set_reverse(bool reverse) { @@ -88,18 +94,25 @@ RC_Channel::set_pwm(int pwm) if(_type == RC_CHANNEL_RANGE){ //Serial.print("range "); control_in = pwm_to_range(); - control_in = (control_in < dead_zone) ? 0 : control_in; - //if (fabs(scale_output) > 0){ - // control_in *= scale_output; - //} - }else{ - control_in = pwm_to_angle(); - control_in = (abs(control_in) < dead_zone) ? 0 : control_in; + control_in = (control_in < _dead_zone) ? 0 : control_in; + + if (fabs(scale_output) != 1){ + control_in *= scale_output; + } + + }else{ + + //RC_CHANNEL_ANGLE, RC_CHANNEL_ANGLE_RAW + control_in = pwm_to_angle(); + // deadzone moved to + //control_in = (abs(control_in) < _dead_zone) ? 0 : control_in; + + if (fabs(scale_output) != 1){ + control_in *= scale_output; + } - //if (fabs(scale_output) > 0){ - // control_in *= scale_output; - //} /* + // coming soon ?? if(expo) { long temp = control_in; temp = (temp * temp) / (long)_high; @@ -133,7 +146,7 @@ RC_Channel::calc_pwm(void) pwm_out = (float)servo_out * .1; radio_out = (pwm_out * _reverse) + radio_trim; - }else{ + }else{ // RC_CHANNEL_ANGLE pwm_out = angle_to_pwm(); radio_out = pwm_out + radio_trim; } @@ -175,10 +188,15 @@ RC_Channel::update_min_max() int16_t RC_Channel::pwm_to_angle() { - if(radio_in > radio_trim) - return _reverse * ((long)_high * (long)(radio_in - radio_trim)) / (long)(radio_max - radio_trim); - else - return _reverse * ((long)_high * (long)(radio_in - radio_trim)) / (long)(radio_trim - radio_min); + int radio_trim_high = radio_trim + _dead_zone; + int radio_trim_low = radio_trim - _dead_zone; + + if(radio_in > radio_trim_high){ + return _reverse * ((long)_high * (long)(radio_in - radio_trim_high)) / (long)(radio_max - radio_trim_high); + }else if(radio_in < radio_trim_low){ + return _reverse * ((long)_high * (long)(radio_in - radio_trim_low)) / (long)(radio_trim_low - radio_min); + }else + return 0; } @@ -196,14 +214,18 @@ RC_Channel::angle_to_pwm() int16_t RC_Channel::pwm_to_range() { - //return (_low + ((_high - _low) * ((float)(radio_in - radio_min) / (float)(radio_max - radio_min)))); - return (_low + ((long)(_high - _low) * (long)(radio_in - radio_min)) / (long)(radio_max - radio_min)); + int radio_trim_low = radio_min + _dead_zone; + + if(radio_in > radio_trim_low) + return (_low + ((long)(_high - _low) * (long)(radio_in - radio_trim_low)) / (long)(radio_max - radio_trim_low)); + else + return 0; } + int16_t RC_Channel::range_to_pwm() { - //return (((float)(servo_out - _low) / (float)(_high - _low)) * (float)(radio_max - radio_min)); return ((long)(servo_out - _low) * (long)(radio_max - radio_min)) / (long)(_high - _low); } diff --git a/libraries/RC_Channel/RC_Channel.h b/libraries/RC_Channel/RC_Channel.h index 922b15540e..9ce43fd1c0 100644 --- a/libraries/RC_Channel/RC_Channel.h +++ b/libraries/RC_Channel/RC_Channel.h @@ -28,7 +28,7 @@ class RC_Channel{ _high(1), _filter(true), _reverse (&_group, 3, 1, name ? PSTR("REV") : 0), - dead_zone(0), + _dead_zone(0), scale_output(1.0) {} @@ -48,6 +48,7 @@ class RC_Channel{ void set_angle(int angle); void set_reverse(bool reverse); bool get_reverse(void); + void set_dead_zone(int dzone); // read input from APM_RC - create a control_in value void set_pwm(int pwm); @@ -63,7 +64,6 @@ class RC_Channel{ // value generated from PWM int16_t control_in; - int16_t dead_zone; // used to keep noise down and create a dead zone. int control_mix(float value); @@ -97,6 +97,7 @@ class RC_Channel{ bool _filter; AP_Int8 _reverse; + int16_t _dead_zone; // used to keep noise down and create a dead zone. uint8_t _type; int16_t _high; int16_t _low; diff --git a/libraries/memcheck/CMakeLists.txt b/libraries/memcheck/CMakeLists.txt deleted file mode 100644 index ec9121b1ce..0000000000 --- a/libraries/memcheck/CMakeLists.txt +++ /dev/null @@ -1,24 +0,0 @@ -set(LIB_NAME memcheck) - -set(${LIB_NAME}_SRCS - memcheck.cpp - #AP_OpticalFlow_ADNS3080.cpp - ) # Firmware sources - -set(${LIB_NAME}_HDRS - memcheck.h - #AP_OpticalFlow_ADNS3080.h - ) - -include_directories( - - - - #${CMAKE_SOURCE_DIR}/libraries/AP_Math - ${CMAKE_SOURCE_DIR}/libraries/AP_Common - #${CMAKE_SOURCE_DIR}/libraries/FastSerial -# - ) - -set(${LIB_NAME}_BOARD mega2560) - -generate_arduino_library(${LIB_NAME})