├── .gitignore ├── Firmware └── JBC-Soldering-Controller │ ├── JBC-Soldering-Controller.ino │ ├── _00_globals.ino │ ├── _01_setup.ino │ ├── _02_interrupts.ino │ ├── _03_loop.ino │ ├── _04_serial_comm.ino │ ├── _05_display.ino │ ├── _99_support_functions.ino │ ├── ads1118.h │ └── calculations.xlsx ├── Hardware ├── 3DModels │ ├── ARDUINO PRO MICRO.SLDASM │ ├── ARDUINO PRO MICRO.STEP │ ├── Arduino Pro Micro Sparkfun.stp │ ├── Assem2.SLDASM │ ├── Assem4.SLDASM │ ├── Board.sldprt │ ├── Body.sldasm │ ├── CaseFront.SLDPRT │ ├── CaseRight.sldprt │ ├── CaseTop.SLDPRT │ ├── Encoder_with_knob.SLDASM │ ├── Encoder_with_knob.STEP │ ├── Hirose-RPC1.STEP │ ├── KNOB_6mmShaft.SLDPRT │ ├── Lead.sldprt │ ├── M2.5X12mmStandoff.SLDPRT │ ├── M2_Screw.SLDPRT │ ├── M2x12mmBrassStandoff.SLDPRT │ ├── M2x3x7mmBrassStandoff.SLDPRT │ ├── MICRO_603 cap on pad.sldprt │ ├── MICRO_603 resistor 102.sldprt │ ├── MICRO_603 resistor 103.sldprt │ ├── MICRO_603 resistor 22.sldprt │ ├── MICRO_603 resistor 331.sldprt │ ├── MICRO_PTC-1206.sldprt │ ├── MICRO_cap106C.sldprt │ ├── MICRO_led.sldprt │ ├── MicroUSB.sldprt │ ├── OLEDFootprint.SLDPRT │ ├── OLED_0.91_128x32.SLDPRT │ ├── OLED_0.91_128x32.stp │ ├── Open_CASCADE_STEP_translator_6.8_5.1.sldprt │ ├── Open_CASCADE_STEP_translator_6.8_5.2.1.sldprt │ ├── PCB.SLDPRT │ ├── PCB.STEP │ ├── PJ-313D.SLDPRT │ ├── PJ-313D.STEP │ ├── Part4.sldprt │ ├── Part5.sldprt │ ├── PowerConnector │ │ ├── DELL_A831M.SLDPRT │ │ ├── DELL_A831M.STEP │ │ ├── Hirose-RPC1.SLDPRT │ │ ├── PWR.SLDPRT │ │ └── dell_jack.STEP │ ├── PowerPlug.sldprt │ ├── ProMicroFootprint.SLDPRT │ ├── SOD 323.sldprt │ ├── SRN5040 series.stp │ ├── SideLeft.sldprt │ ├── SolderingController.SLDASM │ ├── Trimmed_Lead.sldprt │ ├── VN50.SLDASM │ ├── WS2812b.sldprt │ ├── atmega32U4.sldprt │ ├── micro board.sldprt │ ├── micro usb contact.sldprt │ ├── micro usb internal.sldprt │ ├── micro usb shell.sldprt │ ├── micro usb.sldasm │ ├── micro_MIC5219.sldprt │ ├── micro_crystal 5x3.sldprt │ ├── pec11r-4x15k-sxxxx.SLDPRT │ ├── pec11r-4x15k-sxxxx.stp │ ├── sj-2523-smt.SLDPRT │ └── tab.sldprt ├── Documents │ ├── MCP16301 Design Analyzer v1.0.xlsx │ └── MP2456.jpg ├── JBC-Soldering-Controller_SCH_[No Variations].PDF ├── JBC-Soldering_Controller.DsnWrk ├── MainBoard │ ├── Assembly.OutJob │ ├── BOM1.BomDoc │ ├── Controller.SchDoc │ ├── Fabrication.OutJob │ ├── JBC-Soldering-Controller.PrjPCB │ ├── JBC-Soldering-Controller.PrjPCBStructure │ ├── MainBoard.PcbDoc │ ├── MainBoard.PcbDoc.htm │ ├── Power.SchDoc │ ├── Power2.SchDoc │ ├── Power3.SchDoc │ ├── Release Archives │ │ ├── JBC-Soldering-Controller V1.0 with source.zip │ │ └── JBC-Soldering-Controller V1.0.zip │ ├── Sources.OutJob │ └── TopLevel.SchDoc ├── Shared Libraries │ ├── JBC-Soldering-Controller.SCHLIB │ ├── SolderingController.PcbLib │ └── SolderingController.SchLib ├── Template_A.SchDot ├── Template_B.SchDot ├── Template_C.SchDot └── datasheets │ ├── VN5E010AHTR.pdf │ └── ads1118.pdf ├── K Thermocouple Lookup Table.txt ├── LICENSE ├── README.md └── Software └── LabVIEW └── PID Tuning ├── HexStringToBinaryString.vi ├── HexStringToSingle.vi ├── HostPacket.vi ├── InputSimulationMode.ctl ├── PID Mode.ctl ├── PID_TUNING.vi ├── PID_tuningPacket.vi ├── Parameters.ctl ├── ParseArduinoHexPacket.vi ├── ParseControllerPacket.vi ├── Serial - ASCII Characters.ctl ├── Serial - Settings.ctl ├── Serial - XON-XOFF Characters.ctl └── Status.ctl /.gitignore: -------------------------------------------------------------------------------- 1 | Hardware/History/ 2 | Hardware/MainBoard/History/ 3 | Hardware/MainBoard/Project Logs for JBC-Soldering-Controller/ 4 | Hardware/MainBoard/__Previews/ 5 | Hardware/MainBoard/Project Outputs for JBC-Soldering-Controller/ 6 | *.err 7 | Hardware/__Previews/ 8 | -------------------------------------------------------------------------------- /Firmware/JBC-Soldering-Controller/JBC-Soldering-Controller.ino: -------------------------------------------------------------------------------- 1 | /* Copyright (c) 2017 timothyjager 2 | JBC-Soldering-Controller 3 | MIT License. See LICENSE file for details. 4 | */ 5 | 6 | #include 7 | #include 8 | #include 9 | #include 10 | 11 | #include //https://github.com/adafruit/Adafruit-GFX-Library 12 | #include //https://github.com/adafruit/Adafruit_SSD1306 13 | #include //https://github.com/PaulStoffregen/Encoder 14 | #include //https://github.com/PaulStoffregen/TimerOne 15 | #include //https://github.com/greiman/DigitalIO 16 | #include //https://github.com/timothyjager/DellPSU 17 | #include //https://github.com/Chris--A/EEWrap 18 | #include //https://github.com/br3ttb/Arduino-PID-Library/ 19 | 20 | #include "ads1118.h" //Header file for TI Signma Delta ADC 21 | 22 | -------------------------------------------------------------------------------- /Firmware/JBC-Soldering-Controller/_00_globals.ino: -------------------------------------------------------------------------------- 1 | /* Copyright (c) 2017 timothyjager 2 | JBC-Soldering-Controller 3 | MIT License. See LICENSE file for details. 4 | */ 5 | 6 | //----------------Pin Mapping------------------------- 7 | //Arduino Pro-Micro Pinout 8 | //https://cdn.sparkfun.com/assets/9/c/3/c/4/523a1765757b7f5c6e8b4567.png 9 | const int ENC_A = 0; 10 | const int ENC_B = 1; 11 | const int I2C_SDA = 2; 12 | const int I2C_SCL = 3; 13 | const int CS = 4; 14 | const int debug_pin_A = 5; 15 | const int DELL_PSU = 6; 16 | const int WS2812_DATA = 7; 17 | const int CRADLE_SENSOR = 8; 18 | const int LPINA = 9; //Heater PWM 19 | const int VIN_SENSE = 21; 20 | const int CURRENT_SENSE = 20; 21 | const int debug_pin_B = 19; 22 | const int oled_reset = 19; //The oled library requires a reset pin even though we doen thave one connected. use the debug pin to satisfy this requirement. 23 | const int ENC_BUTTON = 18; 24 | const int SPI_SCLK = 15; 25 | const int SPI_MISO = 14; 26 | const int SPI_MOSI = 16; 27 | const int LPINB = 10; //Timer 1 Debug Pin 28 | //----------------------------------------------------- 29 | 30 | 31 | //----------------Function Prototypes------------------ 32 | bool SerialReceive(void); 33 | void SendStatusPacket(void); 34 | int multiMap2(int val, int* _in, int* _out, uint8_t size); 35 | void Check_DELL_PSU(void); 36 | void PulsePin(int pin); 37 | void updateLEDStatus(void); 38 | void ProcessSerialComm(void); 39 | void updateDisplay(bool update_now); 40 | //----------------------------------------------------- 41 | 42 | 43 | 44 | //----------------Structure Definitions---------------- 45 | //EEProm parameter data (https://github.com/Chris--A/EEWrap) 46 | //Use the xxx_e types rather than the standard types like uint8_t 47 | struct NVOL { 48 | uint8_e a; //TODO: add the actual non-volatile parameters to this struct. 49 | int16_e b; 50 | float_e c; 51 | uint8_e str[2][6]; 52 | }; 53 | NVOL nvol EEMEM; //EEMEM tells the compiler that the object resides in the EEPROM 54 | 55 | //System Parameters Data Structure 56 | typedef struct { 57 | byte pid_mode; //PID mode - Automatic=1, Manual=0 58 | byte simulate_input; //this allows us to override the actual input (temperature reading) using the tuning app 59 | int16_t idle_temp_c; 60 | int16_t output_override; 61 | float setpoint; 62 | float kP; 63 | float kI; 64 | float kD; 65 | float simulated_input; 66 | } system_parameters_struct; 67 | 68 | //Status Variables Struct - hold global status values 69 | typedef struct { 70 | byte gpio_port_b; //Port b of GPIO 71 | byte gpio_port_c; //Port C of GPIO 72 | byte gpio_port_d; //Port d of GPIO 73 | byte gpio_port_e; //Port e of GPIO 74 | int16_t encoder_pos; //Enocder Position 75 | int16_t adapter_voltage_mv; //Input power adapter voltage in millivolts 76 | int16_t adc_counts; //ADC value read by ADS1118 77 | int16_t adc_ic_temp_counts; //internal temp of ADS1118 78 | int16_t current_sense_mv; //current sense in milliamps 79 | double pid_setpoint; //setpoint of the PID loop 80 | double tip_temperature_c; //input value of the PID loop 81 | double pid_output; //computed output value of the PID loop 82 | } status_struct; 83 | 84 | 85 | 86 | 87 | //Data structure sent from Arduino to host PC 88 | union controller_packet_struct { 89 | struct { 90 | volatile status_struct status; //Enture status structure 91 | volatile system_parameters_struct params; 92 | } payload; 93 | byte asBytes[sizeof(payload)]; 94 | }; 95 | 96 | 97 | //Data structure sent from host PC 98 | union host_packet_struct { 99 | struct { 100 | byte start_of_packet; //this should always be 0xAB. It was arbitrarily chosen 101 | system_parameters_struct params; 102 | } payload; 103 | byte asBytes[sizeof(payload)]; 104 | }; 105 | //----------------------------------------------------- 106 | 107 | 108 | 109 | //----------------Standard Global Variables---------------- 110 | host_packet_struct host_packet; 111 | controller_packet_struct controller_packet; 112 | volatile status_struct status; 113 | volatile system_parameters_struct params; 114 | 115 | //Hard-coded calibration points. TODO: make these not hard-coded 116 | #define NUM_CAL_POINTS 4 117 | uint16_t adc_reading [NUM_CAL_POINTS] = {283, 584, 919, 1098}; 118 | uint16_t deg_c [NUM_CAL_POINTS] = {105, 200, 300, 345}; 119 | 120 | //x = multiMap2(raw, adc_reading, deg_c, NUM_CAL_POINTS); 121 | 122 | //double kP = 2, kI = 0, kD = 0; //PID tuning values 123 | //----------------------------------------------------- 124 | 125 | 126 | 127 | //----------------Volatile Global Variables------------ 128 | //volatile int16_t adc_value = 0; //ADC value read by ADS1118 129 | //volatile int16_t temperature_value = 0; //internal temp of ADS1118 130 | //volatile int16_t current_sense_raw; //raw adc reading 131 | //volatile double Setpoint, Input, Output; //PID input/output variables 132 | //----------------------------------------------------- 133 | 134 | 135 | //----------------Globals Objects---------------------- 136 | Adafruit_SSD1306 display(oled_reset); //TODO: look into this reset pin. The LCD i'm using does not have a reset pin, just PWR,GND,SDA,SCL 137 | Encoder knob(ENC_A, ENC_B); //Setup the encoder object 138 | DellPSU dell(DELL_PSU); //This object reads data from a DELL power adapter using 1-wire protocol 139 | Adafruit_NeoPixel pixels = Adafruit_NeoPixel(1, WS2812_DATA, NEO_GRB + NEO_KHZ800); 140 | PID myPID(&status.tip_temperature_c, &status.pid_output, &status.pid_setpoint, params.kP, params.kI, params.kD, P_ON_E, DIRECT); //TODO: map this properly to NVOL data storage 141 | //----------------------------------------------------- 142 | 143 | 144 | 145 | 146 | 147 | 148 | 149 | 150 | 151 | -------------------------------------------------------------------------------- /Firmware/JBC-Soldering-Controller/_01_setup.ino: -------------------------------------------------------------------------------- 1 | /* Copyright (c) 2017 timothyjager 2 | JBC-Soldering-Controller 3 | MIT License. See LICENSE file for details. 4 | */ 5 | 6 | //----------------Setup------------------------- 7 | void setup(void) 8 | { 9 | //IO Pin Configuration 10 | fastPinMode(CRADLE_SENSOR, INPUT_PULLUP); //setup cradle detect 11 | fastPinMode(ENC_BUTTON, INPUT_PULLUP); //setup encoder button 12 | fastPinMode(debug_pin_A, OUTPUT); //for debugging the Interrupts 13 | fastPinMode(debug_pin_B, OUTPUT); //for debugging the Interrupts 14 | fastPinMode(CS, OUTPUT); //SPI chip select pin 15 | 16 | //Serial Port 17 | Serial.begin(230400); 18 | 19 | //Neopixel 20 | pixels.begin(); // This initializes the NeoPixel library. 21 | pixels.setPixelColor(0, pixels.Color(0, 0, 10)); // Moderately bright green color. 22 | pixels.show(); 23 | 24 | //Read the NVOL data as a test. 25 | Serial.println(nvol.a); 26 | 27 | //Setup the OLED 28 | display.begin(SSD1306_SWITCHCAPVCC, 0x3C); // initialize with the I2C addr 0x3C (for the 128x32). Module set to generate the OLED driver voltage internally 29 | display.clearDisplay(); // Clear the buffer. 30 | 31 | //Init the ADS1118 ADC 32 | //set CS high as default 33 | fastDigitalWrite(CS, HIGH); 34 | //Start the SPI interface 35 | SPI.begin(); 36 | //Setup the SPI parameters for the ADS1118 37 | SPI.beginTransaction(SPISettings(2000000, MSBFIRST, SPI_MODE1)); 38 | //start an initial reading of the internal temperature 39 | fastDigitalWrite(CS, LOW); 40 | SPI.transfer16(ADS1118_SINGLE_SHOT_INTERNAL_TEMPERATURE); 41 | fastDigitalWrite(CS, HIGH); 42 | delay(10); 43 | fastDigitalWrite(CS, LOW); 44 | status.adc_ic_temp_counts = SPI.transfer16(ADS1118_SINGLE_SHOT_INTERNAL_TEMPERATURE); 45 | fastDigitalWrite(CS, HIGH); 46 | delay(10); 47 | 48 | //Interrupts 49 | /* 50 | The Timer1 interrupts fire at the rising and falling edges of the PWM pulse. 51 | A is used to control our main PWM power to the heater 52 | B is used for sampling the ADC during the offtime of A 53 | We only care about B for ADC sampling, but we need to know if the interrupt is the rising or falling edge. 54 | We want to sample the ADC right after the falling edge of B, and the internal temp after the rising edge of B 55 | Since the falling edge of B always occurs after either edge of A (since B always has a higher duty cycle), we can enable the B interrupt from A 56 | and then just keep track of which edge we are. A bit is toggled each time the interrupt fires to remember if it's the rising or falling edge. 57 | This assumes we will never miss an interrupt. 58 | WE should probably add a handler in case the interrupt gets messed up and we get out of sync. 59 | */ 60 | //setup PWM and interrupts. These use the 16 bit timer1 61 | #define PWM_PERIOD_US 20000 //20000us = 20ms = 50Hz PWM frequency. We have to go slow enough to allow time for sampling the ADC during the PWM off time 62 | #define PWM_PERIOD_MS (PWM_PERIOD_US/1000) //20000/1000 = 20ms 63 | #define PWM_MAX_DUTY 1023 //the timer 1 libray scales the PWM duty cycle from 0 to 1023 where 0=0% and 1023=100% 64 | #define ADC_SAMPLE_WINDOW_US 1200 //1200us = 1.2ms //we need 1.2 ms to sample the ADC. assuming 860 SPS setting 65 | #define ADC_SAMPLE_WINDOW_PWM_DUTY 961 //(((PWM_PERIOD_US-ADC_SAMPLE_WINDOW_US)*PWM_MAX_DUTY)/PWM_PERIOD_US) // we set our PWM duty to as close to 100% as possible while still leaving enough time for the ADC sample. 66 | #define MAX_HEATER_PWM_DUTY ADC_SAMPLE_WINDOW_PWM_DUTY //our maximum allowable heater PWM duty is equal to the sampling window PWM duty. 67 | 68 | Timer1.initialize(PWM_PERIOD_US); //Set timer1 to our main PWM period 69 | Timer1.pwm(LPINB, ADC_SAMPLE_WINDOW_PWM_DUTY); //Set an interupt to define our sample window 70 | Timer1.pwm(LPINA, 60); //100% = 1023 //Set a default PWM value for our output 71 | delay(PWM_PERIOD_MS); //make sure both PWM's have run at least one full period before enabling interrupts 72 | 73 | TIFR1 |= _BV(OCF1A); //clear the A interrupt flag, so it doesn't fire right away, when we enable the A interrupt 74 | TIMSK1 = _BV(OCIE1A); //enable comparator A interrupt vector. This will fire an interrupt on each edge of our main PWM. we only use this once to synchronise the B sampling interrupt. 75 | 76 | //Set up PID Control Loop 77 | myPID.SetMode(MANUAL); 78 | myPID.SetSampleTime(PWM_PERIOD_MS); //Since we run out PID every interupt cylce, we set the sample time (ms) to our PWM timer period 79 | myPID.SetOutputLimits(0, MAX_HEATER_PWM_DUTY); //961max PWM, otherwise it will cut into the sample window TODO:dont leave hard coded 80 | 81 | //TODO: dont leave this hard-coded 82 | params.kP=30.0; 83 | params.kI=1; 84 | params.kD=0.36; 85 | myPID.SetTunings(params.kP, params.kI, params.kD); 86 | 87 | //Detect DELL power supply 88 | Check_DELL_PSU(); 89 | } 90 | 91 | 92 | 93 | -------------------------------------------------------------------------------- /Firmware/JBC-Soldering-Controller/_02_interrupts.ino: -------------------------------------------------------------------------------- 1 | /* Copyright (c) 2017 timothyjager 2 | JBC-Soldering-Controller 3 | MIT License. See LICENSE file for details. 4 | */ 5 | 6 | //----------------Interrupts------------------------ 7 | 8 | //This interrupt is set to fire approximately 1.2ms before the PWM output turn on. It is configured to allow just enough time to sample the ADC while the 9 | //power to the heater is turned off. This means that our max PWM has to be limited to ensure there is a long enough sample window. 10 | //the interupt actually fires twice. once at the beginning of our interval and once at the end. we use this to our advantage by sampling the result of the 11 | //previous sample at each interrupt and then toggling the sample type back and forth between ADC and internal temp. 12 | ISR(TIMER1_COMPB_vect) 13 | { 14 | static bool rising_edge = true; 15 | //Initiate the ADC reading and read back the internal temperature from last time 16 | if (rising_edge) 17 | { 18 | PulsePin(debug_pin_B); 19 | //read back the internal temp while simultaneously changing the config to start a oneshot read from the ADC) 20 | fastDigitalWrite(CS, LOW); 21 | status.adc_ic_temp_counts = SPI.transfer16(ADS1118_SINGLE_SHOT_ADC); 22 | //temperature_value=SPI.transfer16(ADS1118_SINGLE_SHOT_INTERNAL_TEMPERATURE); 23 | fastDigitalWrite(CS, HIGH); 24 | fastDigitalWrite(CS, LOW); 25 | 26 | } 27 | //else retreive the reading from the ADC 28 | else 29 | { 30 | //2 pulses for debugging 31 | PulsePin(debug_pin_B); 32 | PulsePin(debug_pin_B); 33 | //read back the tip temperature from the ADC while simultaneously changing the config to start a oneshot read of internal IC temperature (i.e. cold junction temp) 34 | fastDigitalWrite(CS, LOW); 35 | int16_t adc_raw = SPI.transfer16(ADS1118_SINGLE_SHOT_INTERNAL_TEMPERATURE); 36 | static int16_t adc_raw_last; 37 | //this is a temporary hack because sometimes the ADC returns an odd value. TODO: investigate this. 38 | if (abs(adc_raw-adc_raw_last)<1000) 39 | { 40 | status.adc_counts = adc_raw; 41 | } 42 | adc_raw_last = adc_raw; 43 | 44 | double tip_temp_c = (0.2925 * (double)status.adc_counts) + 3.4536; 45 | 46 | //determine if PID loop should use the actual temperature or simulated temperature from the host. 47 | if (params.simulate_input == 1) 48 | { 49 | status.tip_temperature_c = params.simulated_input; 50 | } 51 | else 52 | { 53 | status.tip_temperature_c = tip_temp_c; 54 | } 55 | 56 | //Compute PID 57 | myPID.Compute(); 58 | //Update PWM output 59 | Timer1.pwm(LPINA, status.pid_output); //100% = 1023 60 | //TODO: verify calling neopixel code within the interrupt doesn't affect the the heater control 61 | updateLEDStatus(); 62 | 63 | //Serial.println(millis()-time_start); 64 | fastDigitalWrite(CS, HIGH); 65 | } 66 | //every other interrupt will be a rising edge, we need to keep track of which is which 67 | rising_edge = !rising_edge; 68 | } 69 | 70 | 71 | //This should only run at the start of the program, then it disables itself 72 | //It's used to start the B interupt at the right time 73 | ISR(TIMER1_COMPA_vect) 74 | { 75 | static bool one_shot = false; 76 | //If we have never run this code before, then run it just once 77 | if (!one_shot) 78 | { 79 | TIFR1 |= _BV(OCF1B); //clear the Timer 1 B interrupt flag so it doesn't fire right after we enable it. We only want to detect new interrupts, not old ones. 80 | TIMSK1 = _BV(OCIE1B); //Enable only interrupt B, This also disables A since A has done it's one and only job of synchronizing the B interrupt. 81 | one_shot = true; //set oneshot to prevent this code from ever running again. It shouldn't try to since this interrupt should now be disable. 82 | } 83 | //4 pulses for debugging with logi analyzer 84 | PulsePin(debug_pin_B); 85 | PulsePin(debug_pin_B); 86 | PulsePin(debug_pin_B); 87 | PulsePin(debug_pin_B); 88 | } 89 | 90 | -------------------------------------------------------------------------------- /Firmware/JBC-Soldering-Controller/_03_loop.ino: -------------------------------------------------------------------------------- 1 | /* Copyright (c) 2017 timothyjager 2 | JBC-Soldering-Controller 3 | MIT License. See LICENSE file for details. 4 | */ 5 | 6 | //----------------Main Loop------------------------ 7 | void loop(void) 8 | { 9 | static bool in_cradle; 10 | bool update_display_now = false; 11 | 12 | //read the encoder knob 13 | static int16_t knob_pos_last = 0; 14 | 15 | status.encoder_pos = knob.read(); //>> 2; //divide by 2 to decrease sensitivity 16 | 17 | //Check if knob has changed 18 | if (status.encoder_pos != knob_pos_last) 19 | { 20 | //Dont allow it to go negative. 21 | if (status.encoder_pos < 0) 22 | { 23 | knob.write(0); 24 | status.encoder_pos = 0; 25 | } 26 | params.setpoint = status.encoder_pos; 27 | if (myPID.GetMode() == AUTOMATIC) 28 | { 29 | status.pid_setpoint = params.setpoint; 30 | } 31 | 32 | update_display_now = true; //refresh the screen more quickly while adjusting the knob 33 | } 34 | knob_pos_last = status.encoder_pos; 35 | 36 | //When button is pressed toggle power on/off 37 | if (fastDigitalRead(ENC_BUTTON) == false) 38 | { 39 | noInterrupts(); 40 | if (params.pid_mode == AUTOMATIC) 41 | { 42 | params.pid_mode = MANUAL; 43 | myPID.SetMode(params.pid_mode); 44 | status.pid_output = 0; 45 | status.pid_setpoint = 0; 46 | } 47 | else 48 | { 49 | params.pid_mode = AUTOMATIC; 50 | myPID.SetMode(params.pid_mode); 51 | status.pid_setpoint = params.setpoint; 52 | } 53 | interrupts(); 54 | delay(200); 55 | while (fastDigitalRead(ENC_BUTTON) == false) 56 | delay(200); 57 | } 58 | 59 | 60 | //When on cradle power on/off 61 | if (fastDigitalRead(CRADLE_SENSOR) == false) 62 | { 63 | noInterrupts(); 64 | if (params.pid_mode == AUTOMATIC) 65 | { 66 | params.pid_mode = MANUAL; 67 | myPID.SetMode(params.pid_mode); 68 | status.pid_output = 0; 69 | status.pid_setpoint = 0; 70 | } 71 | interrupts(); 72 | } 73 | 74 | 75 | //current_sense_raw=analogRead(CURRENT_SENSE); need to figure out how to read this only when the PWM is on. 76 | 77 | 78 | //TODO: Cradle logic: 79 | //TOOD: If off cradle and time < x seconds, then tip ON at MAIN setpoint. If Off cradle and time >= x seconds, then tip off (maybe someone left the handle on the table. yikes!). 80 | //TOOD: If On cradle and time < y seconds, then tip ON at IDLE setpoint. If ON cradle and time >= y seconds, then tip off (someone hasnt used the tip in a long time so power down). 81 | //if (in_cradle) 82 | { 83 | //Setpoint = 0; //turn off the power while in the cradle. //temporary disable for testing PID tuning 84 | //pixels.setPixelColor(0, pixels.Color(0,0,10)); // Blue 85 | } 86 | //else 87 | { 88 | //Setpoint = enc; //set the PID loop to our encoder knob value 89 | //pixels.setPixelColor(0, pixels.Color(10,0,0)); // Red 90 | } 91 | ProcessSerialComm(); 92 | updateDisplay(update_display_now); 93 | } 94 | 95 | 96 | 97 | 98 | -------------------------------------------------------------------------------- /Firmware/JBC-Soldering-Controller/_04_serial_comm.ino: -------------------------------------------------------------------------------- 1 | /* Copyright (c) 2017 timothyjager 2 | JBC-Soldering-Controller 3 | MIT License. See LICENSE file for details. 4 | */ 5 | 6 | //----------------Serial Comm------------------------ 7 | 8 | //process serial communications 9 | //this function shoudl be called cylcilcallly in the main loop 10 | #define SERIAL_COMM_PERIOD_MS 250 //run every 200ms. 11 | void ProcessSerialComm(void) 12 | { 13 | static long next_millis = millis() + SERIAL_COMM_PERIOD_MS; //determine the next time this function should activate 14 | static bool serial_active = false; 15 | 16 | //send-receive with processing if it's time 17 | if (millis() > next_millis) 18 | { 19 | //Check if there is data on the serial port. This indicated the host PC is sending us something. 20 | if (Serial.available()) 21 | { 22 | //try to read and process the serial commands 23 | if (SerialReceive()) 24 | { 25 | serial_active = true; 26 | } 27 | } 28 | //Once we determine there is serial activity, we assume a host is connected, so begin streaming our packet data to the host. TODO: currently no way to detect if the host dissapears. 29 | if (Serial) 30 | { 31 | SendStatusPacket(); 32 | } 33 | next_millis += SERIAL_COMM_PERIOD_MS; //set up our loop to run again in x ms 34 | } 35 | } 36 | 37 | 38 | 39 | //this function sends all of our status values as a hex string. this reduces the CPU load on the MCU since it doesnt have to format float strings. 40 | void SendStatusPacket() 41 | { 42 | /* 43 | controller_packet.status.start_of_packet = 0xBA; 44 | controller_packet.status.setpoint = Setpoint; 45 | noInterrupts(); //make sure we disable interrupts while grabing these volatile values. 46 | controller_packet.status.input = Input; 47 | controller_packet.status.output = Output; 48 | //controller_packet.status.ITerm = myPID.GetITerm(); 49 | interrupts(); 50 | controller_packet.status.kP = myPID.GetKp(); 51 | controller_packet.status.kI = myPID.GetKi(); 52 | controller_packet.status.kD = myPID.GetKd(); 53 | controller_packet.status.automatic = (myPID.GetMode() == AUTOMATIC); 54 | controller_packet.status.simulate_input = host_packet.param.simulate_input; 55 | */ 56 | 57 | //Update GPIO status. 58 | status.gpio_port_b = PINB; 59 | status.gpio_port_c = PINC; 60 | status.gpio_port_d = PIND; 61 | status.gpio_port_e = PINE; 62 | /* 63 | if (params.idle_temp_c > 1) 64 | { 65 | status.encoder_pos = 1; //Enocder Position 66 | status.adapter_voltage_mv = 2; //Input power adapter voltage in millivolts 67 | status.adc_counts = 3; //ADC value read by ADS1118 68 | status.adc_ic_temp_counts = 4; //internal temp of ADS1118 69 | status.current_sense_mv = 5; //current sense in milliamps 70 | status.pid_setpoint = 33000; //setpoint of the PID loop 71 | status.pid_input = 32000; //input value of the PID loop 72 | status.pid_output = -12999; //computed output value of the PID loop 73 | 74 | 75 | params.automatic = 1; //PID mode - Automatic=0, Manual=1 76 | params.simulate_input = 0; //this allows us to override the actual input (temperature reading) using the tuning app 77 | //params.idle_temp_c = 123; 78 | params.setpoint = 1.23; 79 | params.kP = 2.34; 80 | params.kI = 4.56; 81 | params.kD = 6.78; 82 | params.SimulatedInput = 9.101; 83 | } 84 | */ 85 | //Copy status and parameter structures into our packet payload 86 | noInterrupts(); 87 | memcpy(&controller_packet.payload.status, &status, sizeof(status_struct)); 88 | memcpy(&controller_packet.payload.params, ¶ms, sizeof(system_parameters_struct)); 89 | interrupts(); 90 | 91 | //send all of the bytes in the controller_ 92 | //Serial.write("BA"); //Start of packet indicator. TODO: change this to non-hex code 93 | for (int i = 0; i < sizeof(controller_packet_struct); i++) 94 | { 95 | //convert each byte into a hex string. 96 | const char lookup[] = "0123456789abcdef"; 97 | Serial.write(lookup[ controller_packet.asBytes[i] >> 4 ]); 98 | Serial.write(lookup[ controller_packet.asBytes[i] & 0x0f ]); 99 | } 100 | Serial.write('\n'); 101 | } 102 | 103 | //Receive commands from the tuning PC app 104 | bool SerialReceive() 105 | { 106 | bool return_value = false; 107 | // read the bytes sent from tuning app 108 | int index = 0; 109 | //if there are bytes in the serial buffer, then read them until we have received a full packet 110 | while (Serial.available() && index < sizeof(host_packet_struct)) 111 | { 112 | host_packet.asBytes[index] = Serial.read(); 113 | index++; 114 | } 115 | 116 | //when there are no more bytes to read, check if we read the correct number of bytes and make sure our first byte equals our hard-coded start of packet value 117 | if (index == sizeof(host_packet_struct) && host_packet.payload.start_of_packet == 0xAB) 118 | { 119 | noInterrupts(); 120 | memcpy(¶ms, &host_packet.payload.params, sizeof(status_struct)); //copy our payload struct into our param struct 121 | 122 | //Update PID settings 123 | myPID.SetMode(params.pid_mode); 124 | //if we are in manual mode, override the output 125 | if (params.pid_mode == MANUAL) 126 | { 127 | status.pid_output = params.output_override; 128 | } 129 | else 130 | { 131 | status.pid_setpoint = params.setpoint; 132 | } 133 | myPID.SetTunings(params.kP, params.kI, params.kD); 134 | 135 | knob.write(params.setpoint); 136 | interrupts(); 137 | 138 | return_value = true; 139 | } 140 | Serial.flush(); // * clear any random data from the serial buffer 141 | return return_value; 142 | } 143 | -------------------------------------------------------------------------------- /Firmware/JBC-Soldering-Controller/_05_display.ino: -------------------------------------------------------------------------------- 1 | /* Copyright (c) 2017 timothyjager 2 | JBC-Soldering-Controller 3 | MIT License. See LICENSE file for details. 4 | */ 5 | 6 | //----------------OLED Display------------------------ 7 | 8 | 9 | //This updates the OLED display 10 | void updateDisplay(bool update_now) 11 | { 12 | #define DISPLAY_UPDATE_PERIOD 250; 13 | static bool in_cradle; 14 | static long next_millis = millis() + DISPLAY_UPDATE_PERIOD; //determine the next time this function should activate 15 | 16 | //Time to update the display? 17 | if (millis() > next_millis || update_now) 18 | { 19 | //block interrupts while retreiving the temperature values. 20 | noInterrupts(); 21 | //int16_t adc_copy = status.adc_counts; 22 | int16_t tip_temperature_copy = status.tip_temperature_c; 23 | int16_t adc_ic_temp_counts_copy = status.adc_ic_temp_counts; 24 | interrupts(); 25 | 26 | display.clearDisplay(); 27 | display.setTextColor(WHITE); 28 | 29 | display.setTextSize(1); 30 | display.setCursor(0, 0); 31 | display.print("Set"); 32 | display.setCursor(64, 0); 33 | display.print("Deg C"); 34 | 35 | display.setTextSize(2); 36 | display.setCursor(0, 12); 37 | display.print((int16_t)params.setpoint); 38 | 39 | display.setCursor(64, 12); 40 | display.print(tip_temperature_copy); 41 | uint16_t pwm_bar = status.pid_output / 7.5; //scale max PWM value (961) down to 128 pixels. TODO: dont leave this hard coded. 42 | display.fillRect(0, 29, pwm_bar, 3, WHITE); 43 | //display.print(" "); 44 | //display.print(ADS1118_INT_TEMP_C(adc_ic_temp_counts_copy)); 45 | //display.setCursor(0, 20); 46 | 47 | //display.print(status.encoder_pos); 48 | 49 | 50 | display.display(); 51 | if (!update_now) 52 | { 53 | next_millis += DISPLAY_UPDATE_PERIOD; //set up our loop to run again in x ms 54 | } 55 | } 56 | } 57 | 58 | 59 | 60 | /* 61 | if (dell.read_data() == true) 62 | { 63 | display.print(" "); 64 | display.print("DELL PWR "); 65 | } 66 | else 67 | { 68 | display.print(" "); 69 | } 70 | if (fastDigitalRead(CRADLE_SENSOR) == false) 71 | { 72 | display.print(" "); 73 | display.print("CRDL "); 74 | in_cradle = true; 75 | } 76 | else 77 | { 78 | in_cradle = false; 79 | display.print(" "); 80 | } 81 | */ 82 | 83 | 84 | 85 | -------------------------------------------------------------------------------- /Firmware/JBC-Soldering-Controller/_99_support_functions.ino: -------------------------------------------------------------------------------- 1 | /* Copyright (c) 2017 timothyjager 2 | JBC-Soldering-Controller 3 | MIT License. See LICENSE file for details. 4 | */ 5 | 6 | //----------------Support Functions------------------------ 7 | 8 | 9 | //multimap2 10 | //allows for extrapolation if the input value is outside the bounds of the lookup array 11 | //This is a modified version of multimap: https://playground.arduino.cc/Main/MultiMap 12 | //note: the _in array should have increasing values 13 | int multiMap2(int val, int* _in, int* _out, uint8_t size) 14 | { 15 | // take care the value is within range 16 | // val = constrain(val, _in[0], _in[size-1]); 17 | if (val <= _in[0]) return _out[0]; 18 | //if (val >= _in[size-1]) return _out[size-1]; //extrapolate the value using the last 2 xy pairs. 19 | //if (val >= _in[size-1]) return _out[size-1]; //extrapolate the value using the last 2 xy pairs. 20 | 21 | // search right interval 22 | uint8_t pos = 1; // _in[0] allready tested 23 | while (val > _in[pos] && pos < size - 1) pos++; 24 | 25 | // this will handle all exact "points" in the _in array 26 | if (val == _in[pos]) return _out[pos]; 27 | 28 | // interpolate in the right segment for the rest 29 | return (val - _in[pos - 1]) * (_out[pos] - _out[pos - 1]) / (_in[pos] - _in[pos - 1]) + _out[pos - 1]; 30 | } 31 | 32 | 33 | 34 | //try to read the wattage of the power supply 35 | void Check_DELL_PSU(void) 36 | { 37 | display.clearDisplay(); 38 | display.setTextSize(1); 39 | display.setTextColor(WHITE); 40 | display.setCursor(0, 0); 41 | 42 | int PSU_VOLTAGE_RAW = analogRead(VIN_SENSE); 43 | 44 | if (dell.read_data() == true) 45 | { 46 | display.print(dell.watts()); 47 | display.print("W "); 48 | display.print(dell.millivolts()); 49 | display.print("mv "); 50 | display.print(dell.milliamps()); 51 | display.println("mA "); 52 | display.println(dell.response_string()); 53 | //Serial.println(dell.response_string()); 54 | } 55 | else 56 | { 57 | display.print("supply not detected"); 58 | display.setCursor(0, 20); 59 | // read the raw power supply voltage from the resistor divider: 60 | int PSU_VOLTAGE_RAW = analogRead(VIN_SENSE); 61 | long PSU_MILLIVOLTS = map(PSU_VOLTAGE_RAW, 0, 1023, 0.0, 34412); //Resistor divider (30k / 5.1k) scales 34.4V to 5V 62 | display.print(PSU_MILLIVOLTS); 63 | display.print("mV "); 64 | } 65 | display.display(); 66 | delay(4000); 67 | } 68 | 69 | //This function quickly toggles a pin. 70 | //Used for debugging with the logic analyzer 71 | void PulsePin(int pin) 72 | { 73 | fastDigitalWrite(pin, HIGH); 74 | fastDigitalWrite(pin, LOW); 75 | } 76 | 77 | 78 | //This function updates the LED status 79 | //TODO: Implement better LED colors: blue if the power is off and the tip is 'cold'. Yellow if the power is off but the tip is still 'hot'. Red if the power is on. Or maybe transition smoothly to red as it heats up. 80 | void updateLEDStatus(void) 81 | { 82 | if (status.pid_setpoint == 0) 83 | { 84 | pixels.setPixelColor(0, pixels.Color(0, 0, 10)); // Blue 85 | } 86 | else 87 | { 88 | pixels.setPixelColor(0, pixels.Color(10, 0, 0)); // Red 89 | } 90 | pixels.show(); 91 | } 92 | 93 | 94 | 95 | -------------------------------------------------------------------------------- /Firmware/JBC-Soldering-Controller/ads1118.h: -------------------------------------------------------------------------------- 1 | /* Copyright (c) 2017 timothyjager 2 | * TI ADS1118 ADC configuration bits 3 | * MIT License. See LICENSE file for details. 4 | */ 5 | #ifndef ads1118_h 6 | #define ads1118_h 7 | 8 | 9 | //ADS1118 Configuration 10 | //http://www.ti.com/lit/ds/symlink/ads1118.pdf 11 | //Page 25-26 12 | 13 | // |(1=Start Single-shot), (0=no effect) 14 | // | 15 | // | |Mux (000 = P is AIN0 N is AIN1, 001 = P is AIN0 N is AIN3, 010 = P is AIN1 N is AIN3 , 011 = P is AIN2 N is AIN3 16 | // | | 100 = P is AIN0 N is GND, 101 = P is AIN1 N is GND, 110 = P is AIN2 N is GND, 111 = P is AIN3 N is GND) 17 | // | | 18 | // | | |PGA Gain (000 = ±6.144V, 001 = ±4.096V, 010 = ±2.048V, 011 = ±1.024V, 100 = ±0.512V, 101 = ±0.256V) 19 | // | | | 20 | // | | | |Mode (0 = Continuous conversion mode, 1 = Power-down and single-shot mode (default)) 21 | // | | | | 22 | // | | | | |Data Rate (000 = 8SPS, 001 = 16SPS, 010 = 32SPS, 011 = 64SPS, 100 = 128SPS, 101 = 250SPS, 110 = 475SPS, 111 = 860SPS) 23 | // | | | | | 24 | // | | | | | |Sensor Mode (1=Internal Temp Mode, 0=ADC Mode) 25 | // | | | | | | 26 | // | | | | | | |PullUp (0 = Pullup resistor disabled on DOUT/DRDY pin, 1 = Pullup resistor enabled on DOUT/DRDY pin (default)) 27 | // | | | | | | | 28 | // | | | | | | | |Update Config (01 = Valid data, update the Config register (default), 00,11,10 = do not update config register) 29 | // | | | | | | | | 30 | // | | | | | | | | |You must Always Write a 1 to this bit 31 | // | | | | | | | | | 32 | // 1 000 010 1 100 1 1 01 1 = 1000010110011011 = 0x859B (this sets up a single shot for the internal temperature sensor 128SPS) 33 | // 1 100 101 1 111 0 1 01 1 = 1100101111101011 = 0xCBEB (this sets up a single shot for single ended AIN0, PGA 0.256V, 860SPS) 34 | // 1 000 101 1 111 0 1 01 1 = 1000101111101011 = 0x8BEB (this sets up a single shot for differnetial AIN0 AIN1, PGA 0.256V, 860SPS) 35 | #define ADS1118_SINGLE_SHOT_INTERNAL_TEMPERATURE 0x859B 36 | #define ADS1118_SINGLE_SHOT_ADC 0x8BEB 37 | 38 | 39 | //Converts the raw temperature value from the ADS1118 to an integer reading of degrees C. 40 | //The incomming data arrives as a 16 bit value with the MSB first. 41 | //Since our actual data is 14 bit, we need to divide by 4 (or shift 2 bits to the right) to get the correct value 42 | //Also per the datasheet page 18, we need to multiply by 0.03125 to convert this to Degrees F 43 | //In order avoid floats, we will just divide by 32 which is the same as multiplying by 0.03125, but returns an integer 44 | //overall we are dividing by 4 and then again by 32. i.e. dividing by 128 45 | inline int16_t ADS1118_INT_TEMP_C(int16_t internal_temp_raw) 46 | { 47 | return internal_temp_raw/128; 48 | } 49 | 50 | 51 | #endif 52 | -------------------------------------------------------------------------------- /Firmware/JBC-Soldering-Controller/calculations.xlsx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Firmware/JBC-Soldering-Controller/calculations.xlsx -------------------------------------------------------------------------------- /Hardware/3DModels/ARDUINO PRO MICRO.SLDASM: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/ARDUINO PRO MICRO.SLDASM -------------------------------------------------------------------------------- /Hardware/3DModels/Assem2.SLDASM: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/Assem2.SLDASM -------------------------------------------------------------------------------- /Hardware/3DModels/Assem4.SLDASM: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/Assem4.SLDASM -------------------------------------------------------------------------------- /Hardware/3DModels/Board.sldprt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/Board.sldprt -------------------------------------------------------------------------------- /Hardware/3DModels/Body.sldasm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/Body.sldasm -------------------------------------------------------------------------------- /Hardware/3DModels/CaseFront.SLDPRT: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/CaseFront.SLDPRT -------------------------------------------------------------------------------- /Hardware/3DModels/CaseRight.sldprt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/CaseRight.sldprt -------------------------------------------------------------------------------- /Hardware/3DModels/CaseTop.SLDPRT: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/CaseTop.SLDPRT -------------------------------------------------------------------------------- /Hardware/3DModels/Encoder_with_knob.SLDASM: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/Encoder_with_knob.SLDASM -------------------------------------------------------------------------------- /Hardware/3DModels/KNOB_6mmShaft.SLDPRT: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/KNOB_6mmShaft.SLDPRT -------------------------------------------------------------------------------- /Hardware/3DModels/Lead.sldprt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/Lead.sldprt -------------------------------------------------------------------------------- /Hardware/3DModels/M2.5X12mmStandoff.SLDPRT: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/M2.5X12mmStandoff.SLDPRT -------------------------------------------------------------------------------- /Hardware/3DModels/M2_Screw.SLDPRT: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/M2_Screw.SLDPRT -------------------------------------------------------------------------------- /Hardware/3DModels/M2x12mmBrassStandoff.SLDPRT: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/M2x12mmBrassStandoff.SLDPRT -------------------------------------------------------------------------------- /Hardware/3DModels/M2x3x7mmBrassStandoff.SLDPRT: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/M2x3x7mmBrassStandoff.SLDPRT -------------------------------------------------------------------------------- /Hardware/3DModels/MICRO_603 cap on pad.sldprt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/MICRO_603 cap on pad.sldprt -------------------------------------------------------------------------------- /Hardware/3DModels/MICRO_603 resistor 102.sldprt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/MICRO_603 resistor 102.sldprt -------------------------------------------------------------------------------- /Hardware/3DModels/MICRO_603 resistor 103.sldprt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/MICRO_603 resistor 103.sldprt -------------------------------------------------------------------------------- /Hardware/3DModels/MICRO_603 resistor 22.sldprt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/MICRO_603 resistor 22.sldprt -------------------------------------------------------------------------------- /Hardware/3DModels/MICRO_603 resistor 331.sldprt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/MICRO_603 resistor 331.sldprt -------------------------------------------------------------------------------- /Hardware/3DModels/MICRO_PTC-1206.sldprt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/MICRO_PTC-1206.sldprt -------------------------------------------------------------------------------- /Hardware/3DModels/MICRO_cap106C.sldprt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/MICRO_cap106C.sldprt -------------------------------------------------------------------------------- /Hardware/3DModels/MICRO_led.sldprt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/MICRO_led.sldprt -------------------------------------------------------------------------------- /Hardware/3DModels/MicroUSB.sldprt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/MicroUSB.sldprt -------------------------------------------------------------------------------- /Hardware/3DModels/OLEDFootprint.SLDPRT: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/OLEDFootprint.SLDPRT -------------------------------------------------------------------------------- /Hardware/3DModels/OLED_0.91_128x32.SLDPRT: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/OLED_0.91_128x32.SLDPRT -------------------------------------------------------------------------------- /Hardware/3DModels/Open_CASCADE_STEP_translator_6.8_5.1.sldprt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/Open_CASCADE_STEP_translator_6.8_5.1.sldprt -------------------------------------------------------------------------------- /Hardware/3DModels/Open_CASCADE_STEP_translator_6.8_5.2.1.sldprt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/Open_CASCADE_STEP_translator_6.8_5.2.1.sldprt -------------------------------------------------------------------------------- /Hardware/3DModels/PCB.SLDPRT: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/PCB.SLDPRT -------------------------------------------------------------------------------- /Hardware/3DModels/PJ-313D.SLDPRT: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/PJ-313D.SLDPRT -------------------------------------------------------------------------------- /Hardware/3DModels/Part4.sldprt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/Part4.sldprt -------------------------------------------------------------------------------- /Hardware/3DModels/Part5.sldprt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/Part5.sldprt -------------------------------------------------------------------------------- /Hardware/3DModels/PowerConnector/DELL_A831M.SLDPRT: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/PowerConnector/DELL_A831M.SLDPRT -------------------------------------------------------------------------------- /Hardware/3DModels/PowerConnector/Hirose-RPC1.SLDPRT: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/PowerConnector/Hirose-RPC1.SLDPRT -------------------------------------------------------------------------------- /Hardware/3DModels/PowerConnector/PWR.SLDPRT: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/PowerConnector/PWR.SLDPRT -------------------------------------------------------------------------------- /Hardware/3DModels/PowerPlug.sldprt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/PowerPlug.sldprt -------------------------------------------------------------------------------- /Hardware/3DModels/ProMicroFootprint.SLDPRT: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/ProMicroFootprint.SLDPRT -------------------------------------------------------------------------------- /Hardware/3DModels/SOD 323.sldprt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/SOD 323.sldprt -------------------------------------------------------------------------------- /Hardware/3DModels/SideLeft.sldprt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/SideLeft.sldprt -------------------------------------------------------------------------------- /Hardware/3DModels/SolderingController.SLDASM: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/SolderingController.SLDASM -------------------------------------------------------------------------------- /Hardware/3DModels/Trimmed_Lead.sldprt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/Trimmed_Lead.sldprt -------------------------------------------------------------------------------- /Hardware/3DModels/VN50.SLDASM: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/VN50.SLDASM -------------------------------------------------------------------------------- /Hardware/3DModels/WS2812b.sldprt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/WS2812b.sldprt -------------------------------------------------------------------------------- /Hardware/3DModels/atmega32U4.sldprt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/atmega32U4.sldprt -------------------------------------------------------------------------------- /Hardware/3DModels/micro board.sldprt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/micro board.sldprt -------------------------------------------------------------------------------- /Hardware/3DModels/micro usb contact.sldprt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/micro usb contact.sldprt -------------------------------------------------------------------------------- /Hardware/3DModels/micro usb internal.sldprt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/micro usb internal.sldprt -------------------------------------------------------------------------------- /Hardware/3DModels/micro usb shell.sldprt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/micro usb shell.sldprt -------------------------------------------------------------------------------- /Hardware/3DModels/micro usb.sldasm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/micro usb.sldasm -------------------------------------------------------------------------------- /Hardware/3DModels/micro_MIC5219.sldprt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/micro_MIC5219.sldprt -------------------------------------------------------------------------------- /Hardware/3DModels/micro_crystal 5x3.sldprt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/micro_crystal 5x3.sldprt -------------------------------------------------------------------------------- /Hardware/3DModels/pec11r-4x15k-sxxxx.SLDPRT: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/pec11r-4x15k-sxxxx.SLDPRT -------------------------------------------------------------------------------- /Hardware/3DModels/sj-2523-smt.SLDPRT: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/sj-2523-smt.SLDPRT -------------------------------------------------------------------------------- /Hardware/3DModels/tab.sldprt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/3DModels/tab.sldprt -------------------------------------------------------------------------------- /Hardware/Documents/MCP16301 Design Analyzer v1.0.xlsx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/Documents/MCP16301 Design Analyzer v1.0.xlsx -------------------------------------------------------------------------------- /Hardware/Documents/MP2456.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/Documents/MP2456.jpg -------------------------------------------------------------------------------- /Hardware/JBC-Soldering-Controller_SCH_[No Variations].PDF: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/JBC-Soldering-Controller_SCH_[No Variations].PDF -------------------------------------------------------------------------------- /Hardware/JBC-Soldering_Controller.DsnWrk: -------------------------------------------------------------------------------- 1 | [ProjectGroup] 2 | Version=1.0 3 | [Project1] 4 | ProjectPath=MainBoard\JBC-Soldering-Controller.PrjPCB 5 | [Project2] 6 | ProjectPath=..\..\..\eagle\pro-micro\Imported Pro-Micro-v10a.PrjPcb\Pro-Micro-v10a.PrjPcb 7 | [Project3] 8 | ProjectPath=..\..\..\..\..\..\Projects\DMC.Altium.SVN\Scripts\AltiumScriptCentral-master\AltiumScriptCentral.PrjScr 9 | [Project4] 10 | ProjectPath=..\..\..\..\Downloads\SetProjectParameters\SetProjectParameters\Demo.PrjPcb 11 | [Project5] 12 | ProjectPath=..\..\..\..\Downloads\SetProjectParameters\SetProjectParameters\SetProjectParameters.PrjScr 13 | -------------------------------------------------------------------------------- /Hardware/MainBoard/Assembly.OutJob: -------------------------------------------------------------------------------- 1 | [OutputJobFile] 2 | Version=1.0 3 | Caption= 4 | Description= 5 | VaultGUID= 6 | ItemGUID= 7 | ItemHRID= 8 | RevisionGUID= 9 | RevisionId= 10 | VaultHRID= 11 | AutoItemHRID= 12 | NextRevId= 13 | FolderGUID= 14 | LifeCycleDefinitionGUID= 15 | RevisionNamingSchemeGUID= 16 | 17 | [OutputGroup1] 18 | Name= 19 | Description= 20 | TargetOutputMedium=SimpleBOM 21 | VariantName=[No Variations] 22 | VariantScope=1 23 | CurrentConfigurationName=Assembly 24 | TargetPrinter=\\dmc-server\Mr. T 25 | PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintJobKind=1|PrintWhat=1 26 | OutputMedium1=Print Job 27 | OutputMedium1_Type=Printer 28 | OutputMedium1_Printer= 29 | OutputMedium1_PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintJobKind=1|PrintWhat=1 30 | OutputMedium2=BOM 31 | OutputMedium2_Type=GeneratedFiles 32 | OutputMedium3=Video 33 | OutputMedium3_Type=Multimedia 34 | OutputMedium4=Fabrication Outputs 35 | OutputMedium4_Type=GeneratedFiles 36 | OutputMedium5=Assembly 37 | OutputMedium5_Type=GeneratedFiles 38 | OutputMedium6=3DPdf 39 | OutputMedium6_Type=Publish 40 | OutputMedium7=STEP 41 | OutputMedium7_Type=GeneratedFiles 42 | OutputMedium8=SimpleBOM 43 | OutputMedium8_Type=GeneratedFiles 44 | OutputMedium9=PCB Print 45 | OutputMedium9_Type=Publish 46 | OutputMedium10=Schematic 47 | OutputMedium10_Type=Publish 48 | OutputType1=BOM_PartType 49 | OutputName1=Bill of Materials 50 | OutputCategory1=Report 51 | OutputDocumentPath1=[ActiveBOM Document] 52 | OutputVariantName1= 53 | OutputEnabled1=0 54 | OutputEnabled1_OutputMedium1=0 55 | OutputEnabled1_OutputMedium2=1 56 | OutputEnabled1_OutputMedium3=0 57 | OutputEnabled1_OutputMedium4=0 58 | OutputEnabled1_OutputMedium5=0 59 | OutputEnabled1_OutputMedium6=0 60 | OutputEnabled1_OutputMedium7=0 61 | OutputEnabled1_OutputMedium8=0 62 | OutputEnabled1_OutputMedium9=0 63 | OutputEnabled1_OutputMedium10=0 64 | OutputDefault1=0 65 | PageOptions1=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=0|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-3|MediaType=1|DitherType=10|PrintScaleMode=1|PaperKind=Letter|PaperIndex=1 66 | Configuration1_Name1=ColumnNameFormat 67 | Configuration1_Item1=CaptionAsName 68 | Configuration1_Name2=Filter 69 | Configuration1_Item2=545046300E5446696C74657257726170706572000D46696C7465722E416374697665090F46696C7465722E43726974657269610A04000000000000000000 70 | Configuration1_Name3=General 71 | Configuration1_Item3=OpenExported=False|AddToProject=False|ForceFit=False|NotFitted=False|Database=False|DatabasePriority=False|IncludePCBData=False|IncludeVaultData=False|IncludeAlternatives=False|ShowExportOptions=True|TemplateFilename=|BatchMode=5|FormWidth=1442|FormHeight=898|SupplierProdQty=1|SupplierAutoQty=False|SupplierUseCachedPricing=False|SupplierCurrency=USD 72 | Configuration1_Name4=GroupOrder 73 | Configuration1_Item4=Manufacturer Part Number=True 74 | Configuration1_Name5=OutputConfigurationParameter1 75 | Configuration1_Item5=Cross",Checkbox,Triangle|ShowNote=True|ShowNoteCollapsed=True|ExpandDesignator=True|ExpandNetLabel=False|ExpandPort=False|ExpandSheetNum=False|ExpandDocNum=False|PrintArea=0|PrintAreaRect.X1=0|PrintAreaRect.Y1=0|PrintAreaRect.X2=0|PrintAreaRect.Y2=0 76 | Configuration1_Name6=SortOrder 77 | Configuration1_Item6=Designator=Up 78 | Configuration1_Name7=VisibleOrder 79 | Configuration1_Item7=Designator=500|Quantity=70|Manufacturer=100|Manufacturer Part Number=100|Description=300|Comment=200|Footprint=100|Package / Case=100|Supplier 1=100|Supplier Part Number 1=100 80 | OutputType2=Assembly 81 | OutputName2=Assembly Drawings 82 | OutputCategory2=Assembly 83 | OutputDocumentPath2= 84 | OutputVariantName2= 85 | OutputEnabled2=0 86 | OutputEnabled2_OutputMedium1=0 87 | OutputEnabled2_OutputMedium2=0 88 | OutputEnabled2_OutputMedium3=0 89 | OutputEnabled2_OutputMedium4=0 90 | OutputEnabled2_OutputMedium5=0 91 | OutputEnabled2_OutputMedium6=0 92 | OutputEnabled2_OutputMedium7=0 93 | OutputEnabled2_OutputMedium8=0 94 | OutputEnabled2_OutputMedium9=2 95 | OutputEnabled2_OutputMedium10=0 96 | OutputDefault2=0 97 | PageOptions2=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-3|MediaType=1|DitherType=10|PrintScaleMode=1|PaperKind=Letter|PaperIndex=1 98 | Configuration2_Name1=OutputConfigurationParameter1 99 | Configuration2_Item1=DesignatorDisplayMode=Physical|PrintArea=DesignExtent|PrintAreaLowerLeftCornerX=0|PrintAreaLowerLeftCornerY=0|PrintAreaUpperRightCornerX=0|PrintAreaUpperRightCornerY=0|Record=PcbPrintView 100 | Configuration2_Name2=OutputConfigurationParameter2 101 | Configuration2_Item2=IncludeBottomLayerComponents=False|IncludeMultiLayerComponents=True|IncludeTopLayerComponents=True|IncludeViewports=True|Index=0|Mirror=False|Name=Top LayerAssembly Drawing|PadNumberFontSize=14|Record=PcbPrintOut|ShowHoles=False|ShowPadNets=False|ShowPadNumbers=False|SubstituteFonts=False 102 | Configuration2_Name3=OutputConfigurationParameter3 103 | Configuration2_Item3=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Hidden|FFill=Hidden|FPad=Hidden|FRegion=Hidden|FText=Hidden|FTrack=Hidden|FVia=Hidden|Layer=TopLayer|Polygon=Hidden|PrintOutIndex=0|Record=PcbPrintLayer 104 | Configuration2_Name4=OutputConfigurationParameter4 105 | Configuration2_Item4=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=TopOverlay|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer 106 | Configuration2_Name5=OutputConfigurationParameter5 107 | Configuration2_Item5=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Hidden|Layer=MultiLayer|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer 108 | Configuration2_Name6=OutputConfigurationParameter6 109 | Configuration2_Item6=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical1|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer 110 | Configuration2_Name7=OutputConfigurationParameter7 111 | Configuration2_Item7=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical2|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer 112 | Configuration2_Name8=OutputConfigurationParameter8 113 | Configuration2_Item8=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical4|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer 114 | Configuration2_Name9=OutputConfigurationParameter9 115 | Configuration2_Item9=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical13|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer 116 | Configuration2_Name10=OutputConfigurationParameter10 117 | Configuration2_Item10=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical15|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer 118 | Configuration2_Name11=OutputConfigurationParameter11 119 | Configuration2_Item11=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical16|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer 120 | Configuration2_Name12=OutputConfigurationParameter12 121 | Configuration2_Item12=IncludeBottomLayerComponents=True|IncludeMultiLayerComponents=True|IncludeTopLayerComponents=False|IncludeViewports=True|Index=1|Mirror=False|Name=Bottom LayerAssembly Drawing|PadNumberFontSize=14|Record=PcbPrintOut|ShowHoles=False|ShowPadNets=False|ShowPadNumbers=False|SubstituteFonts=False 122 | Configuration2_Name13=OutputConfigurationParameter13 123 | Configuration2_Item13=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Hidden|FFill=Hidden|FPad=Hidden|FRegion=Hidden|FText=Hidden|FTrack=Hidden|FVia=Hidden|Layer=BottomLayer|Polygon=Hidden|PrintOutIndex=1|Record=PcbPrintLayer 124 | Configuration2_Name14=OutputConfigurationParameter14 125 | Configuration2_Item14=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=BottomOverlay|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer 126 | Configuration2_Name15=OutputConfigurationParameter15 127 | Configuration2_Item15=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Hidden|Layer=MultiLayer|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer 128 | Configuration2_Name16=OutputConfigurationParameter16 129 | Configuration2_Item16=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical1|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer 130 | Configuration2_Name17=OutputConfigurationParameter17 131 | Configuration2_Item17=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical2|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer 132 | Configuration2_Name18=OutputConfigurationParameter18 133 | Configuration2_Item18=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical4|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer 134 | Configuration2_Name19=OutputConfigurationParameter19 135 | Configuration2_Item19=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical13|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer 136 | Configuration2_Name20=OutputConfigurationParameter20 137 | Configuration2_Item20=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical15|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer 138 | Configuration2_Name21=OutputConfigurationParameter21 139 | Configuration2_Item21=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical16|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer 140 | PcbPrintPreferences2= 141 | OutputType3=Pick Place 142 | OutputName3=Generates pick and place files 143 | OutputCategory3=Assembly 144 | OutputDocumentPath3= 145 | OutputVariantName3= 146 | OutputEnabled3=0 147 | OutputEnabled3_OutputMedium1=0 148 | OutputEnabled3_OutputMedium2=0 149 | OutputEnabled3_OutputMedium3=0 150 | OutputEnabled3_OutputMedium4=0 151 | OutputEnabled3_OutputMedium5=1 152 | OutputEnabled3_OutputMedium6=0 153 | OutputEnabled3_OutputMedium7=0 154 | OutputEnabled3_OutputMedium8=0 155 | OutputEnabled3_OutputMedium9=0 156 | OutputEnabled3_OutputMedium10=0 157 | OutputDefault3=0 158 | Configuration3_Name1=OutputConfigurationParameter1 159 | Configuration3_Item1=Record=PickPlaceView|Units=Imperial|GenerateCSVFormat=False|GenerateTextFormat=True|ShowUnits=False|Separator=.|ExcludeFilterParam=False|IncludeVariations=True|Filter= |FilterActive=False|Column#1=Name:Designator,Fixed:True,Metric:False,Visible:True,Sort:None,Position:0|Column#2=Name:Comment,Fixed:True,Metric:False,Visible:True,Sort:None,Position:1|Column#3=Name:Layer,Fixed:True,Metric:False,Visible:True,Sort:None,Position:2|Column#4=Name:Footprint,Fixed:True,Metric:False,Visible:True,Sort:None,Position:3|Column#5=Name:Footprint Description,Fixed:True,Metric:False,Visible:False,Sort:None,Position:4|Column#6=Name:Center-X,Fixed:True,Metric:True,Visible:True,Sort:None,Position:5|Column#7=Name:Center-Y,Fixed:True,Metric:True,Visible:True,Sort:None,Position:6|Column#8=Name:Rotation,Fixed:True,Metric:False,Visible:True,Sort:None,Position:7|Column#9=Name:Description,Fixed:True,Metric:False,Visible:True,Sort:None,Position:8|Column#10=Name:ComponentKind,Fixed:True,Metric:False,Visible:False,Sort:None,Position:9|Column#11=Name:Height,Fixed:True,Metric:True,Visible:False,Sort:None,Position:10|Column#12=Name:Ref-X,Fixed:True,Metric:True,Visible:False,Sort:None,Position:11|Column#13=Name:Ref-Y,Fixed:True,Metric:True,Visible:False,Sort:None,Position:12|Column#14=Name:Pad-X,Fixed:True,Metric:True,Visible:False,Sort:None,Position:13|Column#15=Name:Pad-Y,Fixed:True,Metric:True,Visible:False,Sort:None,Position:14|Column#16=Name:Variation,Fixed:True,Metric:False,Visible:True,Sort:None,Position:15 160 | OutputType4=ExportSTEP 161 | OutputName4=Export STEP 162 | OutputCategory4=Export 163 | OutputDocumentPath4= 164 | OutputVariantName4= 165 | OutputEnabled4=0 166 | OutputEnabled4_OutputMedium1=0 167 | OutputEnabled4_OutputMedium2=0 168 | OutputEnabled4_OutputMedium3=0 169 | OutputEnabled4_OutputMedium4=0 170 | OutputEnabled4_OutputMedium5=0 171 | OutputEnabled4_OutputMedium6=0 172 | OutputEnabled4_OutputMedium7=1 173 | OutputEnabled4_OutputMedium8=0 174 | OutputEnabled4_OutputMedium9=0 175 | OutputEnabled4_OutputMedium10=0 176 | OutputDefault4=0 177 | Configuration4_Name1=OutputConfigurationParameter1 178 | Configuration4_Item1=Record=ExportSTEPView|ExportComponentOptions=0|ExportModelsOption=2|ExportHolesOption=0|CanSelectPrimitives=False|IncludeMechanicalPadHoles=True|IncludeElectricalPadHoles=True|IncludeFreePadHoles=True|ExportFoldedBoard=True|ExportFoldedBoardRate=0|ComponentSuffixType=0|ComponentSuffix= |ExportCopperOption=0|ExportCopperLayer=0|ExportPadAndViaBarrelsOnly=False|IgnoreBoardCopperLayerColors=False|ExportAsSinglePart=False|IncludeCoverLayer=True 179 | OutputType5=PCB Print 180 | OutputName5=PCB Prints 181 | OutputCategory5=Documentation 182 | OutputDocumentPath5= 183 | OutputVariantName5= 184 | OutputEnabled5=0 185 | OutputEnabled5_OutputMedium1=0 186 | OutputEnabled5_OutputMedium2=0 187 | OutputEnabled5_OutputMedium3=0 188 | OutputEnabled5_OutputMedium4=0 189 | OutputEnabled5_OutputMedium5=0 190 | OutputEnabled5_OutputMedium6=0 191 | OutputEnabled5_OutputMedium7=0 192 | OutputEnabled5_OutputMedium8=0 193 | OutputEnabled5_OutputMedium9=1 194 | OutputEnabled5_OutputMedium10=0 195 | OutputDefault5=0 196 | PageOptions5=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=0|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-3|MediaType=1|DitherType=10|PrintScaleMode=0|PaperKind=Letter|PaperIndex=1 197 | Configuration5_Name1=OutputConfigurationParameter1 198 | Configuration5_Item1=DesignatorDisplayMode=Physical|PrintArea=DesignExtent|PrintAreaLowerLeftCornerX=0|PrintAreaLowerLeftCornerY=0|PrintAreaUpperRightCornerX=0|PrintAreaUpperRightCornerY=0|Record=PcbPrintView 199 | Configuration5_Name2=OutputConfigurationParameter2 200 | Configuration5_Item2=IncludeBottomLayerComponents=True|IncludeMultiLayerComponents=True|IncludeTopLayerComponents=True|IncludeViewports=True|Index=0|Mirror=False|Name=Multilayer Composite Print|PadNumberFontSize=14|Record=PcbPrintOut|ShowHoles=False|ShowPadNets=False|ShowPadNumbers=False|SubstituteFonts=False 201 | Configuration5_Name3=OutputConfigurationParameter3 202 | Configuration5_Item3=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=TopOverlay|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer 203 | Configuration5_Name4=OutputConfigurationParameter4 204 | Configuration5_Item4=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=TopLayer|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer 205 | Configuration5_Name5=OutputConfigurationParameter5 206 | Configuration5_Item5=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=MultiLayer|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer 207 | Configuration5_Name6=OutputConfigurationParameter6 208 | Configuration5_Item6=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical1|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer 209 | Configuration5_Name7=OutputConfigurationParameter7 210 | Configuration5_Item7=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical2|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer 211 | Configuration5_Name8=OutputConfigurationParameter8 212 | Configuration5_Item8=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical4|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer 213 | Configuration5_Name9=OutputConfigurationParameter9 214 | Configuration5_Item9=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical13|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer 215 | Configuration5_Name10=OutputConfigurationParameter10 216 | Configuration5_Item10=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical15|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer 217 | Configuration5_Name11=OutputConfigurationParameter11 218 | Configuration5_Item11=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical16|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer 219 | Configuration5_Name12=OutputConfigurationParameter12 220 | Configuration5_Item12=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=BottomLayer|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer 221 | Configuration5_Name13=OutputConfigurationParameter13 222 | Configuration5_Item13=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=InternalPlane2|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer 223 | Configuration5_Name14=OutputConfigurationParameter14 224 | Configuration5_Item14=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=InternalPlane1|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer 225 | PcbPrintPreferences5= 226 | OutputType6=PDF3D 227 | OutputName6=PDF3D 228 | OutputCategory6=Documentation 229 | OutputDocumentPath6= 230 | OutputVariantName6= 231 | OutputEnabled6=0 232 | OutputEnabled6_OutputMedium1=0 233 | OutputEnabled6_OutputMedium2=0 234 | OutputEnabled6_OutputMedium3=0 235 | OutputEnabled6_OutputMedium4=0 236 | OutputEnabled6_OutputMedium5=0 237 | OutputEnabled6_OutputMedium6=1 238 | OutputEnabled6_OutputMedium7=0 239 | OutputEnabled6_OutputMedium8=0 240 | OutputEnabled6_OutputMedium9=0 241 | OutputEnabled6_OutputMedium10=0 242 | OutputDefault6=0 243 | PageOptions6=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-3|MediaType=1|DitherType=10|PrintScaleMode=1|PaperKind=Letter|PaperIndex=1 244 | Configuration6_Name1=OutputConfigurationParameter1 245 | Configuration6_Item1=Record=ExportPDF3DSetting|Version=110|Format=0|Flags=8158|Scheme=0|ViewColorR0=255|ViewColorG0=255|ViewColorB0=255|ViewLignt0=9|ViewColorR1=255|ViewColorG1=255|ViewColorB1=255|ViewLignt1=9|ViewColorR2=255|ViewColorG2=255|ViewColorB2=255|ViewLignt2=9|ViewColorR3=255|ViewColorG3=255|ViewColorB3=255|ViewLignt3=9 246 | OutputType7=Schematic Print 247 | OutputName7=Schematic Prints 248 | OutputCategory7=Documentation 249 | OutputDocumentPath7=[Project Physical Documents] 250 | OutputVariantName7= 251 | OutputEnabled7=0 252 | OutputEnabled7_OutputMedium1=0 253 | OutputEnabled7_OutputMedium2=0 254 | OutputEnabled7_OutputMedium3=0 255 | OutputEnabled7_OutputMedium4=0 256 | OutputEnabled7_OutputMedium5=0 257 | OutputEnabled7_OutputMedium6=0 258 | OutputEnabled7_OutputMedium7=0 259 | OutputEnabled7_OutputMedium8=0 260 | OutputEnabled7_OutputMedium9=0 261 | OutputEnabled7_OutputMedium10=1 262 | OutputDefault7=0 263 | PageOptions7=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=0|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-3|MediaType=1|DitherType=10|PrintScaleMode=1|PaperKind=Letter|PaperIndex=1 264 | Configuration7_Name1=OutputConfigurationParameter1 265 | Configuration7_Item1=Record=SchPrintView|ShowNoERC=True|ShowParamSet=True|ShowProbe=True|ShowBlanket=True|NoERCSymbolsToShow="Thin Cross","Thick Cross","Small Cross",Checkbox,Triangle|ShowNote=True|ShowNoteCollapsed=True|ExpandDesignator=True|ExpandNetLabel=False|ExpandPort=False|ExpandSheetNum=False|ExpandDocNum=False|PrintArea=0|PrintAreaRect.X1=0|PrintAreaRect.Y1=0|PrintAreaRect.X2=0|PrintAreaRect.Y2=0 266 | OutputType8=BOM_PartType 267 | OutputName8=SimpleBOM 268 | OutputCategory8=Report 269 | OutputDocumentPath8=[ActiveBOM Document] 270 | OutputVariantName8= 271 | OutputEnabled8=1 272 | OutputEnabled8_OutputMedium1=0 273 | OutputEnabled8_OutputMedium2=0 274 | OutputEnabled8_OutputMedium3=0 275 | OutputEnabled8_OutputMedium4=0 276 | OutputEnabled8_OutputMedium5=0 277 | OutputEnabled8_OutputMedium6=0 278 | OutputEnabled8_OutputMedium7=0 279 | OutputEnabled8_OutputMedium8=1 280 | OutputEnabled8_OutputMedium9=0 281 | OutputEnabled8_OutputMedium10=0 282 | OutputDefault8=0 283 | PageOptions8=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=0|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-3|MediaType=1|DitherType=10|PrintScaleMode=1|PaperKind=Letter (8.5" x 11")|PaperIndex=1 284 | Configuration8_Name1=ColumnNameFormat 285 | Configuration8_Item1=CaptionAsName 286 | Configuration8_Name2=Filter 287 | Configuration8_Item2=545046300E5446696C74657257726170706572000D46696C7465722E416374697665090F46696C7465722E43726974657269610A04000000000000000000 288 | Configuration8_Name3=General 289 | Configuration8_Item3=OpenExported=False|AddToProject=False|ForceFit=False|NotFitted=False|Database=False|DatabasePriority=False|IncludePCBData=False|IncludeVaultData=False|IncludeAlternatives=False|ShowExportOptions=True|TemplateFilename=|BatchMode=5|FormWidth=1442|FormHeight=898|SupplierProdQty=1|SupplierAutoQty=False|SupplierUseCachedPricing=False|SupplierCurrency=USD 290 | Configuration8_Name4=GroupOrder 291 | Configuration8_Item4= 292 | Configuration8_Name5=SortOrder 293 | Configuration8_Item5=Designator=Up 294 | Configuration8_Name6=VisibleOrder 295 | Configuration8_Item6=Designator=100|Manufacturer Part Number=100|Supplier Part Number 1=100 296 | 297 | [PublishSettings] 298 | OutputFilePath2=C:\Projects\EssexO2gauge\trunk\Hardware\MainBoard\Project Outputs for Essex_O2_Monitor\ 299 | ReleaseManaged2=1 300 | OutputBasePath2= 301 | OutputPathMedia2= 302 | OutputPathMediaValue2= 303 | OutputPathOutputer2=[Output Type] 304 | OutputPathOutputerPrefix2= 305 | OutputPathOutputerValue2= 306 | OutputFileName2= 307 | OutputFileNameMulti2==ProjectName+'_BOM_'+VariantName 308 | UseOutputNameForMulti2=0 309 | OutputFileNameSpecial2= 310 | OpenOutput2=1 311 | OutputFilePath3= 312 | ReleaseManaged3=1 313 | OutputBasePath3= 314 | OutputPathMedia3= 315 | OutputPathMediaValue3= 316 | OutputPathOutputer3=[Output Type] 317 | OutputPathOutputerPrefix3= 318 | OutputPathOutputerValue3= 319 | OutputFileName3= 320 | OutputFileNameMulti3= 321 | UseOutputNameForMulti3=1 322 | OutputFileNameSpecial3= 323 | OpenOutput3=1 324 | PromptOverwrite3=1 325 | PublishMethod3=5 326 | ZoomLevel3=50 327 | FitSCHPrintSizeToDoc3=1 328 | FitPCBPrintSizeToDoc3=1 329 | GenerateNetsInfo3=1 330 | MarkPins3=1 331 | MarkNetLabels3=1 332 | MarkPortsId3=1 333 | MediaFormat3=Windows Media file (*.wmv,*.wma,*.asf) 334 | FixedDimensions3=1 335 | Width3=352 336 | Height3=288 337 | MultiFile3=0 338 | FramesPerSecond3=25 339 | FramesPerSecondDenom3=1 340 | AviPixelFormat3=7 341 | AviCompression3=MP42 MS-MPEG4 V2 342 | AviQuality3=100 343 | FFmpegVideoCodecId3=13 344 | FFmpegPixelFormat3=0 345 | FFmpegQuality3=80 346 | WmvVideoCodecName3=Windows Media Video V7 347 | WmvQuality3=80 348 | OutputFilePath4=C:\Projects\EssexO2gauge\trunk\Hardware\MainBoard\Project Outputs for Essex_O2_Monitor\ 349 | ReleaseManaged4=1 350 | OutputBasePath4=Project Outputs for JBC-Soldering-Controller 351 | OutputPathMedia4= 352 | OutputPathMediaValue4= 353 | OutputPathOutputer4=[Output Type] 354 | OutputPathOutputerPrefix4= 355 | OutputPathOutputerValue4= 356 | OutputFileName4= 357 | OutputFileNameMulti4==ProjectName 358 | UseOutputNameForMulti4=0 359 | OutputFileNameSpecial4= 360 | OpenOutput4=1 361 | OutputFilePath5=C:\Projects\EssexO2gauge\trunk\Hardware\MainBoard\Project Outputs for Essex_O2_Monitor\ 362 | ReleaseManaged5=1 363 | OutputBasePath5= 364 | OutputPathMedia5= 365 | OutputPathMediaValue5= 366 | OutputPathOutputer5=[Output Type] 367 | OutputPathOutputerPrefix5= 368 | OutputPathOutputerValue5= 369 | OutputFileName5= 370 | OutputFileNameMulti5= 371 | UseOutputNameForMulti5=1 372 | OutputFileNameSpecial5= 373 | OpenOutput5=1 374 | OutputFilePath6=C:\Projects\EssexO2gauge\trunk\Hardware\MainBoard\Project Outputs for Essex_O2_Monitor\3DPdf\TopBoard.PDF 375 | ReleaseManaged6=1 376 | OutputBasePath6= 377 | OutputPathMedia6=[Media Name] 378 | OutputPathMediaValue6= 379 | OutputPathOutputer6=[Output Type] 380 | OutputPathOutputerPrefix6= 381 | OutputPathOutputerValue6= 382 | OutputFileName6=Assembly.PDF 383 | OutputFileNameMulti6= 384 | UseOutputNameForMulti6=0 385 | OutputFileNameSpecial6==ProjectName+'_3DPCB_'+VariantName 386 | OpenOutput6=1 387 | PromptOverwrite6=1 388 | PublishMethod6=0 389 | ZoomLevel6=50 390 | FitSCHPrintSizeToDoc6=1 391 | FitPCBPrintSizeToDoc6=1 392 | GenerateNetsInfo6=1 393 | MarkPins6=1 394 | MarkNetLabels6=1 395 | MarkPortsId6=1 396 | GenerateTOC6=1 397 | ShowComponentParameters6=1 398 | GlobalBookmarks6=0 399 | PDFACompliance6=Disabled 400 | PDFVersion6=Default 401 | OutputFilePath7=C:\Projects\EssexO2gauge\trunk\Hardware\MainBoard\Project Outputs for Essex_O2_Monitor\STEP\ 402 | ReleaseManaged7=1 403 | OutputBasePath7= 404 | OutputPathMedia7=[Media Name] 405 | OutputPathMediaValue7= 406 | OutputPathOutputer7= 407 | OutputPathOutputerPrefix7= 408 | OutputPathOutputerValue7= 409 | OutputFileName7= 410 | OutputFileNameMulti7= 411 | UseOutputNameForMulti7=1 412 | OutputFileNameSpecial7= 413 | OpenOutput7=1 414 | OutputFilePath8=C:\Users\timj\Documents\Arduino\JBC-Soldering-Controller\Hardware\MainBoard\Project Outputs for JBC-Soldering-Controller\ 415 | ReleaseManaged8=1 416 | OutputBasePath8=Project Outputs for JBC-Soldering-Controller 417 | OutputPathMedia8= 418 | OutputPathMediaValue8= 419 | OutputPathOutputer8=[Output Name] 420 | OutputPathOutputerPrefix8= 421 | OutputPathOutputerValue8= 422 | OutputFileName8= 423 | OutputFileNameMulti8==ProjectName+'_SIMPLE_BOM_'+VariantName 424 | UseOutputNameForMulti8=0 425 | OutputFileNameSpecial8= 426 | OpenOutput8=1 427 | OutputFilePath9=C:\Projects\EssexO2gauge\trunk\Hardware\MainBoard\Project Outputs for Essex_O2_Monitor\Assembly.PDF 428 | ReleaseManaged9=1 429 | OutputBasePath9= 430 | OutputPathMedia9=[Media Name] 431 | OutputPathMediaValue9= 432 | OutputPathOutputer9=[Output Type] 433 | OutputPathOutputerPrefix9= 434 | OutputPathOutputerValue9= 435 | OutputFileName9=Assembly.PDF 436 | OutputFileNameMulti9= 437 | UseOutputNameForMulti9=0 438 | OutputFileNameSpecial9==ProjectName+'_PCB_'+VariantName 439 | OpenOutput9=1 440 | PromptOverwrite9=1 441 | PublishMethod9=0 442 | ZoomLevel9=50 443 | FitSCHPrintSizeToDoc9=1 444 | FitPCBPrintSizeToDoc9=1 445 | GenerateNetsInfo9=1 446 | MarkPins9=1 447 | MarkNetLabels9=1 448 | MarkPortsId9=1 449 | GenerateTOC9=1 450 | ShowComponentParameters9=1 451 | GlobalBookmarks9=0 452 | PDFACompliance9=Disabled 453 | PDFVersion9=Default 454 | OutputFilePath10=C:\Projects\EssexO2gauge\trunk\Hardware\MainBoard\Project Outputs for Essex_O2_Monitor\Assembly.PDF 455 | ReleaseManaged10=1 456 | OutputBasePath10= 457 | OutputPathMedia10=[Media Name] 458 | OutputPathMediaValue10= 459 | OutputPathOutputer10=[Output Type] 460 | OutputPathOutputerPrefix10= 461 | OutputPathOutputerValue10= 462 | OutputFileName10=Assembly.PDF 463 | OutputFileNameMulti10= 464 | UseOutputNameForMulti10=0 465 | OutputFileNameSpecial10==ProjectName+'_SCH_'+VariantName 466 | OpenOutput10=1 467 | PromptOverwrite10=1 468 | PublishMethod10=0 469 | ZoomLevel10=50 470 | FitSCHPrintSizeToDoc10=1 471 | FitPCBPrintSizeToDoc10=1 472 | GenerateNetsInfo10=1 473 | MarkPins10=1 474 | MarkNetLabels10=1 475 | MarkPortsId10=1 476 | GenerateTOC10=1 477 | ShowComponentParameters10=1 478 | GlobalBookmarks10=0 479 | PDFACompliance10=Disabled 480 | PDFVersion10=Default 481 | 482 | [GeneratedFilesSettings] 483 | RelativeOutputPath2=C:\Projects\EssexO2gauge\trunk\Hardware\MainBoard\Project Outputs for Essex_O2_Monitor\ 484 | OpenOutputs2=1 485 | AddToProject2=1 486 | TimestampFolder2=0 487 | UseOutputName2=0 488 | OpenODBOutput2=0 489 | OpenGerberOutput2=0 490 | OpenNCDrillOutput2=0 491 | OpenIPCOutput2=0 492 | EnableReload2=0 493 | RelativeOutputPath3= 494 | OpenOutputs3=1 495 | RelativeOutputPath4=C:\Projects\EssexO2gauge\trunk\Hardware\MainBoard\Project Outputs for Essex_O2_Monitor\ 496 | OpenOutputs4=1 497 | AddToProject4=1 498 | TimestampFolder4=0 499 | UseOutputName4=0 500 | OpenODBOutput4=0 501 | OpenGerberOutput4=0 502 | OpenNCDrillOutput4=0 503 | OpenIPCOutput4=0 504 | EnableReload4=0 505 | RelativeOutputPath5=C:\Projects\EssexO2gauge\trunk\Hardware\MainBoard\Project Outputs for Essex_O2_Monitor\ 506 | OpenOutputs5=1 507 | AddToProject5=1 508 | TimestampFolder5=0 509 | UseOutputName5=0 510 | OpenODBOutput5=0 511 | OpenGerberOutput5=0 512 | OpenNCDrillOutput5=0 513 | OpenIPCOutput5=0 514 | EnableReload5=0 515 | RelativeOutputPath6=C:\Projects\EssexO2gauge\trunk\Hardware\MainBoard\Project Outputs for Essex_O2_Monitor\3DPdf\TopBoard.PDF 516 | OpenOutputs6=1 517 | RelativeOutputPath7=C:\Projects\EssexO2gauge\trunk\Hardware\MainBoard\Project Outputs for Essex_O2_Monitor\STEP\ 518 | OpenOutputs7=1 519 | AddToProject7=1 520 | TimestampFolder7=0 521 | UseOutputName7=0 522 | OpenODBOutput7=0 523 | OpenGerberOutput7=0 524 | OpenNCDrillOutput7=0 525 | OpenIPCOutput7=0 526 | EnableReload7=0 527 | RelativeOutputPath8=C:\Users\timj\Documents\Arduino\JBC-Soldering-Controller\Hardware\MainBoard\Project Outputs for JBC-Soldering-Controller\ 528 | OpenOutputs8=1 529 | AddToProject8=1 530 | TimestampFolder8=0 531 | UseOutputName8=0 532 | OpenODBOutput8=0 533 | OpenGerberOutput8=0 534 | OpenNCDrillOutput8=0 535 | OpenIPCOutput8=0 536 | EnableReload8=0 537 | RelativeOutputPath9=C:\Projects\EssexO2gauge\trunk\Hardware\MainBoard\Project Outputs for Essex_O2_Monitor\Assembly.PDF 538 | OpenOutputs9=1 539 | RelativeOutputPath10=C:\Projects\EssexO2gauge\trunk\Hardware\MainBoard\Project Outputs for Essex_O2_Monitor\Assembly.PDF 540 | OpenOutputs10=1 541 | 542 | -------------------------------------------------------------------------------- /Hardware/MainBoard/BOM1.BomDoc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/MainBoard/BOM1.BomDoc -------------------------------------------------------------------------------- /Hardware/MainBoard/Controller.SchDoc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/MainBoard/Controller.SchDoc -------------------------------------------------------------------------------- /Hardware/MainBoard/Fabrication.OutJob: -------------------------------------------------------------------------------- 1 | [OutputJobFile] 2 | Version=1.0 3 | Caption= 4 | Description= 5 | VaultGUID= 6 | ItemGUID= 7 | ItemHRID= 8 | RevisionGUID= 9 | RevisionId= 10 | VaultHRID= 11 | AutoItemHRID= 12 | NextRevId= 13 | FolderGUID= 14 | LifeCycleDefinitionGUID= 15 | RevisionNamingSchemeGUID= 16 | 17 | [OutputGroup1] 18 | Name=Fabrication.OutJob 19 | Description= 20 | TargetOutputMedium=Fabrication Outputs 21 | VariantName=[No Variations] 22 | VariantScope=1 23 | CurrentConfigurationName= 24 | TargetPrinter=\\dmc-server\Mr. T 25 | PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintJobKind=1|PrintWhat=1 26 | OutputMedium1=Print Job 27 | OutputMedium1_Type=Printer 28 | OutputMedium1_Printer= 29 | OutputMedium1_PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintJobKind=1|PrintWhat=1 30 | OutputMedium2=Video 31 | OutputMedium2_Type=Multimedia 32 | OutputMedium3=Fabrication Outputs 33 | OutputMedium3_Type=GeneratedFiles 34 | OutputMedium4=Drill 35 | OutputMedium4_Type=Publish 36 | OutputType1=Gerber 37 | OutputName1=Gerber Files 38 | OutputCategory1=Fabrication 39 | OutputDocumentPath1= 40 | OutputVariantName1= 41 | OutputEnabled1=1 42 | OutputEnabled1_OutputMedium1=0 43 | OutputEnabled1_OutputMedium2=0 44 | OutputEnabled1_OutputMedium3=1 45 | OutputEnabled1_OutputMedium4=0 46 | OutputDefault1=0 47 | Configuration1_Name1=OutputConfigurationParameter1 48 | Configuration1_Item1=AddToAllLayerClasses.Set= |AddToAllPlots.Set=SerializeLayerHash.Version~2,ClassName~TLayerToBoolean|CentrePlots=False|DrillDrawingSymbol=GraphicsSymbol|DrillDrawingSymbolSize=200000|EmbeddedApertures=True|FilmBorderSize=10000000|FilmXSize=200000000|FilmYSize=160000000|FlashAllFills=False|FlashPadShapes=True|G54OnApertureChange=False|GenerateDRCRulesFile=True|GenerateDRCRulesFile=True|GenerateReliefShapes=True|GerberUnit=Imperial|GerberUnit=Imperial|IncludeUnconnectedMidLayerPads=False|LayerClassesMirror.Set= |LayerClassesPlot.Set="All Layers"|LeadingAndTrailingZeroesMode=SuppressLeadingZeroes|MaxApertureSize=2500000|MinusApertureTolerance=50|MinusApertureTolerance=50|Mirror.Set=SerializeLayerHash.Version~2,ClassName~TLayerToBoolean|MirrorDrillDrawingPlots=False|MirrorDrillGuidePlots=False|NoRegularPolygons=False|NumberOfDecimals=5|NumberOfDecimals=5|OptimizeChangeLocationCommands=True|OptimizeChangeLocationCommands=True|OriginPosition=Relative|Panelize=False|Plot.Set=SerializeLayerHash.Version~2,ClassName~TLayerToBoolean,16973830~1,16973832~1,16973834~1,16777217~1,16842751~1,16973835~1,16973833~1,16973831~1,16908289~1,16908290~1,16908291~1,16908292~1,16908293~1,16908297~1,16908301~1,16908303~1,16973837~1,16973848~1,16973849~1|PlotPositivePlaneLayers=False|PlotUsedDrillDrawingLayerPairs=True|PlotUsedDrillGuideLayerPairs=True|PlusApertureTolerance=50|PlusApertureTolerance=50|Record=GerberView|SoftwareArcs=False|Sorted=False|Sorted=False 49 | OutputType2=NC Drill 50 | OutputName2=NC Drill Files 51 | OutputCategory2=Fabrication 52 | OutputDocumentPath2= 53 | OutputVariantName2= 54 | OutputEnabled2=1 55 | OutputEnabled2_OutputMedium1=0 56 | OutputEnabled2_OutputMedium2=0 57 | OutputEnabled2_OutputMedium3=2 58 | OutputEnabled2_OutputMedium4=0 59 | OutputDefault2=0 60 | Configuration2_Name1=OutputConfigurationParameter1 61 | Configuration2_Item1=BoardEdgeRoutToolDia=2000000|GenerateBoardEdgeRout=False|GenerateDrilledSlotsG85=True|GenerateEIADrillFile=False|GenerateSeparatePlatedNonPlatedFiles=False|NumberOfDecimals=4|NumberOfUnits=2|OptimizeChangeLocationCommands=True|OriginPosition=Relative|Record=DrillView|Units=Imperial|ZeroesMode=SuppressLeadingZeroes 62 | OutputType3=ODB 63 | OutputName3=ODB++ Files 64 | OutputCategory3=Fabrication 65 | OutputDocumentPath3= 66 | OutputVariantName3= 67 | OutputEnabled3=1 68 | OutputEnabled3_OutputMedium1=0 69 | OutputEnabled3_OutputMedium2=0 70 | OutputEnabled3_OutputMedium3=3 71 | OutputEnabled3_OutputMedium4=0 72 | OutputDefault3=0 73 | Configuration3_Name1=OutputConfigurationParameter1 74 | Configuration3_Item1=AddToAllLayerClasses.Set= |AddToAllPlots_Mechanical 1=False|AddToAllPlots_Mechanical 10=False|AddToAllPlots_Mechanical 11=False|AddToAllPlots_Mechanical 12=False|AddToAllPlots_Mechanical 13=False|AddToAllPlots_Mechanical 14=False|AddToAllPlots_Mechanical 15=False|AddToAllPlots_Mechanical 16=False|AddToAllPlots_Mechanical 2=False|AddToAllPlots_Mechanical 3=False|AddToAllPlots_Mechanical 4=False|AddToAllPlots_Mechanical 5=False|AddToAllPlots_Mechanical 6=False|AddToAllPlots_Mechanical 7=False|AddToAllPlots_Mechanical 8=False|AddToAllPlots_Mechanical 9=False|ExportPositivePlaneLayers=False|GenerateDRCRulesFile=False|IncludeUnconnectedMidLayerPads=False|LayerClassesPlot.Set="All Layers"|ObjsInsideBoardOutlineOnly=False|ODBProfileLayer=-1000|PlotBottomLayerPlot=True|PlotBottomOverlayPlot=True|PlotBottomPastePlot=True|PlotBottomSolderPlot=True|PlotInternalPlane10Plot=False|PlotInternalPlane11Plot=False|PlotInternalPlane12Plot=False|PlotInternalPlane13Plot=False|PlotInternalPlane14Plot=False|PlotInternalPlane15Plot=False|PlotInternalPlane16Plot=False|PlotInternalPlane1Plot=False|PlotInternalPlane2Plot=False|PlotInternalPlane3Plot=False|PlotInternalPlane4Plot=False|PlotInternalPlane5Plot=False|PlotInternalPlane6Plot=False|PlotInternalPlane7Plot=False|PlotInternalPlane8Plot=False|PlotInternalPlane9Plot=False|PlotKeepOutLayerPlot=True|PlotMechanical10Plot=False|PlotMechanical11Plot=False|PlotMechanical12Plot=False|PlotMechanical13Plot=True|PlotMechanical14Plot=False|PlotMechanical15Plot=True|PlotMechanical16Plot=True|PlotMechanical1Plot=True|PlotMechanical2Plot=True|PlotMechanical3Plot=False|PlotMechanical4Plot=True|PlotMechanical5Plot=False|PlotMechanical6Plot=False|PlotMechanical7Plot=False|PlotMechanical8Plot=False|PlotMechanical9Plot=False|PlotMidLayer10Plot=False|PlotMidLayer11Plot=False|PlotMidLayer12Plot=False|PlotMidLayer13Plot=False|PlotMidLayer14Plot=False|PlotMidLayer15Plot=False|PlotMidLayer16Plot=False|PlotMidLayer17Plot=False|PlotMidLayer18Plot=False|PlotMidLayer19Plot=False|PlotMidLayer1Plot=False|PlotMidLayer20Plot=False|PlotMidLayer21Plot=False|PlotMidLayer22Plot=False|PlotMidLayer23Plot=False|PlotMidLayer24Plot=False|PlotMidLayer25Plot=False|PlotMidLayer26Plot=False|PlotMidLayer27Plot=False|PlotMidLayer28Plot=False|PlotMidLayer29Plot=False|PlotMidLayer2Plot=False|PlotMidLayer30Plot=False|PlotMidLayer3Plot=False|PlotMidLayer4Plot=False|PlotMidLayer5Plot=False|PlotMidLayer6Plot=False|PlotMidLayer7Plot=False|PlotMidLayer8Plot=False|PlotMidLayer9Plot=False|PlotTopLayerPlot=True|PlotTopOverlayPlot=True|PlotTopPastePlot=True|PlotTopSolderPlot=True|Record=ODBView 75 | OutputType4=Drill 76 | OutputName4=Drill Drawing/Guides 77 | OutputCategory4=Fabrication 78 | OutputDocumentPath4= 79 | OutputVariantName4= 80 | OutputEnabled4=0 81 | OutputEnabled4_OutputMedium1=0 82 | OutputEnabled4_OutputMedium2=0 83 | OutputEnabled4_OutputMedium3=0 84 | OutputEnabled4_OutputMedium4=1 85 | OutputDefault4=0 86 | PageOptions4=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-3|MediaType=1|DitherType=10|PrintScaleMode=1|PaperKind=Letter|PaperIndex=1 87 | Configuration4_Name1=OutputConfigurationParameter1 88 | Configuration4_Item1=DesignatorDisplayMode=Physical|PrintArea=DesignExtent|PrintAreaLowerLeftCornerX=0|PrintAreaLowerLeftCornerY=0|PrintAreaUpperRightCornerX=0|PrintAreaUpperRightCornerY=0|Record=PcbPrintView 89 | Configuration4_Name2=OutputConfigurationParameter2 90 | Configuration4_Item2=IncludeBottomLayerComponents=True|IncludeMultiLayerComponents=True|IncludeTopLayerComponents=True|IncludeViewports=True|Index=0|Mirror=False|Name=Drill Drawing For (Bottom Layer,Top Layer)|PadNumberFontSize=14|Record=PcbPrintOut|ShowHoles=False|ShowPadNets=False|ShowPadNumbers=False|SubstituteFonts=False 91 | Configuration4_Name3=OutputConfigurationParameter3 92 | Configuration4_Item3=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=BottomLayer|DLayer2=TopLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=DrillDrawing|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer 93 | Configuration4_Name4=OutputConfigurationParameter4 94 | Configuration4_Item4=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical1|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer 95 | Configuration4_Name5=OutputConfigurationParameter5 96 | Configuration4_Item5=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical2|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer 97 | Configuration4_Name6=OutputConfigurationParameter6 98 | Configuration4_Item6=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical4|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer 99 | Configuration4_Name7=OutputConfigurationParameter7 100 | Configuration4_Item7=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical13|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer 101 | Configuration4_Name8=OutputConfigurationParameter8 102 | Configuration4_Item8=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical15|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer 103 | Configuration4_Name9=OutputConfigurationParameter9 104 | Configuration4_Item9=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical16|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer 105 | PcbPrintPreferences4= 106 | OutputType5=Board Stack Report 107 | OutputName5=Report Board Stack 108 | OutputCategory5=Fabrication 109 | OutputDocumentPath5= 110 | OutputVariantName5= 111 | OutputEnabled5=1 112 | OutputEnabled5_OutputMedium1=0 113 | OutputEnabled5_OutputMedium2=0 114 | OutputEnabled5_OutputMedium3=4 115 | OutputEnabled5_OutputMedium4=0 116 | OutputDefault5=0 117 | PageOptions5=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=0|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-3|MediaType=1|DitherType=10|PrintScaleMode=1|PaperKind=Letter|PaperIndex=1 118 | Configuration5_Name1=OutputConfigurationParameter1 119 | Configuration5_Item1=Record=LayerStackReportView|Units=Metric 120 | 121 | [PublishSettings] 122 | OutputFilePath2= 123 | ReleaseManaged2=1 124 | OutputBasePath2=Project Outputs for JBC-Soldering-Controller 125 | OutputPathMedia2= 126 | OutputPathMediaValue2= 127 | OutputPathOutputer2=[Output Type] 128 | OutputPathOutputerPrefix2= 129 | OutputPathOutputerValue2= 130 | OutputFileName2= 131 | OutputFileNameMulti2= 132 | UseOutputNameForMulti2=1 133 | OutputFileNameSpecial2= 134 | OpenOutput2=1 135 | PromptOverwrite2=1 136 | PublishMethod2=5 137 | ZoomLevel2=50 138 | FitSCHPrintSizeToDoc2=1 139 | FitPCBPrintSizeToDoc2=1 140 | GenerateNetsInfo2=1 141 | MarkPins2=1 142 | MarkNetLabels2=1 143 | MarkPortsId2=1 144 | MediaFormat2=Windows Media file (*.wmv,*.wma,*.asf) 145 | FixedDimensions2=1 146 | Width2=352 147 | Height2=288 148 | MultiFile2=0 149 | FramesPerSecond2=25 150 | FramesPerSecondDenom2=1 151 | AviPixelFormat2=7 152 | AviCompression2=MP42 MS-MPEG4 V2 153 | AviQuality2=100 154 | FFmpegVideoCodecId2=13 155 | FFmpegPixelFormat2=0 156 | FFmpegQuality2=80 157 | WmvVideoCodecName2=Windows Media Video V7 158 | WmvQuality2=80 159 | OutputFilePath3=C:\Users\timj\Documents\Arduino\JBC-Soldering-Controller\Hardware\MainBoard\Project Outputs for JBC-Soldering-Controller\ 160 | ReleaseManaged3=1 161 | OutputBasePath3=Project Outputs for JBC-Soldering-Controller 162 | OutputPathMedia3= 163 | OutputPathMediaValue3= 164 | OutputPathOutputer3=[Output Type] 165 | OutputPathOutputerPrefix3= 166 | OutputPathOutputerValue3= 167 | OutputFileName3= 168 | OutputFileNameMulti3==ProjectName 169 | UseOutputNameForMulti3=0 170 | OutputFileNameSpecial3= 171 | OpenOutput3=1 172 | OutputFilePath4=C:\Projects\EssexO2gauge\trunk\Hardware\MainBoard\Project Outputs for Essex_O2_Monitor\Drill\TopBoard.PDF 173 | ReleaseManaged4=1 174 | OutputBasePath4=Project Outputs for JBC-Soldering-Controller 175 | OutputPathMedia4=[Media Name] 176 | OutputPathMediaValue4= 177 | OutputPathOutputer4=[Output Type] 178 | OutputPathOutputerPrefix4= 179 | OutputPathOutputerValue4= 180 | OutputFileName4=Fabrication.PDF 181 | OutputFileNameMulti4= 182 | UseOutputNameForMulti4=0 183 | OutputFileNameSpecial4==ProjectName+'_DRILL_DRAWING' 184 | OpenOutput4=1 185 | PromptOverwrite4=1 186 | PublishMethod4=0 187 | ZoomLevel4=50 188 | FitSCHPrintSizeToDoc4=1 189 | FitPCBPrintSizeToDoc4=1 190 | GenerateNetsInfo4=1 191 | MarkPins4=1 192 | MarkNetLabels4=1 193 | MarkPortsId4=1 194 | GenerateTOC4=1 195 | ShowComponentParameters4=1 196 | GlobalBookmarks4=0 197 | PDFACompliance4=Disabled 198 | PDFVersion4=Default 199 | 200 | [GeneratedFilesSettings] 201 | RelativeOutputPath2= 202 | OpenOutputs2=1 203 | RelativeOutputPath3=C:\Users\timj\Documents\Arduino\JBC-Soldering-Controller\Hardware\MainBoard\Project Outputs for JBC-Soldering-Controller\ 204 | OpenOutputs3=1 205 | AddToProject3=1 206 | TimestampFolder3=0 207 | UseOutputName3=0 208 | OpenODBOutput3=0 209 | OpenGerberOutput3=0 210 | OpenNCDrillOutput3=0 211 | OpenIPCOutput3=0 212 | EnableReload3=0 213 | RelativeOutputPath4=C:\Projects\EssexO2gauge\trunk\Hardware\MainBoard\Project Outputs for Essex_O2_Monitor\Drill\TopBoard.PDF 214 | OpenOutputs4=1 215 | 216 | -------------------------------------------------------------------------------- /Hardware/MainBoard/JBC-Soldering-Controller.PrjPCB: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/MainBoard/JBC-Soldering-Controller.PrjPCB -------------------------------------------------------------------------------- /Hardware/MainBoard/JBC-Soldering-Controller.PrjPCBStructure: -------------------------------------------------------------------------------- 1 | Record=TopLevelDocument|FileName=TopLevel.SchDoc 2 | Record=SheetSymbol|SourceDocument=TopLevel.SchDoc|Designator=Controller|SchDesignator=Controller|FileName=Controller.SchDoc|SymbolType=Normal|RawFileName=Controller.SchDoc|DesignItemId= |SourceLibraryName= |ObjectKind=Sheet Symbol|RevisionGUID= |ItemGUID= |VaultGUID= 3 | -------------------------------------------------------------------------------- /Hardware/MainBoard/MainBoard.PcbDoc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/MainBoard/MainBoard.PcbDoc -------------------------------------------------------------------------------- /Hardware/MainBoard/MainBoard.PcbDoc.htm: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 104 | 105 | 119 | 120 | 121 | 122 | Reporting Options 123 |

File in Previous Format

124 | 125 | 126 | 127 | 128 | 129 | 130 | 131 | 132 | 133 | 134 | 135 | 136 | 137 | 138 | 139 | 140 | 141 |
Date:6/10/2017
Time:3:25:28 PM
Filename:C:\Users\timj\Documents\Arduino\JBC-Soldering-Controller\Hardware\MainBoard\MainBoard.PcbDoc
142 | 143 |
144 | 145 | 146 | 147 | 148 | 149 | 150 | 151 |
VersionWarning
152 |

153 |

This file was generated by an earlier version of the software

154 | 155 | 156 | -------------------------------------------------------------------------------- /Hardware/MainBoard/Power.SchDoc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/MainBoard/Power.SchDoc -------------------------------------------------------------------------------- /Hardware/MainBoard/Power2.SchDoc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/MainBoard/Power2.SchDoc -------------------------------------------------------------------------------- /Hardware/MainBoard/Power3.SchDoc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/MainBoard/Power3.SchDoc -------------------------------------------------------------------------------- /Hardware/MainBoard/Release Archives/JBC-Soldering-Controller V1.0 with source.zip: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/MainBoard/Release Archives/JBC-Soldering-Controller V1.0 with source.zip -------------------------------------------------------------------------------- /Hardware/MainBoard/Release Archives/JBC-Soldering-Controller V1.0.zip: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/MainBoard/Release Archives/JBC-Soldering-Controller V1.0.zip -------------------------------------------------------------------------------- /Hardware/MainBoard/Sources.OutJob: -------------------------------------------------------------------------------- 1 | [OutputJobFile] 2 | Version=1.0 3 | Caption= 4 | Description= 5 | VaultGUID= 6 | ItemGUID= 7 | ItemHRID= 8 | RevisionGUID= 9 | RevisionId= 10 | VaultHRID= 11 | AutoItemHRID= 12 | NextRevId= 13 | FolderGUID= 14 | LifeCycleDefinitionGUID= 15 | RevisionNamingSchemeGUID= 16 | 17 | [OutputGroup1] 18 | Name=Job Group 19 | Description= 20 | TargetOutputMedium=Schematic 21 | VariantName=[No Variations] 22 | VariantScope=1 23 | CurrentConfigurationName=Sources 24 | TargetPrinter=Virtual Printer 25 | PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintJobKind=1|PrintWhat=1 26 | OutputMedium1=Print Job 27 | OutputMedium1_Type=Printer 28 | OutputMedium1_Printer= 29 | OutputMedium1_PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintJobKind=1|PrintWhat=1 30 | OutputMedium2=Schematic 31 | OutputMedium2_Type=Publish 32 | OutputMedium3=BOM 33 | OutputMedium3_Type=GeneratedFiles 34 | OutputMedium4=Video 35 | OutputMedium4_Type=Multimedia 36 | OutputMedium5=Fabrication Outputs 37 | OutputMedium5_Type=GeneratedFiles 38 | OutputMedium6=Assembly 39 | OutputMedium6_Type=GeneratedFiles 40 | OutputMedium7=Drill 41 | OutputMedium7_Type=Publish 42 | OutputMedium8=3DPdf 43 | OutputMedium8_Type=Publish 44 | OutputMedium9=STEP 45 | OutputMedium9_Type=GeneratedFiles 46 | OutputType1=Schematic Print 47 | OutputName1=Schematic Prints 48 | OutputCategory1=Documentation 49 | OutputDocumentPath1=[Project Physical Documents] 50 | OutputVariantName1=V1.1_Light 51 | OutputEnabled1=1 52 | OutputEnabled1_OutputMedium1=0 53 | OutputEnabled1_OutputMedium2=1 54 | OutputEnabled1_OutputMedium3=0 55 | OutputEnabled1_OutputMedium4=0 56 | OutputEnabled1_OutputMedium5=0 57 | OutputEnabled1_OutputMedium6=0 58 | OutputEnabled1_OutputMedium7=0 59 | OutputEnabled1_OutputMedium8=0 60 | OutputEnabled1_OutputMedium9=0 61 | OutputDefault1=0 62 | PageOptions1=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=0|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-3|MediaType=1|DitherType=10|PrintScaleMode=1|PaperKind=Letter|PaperIndex=1 63 | Configuration1_Name1=OutputConfigurationParameter1 64 | Configuration1_Item1=Record=SchPrintView|ShowNoERC=True|ShowParamSet=True|ShowProbe=True|ShowBlanket=True|NoERCSymbolsToShow="Thin Cross","Thick Cross","Small Cross",Checkbox,Triangle|ShowNote=True|ShowNoteCollapsed=True|ExpandDesignator=True|ExpandNetLabel=False|ExpandPort=False|ExpandSheetNum=False|ExpandDocNum=False|PrintArea=0|PrintAreaRect.X1=0|PrintAreaRect.Y1=0|PrintAreaRect.X2=0|PrintAreaRect.Y2=0 65 | OutputType2=ExportSTEP 66 | OutputName2=Export STEP 67 | OutputCategory2=Export 68 | OutputDocumentPath2= 69 | OutputVariantName2= 70 | OutputEnabled2=0 71 | OutputEnabled2_OutputMedium1=0 72 | OutputEnabled2_OutputMedium2=0 73 | OutputEnabled2_OutputMedium3=0 74 | OutputEnabled2_OutputMedium4=0 75 | OutputEnabled2_OutputMedium5=0 76 | OutputEnabled2_OutputMedium6=0 77 | OutputEnabled2_OutputMedium7=0 78 | OutputEnabled2_OutputMedium8=0 79 | OutputEnabled2_OutputMedium9=1 80 | OutputDefault2=0 81 | Configuration2_Name1=OutputConfigurationParameter1 82 | Configuration2_Item1=Record=ExportSTEPView|ExportComponentOptions=0|ExportModelsOption=2|ExportHolesOption=0|CanSelectPrimitives=False|IncludeMechanicalPadHoles=True|IncludeElectricalPadHoles=True|IncludeFreePadHoles=True|ExportFoldedBoard=True|ExportFoldedBoardRate=0|ComponentSuffixType=0|ComponentSuffix= |ExportCopperOption=0|ExportCopperLayer=0|ExportPadAndViaBarrelsOnly=False|IgnoreBoardCopperLayerColors=False|ExportAsSinglePart=False|IncludeCoverLayer=True 83 | 84 | [PublishSettings] 85 | OutputFilePath2=C:\Projects\EssexO2gauge\trunk\Hardware\MainBoard\Project Outputs for Essex_O2_Monitor\Documentation\Essex_O2_Monitor_SCH_VariantName.PDF 86 | ReleaseManaged2=1 87 | OutputBasePath2= 88 | OutputPathMedia2= 89 | OutputPathMediaValue2=Documentation 90 | OutputPathOutputer2= 91 | OutputPathOutputerPrefix2= 92 | OutputPathOutputerValue2= 93 | OutputFileName2=Sources.PDF 94 | OutputFileNameMulti2==ProjectName 95 | UseOutputNameForMulti2=0 96 | OutputFileNameSpecial2==ProjectName+'_SCH_'+VariantName 97 | OpenOutput2=1 98 | PromptOverwrite2=1 99 | PublishMethod2=0 100 | ZoomLevel2=50 101 | FitSCHPrintSizeToDoc2=1 102 | FitPCBPrintSizeToDoc2=1 103 | GenerateNetsInfo2=1 104 | MarkPins2=1 105 | MarkNetLabels2=1 106 | MarkPortsId2=1 107 | GenerateTOC2=1 108 | ShowComponentParameters2=1 109 | GlobalBookmarks2=0 110 | PDFACompliance2=Disabled 111 | PDFVersion2=Default 112 | OutputFilePath3=C:\Projects\EssexO2gauge\trunk\Hardware\MainBoard\Project Outputs for Essex_O2_Monitor\ 113 | ReleaseManaged3=1 114 | OutputBasePath3=Project Outputs for JBC-Soldering-Controller 115 | OutputPathMedia3= 116 | OutputPathMediaValue3= 117 | OutputPathOutputer3=[Output Type] 118 | OutputPathOutputerPrefix3= 119 | OutputPathOutputerValue3= 120 | OutputFileName3= 121 | OutputFileNameMulti3==ProjectName+'_BOM_'+VariantName 122 | UseOutputNameForMulti3=0 123 | OutputFileNameSpecial3= 124 | OpenOutput3=1 125 | OutputFilePath4= 126 | ReleaseManaged4=1 127 | OutputBasePath4=Project Outputs for JBC-Soldering-Controller 128 | OutputPathMedia4= 129 | OutputPathMediaValue4= 130 | OutputPathOutputer4=[Output Type] 131 | OutputPathOutputerPrefix4= 132 | OutputPathOutputerValue4= 133 | OutputFileName4= 134 | OutputFileNameMulti4= 135 | UseOutputNameForMulti4=1 136 | OutputFileNameSpecial4= 137 | OpenOutput4=1 138 | PromptOverwrite4=1 139 | PublishMethod4=5 140 | ZoomLevel4=50 141 | FitSCHPrintSizeToDoc4=1 142 | FitPCBPrintSizeToDoc4=1 143 | GenerateNetsInfo4=1 144 | MarkPins4=1 145 | MarkNetLabels4=1 146 | MarkPortsId4=1 147 | MediaFormat4=Windows Media file (*.wmv,*.wma,*.asf) 148 | FixedDimensions4=1 149 | Width4=352 150 | Height4=288 151 | MultiFile4=0 152 | FramesPerSecond4=25 153 | FramesPerSecondDenom4=1 154 | AviPixelFormat4=7 155 | AviCompression4=MP42 MS-MPEG4 V2 156 | AviQuality4=100 157 | FFmpegVideoCodecId4=13 158 | FFmpegPixelFormat4=0 159 | FFmpegQuality4=80 160 | WmvVideoCodecName4=Windows Media Video V7 161 | WmvQuality4=80 162 | OutputFilePath5=C:\Projects\EssexO2gauge\trunk\Hardware\MainBoard\Project Outputs for Essex_O2_Monitor\ 163 | ReleaseManaged5=1 164 | OutputBasePath5=Project Outputs for JBC-Soldering-Controller 165 | OutputPathMedia5= 166 | OutputPathMediaValue5= 167 | OutputPathOutputer5=[Output Type] 168 | OutputPathOutputerPrefix5= 169 | OutputPathOutputerValue5= 170 | OutputFileName5= 171 | OutputFileNameMulti5==ProjectName 172 | UseOutputNameForMulti5=0 173 | OutputFileNameSpecial5= 174 | OpenOutput5=1 175 | OutputFilePath6=C:\Projects\EssexO2gauge\trunk\Hardware\MainBoard\Project Outputs for Essex_O2_Monitor\ 176 | ReleaseManaged6=1 177 | OutputBasePath6=Project Outputs for JBC-Soldering-Controller 178 | OutputPathMedia6= 179 | OutputPathMediaValue6= 180 | OutputPathOutputer6=[Output Type] 181 | OutputPathOutputerPrefix6= 182 | OutputPathOutputerValue6= 183 | OutputFileName6= 184 | OutputFileNameMulti6= 185 | UseOutputNameForMulti6=1 186 | OutputFileNameSpecial6= 187 | OpenOutput6=1 188 | OutputFilePath7=C:\Projects\snoozHW\MainDevice\Project Outputs for TopBoard\Drill\TopBoard.PDF 189 | ReleaseManaged7=1 190 | OutputBasePath7=Project Outputs for JBC-Soldering-Controller 191 | OutputPathMedia7=[Media Name] 192 | OutputPathMediaValue7= 193 | OutputPathOutputer7=[Output Type] 194 | OutputPathOutputerPrefix7= 195 | OutputPathOutputerValue7= 196 | OutputFileName7=TopBoard.PDF 197 | OutputFileNameMulti7= 198 | UseOutputNameForMulti7=1 199 | OutputFileNameSpecial7= 200 | OpenOutput7=1 201 | PromptOverwrite7=1 202 | PublishMethod7=0 203 | ZoomLevel7=50 204 | FitSCHPrintSizeToDoc7=1 205 | FitPCBPrintSizeToDoc7=1 206 | GenerateNetsInfo7=1 207 | MarkPins7=1 208 | MarkNetLabels7=1 209 | MarkPortsId7=1 210 | GenerateTOC7=1 211 | ShowComponentParameters7=1 212 | GlobalBookmarks7=0 213 | PDFACompliance7=Disabled 214 | PDFVersion7=Default 215 | OutputFilePath8=C:\Projects\snoozHW\MainDevice\Project Outputs for TopBoard\TopBoard.PDF 216 | ReleaseManaged8=1 217 | OutputBasePath8=Project Outputs for JBC-Soldering-Controller 218 | OutputPathMedia8=[Media Name] 219 | OutputPathMediaValue8= 220 | OutputPathOutputer8=[Output Type] 221 | OutputPathOutputerPrefix8= 222 | OutputPathOutputerValue8= 223 | OutputFileName8=TopBoard.PDF 224 | OutputFileNameMulti8= 225 | UseOutputNameForMulti8=1 226 | OutputFileNameSpecial8= 227 | OpenOutput8=1 228 | PromptOverwrite8=1 229 | PublishMethod8=0 230 | ZoomLevel8=50 231 | FitSCHPrintSizeToDoc8=1 232 | FitPCBPrintSizeToDoc8=1 233 | GenerateNetsInfo8=1 234 | MarkPins8=1 235 | MarkNetLabels8=1 236 | MarkPortsId8=1 237 | GenerateTOC8=1 238 | ShowComponentParameters8=1 239 | GlobalBookmarks8=0 240 | PDFACompliance8=Disabled 241 | PDFVersion8=Default 242 | OutputFilePath9=C:\Projects\EssexO2gauge\trunk\Hardware\MainBoard\Project Outputs for Essex_O2_Monitor\STEP\ 243 | ReleaseManaged9=1 244 | OutputBasePath9=Project Outputs for JBC-Soldering-Controller 245 | OutputPathMedia9=[Media Name] 246 | OutputPathMediaValue9= 247 | OutputPathOutputer9= 248 | OutputPathOutputerPrefix9= 249 | OutputPathOutputerValue9= 250 | OutputFileName9= 251 | OutputFileNameMulti9= 252 | UseOutputNameForMulti9=1 253 | OutputFileNameSpecial9= 254 | OpenOutput9=1 255 | 256 | [GeneratedFilesSettings] 257 | RelativeOutputPath2=C:\Projects\EssexO2gauge\trunk\Hardware\MainBoard\Project Outputs for Essex_O2_Monitor\Documentation\Essex_O2_Monitor_SCH_VariantName.PDF 258 | OpenOutputs2=1 259 | RelativeOutputPath3=C:\Projects\EssexO2gauge\trunk\Hardware\MainBoard\Project Outputs for Essex_O2_Monitor\ 260 | OpenOutputs3=1 261 | AddToProject3=1 262 | TimestampFolder3=0 263 | UseOutputName3=0 264 | OpenODBOutput3=0 265 | OpenGerberOutput3=0 266 | OpenNCDrillOutput3=0 267 | OpenIPCOutput3=0 268 | EnableReload3=0 269 | RelativeOutputPath4= 270 | OpenOutputs4=1 271 | RelativeOutputPath5=C:\Projects\EssexO2gauge\trunk\Hardware\MainBoard\Project Outputs for Essex_O2_Monitor\ 272 | OpenOutputs5=1 273 | AddToProject5=1 274 | TimestampFolder5=0 275 | UseOutputName5=0 276 | OpenODBOutput5=0 277 | OpenGerberOutput5=0 278 | OpenNCDrillOutput5=0 279 | OpenIPCOutput5=0 280 | EnableReload5=0 281 | RelativeOutputPath6=C:\Projects\EssexO2gauge\trunk\Hardware\MainBoard\Project Outputs for Essex_O2_Monitor\ 282 | OpenOutputs6=1 283 | AddToProject6=1 284 | TimestampFolder6=0 285 | UseOutputName6=0 286 | OpenODBOutput6=0 287 | OpenGerberOutput6=0 288 | OpenNCDrillOutput6=0 289 | OpenIPCOutput6=0 290 | EnableReload6=0 291 | RelativeOutputPath7=C:\Projects\snoozHW\MainDevice\Project Outputs for TopBoard\Drill\TopBoard.PDF 292 | OpenOutputs7=1 293 | RelativeOutputPath8=C:\Projects\snoozHW\MainDevice\Project Outputs for TopBoard\TopBoard.PDF 294 | OpenOutputs8=1 295 | RelativeOutputPath9=C:\Projects\EssexO2gauge\trunk\Hardware\MainBoard\Project Outputs for Essex_O2_Monitor\STEP\ 296 | OpenOutputs9=1 297 | AddToProject9=1 298 | TimestampFolder9=0 299 | UseOutputName9=0 300 | OpenODBOutput9=0 301 | OpenGerberOutput9=0 302 | OpenNCDrillOutput9=0 303 | OpenIPCOutput9=0 304 | EnableReload9=0 305 | 306 | -------------------------------------------------------------------------------- /Hardware/MainBoard/TopLevel.SchDoc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/MainBoard/TopLevel.SchDoc -------------------------------------------------------------------------------- /Hardware/Shared Libraries/JBC-Soldering-Controller.SCHLIB: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/Shared Libraries/JBC-Soldering-Controller.SCHLIB -------------------------------------------------------------------------------- /Hardware/Shared Libraries/SolderingController.PcbLib: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/Shared Libraries/SolderingController.PcbLib -------------------------------------------------------------------------------- /Hardware/Shared Libraries/SolderingController.SchLib: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/Shared Libraries/SolderingController.SchLib -------------------------------------------------------------------------------- /Hardware/Template_A.SchDot: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/Template_A.SchDot -------------------------------------------------------------------------------- /Hardware/Template_B.SchDot: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/Template_B.SchDot -------------------------------------------------------------------------------- /Hardware/Template_C.SchDot: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/Template_C.SchDot -------------------------------------------------------------------------------- /Hardware/datasheets/VN5E010AHTR.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/datasheets/VN5E010AHTR.pdf -------------------------------------------------------------------------------- /Hardware/datasheets/ads1118.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Hardware/datasheets/ads1118.pdf -------------------------------------------------------------------------------- /K Thermocouple Lookup Table.txt: -------------------------------------------------------------------------------- 1 | K Thermocouple Lookup Table 2 | Deg. C mV uV 3 | 0 0.00000 0 4 | 1 0.03900 39 5 | 2 0.07900 79 6 | 3 0.11900 119 7 | 4 0.15800 158 8 | 5 0.19800 198 9 | 6 0.23800 238 10 | 7 0.27700 277 11 | 8 0.31700 317 12 | 9 0.35700 357 13 | 10 0.39700 397 14 | 11 0.43700 437 15 | 12 0.47700 477 16 | 13 0.51700 517 17 | 14 0.55700 557 18 | 15 0.59700 597 19 | 16 0.63700 637 20 | 17 0.67700 677 21 | 18 0.71800 718 22 | 19 0.75800 758 23 | 20 0.79800 798 24 | 21 0.83800 838 25 | 22 0.87900 879 26 | 23 0.91900 919 27 | 24 0.96000 960 28 | 25 1.00000 1000 29 | 26 1.04100 1041 30 | 27 1.08100 1081 31 | 28 1.12200 1122 32 | 29 1.16300 1163 33 | 30 1.20300 1203 34 | 31 1.24400 1244 35 | 32 1.28500 1285 36 | 33 1.32600 1326 37 | 34 1.36600 1366 38 | 35 1.40700 1407 39 | 36 1.44800 1448 40 | 37 1.48900 1489 41 | 38 1.53000 1530 42 | 39 1.57100 1571 43 | 40 1.61200 1612 44 | 41 1.65300 1653 45 | 42 1.69400 1694 46 | 43 1.73500 1735 47 | 44 1.77600 1776 48 | 45 1.81700 1817 49 | 46 1.85800 1858 50 | 47 1.89900 1899 51 | 48 1.94100 1941 52 | 49 1.98200 1982 53 | 50 2.02300 2023 54 | 51 2.06400 2064 55 | 52 2.10600 2106 56 | 53 2.14700 2147 57 | 54 2.18800 2188 58 | 55 2.23000 2230 59 | 56 2.27100 2271 60 | 57 2.31200 2312 61 | 58 2.35400 2354 62 | 59 2.39500 2395 63 | 60 2.43600 2436 64 | 61 2.47800 2478 65 | 62 2.51900 2519 66 | 63 2.56100 2561 67 | 64 2.60200 2602 68 | 65 2.64400 2644 69 | 66 2.68500 2685 70 | 67 2.72700 2727 71 | 68 2.76800 2768 72 | 69 2.81000 2810 73 | 70 2.85100 2851 74 | 71 2.89300 2893 75 | 72 2.93400 2934 76 | 73 2.97600 2976 77 | 74 3.01700 3017 78 | 75 3.05900 3059 79 | 76 3.10000 3100 80 | 77 3.14200 3142 81 | 78 3.18400 3184 82 | 79 3.22500 3225 83 | 80 3.26700 3267 84 | 81 3.30800 3308 85 | 82 3.35000 3350 86 | 83 3.39100 3391 87 | 84 3.43300 3433 88 | 85 3.47400 3474 89 | 86 3.51600 3516 90 | 87 3.55700 3557 91 | 88 3.59900 3599 92 | 89 3.64000 3640 93 | 90 3.68200 3682 94 | 91 3.72300 3723 95 | 92 3.76500 3765 96 | 93 3.80600 3806 97 | 94 3.84800 3848 98 | 95 3.88900 3889 99 | 96 3.93100 3931 100 | 97 3.97200 3972 101 | 98 4.01300 4013 102 | 99 4.05500 4055 103 | 100 4.09600 4096 104 | 101 4.13800 4138 105 | 102 4.17900 4179 106 | 103 4.22000 4220 107 | 104 4.26200 4262 108 | 105 4.30300 4303 109 | 106 4.34400 4344 110 | 107 4.38500 4385 111 | 108 4.42700 4427 112 | 109 4.46800 4468 113 | 110 4.50900 4509 114 | 111 4.55000 4550 115 | 112 4.59100 4591 116 | 113 4.63300 4633 117 | 114 4.67400 4674 118 | 115 4.71500 4715 119 | 116 4.75600 4756 120 | 117 4.79700 4797 121 | 118 4.83800 4838 122 | 119 4.87900 4879 123 | 120 4.92000 4920 124 | 121 4.96100 4961 125 | 122 5.00200 5002 126 | 123 5.04300 5043 127 | 124 5.08400 5084 128 | 125 5.12400 5124 129 | 126 5.16500 5165 130 | 127 5.20600 5206 131 | 128 5.24700 5247 132 | 129 5.28800 5288 133 | 130 5.32800 5328 134 | 131 5.36900 5369 135 | 132 5.41000 5410 136 | 133 5.45000 5450 137 | 134 5.49100 5491 138 | 135 5.53200 5532 139 | 136 5.57200 5572 140 | 137 5.61300 5613 141 | 138 5.65300 5653 142 | 139 5.69400 5694 143 | 140 5.73500 5735 144 | 141 5.77500 5775 145 | 142 5.81500 5815 146 | 143 5.85600 5856 147 | 144 5.89600 5896 148 | 145 5.93700 5937 149 | 146 5.97700 5977 150 | 147 6.01700 6017 151 | 148 6.05800 6058 152 | 149 6.09800 6098 153 | 150 6.13800 6138 154 | 151 6.17900 6179 155 | 152 6.21900 6219 156 | 153 6.25900 6259 157 | 154 6.29900 6299 158 | 155 6.33900 6339 159 | 156 6.38000 6380 160 | 157 6.42000 6420 161 | 158 6.46000 6460 162 | 159 6.50000 6500 163 | 160 6.54000 6540 164 | 161 6.58000 6580 165 | 162 6.62000 6620 166 | 163 6.66000 6660 167 | 164 6.70100 6701 168 | 165 6.74100 6741 169 | 166 6.78100 6781 170 | 167 6.82100 6821 171 | 168 6.86100 6861 172 | 169 6.90100 6901 173 | 170 6.94100 6941 174 | 171 6.98100 6981 175 | 172 7.02100 7021 176 | 173 7.06000 7060 177 | 174 7.10000 7100 178 | 175 7.14000 7140 179 | 176 7.18000 7180 180 | 177 7.22000 7220 181 | 178 7.26000 7260 182 | 179 7.30000 7300 183 | 180 7.34000 7340 184 | 181 7.38000 7380 185 | 182 7.42000 7420 186 | 183 7.46000 7460 187 | 184 7.50000 7500 188 | 185 7.54000 7540 189 | 186 7.57900 7579 190 | 187 7.61900 7619 191 | 188 7.65900 7659 192 | 189 7.69900 7699 193 | 190 7.73900 7739 194 | 191 7.77900 7779 195 | 192 7.81900 7819 196 | 193 7.85900 7859 197 | 194 7.89900 7899 198 | 195 7.93900 7939 199 | 196 7.97900 7979 200 | 197 8.01900 8019 201 | 198 8.05900 8059 202 | 199 8.09900 8099 203 | 200 8.13800 8138 204 | 201 8.17800 8178 205 | 202 8.21800 8218 206 | 203 8.25800 8258 207 | 204 8.29800 8298 208 | 205 8.33800 8338 209 | 206 8.37800 8378 210 | 207 8.41800 8418 211 | 208 8.45800 8458 212 | 209 8.49900 8499 213 | 210 8.53900 8539 214 | 211 8.57900 8579 215 | 212 8.61900 8619 216 | 213 8.65900 8659 217 | 214 8.69900 8699 218 | 215 8.73900 8739 219 | 216 8.77900 8779 220 | 217 8.81900 8819 221 | 218 8.86000 8860 222 | 219 8.90000 8900 223 | 220 8.94000 8940 224 | 221 8.98000 8980 225 | 222 9.02000 9020 226 | 223 9.06100 9061 227 | 224 9.10100 9101 228 | 225 9.14100 9141 229 | 226 9.18100 9181 230 | 227 9.22200 9222 231 | 228 9.26200 9262 232 | 229 9.30200 9302 233 | 230 9.34300 9343 234 | 231 9.38300 9383 235 | 232 9.42300 9423 236 | 233 9.46400 9464 237 | 234 9.50400 9504 238 | 235 9.54500 9545 239 | 236 9.58500 9585 240 | 237 9.62600 9626 241 | 238 9.66600 9666 242 | 239 9.70700 9707 243 | 240 9.74700 9747 244 | 241 9.78800 9788 245 | 242 9.82800 9828 246 | 243 9.86900 9869 247 | 244 9.90900 9909 248 | 245 9.95000 9950 249 | 246 9.99100 9991 250 | 247 10.03100 10031 251 | 248 10.07200 10072 252 | 249 10.11300 10113 253 | 250 10.15300 10153 254 | 251 10.19400 10194 255 | 252 10.23500 10235 256 | 253 10.27600 10276 257 | 254 10.31600 10316 258 | 255 10.35700 10357 259 | 256 10.39800 10398 260 | 257 10.43900 10439 261 | 258 10.48000 10480 262 | 259 10.52000 10520 263 | 260 10.56100 10561 264 | 261 10.60200 10602 265 | 262 10.64300 10643 266 | 263 10.68400 10684 267 | 264 10.72500 10725 268 | 265 10.76600 10766 269 | 266 10.80700 10807 270 | 267 10.84800 10848 271 | 268 10.88900 10889 272 | 269 10.93000 10930 273 | 270 10.97100 10971 274 | 271 11.01200 11012 275 | 272 11.05300 11053 276 | 273 11.09400 11094 277 | 274 11.13500 11135 278 | 275 11.17600 11176 279 | 276 11.21700 11217 280 | 277 11.25900 11259 281 | 278 11.30000 11300 282 | 279 11.34100 11341 283 | 280 11.38200 11382 284 | 281 11.42300 11423 285 | 282 11.46500 11465 286 | 283 11.50600 11506 287 | 284 11.54700 11547 288 | 285 11.58800 11588 289 | 286 11.63000 11630 290 | 287 11.67100 11671 291 | 288 11.71200 11712 292 | 289 11.75300 11753 293 | 290 11.79500 11795 294 | 291 11.83600 11836 295 | 292 11.87700 11877 296 | 293 11.91900 11919 297 | 294 11.96000 11960 298 | 295 12.00100 12001 299 | 296 12.04300 12043 300 | 297 12.08400 12084 301 | 298 12.12600 12126 302 | 299 12.16700 12167 303 | 300 12.20900 12209 304 | 301 12.25000 12250 305 | 302 12.29100 12291 306 | 303 12.33300 12333 307 | 304 12.37400 12374 308 | 305 12.41600 12416 309 | 306 12.45700 12457 310 | 307 12.49900 12499 311 | 308 12.54000 12540 312 | 309 12.58200 12582 313 | 310 12.62400 12624 314 | 311 12.66500 12665 315 | 312 12.70700 12707 316 | 313 12.74800 12748 317 | 314 12.79000 12790 318 | 315 12.83100 12831 319 | 316 12.87300 12873 320 | 317 12.91500 12915 321 | 318 12.95600 12956 322 | 319 12.99800 12998 323 | 320 13.04000 13040 324 | 321 13.08100 13081 325 | 322 13.12300 13123 326 | 323 13.16500 13165 327 | 324 13.20600 13206 328 | 325 13.24800 13248 329 | 326 13.29000 13290 330 | 327 13.33100 13331 331 | 328 13.37300 13373 332 | 329 13.41500 13415 333 | 330 13.45700 13457 334 | 331 13.49800 13498 335 | 332 13.54000 13540 336 | 333 13.58200 13582 337 | 334 13.62400 13624 338 | 335 13.66500 13665 339 | 336 13.70700 13707 340 | 337 13.74900 13749 341 | 338 13.79100 13791 342 | 339 13.83300 13833 343 | 340 13.87400 13874 344 | 341 13.91600 13916 345 | 342 13.95800 13958 346 | 343 14.00000 14000 347 | 344 14.04200 14042 348 | 345 14.08400 14084 349 | 346 14.12600 14126 350 | 347 14.16700 14167 351 | 348 14.20900 14209 352 | 349 14.25100 14251 353 | 350 14.29300 14293 354 | 351 14.33500 14335 355 | 352 14.37700 14377 356 | 353 14.41900 14419 357 | 354 14.46100 14461 358 | 355 14.50300 14503 359 | 356 14.54500 14545 360 | 357 14.58700 14587 361 | 358 14.62900 14629 362 | 359 14.67100 14671 363 | 360 14.71300 14713 364 | 361 14.75500 14755 365 | 362 14.79700 14797 366 | 363 14.83900 14839 367 | 364 14.88100 14881 368 | 365 14.92300 14923 369 | 366 14.96500 14965 370 | 367 15.00700 15007 371 | 368 15.04900 15049 372 | 369 15.09100 15091 373 | 370 15.13300 15133 374 | 371 15.17500 15175 375 | 372 15.21700 15217 376 | 373 15.25900 15259 377 | 374 15.30100 15301 378 | 375 15.34300 15343 379 | 376 15.38500 15385 380 | 377 15.42700 15427 381 | 378 15.46900 15469 382 | 379 15.51100 15511 383 | 380 15.55400 15554 384 | 381 15.59600 15596 385 | 382 15.63800 15638 386 | 383 15.68000 15680 387 | 384 15.72200 15722 388 | 385 15.76400 15764 389 | 386 15.80600 15806 390 | 387 15.84900 15849 391 | 388 15.89100 15891 392 | 389 15.93300 15933 393 | 390 15.97500 15975 394 | 391 16.01700 16017 395 | 392 16.05900 16059 396 | 393 16.10200 16102 397 | 394 16.14400 16144 398 | 395 16.18600 16186 399 | 396 16.22800 16228 400 | 397 16.27000 16270 401 | 398 16.31300 16313 402 | 399 16.35500 16355 403 | 400 16.39700 16397 404 | 401 16.43900 16439 405 | 402 16.48200 16482 406 | 403 16.52400 16524 407 | 404 16.56600 16566 408 | 405 16.60800 16608 409 | 406 16.65100 16651 410 | 407 16.69300 16693 411 | 408 16.73500 16735 412 | 409 16.77800 16778 413 | 410 16.82000 16820 414 | 411 16.86200 16862 415 | 412 16.90400 16904 416 | 413 16.94700 16947 417 | 414 16.98900 16989 418 | 415 17.03100 17031 419 | 416 17.07400 17074 420 | 417 17.11600 17116 421 | 418 17.15800 17158 422 | 419 17.20100 17201 423 | 420 17.24300 17243 424 | 421 17.28500 17285 425 | 422 17.32800 17328 426 | 423 17.37000 17370 427 | 424 17.41300 17413 428 | 425 17.45500 17455 429 | 426 17.49700 17497 430 | 427 17.54000 17540 431 | 428 17.58200 17582 432 | 429 17.62400 17624 433 | 430 17.66700 17667 434 | 431 17.70900 17709 435 | 432 17.75200 17752 436 | 433 17.79400 17794 437 | 434 17.83700 17837 438 | 435 17.87900 17879 439 | 436 17.92100 17921 440 | 437 17.96400 17964 441 | 438 18.00600 18006 442 | 439 18.04900 18049 443 | 440 18.09100 18091 444 | 441 18.13400 18134 445 | 442 18.17600 18176 446 | 443 18.21800 18218 447 | 444 18.26100 18261 448 | 445 18.30300 18303 449 | 446 18.34600 18346 450 | 447 18.38800 18388 451 | 448 18.43100 18431 452 | 449 18.47300 18473 453 | 450 18.51600 18516 454 | 451 18.55800 18558 455 | 452 18.60100 18601 456 | 453 18.64300 18643 457 | 454 18.68600 18686 458 | 455 18.72800 18728 459 | 456 18.77100 18771 460 | 457 18.81300 18813 461 | 458 18.85600 18856 462 | 459 18.89800 18898 463 | 460 18.94100 18941 464 | 461 18.98300 18983 465 | 462 19.02600 19026 466 | 463 19.06800 19068 467 | 464 19.11100 19111 468 | 465 19.15400 19154 469 | 466 19.19600 19196 470 | 467 19.23900 19239 471 | 468 19.28100 19281 472 | 469 19.32400 19324 473 | 470 19.36600 19366 474 | 471 19.40900 19409 475 | 472 19.45100 19451 476 | 473 19.49400 19494 477 | 474 19.53700 19537 478 | 475 19.57900 19579 479 | 476 19.62200 19622 480 | 477 19.66400 19664 481 | 478 19.70700 19707 482 | 479 19.75000 19750 483 | 480 19.79200 19792 484 | 481 19.83500 19835 485 | 482 19.87700 19877 486 | 483 19.92000 19920 487 | 484 19.96200 19962 488 | 485 20.00500 20005 489 | 486 20.04800 20048 490 | 487 20.09000 20090 491 | 488 20.13300 20133 492 | 489 20.17500 20175 493 | 490 20.21800 20218 494 | 491 20.26100 20261 495 | 492 20.30300 20303 496 | 493 20.34600 20346 497 | 494 20.38900 20389 498 | 495 20.43100 20431 499 | 496 20.47400 20474 500 | 497 20.51600 20516 501 | 498 20.55900 20559 502 | 499 20.60200 20602 503 | 500 20.64400 20644 504 | 501 20.68700 20687 505 | 502 20.73000 20730 506 | 503 20.77200 20772 507 | 504 20.81500 20815 508 | 505 20.85700 20857 509 | 506 20.90000 20900 510 | 507 20.94300 20943 511 | 508 20.98500 20985 512 | 509 21.02800 21028 513 | 510 21.07100 21071 514 | 511 21.11300 21113 515 | 512 21.15600 21156 516 | 513 21.19900 21199 517 | 514 21.24100 21241 518 | 515 21.28400 21284 519 | 516 21.32600 21326 520 | 517 21.36900 21369 521 | 518 21.41200 21412 522 | 519 21.45400 21454 523 | 520 21.49700 21497 524 | 521 21.54000 21540 525 | 522 21.58200 21582 526 | 523 21.62500 21625 527 | 524 21.66800 21668 528 | 525 21.71000 21710 529 | 526 21.75300 21753 530 | 527 21.79600 21796 531 | 528 21.83800 21838 532 | 529 21.88100 21881 533 | 530 21.92400 21924 534 | 531 21.96600 21966 535 | 532 22.00900 22009 536 | 533 22.05200 22052 537 | 534 22.09400 22094 538 | 535 22.13700 22137 539 | 536 22.17900 22179 540 | 537 22.22200 22222 541 | 538 22.26500 22265 542 | 539 22.30700 22307 543 | 540 22.35000 22350 544 | 541 22.39300 22393 545 | 542 22.43500 22435 546 | 543 22.47800 22478 547 | 544 22.52100 22521 548 | 545 22.56300 22563 549 | 546 22.60600 22606 550 | 547 22.64900 22649 551 | 548 22.69100 22691 552 | 549 22.73400 22734 553 | 550 22.77600 22776 554 | 551 22.81900 22819 555 | 552 22.86200 22862 556 | 553 22.90400 22904 557 | 554 22.94700 22947 558 | 555 22.99000 22990 559 | 556 23.03200 23032 560 | 557 23.07500 23075 561 | 558 23.11700 23117 562 | 559 23.16000 23160 563 | 560 23.20300 23203 564 | 561 23.24500 23245 565 | 562 23.28800 23288 566 | 563 23.33100 23331 567 | 564 23.37300 23373 568 | 565 23.41600 23416 569 | 566 23.45800 23458 570 | 567 23.50100 23501 571 | 568 23.54400 23544 572 | 569 23.58600 23586 573 | 570 23.62900 23629 574 | 571 23.67100 23671 575 | 572 23.71400 23714 576 | 573 23.75700 23757 577 | 574 23.79900 23799 578 | 575 23.84200 23842 579 | 576 23.88400 23884 580 | 577 23.92700 23927 581 | 578 23.97000 23970 582 | 579 24.01200 24012 583 | 580 24.05500 24055 584 | 581 24.09700 24097 585 | 582 24.14000 24140 586 | 583 24.18200 24182 587 | 584 24.22500 24225 588 | 585 24.26700 24267 589 | 586 24.31000 24310 590 | 587 24.35300 24353 591 | 588 24.39500 24395 592 | 589 24.43800 24438 593 | 590 24.48000 24480 594 | 591 24.52300 24523 595 | 592 24.56500 24565 596 | 593 24.60800 24608 597 | 594 24.65000 24650 598 | 595 24.69300 24693 599 | 596 24.73500 24735 600 | 597 24.77800 24778 601 | 598 24.82000 24820 602 | 599 24.86300 24863 603 | 600 24.90500 24905 604 | 601 24.94800 24948 605 | 602 24.99000 24990 606 | 603 25.03300 25033 607 | 604 25.07500 25075 608 | 605 25.11800 25118 609 | 606 25.16000 25160 610 | 607 25.20300 25203 611 | 608 25.24500 25245 612 | 609 25.28800 25288 613 | 610 25.33000 25330 614 | 611 25.37300 25373 615 | 612 25.41500 25415 616 | 613 25.45800 25458 617 | 614 25.50000 25500 618 | 615 25.54300 25543 619 | 616 25.58500 25585 620 | 617 25.62700 25627 621 | 618 25.67000 25670 622 | 619 25.71200 25712 623 | 620 25.75500 25755 624 | 621 25.79700 25797 625 | 622 25.84000 25840 626 | 623 25.88200 25882 627 | 624 25.92400 25924 628 | 625 25.96700 25967 629 | 626 26.00900 26009 630 | 627 26.05200 26052 631 | 628 26.09400 26094 632 | 629 26.13600 26136 633 | 630 26.17900 26179 634 | 631 26.22100 26221 635 | 632 26.26300 26263 636 | 633 26.30600 26306 637 | 634 26.34800 26348 638 | 635 26.39000 26390 639 | 636 26.43300 26433 640 | 637 26.47500 26475 641 | 638 26.51700 26517 642 | 639 26.56000 26560 643 | 640 26.60200 26602 644 | 641 26.64400 26644 645 | 642 26.68700 26687 646 | 643 26.72900 26729 647 | 644 26.77100 26771 648 | 645 26.81400 26814 649 | 646 26.85600 26856 650 | 647 26.89800 26898 651 | 648 26.94000 26940 652 | 649 26.98300 26983 653 | 650 27.02500 27025 654 | 651 27.06700 27067 655 | 652 27.10900 27109 656 | 653 27.15200 27152 657 | 654 27.19400 27194 658 | 655 27.23600 27236 659 | 656 27.27800 27278 660 | 657 27.32000 27320 661 | 658 27.36300 27363 662 | 659 27.40500 27405 663 | 660 27.44700 27447 664 | 661 27.48900 27489 665 | 662 27.53100 27531 666 | 663 27.57400 27574 667 | 664 27.61600 27616 668 | 665 27.65800 27658 669 | 666 27.70000 27700 670 | 667 27.74200 27742 671 | 668 27.78400 27784 672 | 669 27.82600 27826 673 | 670 27.86900 27869 674 | 671 27.91100 27911 675 | 672 27.95300 27953 676 | 673 27.99500 27995 677 | 674 28.03700 28037 678 | 675 28.07900 28079 679 | 676 28.12100 28121 680 | 677 28.16300 28163 681 | 678 28.20500 28205 682 | 679 28.24700 28247 683 | 680 28.28900 28289 684 | 681 28.33200 28332 685 | 682 28.37400 28374 686 | 683 28.41600 28416 687 | 684 28.45800 28458 688 | 685 28.50000 28500 689 | 686 28.54200 28542 690 | 687 28.58400 28584 691 | 688 28.62600 28626 692 | 689 28.66800 28668 693 | 690 28.71000 28710 694 | 691 28.75200 28752 695 | 692 28.79400 28794 696 | 693 28.83500 28835 697 | 694 28.87700 28877 698 | 695 28.91900 28919 699 | 696 28.96100 28961 700 | 697 29.00300 29003 701 | 698 29.04500 29045 702 | 699 29.08700 29087 703 | 700 29.12900 29129 704 | 701 29.17100 29171 705 | 702 29.21300 29213 706 | 703 29.25500 29255 707 | 704 29.29700 29297 708 | 705 29.33800 29338 709 | 706 29.38000 29380 710 | 707 29.42200 29422 711 | 708 29.46400 29464 712 | 709 29.50600 29506 713 | 710 29.54800 29548 714 | 711 29.58900 29589 715 | 712 29.63100 29631 716 | 713 29.67300 29673 717 | 714 29.71500 29715 718 | 715 29.75700 29757 719 | 716 29.79800 29798 720 | 717 29.84000 29840 721 | 718 29.88200 29882 722 | 719 29.92400 29924 723 | 720 29.96500 29965 724 | 721 30.00700 30007 725 | 722 30.04900 30049 726 | 723 30.09000 30090 727 | 724 30.13200 30132 728 | 725 30.17400 30174 729 | 726 30.21600 30216 730 | 727 30.25700 30257 731 | 728 30.29900 30299 732 | 729 30.34100 30341 733 | 730 30.38200 30382 734 | 731 30.42400 30424 735 | 732 30.46600 30466 736 | 733 30.50700 30507 737 | 734 30.54900 30549 738 | 735 30.59000 30590 739 | 736 30.63200 30632 740 | 737 30.67400 30674 741 | 738 30.71500 30715 742 | 739 30.75700 30757 743 | 740 30.79800 30798 744 | 741 30.84000 30840 745 | 742 30.88100 30881 746 | 743 30.92300 30923 747 | 744 30.96400 30964 748 | 745 31.00600 31006 749 | 746 31.04700 31047 750 | 747 31.08900 31089 751 | 748 31.13000 31130 752 | 749 31.17200 31172 753 | 750 31.21300 31213 754 | 751 31.25500 31255 755 | 752 31.29600 31296 756 | 753 31.33800 31338 757 | 754 31.37900 31379 758 | 755 31.42100 31421 759 | 756 31.46200 31462 760 | 757 31.50400 31504 761 | 758 31.54500 31545 762 | 759 31.58600 31586 763 | 760 31.62800 31628 764 | 761 31.66900 31669 765 | 762 31.71000 31710 766 | 763 31.75200 31752 767 | 764 31.79300 31793 768 | 765 31.83400 31834 769 | 766 31.87600 31876 770 | 767 31.91700 31917 771 | 768 31.95800 31958 772 | 769 32.00000 32000 773 | 770 32.04100 32041 774 | 771 32.08200 32082 775 | 772 32.12400 32124 776 | 773 32.16500 32165 777 | 774 32.20600 32206 778 | 775 32.24700 32247 779 | 776 32.28900 32289 780 | 777 32.33000 32330 781 | 778 32.37100 32371 782 | 779 32.41200 32412 783 | 780 32.45300 32453 784 | 781 32.49500 32495 785 | 782 32.53600 32536 786 | 783 32.57700 32577 787 | 784 32.61800 32618 788 | 785 32.65900 32659 789 | 786 32.70000 32700 790 | 787 32.74200 32742 791 | 788 32.78300 32783 792 | 789 32.82400 32824 793 | 790 32.86500 32865 794 | 791 32.90600 32906 795 | 792 32.94700 32947 796 | 793 32.98800 32988 797 | 794 33.02900 33029 798 | 795 33.07000 33070 799 | 796 33.11100 33111 800 | 797 33.15200 33152 801 | 798 33.19300 33193 802 | 799 33.23400 33234 803 | 800 33.27500 33275 804 | 801 33.31600 33316 805 | 802 33.35700 33357 806 | 803 33.39800 33398 807 | 804 33.43900 33439 808 | 805 33.48000 33480 809 | 806 33.52100 33521 810 | 807 33.56200 33562 811 | 808 33.60300 33603 812 | 809 33.64400 33644 813 | 810 33.68500 33685 814 | 811 33.72600 33726 815 | 812 33.76700 33767 816 | 813 33.80800 33808 817 | 814 33.84800 33848 818 | 815 33.88900 33889 819 | 816 33.93000 33930 820 | 817 33.97100 33971 821 | 818 34.01200 34012 822 | 819 34.05300 34053 823 | 820 34.09300 34093 824 | 821 34.13400 34134 825 | 822 34.17500 34175 826 | 823 34.21600 34216 827 | 824 34.25700 34257 828 | 825 34.29700 34297 829 | 826 34.33800 34338 830 | 827 34.37900 34379 831 | 828 34.42000 34420 832 | 829 34.46000 34460 833 | 830 34.50100 34501 834 | 831 34.54200 34542 835 | 832 34.58200 34582 836 | 833 34.62300 34623 837 | 834 34.66400 34664 838 | 835 34.70400 34704 839 | 836 34.74500 34745 840 | 837 34.78600 34786 841 | 838 34.82600 34826 842 | 839 34.86700 34867 843 | 840 34.90800 34908 844 | 841 34.94800 34948 845 | 842 34.98900 34989 846 | 843 35.02900 35029 847 | 844 35.07000 35070 848 | 845 35.11000 35110 849 | 846 35.15100 35151 850 | 847 35.19200 35192 851 | 848 35.23200 35232 852 | 849 35.27300 35273 853 | 850 35.31300 35313 854 | 851 35.35400 35354 855 | 852 35.39400 35394 856 | 853 35.43500 35435 857 | 854 35.47500 35475 858 | 855 35.51600 35516 859 | 856 35.55600 35556 860 | 857 35.59600 35596 861 | 858 35.63700 35637 862 | 859 35.67700 35677 863 | 860 35.71800 35718 864 | 861 35.75800 35758 865 | 862 35.79800 35798 866 | 863 35.83900 35839 867 | 864 35.87900 35879 868 | 865 35.92000 35920 869 | 866 35.96000 35960 870 | 867 36.00000 36000 871 | 868 36.04100 36041 872 | 869 36.08100 36081 873 | 870 36.12100 36121 874 | 871 36.16200 36162 875 | 872 36.20200 36202 876 | 873 36.24200 36242 877 | 874 36.28200 36282 878 | 875 36.32300 36323 879 | 876 36.36300 36363 880 | 877 36.40300 36403 881 | 878 36.44300 36443 882 | 879 36.48400 36484 883 | 880 36.52400 36524 884 | 881 36.56400 36564 885 | 882 36.60400 36604 886 | 883 36.64400 36644 887 | 884 36.68500 36685 888 | 885 36.72500 36725 889 | 886 36.76500 36765 890 | 887 36.80500 36805 891 | 888 36.84500 36845 892 | 889 36.88500 36885 893 | 890 36.92500 36925 894 | 891 36.96500 36965 895 | 892 37.00600 37006 896 | 893 37.04600 37046 897 | 894 37.08600 37086 898 | 895 37.12600 37126 899 | 896 37.16600 37166 900 | 897 37.20600 37206 901 | 898 37.24600 37246 902 | 899 37.28600 37286 903 | 900 37.32600 37326 904 | 901 37.36600 37366 905 | 902 37.40600 37406 906 | 903 37.44600 37446 907 | 904 37.48600 37486 908 | 905 37.52600 37526 909 | 906 37.56600 37566 910 | 907 37.60600 37606 911 | 908 37.64600 37646 912 | 909 37.68600 37686 913 | 910 37.72500 37725 914 | 911 37.76500 37765 915 | 912 37.80500 37805 916 | 913 37.84500 37845 917 | 914 37.88500 37885 918 | 915 37.92500 37925 919 | 916 37.96500 37965 920 | 917 38.00500 38005 921 | 918 38.04400 38044 922 | 919 38.08400 38084 923 | 920 38.12400 38124 924 | 921 38.16400 38164 925 | 922 38.20400 38204 926 | 923 38.24300 38243 927 | 924 38.28300 38283 928 | 925 38.32300 38323 929 | 926 38.36300 38363 930 | 927 38.40200 38402 931 | 928 38.44200 38442 932 | 929 38.48200 38482 933 | 930 38.52200 38522 934 | 931 38.56100 38561 935 | 932 38.60100 38601 936 | 933 38.64100 38641 937 | 934 38.68000 38680 938 | 935 38.72000 38720 939 | 936 38.76000 38760 940 | 937 38.79900 38799 941 | 938 38.83900 38839 942 | 939 38.87800 38878 943 | 940 38.91800 38918 944 | 941 38.95800 38958 945 | 942 38.99700 38997 946 | 943 39.03700 39037 947 | 944 39.07600 39076 948 | 945 39.11600 39116 949 | 946 39.15500 39155 950 | 947 39.19500 39195 951 | 948 39.23500 39235 952 | 949 39.27400 39274 953 | 950 39.31400 39314 954 | 951 39.35300 39353 955 | 952 39.39300 39393 956 | 953 39.43200 39432 957 | 954 39.47100 39471 958 | 955 39.51100 39511 959 | 956 39.55000 39550 960 | 957 39.59000 39590 961 | 958 39.62900 39629 962 | 959 39.66900 39669 963 | 960 39.70800 39708 964 | 961 39.74700 39747 965 | 962 39.78700 39787 966 | 963 39.82600 39826 967 | 964 39.86600 39866 968 | 965 39.90500 39905 969 | 966 39.94400 39944 970 | 967 39.98400 39984 971 | 968 40.02300 40023 972 | 969 40.06200 40062 973 | 970 40.10100 40101 974 | 971 40.14100 40141 975 | 972 40.18000 40180 976 | 973 40.21900 40219 977 | 974 40.25900 40259 978 | 975 40.29800 40298 979 | 976 40.33700 40337 980 | 977 40.37600 40376 981 | 978 40.41500 40415 982 | 979 40.45500 40455 983 | 980 40.49400 40494 984 | 981 40.53300 40533 985 | 982 40.57200 40572 986 | 983 40.61100 40611 987 | 984 40.65100 40651 988 | 985 40.69000 40690 989 | 986 40.72900 40729 990 | 987 40.76800 40768 991 | 988 40.80700 40807 992 | 989 40.84600 40846 993 | 990 40.88500 40885 994 | 991 40.92400 40924 995 | 992 40.96300 40963 996 | 993 41.00200 41002 997 | 994 41.04200 41042 998 | 995 41.08100 41081 999 | 996 41.12000 41120 1000 | 997 41.15900 41159 1001 | 998 41.19800 41198 1002 | 999 41.23700 41237 1003 | 1000 41.27600 41276 1004 | 1001 41.31500 41315 1005 | 1002 41.35400 41354 1006 | 1003 41.39300 41393 1007 | 1004 41.43100 41431 1008 | 1005 41.47000 41470 1009 | 1006 41.50900 41509 1010 | 1007 41.54800 41548 1011 | 1008 41.58700 41587 1012 | 1009 41.62600 41626 1013 | 1010 41.66500 41665 1014 | 1011 41.70400 41704 1015 | 1012 41.74300 41743 1016 | 1013 41.78100 41781 1017 | 1014 41.82000 41820 1018 | 1015 41.85900 41859 1019 | 1016 41.89800 41898 1020 | 1017 41.93700 41937 1021 | 1018 41.97600 41976 1022 | 1019 42.01400 42014 1023 | 1020 42.05300 42053 1024 | 1021 42.09200 42092 1025 | 1022 42.13100 42131 1026 | 1023 42.16900 42169 1027 | 1024 42.20800 42208 1028 | 1025 42.24700 42247 1029 | 1026 42.28600 42286 1030 | 1027 42.32400 42324 1031 | 1028 42.36300 42363 1032 | 1029 42.40200 42402 1033 | 1030 42.44000 42440 1034 | 1031 42.47900 42479 1035 | 1032 42.51800 42518 1036 | 1033 42.55600 42556 1037 | 1034 42.59500 42595 1038 | 1035 42.63300 42633 1039 | 1036 42.67200 42672 1040 | 1037 42.71100 42711 1041 | 1038 42.74900 42749 1042 | 1039 42.78800 42788 1043 | 1040 42.82600 42826 1044 | 1041 42.86500 42865 1045 | 1042 42.90300 42903 1046 | 1043 42.94200 42942 1047 | 1044 42.98000 42980 1048 | 1045 43.01900 43019 1049 | 1046 43.05700 43057 1050 | 1047 43.09600 43096 1051 | 1048 43.13400 43134 1052 | 1049 43.17300 43173 1053 | 1050 43.21100 43211 1054 | 1051 43.25000 43250 1055 | 1052 43.28800 43288 1056 | 1053 43.32700 43327 1057 | 1054 43.36500 43365 1058 | 1055 43.40300 43403 1059 | 1056 43.44200 43442 1060 | 1057 43.48000 43480 1061 | 1058 43.51800 43518 1062 | 1059 43.55700 43557 1063 | 1060 43.59500 43595 1064 | 1061 43.63300 43633 1065 | 1062 43.67200 43672 1066 | 1063 43.71000 43710 1067 | 1064 43.74800 43748 1068 | 1065 43.78700 43787 1069 | 1066 43.82500 43825 1070 | 1067 43.86300 43863 1071 | 1068 43.90100 43901 1072 | 1069 43.94000 43940 1073 | 1070 43.97800 43978 1074 | 1071 44.01600 44016 1075 | 1072 44.05400 44054 1076 | 1073 44.09200 44092 1077 | 1074 44.13000 44130 1078 | 1075 44.16900 44169 1079 | 1076 44.20700 44207 1080 | 1077 44.24500 44245 1081 | 1078 44.28300 44283 1082 | 1079 44.32100 44321 1083 | 1080 44.35900 44359 1084 | 1081 44.39700 44397 1085 | 1082 44.43500 44435 1086 | 1083 44.47300 44473 1087 | 1084 44.51200 44512 1088 | 1085 44.55000 44550 1089 | 1086 44.58800 44588 1090 | 1087 44.62600 44626 1091 | 1088 44.66400 44664 1092 | 1089 44.70200 44702 1093 | 1090 44.74000 44740 1094 | 1091 44.77800 44778 1095 | 1092 44.81600 44816 1096 | 1093 44.85300 44853 1097 | 1094 44.89100 44891 1098 | 1095 44.92900 44929 1099 | 1096 44.96700 44967 1100 | 1097 45.00500 45005 1101 | 1098 45.04300 45043 1102 | 1099 45.08100 45081 1103 | 1100 45.11900 45119 1104 | 1101 45.15700 45157 1105 | 1102 45.19400 45194 1106 | 1103 45.23200 45232 1107 | 1104 45.27000 45270 1108 | 1105 45.30800 45308 1109 | 1106 45.34600 45346 1110 | 1107 45.38300 45383 1111 | 1108 45.42100 45421 1112 | 1109 45.45900 45459 1113 | 1110 45.49700 45497 1114 | 1111 45.53400 45534 1115 | 1112 45.57200 45572 1116 | 1113 45.61000 45610 1117 | 1114 45.64700 45647 1118 | 1115 45.68500 45685 1119 | 1116 45.72300 45723 1120 | 1117 45.76000 45760 1121 | 1118 45.79800 45798 1122 | 1119 45.83600 45836 1123 | 1120 45.87300 45873 1124 | 1121 45.91100 45911 1125 | 1122 45.94800 45948 1126 | 1123 45.98600 45986 1127 | 1124 46.02400 46024 1128 | 1125 46.06100 46061 1129 | 1126 46.09900 46099 1130 | 1127 46.13600 46136 1131 | 1128 46.17400 46174 1132 | 1129 46.21100 46211 1133 | 1130 46.24900 46249 1134 | 1131 46.28600 46286 1135 | 1132 46.32400 46324 1136 | 1133 46.36100 46361 1137 | 1134 46.39800 46398 1138 | 1135 46.43600 46436 1139 | 1136 46.47300 46473 1140 | 1137 46.51100 46511 1141 | 1138 46.54800 46548 1142 | 1139 46.58500 46585 1143 | 1140 46.62300 46623 1144 | 1141 46.66000 46660 1145 | 1142 46.69700 46697 1146 | 1143 46.73500 46735 1147 | 1144 46.77200 46772 1148 | 1145 46.80900 46809 1149 | 1146 46.84700 46847 1150 | 1147 46.88400 46884 1151 | 1148 46.92100 46921 1152 | 1149 46.95800 46958 1153 | 1150 46.99500 46995 1154 | 1151 47.03300 47033 1155 | 1152 47.07000 47070 1156 | 1153 47.10700 47107 1157 | 1154 47.14400 47144 1158 | 1155 47.18100 47181 1159 | 1156 47.21800 47218 1160 | 1157 47.25600 47256 1161 | 1158 47.29300 47293 1162 | 1159 47.33000 47330 1163 | 1160 47.36700 47367 1164 | 1161 47.40400 47404 1165 | 1162 47.44100 47441 1166 | 1163 47.47800 47478 1167 | 1164 47.51500 47515 1168 | 1165 47.55200 47552 1169 | 1166 47.58900 47589 1170 | 1167 47.62600 47626 1171 | 1168 47.66300 47663 1172 | 1169 47.70000 47700 1173 | 1170 47.73700 47737 1174 | 1171 47.77400 47774 1175 | 1172 47.81100 47811 1176 | 1173 47.84800 47848 1177 | 1174 47.88400 47884 1178 | 1175 47.92100 47921 1179 | 1176 47.95800 47958 1180 | 1177 47.99500 47995 1181 | 1178 48.03200 48032 1182 | 1179 48.06900 48069 1183 | 1180 48.10500 48105 1184 | 1181 48.14200 48142 1185 | 1182 48.17900 48179 1186 | 1183 48.21600 48216 1187 | 1184 48.25200 48252 1188 | 1185 48.28900 48289 1189 | 1186 48.32600 48326 1190 | 1187 48.36300 48363 1191 | 1188 48.39900 48399 1192 | 1189 48.43600 48436 1193 | 1190 48.47300 48473 1194 | 1191 48.50900 48509 1195 | 1192 48.54600 48546 1196 | 1193 48.58200 48582 1197 | 1194 48.61900 48619 1198 | 1195 48.65600 48656 1199 | 1196 48.69200 48692 1200 | 1197 48.72900 48729 1201 | 1198 48.76500 48765 1202 | 1199 48.80200 48802 1203 | 1200 48.83800 48838 1204 | 1201 48.87500 48875 1205 | 1202 48.91100 48911 1206 | 1203 48.94800 48948 1207 | 1204 48.98400 48984 1208 | 1205 49.02100 49021 1209 | 1206 49.05700 49057 1210 | 1207 49.09300 49093 1211 | 1208 49.13000 49130 1212 | 1209 49.16600 49166 1213 | 1210 49.20200 49202 1214 | 1211 49.23900 49239 1215 | 1212 49.27500 49275 1216 | 1213 49.31100 49311 1217 | 1214 49.34800 49348 1218 | 1215 49.38400 49384 1219 | 1216 49.42000 49420 1220 | 1217 49.45600 49456 1221 | 1218 49.49300 49493 1222 | 1219 49.52900 49529 1223 | 1220 49.56500 49565 1224 | 1221 49.60100 49601 1225 | 1222 49.63700 49637 1226 | 1223 49.67400 49674 1227 | 1224 49.71000 49710 1228 | 1225 49.74600 49746 1229 | 1226 49.78200 49782 1230 | 1227 49.81800 49818 1231 | 1228 49.85400 49854 1232 | 1229 49.89000 49890 1233 | 1230 49.92600 49926 1234 | 1231 49.96200 49962 1235 | 1232 49.99800 49998 1236 | 1233 50.03400 50034 1237 | 1234 50.07000 50070 1238 | 1235 50.10600 50106 1239 | 1236 50.14200 50142 1240 | 1237 50.17800 50178 1241 | 1238 50.21400 50214 1242 | 1239 50.25000 50250 1243 | 1240 50.28600 50286 1244 | 1241 50.32200 50322 1245 | 1242 50.35800 50358 1246 | 1243 50.39300 50393 1247 | 1244 50.42900 50429 1248 | 1245 50.46500 50465 1249 | 1246 50.50100 50501 1250 | 1247 50.53700 50537 1251 | 1248 50.57200 50572 1252 | 1249 50.60800 50608 1253 | 1250 50.64400 50644 1254 | 1251 50.68000 50680 1255 | 1252 50.71500 50715 1256 | 1253 50.75100 50751 1257 | 1254 50.78700 50787 1258 | 1255 50.82200 50822 1259 | 1256 50.85800 50858 1260 | 1257 50.89400 50894 1261 | 1258 50.92900 50929 1262 | 1259 50.96500 50965 1263 | 1260 51.00000 51000 1264 | 1261 51.03600 51036 1265 | 1262 51.07100 51071 1266 | 1263 51.10700 51107 1267 | 1264 51.14200 51142 1268 | 1265 51.17800 51178 1269 | 1266 51.21300 51213 1270 | 1267 51.24900 51249 1271 | 1268 51.28400 51284 1272 | 1269 51.32000 51320 1273 | 1270 51.35500 51355 1274 | 1271 51.39100 51391 1275 | 1272 51.42600 51426 1276 | 1273 51.46100 51461 1277 | 1274 51.49700 51497 1278 | 1275 51.53200 51532 1279 | 1276 51.56700 51567 1280 | 1277 51.60300 51603 1281 | 1278 51.63800 51638 1282 | 1279 51.67300 51673 1283 | 1280 51.70800 51708 1284 | 1281 51.74400 51744 1285 | 1282 51.77900 51779 1286 | 1283 51.81400 51814 1287 | 1284 51.84900 51849 1288 | 1285 51.88500 51885 1289 | 1286 51.92000 51920 1290 | 1287 51.95500 51955 1291 | 1288 51.99000 51990 1292 | 1289 52.02500 52025 1293 | 1290 52.06000 52060 1294 | 1291 52.09500 52095 1295 | 1292 52.13000 52130 1296 | 1293 52.16500 52165 1297 | 1294 52.20000 52200 1298 | 1295 52.23500 52235 1299 | 1296 52.27000 52270 1300 | 1297 52.30500 52305 1301 | 1298 52.34000 52340 1302 | 1299 52.37500 52375 1303 | 1300 52.41000 52410 1304 | 1301 52.44500 52445 1305 | 1302 52.48000 52480 1306 | 1303 52.51500 52515 1307 | 1304 52.55000 52550 1308 | 1305 52.58500 52585 1309 | 1306 52.62000 52620 1310 | 1307 52.65400 52654 1311 | 1308 52.68900 52689 1312 | 1309 52.72400 52724 1313 | 1310 52.75900 52759 1314 | 1311 52.79400 52794 1315 | 1312 52.82800 52828 1316 | 1313 52.86300 52863 1317 | 1314 52.89800 52898 1318 | 1315 52.93200 52932 1319 | 1316 52.96700 52967 1320 | 1317 53.00200 53002 1321 | 1318 53.03700 53037 1322 | 1319 53.07100 53071 1323 | 1320 53.10600 53106 1324 | 1321 53.14000 53140 1325 | 1322 53.17500 53175 1326 | 1323 53.21000 53210 1327 | 1324 53.24400 53244 1328 | 1325 53.27900 53279 1329 | 1326 53.31300 53313 1330 | 1327 53.34800 53348 1331 | 1328 53.38200 53382 1332 | 1329 53.41700 53417 1333 | 1330 53.45100 53451 1334 | 1331 53.48600 53486 1335 | 1332 53.52000 53520 1336 | 1333 53.55500 53555 1337 | 1334 53.58900 53589 1338 | 1335 53.62300 53623 1339 | 1336 53.65800 53658 1340 | 1337 53.69200 53692 1341 | 1338 53.72700 53727 1342 | 1339 53.76100 53761 1343 | 1340 53.79500 53795 1344 | 1341 53.83000 53830 1345 | 1342 53.86400 53864 1346 | 1343 53.89800 53898 1347 | 1344 53.93200 53932 1348 | 1345 53.96700 53967 1349 | 1346 54.00100 54001 1350 | 1347 54.03500 54035 1351 | 1348 54.06900 54069 1352 | 1349 54.10400 54104 1353 | 1350 54.13800 54138 1354 | 1351 54.17200 54172 1355 | 1352 54.20600 54206 1356 | 1353 54.24000 54240 1357 | 1354 54.27400 54274 1358 | 1355 54.30800 54308 1359 | 1356 54.34300 54343 1360 | 1357 54.37700 54377 1361 | 1358 54.41100 54411 1362 | 1359 54.44500 54445 1363 | 1360 54.47900 54479 1364 | 1361 54.51300 54513 1365 | 1362 54.54700 54547 1366 | 1363 54.58100 54581 1367 | 1364 54.61500 54615 1368 | 1365 54.64900 54649 1369 | 1366 54.68300 54683 1370 | 1367 54.71700 54717 1371 | 1368 54.75100 54751 1372 | 1369 54.78500 54785 1373 | 1370 54.81900 54819 1374 | 1371 54.85200 54852 1375 | 1372 54.88600 54886 1376 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | MIT License 2 | 3 | Copyright (c) 2017 timothyjager 4 | 5 | Permission is hereby granted, free of charge, to any person obtaining a copy 6 | of this software and associated documentation files (the "Software"), to deal 7 | in the Software without restriction, including without limitation the rights 8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 9 | copies of the Software, and to permit persons to whom the Software is 10 | furnished to do so, subject to the following conditions: 11 | 12 | The above copyright notice and this permission notice shall be included in all 13 | copies or substantial portions of the Software. 14 | 15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 21 | SOFTWARE. 22 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # JBC-Soldering-Controller 2 | A DIY soldering controller for JBC T245 handle & C245 tips 3 | -------------------------------------------------------------------------------- /Software/LabVIEW/PID Tuning/HexStringToBinaryString.vi: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Software/LabVIEW/PID Tuning/HexStringToBinaryString.vi -------------------------------------------------------------------------------- /Software/LabVIEW/PID Tuning/HexStringToSingle.vi: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Software/LabVIEW/PID Tuning/HexStringToSingle.vi -------------------------------------------------------------------------------- /Software/LabVIEW/PID Tuning/HostPacket.vi: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Software/LabVIEW/PID Tuning/HostPacket.vi -------------------------------------------------------------------------------- /Software/LabVIEW/PID Tuning/InputSimulationMode.ctl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Software/LabVIEW/PID Tuning/InputSimulationMode.ctl -------------------------------------------------------------------------------- /Software/LabVIEW/PID Tuning/PID Mode.ctl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Software/LabVIEW/PID Tuning/PID Mode.ctl -------------------------------------------------------------------------------- /Software/LabVIEW/PID Tuning/PID_TUNING.vi: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Software/LabVIEW/PID Tuning/PID_TUNING.vi -------------------------------------------------------------------------------- /Software/LabVIEW/PID Tuning/PID_tuningPacket.vi: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Software/LabVIEW/PID Tuning/PID_tuningPacket.vi -------------------------------------------------------------------------------- /Software/LabVIEW/PID Tuning/Parameters.ctl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Software/LabVIEW/PID Tuning/Parameters.ctl -------------------------------------------------------------------------------- /Software/LabVIEW/PID Tuning/ParseArduinoHexPacket.vi: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Software/LabVIEW/PID Tuning/ParseArduinoHexPacket.vi -------------------------------------------------------------------------------- /Software/LabVIEW/PID Tuning/ParseControllerPacket.vi: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Software/LabVIEW/PID Tuning/ParseControllerPacket.vi -------------------------------------------------------------------------------- /Software/LabVIEW/PID Tuning/Serial - ASCII Characters.ctl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Software/LabVIEW/PID Tuning/Serial - ASCII Characters.ctl -------------------------------------------------------------------------------- /Software/LabVIEW/PID Tuning/Serial - Settings.ctl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Software/LabVIEW/PID Tuning/Serial - Settings.ctl -------------------------------------------------------------------------------- /Software/LabVIEW/PID Tuning/Serial - XON-XOFF Characters.ctl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Software/LabVIEW/PID Tuning/Serial - XON-XOFF Characters.ctl -------------------------------------------------------------------------------- /Software/LabVIEW/PID Tuning/Status.ctl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/timothyjager/JBC-Soldering-Controller/98790e45c18e6d81bd306c7721eb31600e52d460/Software/LabVIEW/PID Tuning/Status.ctl --------------------------------------------------------------------------------