1
0
forked from me/IronOS

Backport some master changes

This commit is contained in:
Ben V. Brown
2020-09-17 19:05:55 +10:00
parent b4c8fc2aab
commit 8074255b9e
23 changed files with 754 additions and 581 deletions

View File

@@ -10,6 +10,8 @@
#include "systick.h"
#include <IRQ.h>
//2 second filter (ADC is PID_TIM_HZ Hz)
history<uint16_t, PID_TIM_HZ> rawTempFilter = {{0}, 0, 0};
void resetWatchdog() {
//TODO
}
@@ -24,9 +26,79 @@ uint16_t getTipInstantTemperature() {
return sum; // 8x over sample
}
// Timer callbacks
// TODO
// Handle callback of the PWM modulator to enable / disable the output PWM
uint16_t getTipRawTemp(uint8_t refresh)
{
if (refresh)
{
uint16_t lastSample = getTipInstantTemperature();
rawTempFilter.update(lastSample);
return lastSample;
}
else
{
return rawTempFilter.average();
}
}
uint16_t getHandleTemperature()
{
#ifdef TEMP_TMP36
// We return the current handle temperature in X10 C
// TMP36 in handle, 0.5V offset and then 10mV per deg C (0.75V @ 25C for
// example) STM32 = 4096 count @ 3.3V input -> But We oversample by 32/(2^2) =
// 8 times oversampling Therefore 32768 is the 3.3V input, so 0.1007080078125
// mV per count So we need to subtract an offset of 0.5V to center on 0C
// (4964.8 counts)
//
int32_t result = getADC(0);
result -= 4965; // remove 0.5V offset
// 10mV per C
// 99.29 counts per Deg C above 0C
result *= 100;
result /= 993;
return result;
#else
#error
#endif
}
uint16_t getInputVoltageX10(uint16_t divisor, uint8_t sample)
{
// ADC maximum is 32767 == 3.3V at input == 28.05V at VIN
// Therefore we can divide down from there
// Multiplying ADC max by 4 for additional calibration options,
// ideal term is 467
#ifdef MODEL_TS100
#define BATTFILTERDEPTH 32
#else
#define BATTFILTERDEPTH 8
#endif
static uint8_t preFillneeded = 10;
static uint32_t samples[BATTFILTERDEPTH];
static uint8_t index = 0;
if (preFillneeded)
{
for (uint8_t i = 0; i < BATTFILTERDEPTH; i++)
samples[i] = getADC(1);
preFillneeded--;
}
if (sample)
{
samples[index] = getADC(1);
index = (index + 1) % BATTFILTERDEPTH;
}
uint32_t sum = 0;
for (uint8_t i = 0; i < BATTFILTERDEPTH; i++)
sum += samples[i];
sum /= BATTFILTERDEPTH;
if (divisor == 0)
{
divisor = 1;
}
return sum * 4 / divisor;
}
void unstick_I2C() {
// TODO

View File

@@ -15,24 +15,13 @@
#include "protocol_rx.h"
#include "protocol_tx.h"
#include "int_n.h"
#include "hard_reset.h"
void fusb302_start_processing() {
/* Initialize the FUSB302B */
resetWatchdog();
fusb_setup();
resetWatchdog();
/* Create the policy engine thread. */
PolicyEngine::init();
/* Create the protocol layer threads. */
ProtocolReceive::init();
ProtocolTransmit::init();
ResetHandler::init();
resetWatchdog();
/* Create the INT_N thread. */
ProtocolReceive::init();
InterruptHandler::init();
}
#endif

View File

@@ -21,7 +21,6 @@
#include "fusb302b.h"
#include "protocol_rx.h"
#include "protocol_tx.h"
#include "hard_reset.h"
#include "policy_engine.h"
#include "protocol_rx.h"
#include "protocol_tx.h"
@@ -41,8 +40,6 @@ void InterruptHandler::init() {
void InterruptHandler::Thread(const void *arg) {
(void) arg;
union fusb_status status;
volatile uint32_t events;
bool notifSent = false;
while (true) {
/* If the INT_N line is low */
if (xTaskNotifyWait(0x00, 0x0F, NULL,
@@ -50,7 +47,6 @@ void InterruptHandler::Thread(const void *arg) {
//delay slightly so we catch the crc with better timing
osDelay(1);
}
notifSent = false;
/* Read the FUSB302B status and interrupt registers */
fusb_get_status(&status);
/* If the I_TXSENT or I_RETRYFAIL flag is set, tell the Protocol TX
@@ -58,43 +54,23 @@ void InterruptHandler::Thread(const void *arg) {
if (status.interrupta & FUSB_INTERRUPTA_I_TXSENT) {
ProtocolTransmit::notify(
ProtocolTransmit::Notifications::PDB_EVT_PRLTX_I_TXSENT);
notifSent = true;
}
if (status.interrupta & FUSB_INTERRUPTA_I_RETRYFAIL) {
ProtocolTransmit::notify(
ProtocolTransmit::Notifications::PDB_EVT_PRLTX_I_RETRYFAIL);
notifSent = true;
}
/* If the I_GCRCSENT flag is set, tell the Protocol RX thread */
//This means a message was recieved with a good CRC
if (status.interruptb & FUSB_INTERRUPTB_I_GCRCSENT) {
ProtocolReceive::notify(PDB_EVT_PRLRX_I_GCRCSENT);
notifSent = true;
}
/* If the I_HARDRST or I_HARDSENT flag is set, tell the Hard Reset
* thread */
if (notifSent == false) {
events = 0;
if (status.interrupta & FUSB_INTERRUPTA_I_HARDRST) {
events |= PDB_EVT_HARDRST_I_HARDRST;
notifSent = true;
} else if (status.interrupta & FUSB_INTERRUPTA_I_HARDSENT) {
events |= PDB_EVT_HARDRST_I_HARDSENT;
notifSent = true;
}
if (events) {
ResetHandler::notify(events);
}
}
/* If the I_OCP_TEMP and OVRTEMP flags are set, tell the Policy
* Engine thread */
if (status.interrupta & FUSB_INTERRUPTA_I_OCP_TEMP
&& status.status1 & FUSB_STATUS1_OVRTEMP) {
PolicyEngine::notify(PDB_EVT_PE_I_OVRTEMP);
notifSent = true;
}
}
}

View File

@@ -20,7 +20,6 @@
#include "int_n.h"
#include <pd.h>
#include "protocol_tx.h"
#include "hard_reset.h"
#include "fusb302b.h"
bool PolicyEngine::pdNegotiationComplete;
int PolicyEngine::current_voltage_mv;
@@ -189,15 +188,15 @@ PolicyEngine::policy_engine_state PolicyEngine::pe_sink_wait_cap() {
&& PD_NUMOBJ_GET(&tempMessage) > 0) {
/* First, determine what PD revision we're using */
if ((hdr_template & PD_HDR_SPECREV) == PD_SPECREV_1_0) {
// /* If the other end is using at least version 3.0, we'll
// * use version 3.0. */
// if ((tempMessage.hdr & PD_HDR_SPECREV) >= PD_SPECREV_3_0) {
// hdr_template |= PD_SPECREV_3_0;
// /* Otherwise, use 2.0. Don't worry about the 1.0 case
// * because we don't have hardware for PD 1.0 signaling. */
// } else {
/* If the other end is using at least version 3.0, we'll
* use version 3.0. */
if ((tempMessage.hdr & PD_HDR_SPECREV) >= PD_SPECREV_3_0) {
hdr_template |= PD_SPECREV_3_0;
/* Otherwise, use 2.0. Don't worry about the 1.0 case
* because we don't have hardware for PD 1.0 signaling. */
} else {
hdr_template |= PD_SPECREV_2_0;
// }
}
}
return PESinkEvalCap;
/* If the message was a Soft_Reset, do the soft reset procedure */
@@ -516,11 +515,8 @@ PolicyEngine::policy_engine_state PolicyEngine::pe_sink_hard_reset() {
if (_hard_reset_counter > PD_N_HARD_RESET_COUNT) {
return PESinkSourceUnresponsive;
}
/* Generate a hard reset signal */
ResetHandler::notify(PDB_EVT_HARDRST_RESET);
waitForEvent(PDB_EVT_PE_HARD_SENT);
//So, we could send a hardreset here; however that will cause a power cycle on the PSU end.. Which will then reset this MCU
//So therefore we went get anywhere :)
/* Increment HardResetCounter */
_hard_reset_counter++;
@@ -537,9 +533,6 @@ PolicyEngine::policy_engine_state PolicyEngine::pe_sink_transition_default() {
/* Since we never change our data role from UFP, there is no reason to set
* it here. */
/* Tell the protocol layer we're done with the reset */
ResetHandler::notify( PDB_EVT_HARDRST_DONE);
return PESinkStartup;
}

View File

@@ -36,9 +36,12 @@ void I2CBB::init() {
}
bool I2CBB::probe(uint8_t address) {
if (!lock())
return false;
start();
bool ack = send(address);
stop();
unlock();
return ack;
}

View File

@@ -18,46 +18,42 @@
*
*
*/
class FRToSI2C
{
class FRToSI2C {
public:
static void init()
{
I2CSemaphore = nullptr;
}
static void FRToSInit()
{
static void FRToSInit() {
I2CSemaphore = xSemaphoreCreateBinaryStatic(&xSemaphoreBuffer);
xSemaphoreGive(I2CSemaphore);
I2CSemaphore2 = xSemaphoreCreateBinaryStatic(&xSemaphoreBuffer2);
xSemaphoreGive(I2CSemaphore2);
}
static void CpltCallback(); //Normal Tx Callback
static bool Mem_Read(uint16_t DevAddress, uint16_t MemAddress,
uint8_t *pData, uint16_t Size);
static void Mem_Write(uint16_t DevAddress, uint16_t MemAddress,
static bool Mem_Write(uint16_t DevAddress, uint16_t MemAddress,
uint8_t *pData, uint16_t Size);
//Returns true if device ACK's being addressed
static bool probe(uint16_t DevAddress);
static void Transmit(uint16_t DevAddress, uint8_t *pData, uint16_t Size);
static bool Transmit(uint16_t DevAddress, uint8_t *pData, uint16_t Size);
static void Receive(uint16_t DevAddress, uint8_t *pData, uint16_t Size);
static void TransmitReceive(uint16_t DevAddress, uint8_t *pData_tx,
uint16_t Size_tx, uint8_t *pData_rx, uint16_t Size_rx);
static void I2C_RegisterWrite(uint8_t address, uint8_t reg, uint8_t data);
static bool I2C_RegisterWrite(uint8_t address, uint8_t reg, uint8_t data);
static uint8_t I2C_RegisterRead(uint8_t address, uint8_t reg);
//These are public locks that let code lock the bus for back-to-back operations
static bool lock2();
static void unlock2();
static bool lock2();
private:
static bool lock();
static void unlock();
static bool lock();
static void I2C_Unstick();
static SemaphoreHandle_t I2CSemaphore;
static StaticSemaphore_t xSemaphoreBuffer;
static SemaphoreHandle_t I2CSemaphore2;
static StaticSemaphore_t xSemaphoreBuffer2;
};
#endif /* FRTOSI2C_HPP_ */

View File

@@ -10,8 +10,7 @@
#include "LIS2DH12.hpp"
#include "cmsis_os.h"
typedef struct
{
typedef struct {
const uint8_t reg;
const uint8_t value;
} LIS_REG;
@@ -20,32 +19,23 @@ static const LIS_REG i2c_registers[] = {{LIS_CTRL_REG1, 0x17}, // 25Hz
{ LIS_CTRL_REG2, 0b00001000 }, // Highpass filter off
{ LIS_CTRL_REG3, 0b01100000 }, // Setup interrupt pins
{ LIS_CTRL_REG4, 0b00001000 }, // Block update mode off, HR on
{LIS_CTRL_REG5, 0b00000010},
{LIS_CTRL_REG6, 0b01100010},
{ LIS_CTRL_REG5, 0b00000010 }, { LIS_CTRL_REG6, 0b01100010 },
//Basically setup the unit to run, and enable 4D orientation detection
{ LIS_INT2_CFG, 0b01111110 }, //setup for movement detection
{LIS_INT2_THS, 0x28},
{LIS_INT2_DURATION, 64},
{LIS_INT1_CFG, 0b01111110},
{LIS_INT1_THS, 0x28},
{LIS_INT1_DURATION, 64}};
{ LIS_INT2_THS, 0x28 }, { LIS_INT2_DURATION, 64 }, {
LIS_INT1_CFG, 0b01111110 }, { LIS_INT1_THS, 0x28 }, {
LIS_INT1_DURATION, 64 } };
void LIS2DH12::initalize()
{
#ifdef ACCEL_LIS
void LIS2DH12::initalize() {
for (size_t index = 0;
index < (sizeof(i2c_registers) / sizeof(i2c_registers[0]));
index++)
{
index++) {
FRToSI2C::I2C_RegisterWrite(LIS2DH_I2C_ADDRESS,
i2c_registers[index].reg, i2c_registers[index].value);
}
#endif
}
void LIS2DH12::getAxisReadings(int16_t &x, int16_t &y, int16_t &z)
{
#ifdef ACCEL_LIS
void LIS2DH12::getAxisReadings(int16_t &x, int16_t &y, int16_t &z) {
std::array<int16_t, 3> sensorData;
FRToSI2C::Mem_Read(LIS2DH_I2C_ADDRESS, 0xA8,
@@ -55,10 +45,8 @@ void LIS2DH12::getAxisReadings(int16_t &x, int16_t &y, int16_t &z)
x = sensorData[0];
y = sensorData[1];
z = sensorData[2];
#endif
}
bool LIS2DH12::detect()
{
bool LIS2DH12::detect() {
return FRToSI2C::probe(LIS2DH_I2C_ADDRESS);
}

View File

@@ -11,18 +11,15 @@
#include "LIS2DH12_defines.hpp"
#include "BSP.h"
class LIS2DH12
{
class LIS2DH12 {
public:
static bool detect();
static void initalize();
//1 = rh, 2,=lh, 8=flat
static Orientation getOrientation()
{
static Orientation getOrientation() {
#ifdef LIS_ORI_FLIP
uint8_t val = (FRToSI2C::I2C_RegisterRead(LIS2DH_I2C_ADDRESS,
LIS_INT2_SRC) >>
2);
LIS_INT2_SRC) >> 2);
if (val == 8)
val = 3;
else if (val == 1)
@@ -33,10 +30,8 @@ public:
val = 3;
return static_cast<Orientation>(val);
#endif
#ifdef ACCEL_LIS
#ifdef MODEL_TS100
return static_cast<Orientation>((FRToSI2C::I2C_RegisterRead(LIS2DH_I2C_ADDRESS,LIS_INT2_SRC) >> 2) - 1);
#else
return Orientation::ORIENTATION_FLAT;
#endif
}
static void getAxisReadings(int16_t& x, int16_t& y, int16_t& z);

View File

@@ -0,0 +1,171 @@
/*
FreeRTOS V9.0.0 - Copyright (C) 2016 Real Time Engineers Ltd.
All rights reserved
VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
This file is part of the FreeRTOS distribution.
FreeRTOS is free software; you can redistribute it and/or modify it under
the terms of the GNU General Public License (version 2) as published by the
Free Software Foundation >>!AND MODIFIED BY!<< the FreeRTOS exception.
***************************************************************************
>>! NOTE: The modification to the GPL is included to allow you to !<<
>>! distribute a combined work that includes FreeRTOS without being !<<
>>! obliged to provide the source code for proprietary components !<<
>>! outside of the FreeRTOS kernel. !<<
***************************************************************************
FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY
WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
FOR A PARTICULAR PURPOSE. Full license text is available on the following
link: http://www.freertos.org/a00114.html
***************************************************************************
* *
* FreeRTOS provides completely free yet professionally developed, *
* robust, strictly quality controlled, supported, and cross *
* platform software that is more than just the market leader, it *
* is the industry's de facto standard. *
* *
* Help yourself get started quickly while simultaneously helping *
* to support the FreeRTOS project by purchasing a FreeRTOS *
* tutorial book, reference manual, or both: *
* http://www.FreeRTOS.org/Documentation *
* *
***************************************************************************
http://www.FreeRTOS.org/FAQHelp.html - Having a problem? Start by reading
the FAQ page "My application does not run, what could be wrong?". Have you
defined configASSERT()?
http://www.FreeRTOS.org/support - In return for receiving this top quality
embedded software for free we request you assist our global community by
participating in the support forum.
http://www.FreeRTOS.org/training - Investing in training allows your team to
be as productive as possible as early as possible. Now you can receive
FreeRTOS training directly from Richard Barry, CEO of Real Time Engineers
Ltd, and the world's leading authority on the world's leading RTOS.
http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
including FreeRTOS+Trace - an indispensable productivity tool, a DOS
compatible FAT file system, and our tiny thread aware UDP/IP stack.
http://www.FreeRTOS.org/labs - Where new FreeRTOS products go to incubate.
Come and try FreeRTOS+TCP, our new open source TCP/IP stack for FreeRTOS.
http://www.OpenRTOS.com - Real Time Engineers ltd. license FreeRTOS to High
Integrity Systems ltd. to sell under the OpenRTOS brand. Low cost OpenRTOS
licenses offer ticketed support, indemnification and commercial middleware.
http://www.SafeRTOS.com - High Integrity Systems also provide a safety
engineered and independently SIL3 certified version for use in safety and
mission critical applications that require provable dependability.
1 tab == 4 spaces!
*/
#ifndef FREERTOS_CONFIG_H
#define FREERTOS_CONFIG_H
/*-----------------------------------------------------------
* Application specific definitions.
*
* These definitions should be adjusted for your particular hardware and
* application requirements.
*
* THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE
* FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE.
*
* See http://www.freertos.org/a00110.html.
*----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
/* Section where include file can be added */
/* USER CODE END Includes */
/* Ensure stdint is only used by the compiler, and not the assembler. */
#if defined(__ICCARM__) || defined(__CC_ARM) || defined(__GNUC__)
#include <stdint.h>
extern uint32_t SystemCoreClock;
#endif
#define configUSE_PREEMPTION 1
#define configSUPPORT_STATIC_ALLOCATION 1
#define configSUPPORT_DYNAMIC_ALLOCATION 0
#define configUSE_IDLE_HOOK 1
#define configUSE_TICK_HOOK 0
#define configCPU_CLOCK_HZ ( SystemCoreClock )
#define configTICK_RATE_HZ ((TickType_t)1000)
#define configMAX_PRIORITIES ( 6 )
#define configMINIMAL_STACK_SIZE ((uint16_t)256)
#define configTOTAL_HEAP_SIZE ((size_t)1024*14) /*Currently use about 9000*/
#define configMAX_TASK_NAME_LEN ( 32 )
#define configUSE_16_BIT_TICKS 0
#define configUSE_MUTEXES 1
#define configQUEUE_REGISTRY_SIZE 8
#define configUSE_TIMERS 0
#define configUSE_PORT_OPTIMISED_TASK_SELECTION 1
#define configCHECK_FOR_STACK_OVERFLOW 2 /*Bump this to 2 during development and bug hunting*/
/* Co-routine definitions. */
#define configUSE_CO_ROUTINES 0
#define configMAX_CO_ROUTINE_PRIORITIES ( 2 )
/* Set the following definitions to 1 to include the API function, or zero
to exclude the API function. */
#define INCLUDE_vTaskPrioritySet 1
#define INCLUDE_uxTaskPriorityGet 0
#define INCLUDE_vTaskDelete 0
#define INCLUDE_vTaskCleanUpResources 0
#define INCLUDE_vTaskSuspend 0
#define INCLUDE_vTaskDelayUntil 0
#define INCLUDE_vTaskDelay 1
#define INCLUDE_xTaskGetSchedulerState 1
#define INCLUDE_uxTaskGetStackHighWaterMark 1
/* Cortex-M specific definitions. */
#ifdef __NVIC_PRIO_BITS
/* __BVIC_PRIO_BITS will be specified when CMSIS is being used. */
#define configPRIO_BITS __NVIC_PRIO_BITS
#else
#define configPRIO_BITS 4
#endif
/* The lowest interrupt priority that can be used in a call to a "set priority"
function. */
#define configLIBRARY_LOWEST_INTERRUPT_PRIORITY 15
/* The highest interrupt priority that can be used by any interrupt service
routine that makes calls to interrupt safe FreeRTOS API functions. DO NOT CALL
INTERRUPT SAFE FREERTOS API FUNCTIONS FROM ANY INTERRUPT THAT HAS A HIGHER
PRIORITY THAN THIS! (higher priorities are lower numeric values. */
#define configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY 5
/* Interrupt priorities used by the kernel port layer itself. These are generic
to all Cortex-M ports, and do not rely on any particular library functions. */
#define configKERNEL_INTERRUPT_PRIORITY ( configLIBRARY_LOWEST_INTERRUPT_PRIORITY << (8 - configPRIO_BITS) )
/* !!!! configMAX_SYSCALL_INTERRUPT_PRIORITY must not be set to zero !!!!
See http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html. */
#define configMAX_SYSCALL_INTERRUPT_PRIORITY ( configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY << (8 - configPRIO_BITS) )
/* Normal assert() semantics without relying on the provision of an assert.h
header file. */
/* USER CODE BEGIN 1 */
#define configASSERT( x ) if ((x) == 0) {taskDISABLE_INTERRUPTS(); for( ;; );}
/* USER CODE END 1 */
/* Definitions that map the FreeRTOS port interrupt handlers to their CMSIS
standard names. */
#define vPortSVCHandler SVC_Handler
#define xPortPendSVHandler PendSV_Handler
#if configUSE_TIMERS
#define configTIMER_TASK_PRIORITY 2
#define configTIMER_QUEUE_LENGTH 8
#define configTIMER_TASK_STACK_DEPTH (512/4)
#endif
#endif /* FREERTOS_CONFIG_H */

View File

@@ -9,11 +9,11 @@
#define INC_FREERTOSHOOKS_H_
#include "FreeRTOS.h"
#include "cmsis_os.h"
#include "unit.h"
#ifdef __cplusplus
extern "C"
{
extern "C" {
#endif
// RToS
@@ -24,4 +24,5 @@ extern "C"
}
#endif
#endif /* INC_FREERTOSHOOKS_H_ */

View File

@@ -11,7 +11,7 @@
#define SETTINGS_H_
#include <stdint.h>
#include "unit.h"
#define SETTINGSVERSION (0x20)
#define SETTINGSVERSION ( 0x21 )
/*Change this if you change the struct below to prevent people getting \
out of sync*/
@@ -19,8 +19,7 @@
* This struct must be a multiple of 2 bytes as it is saved / restored from
* flash in uint16_t chunks
*/
typedef struct
{
typedef struct {
uint8_t version; // Used to track if a reset is needed on firmware upgrade
uint16_t SolderingTemp; // current set point for the iron
@@ -32,8 +31,7 @@ typedef struct
uint8_t autoStartMode :2; // Should the unit automatically jump straight
// into soldering mode when power is applied
uint8_t ShutdownTime; // Time until unit shuts down if left alone
uint8_t boostModeEnabled : 1; // Boost mode swaps BUT_A in soldering mode to
// temporary soldering temp over-ride
uint8_t coolingTempBlink :1; // Should the temperature blink on the cool
// down screen until its <50C
uint8_t detailedIDLE :1; // Detailed idle screen
@@ -49,7 +47,6 @@ typedef struct
uint16_t CalibrationOffset; // This stores the temperature offset for this tip
// in the iron.
uint8_t powerLimitEnable; // Allow toggling of power limit without changing value
uint8_t powerLimit; // Maximum power iron allowed to output
uint16_t TipGain; // uV/C * 10, it can be used to convert tip thermocouple voltage to temperateture TipV/TipGain = TipTemp

View File

@@ -9,16 +9,12 @@
#define TRANSLATION_H_
#include "unit.h"
#include "stdint.h"
enum ShortNameType {
SHORT_NAME_SINGLE_LINE = 1, SHORT_NAME_DOUBLE_LINE = 2,
};
extern const uint8_t USER_FONT_12[];
extern const uint8_t USER_FONT_6x8[];
/*
* When SettingsShortNameType is SHORT_NAME_SINGLE_LINE
* use SettingsShortNames as SettingsShortNames[16][1].. second column undefined
*/
extern const enum ShortNameType SettingsShortNameType;
extern const char *SettingsShortNames[28][2];
extern const char *SettingsDescriptions[28];
extern const char *SettingsMenuEntries[4];

View File

@@ -11,7 +11,7 @@
#include "Settings.h"
#include "BSP.h"
#define PRESS_ACCEL_STEP 3
#define PRESS_ACCEL_STEP 30
#define PRESS_ACCEL_INTERVAL_MIN 100
#define PRESS_ACCEL_INTERVAL_MAX 300
@@ -19,16 +19,12 @@
//Declarations for all the methods for the settings menu (at end of this file)
//Wrapper for holding a function pointer
typedef struct state_func_t {
void (*func)(void);
} state_func;
//Struct for holding the function pointers and descriptions
typedef struct {
const char *description;
const state_func incrementHandler;
const state_func draw;
// return true if increment reached the maximum value
bool (* const incrementHandler)(void);
void (* const draw)(void);
} menuitem;
void enterSettingsMenu();

View File

@@ -8,8 +8,7 @@ extern uint32_t currentTempTargetDegC;
extern bool settingsWereReset;
extern bool usb_pd_available;
#ifdef __cplusplus
extern "C"
{
extern "C" {
#endif
void vApplicationStackOverflowHook(TaskHandle_t *pxTask,

View File

@@ -7,9 +7,7 @@
#include "FreeRTOSHooks.h"
#include "BSP.h"
#include "cmsis_os.h"
void vApplicationIdleHook(void)
{
void vApplicationIdleHook(void) {
resetWatchdog();
}
@@ -18,19 +16,19 @@ static StaticTask_t xIdleTaskTCBBuffer;
static StackType_t xIdleStack[configMINIMAL_STACK_SIZE];
void vApplicationGetIdleTaskMemory(StaticTask_t **ppxIdleTaskTCBBuffer,
StackType_t **ppxIdleTaskStackBuffer, uint32_t *pulIdleTaskStackSize)
{
StackType_t **ppxIdleTaskStackBuffer, uint32_t *pulIdleTaskStackSize) {
*ppxIdleTaskTCBBuffer = &xIdleTaskTCBBuffer;
*ppxIdleTaskStackBuffer = &xIdleStack[0];
*pulIdleTaskStackSize = configMINIMAL_STACK_SIZE;
/* place for user code */
}
void vApplicationStackOverflowHook(TaskHandle_t *pxTask,
signed portCHAR *pcTaskName)
{
signed portCHAR *pcTaskName) {
(void) pxTask;
(void) pcTaskName;
// We dont have a good way to handle a stack overflow at this point in time
reboot();
}

View File

@@ -12,9 +12,7 @@
#include "Setup.h"
#include "../../configuration.h"
#include "BSP.h"
#define FLASH_ADDR \
(0x8000000 | \
0xFC00) /*Flash start OR'ed with the maximum amount of flash - 1024 bytes*/
#include "string.h"
volatile systemSettingsType systemSettings;
@@ -65,7 +63,6 @@ void resetSettings() {
systemSettings.sensitivity = SENSITIVITY; // Default high sensitivity
systemSettings.voltageDiv = VOLTAGE_DIV; // Default divider from schematic
systemSettings.ShutdownTime = SHUTDOWN_TIME; // How many minutes until the unit turns itself off
systemSettings.boostModeEnabled = BOOST_MODE_ENABLED; // Default to having boost mode on as most people prefer it
systemSettings.BoostTemp = BOOST_TEMP; // default to 400C
systemSettings.autoStartMode = AUTO_START_MODE; // Auto start off for safety
systemSettings.coolingTempBlink = COOLING_TEMP_BLINK; // Blink the temperature on the cooling screen when its > 50C
@@ -73,7 +70,6 @@ void resetSettings() {
systemSettings.temperatureInF = TEMPERATURE_INF; // default to 0
#endif
systemSettings.descriptionScrollSpeed = DESCRIPTION_SCROLL_SPEED; // default to slow
systemSettings.powerLimitEnable = POWER_LIMIT_ENABLE; // Default to no power limit
systemSettings.CalibrationOffset = CALIBRATION_OFFSET; // the adc offset in uV
systemSettings.powerLimit = POWER_LIMIT; // 30 watts default limit
systemSettings.ReverseButtonTempChangeEnabled = REVERSE_BUTTON_TEMP_CHANGE; //

View File

@@ -18,70 +18,66 @@
void gui_Menu(const menuitem *menu);
#ifdef MODEL_TS100
static void settings_setInputVRange(void);
static bool settings_setInputVRange(void);
static void settings_displayInputVRange(void);
#else
static void settings_setInputPRange(void);
static bool settings_setInputPRange(void);
static void settings_displayInputPRange(void);
#endif
static void settings_setSleepTemp(void);
static bool settings_setSleepTemp(void);
static void settings_displaySleepTemp(void);
static void settings_setSleepTime(void);
static bool settings_setSleepTime(void);
static void settings_displaySleepTime(void);
static void settings_setShutdownTime(void);
static bool settings_setShutdownTime(void);
static void settings_displayShutdownTime(void);
static void settings_setSensitivity(void);
static bool settings_setSensitivity(void);
static void settings_displaySensitivity(void);
#ifdef ENABLED_FAHRENHEIT_SUPPORT
static void settings_setTempF(void);
static bool settings_setTempF(void);
static void settings_displayTempF(void);
#endif
static void settings_setAdvancedSolderingScreens(void);
static bool settings_setAdvancedSolderingScreens(void);
static void settings_displayAdvancedSolderingScreens(void);
static void settings_setAdvancedIDLEScreens(void);
static bool settings_setAdvancedIDLEScreens(void);
static void settings_displayAdvancedIDLEScreens(void);
static void settings_setScrollSpeed(void);
static bool settings_setScrollSpeed(void);
static void settings_displayScrollSpeed(void);
static void settings_setPowerLimitEnable(void);
static void settings_displayPowerLimitEnable(void);
static void settings_setPowerLimit(void);
static bool settings_setPowerLimit(void);
static void settings_displayPowerLimit(void);
static void settings_setDisplayRotation(void);
static bool settings_setDisplayRotation(void);
static void settings_displayDisplayRotation(void);
static void settings_setBoostModeEnabled(void);
static void settings_displayBoostModeEnabled(void);
static void settings_setBoostTemp(void);
static bool settings_setBoostTemp(void);
static void settings_displayBoostTemp(void);
static void settings_setAutomaticStartMode(void);
static bool settings_setAutomaticStartMode(void);
static void settings_displayAutomaticStartMode(void);
static void settings_setCoolingBlinkEnabled(void);
static bool settings_setCoolingBlinkEnabled(void);
static void settings_displayCoolingBlinkEnabled(void);
static void settings_setResetSettings(void);
static bool settings_setResetSettings(void);
static void settings_displayResetSettings(void);
static void settings_setCalibrate(void);
static bool settings_setCalibrate(void);
static void settings_displayCalibrate(void);
static void settings_setTipGain(void);
static bool settings_setTipGain(void);
static void settings_displayTipGain(void);
static void settings_setCalibrateVIN(void);
static bool settings_setCalibrateVIN(void);
static void settings_displayCalibrateVIN(void);
static void settings_displayReverseButtonTempChangeEnabled(void);
static void settings_setReverseButtonTempChangeEnabled(void);
static bool settings_setReverseButtonTempChangeEnabled(void);
static void settings_displayTempChangeShortStep(void);
static void settings_setTempChangeShortStep(void);
static bool settings_setTempChangeShortStep(void);
static void settings_displayTempChangeLongStep(void);
static void settings_setTempChangeLongStep(void);
static bool settings_setTempChangeLongStep(void);
static void settings_displayPowerPulse(void);
static void settings_setPowerPulse(void);
static bool settings_setPowerPulse(void);
// Menu functions
static void settings_displaySolderingMenu(void);
static void settings_enterSolderingMenu(void);
static bool settings_enterSolderingMenu(void);
static void settings_displayPowerMenu(void);
static void settings_enterPowerMenu(void);
static bool settings_enterPowerMenu(void);
static void settings_displayUIMenu(void);
static void settings_enterUIMenu(void);
static bool settings_enterUIMenu(void);
static void settings_displayAdvancedMenu(void);
static void settings_enterAdvancedMenu(void);
static bool settings_enterAdvancedMenu(void);
/*
* Root Settings Menu
*
@@ -129,21 +125,19 @@ const menuitem rootSettingsMenu[] {
* Exit
*/
#ifdef MODEL_TS100
{ (const char*) SettingsDescriptions[0], { settings_setInputVRange }, {
settings_displayInputVRange } }, /*Voltage input*/
{ (const char*) SettingsDescriptions[0], settings_setInputVRange,
settings_displayInputVRange }, /*Voltage input*/
#else
{ (const char*) SettingsDescriptions[20], { settings_setInputPRange }, {
settings_displayInputPRange } }, /*Voltage input*/
{ (const char*) SettingsDescriptions[19], settings_setInputPRange,
settings_displayInputPRange }, /*Voltage input*/
#endif
{ (const char*) NULL, { settings_enterSolderingMenu }, {
settings_displaySolderingMenu } }, /*Soldering*/
{ (const char*) NULL, { settings_enterPowerMenu }, {
settings_displayPowerMenu } }, /*Sleep Options Menu*/
{ (const char*) NULL, { settings_enterUIMenu },
{ settings_displayUIMenu } }, /*UI Menu*/
{ (const char*) NULL, { settings_enterAdvancedMenu }, {
settings_displayAdvancedMenu } }, /*Advanced Menu*/
{ NULL, { NULL }, { NULL } } // end of menu marker. DO NOT REMOVE
{ (const char*) NULL, settings_enterSolderingMenu,
settings_displaySolderingMenu }, /*Soldering*/
{ (const char*) NULL, settings_enterPowerMenu, settings_displayPowerMenu }, /*Sleep Options Menu*/
{ (const char*) NULL, settings_enterUIMenu, settings_displayUIMenu }, /*UI Menu*/
{ (const char*) NULL, settings_enterAdvancedMenu,
settings_displayAdvancedMenu }, /*Advanced Menu*/
{ NULL, NULL, NULL } // end of menu marker. DO NOT REMOVE
};
const menuitem solderingMenu[] = {
@@ -154,17 +148,15 @@ const menuitem solderingMenu[] = {
* Temp change short step
* Temp change long step
*/
{ (const char*) SettingsDescriptions[8], { settings_setBoostModeEnabled }, {
settings_displayBoostModeEnabled } }, /*Enable Boost*/
{ (const char*) SettingsDescriptions[9], { settings_setBoostTemp }, {
settings_displayBoostTemp } }, /*Boost Temp*/
{ (const char*) SettingsDescriptions[10], { settings_setAutomaticStartMode }, {
settings_displayAutomaticStartMode } }, /*Auto start*/
{ (const char*) SettingsDescriptions[24], { settings_setTempChangeShortStep }, {
settings_displayTempChangeShortStep } }, /*Temp change short step*/
{ (const char*) SettingsDescriptions[25], { settings_setTempChangeLongStep }, {
settings_displayTempChangeLongStep } }, /*Temp change long step*/
{ NULL, { NULL }, { NULL } } // end of menu marker. DO NOT REMOVE
{ (const char*) SettingsDescriptions[8], settings_setBoostTemp,
settings_displayBoostTemp }, /*Boost Temp*/
{ (const char*) SettingsDescriptions[9], settings_setAutomaticStartMode,
settings_displayAutomaticStartMode }, /*Auto start*/
{ (const char*) SettingsDescriptions[22], settings_setTempChangeShortStep,
settings_displayTempChangeShortStep }, /*Temp change short step*/
{ (const char*) SettingsDescriptions[23], settings_setTempChangeLongStep,
settings_displayTempChangeLongStep }, /*Temp change long step*/
{ NULL, NULL, NULL } // end of menu marker. DO NOT REMOVE
};
const menuitem UIMenu[] = {
/*
@@ -176,21 +168,20 @@ const menuitem UIMenu[] = {
* Reverse Temp change buttons + -
*/
#ifdef ENABLED_FAHRENHEIT_SUPPORT
{ (const char*) SettingsDescriptions[5], { settings_setTempF }, {
settings_displayTempF } }, /* Temperature units*/
{ (const char*) SettingsDescriptions[5], settings_setTempF,
settings_displayTempF }, /* Temperature units*/
#endif
{ (const char*) SettingsDescriptions[7],
{ settings_setDisplayRotation }, {
settings_displayDisplayRotation } }, /*Display Rotation*/
{ (const char*) SettingsDescriptions[11], {
settings_setCoolingBlinkEnabled }, {
settings_displayCoolingBlinkEnabled } }, /*Cooling blink warning*/
{ (const char*) SettingsDescriptions[16], { settings_setScrollSpeed }, {
settings_displayScrollSpeed } }, /*Scroll Speed for descriptions*/
{ (const char*) SettingsDescriptions[23], {
settings_setReverseButtonTempChangeEnabled }, {
settings_displayReverseButtonTempChangeEnabled } }, /* Reverse Temp change buttons + - */
{ NULL, { NULL }, { NULL } } // end of menu marker. DO NOT REMOVE
{ (const char*) SettingsDescriptions[7], settings_setDisplayRotation,
settings_displayDisplayRotation }, /*Display Rotation*/
{ (const char*) SettingsDescriptions[10],
settings_setCoolingBlinkEnabled,
settings_displayCoolingBlinkEnabled }, /*Cooling blink warning*/
{ (const char*) SettingsDescriptions[15], settings_setScrollSpeed,
settings_displayScrollSpeed }, /*Scroll Speed for descriptions*/
{ (const char*) SettingsDescriptions[21],
settings_setReverseButtonTempChangeEnabled,
settings_displayReverseButtonTempChangeEnabled }, /* Reverse Temp change buttons + - */
{ NULL, NULL, NULL } // end of menu marker. DO NOT REMOVE
};
const menuitem PowerMenu[] = {
/*
@@ -199,20 +190,19 @@ const menuitem PowerMenu[] = {
* Shutdown Time
* Motion Sensitivity
*/
{ (const char*) SettingsDescriptions[1], { settings_setSleepTemp }, {
settings_displaySleepTemp } }, /*Sleep Temp*/
{ (const char*) SettingsDescriptions[2], { settings_setSleepTime }, {
settings_displaySleepTime } }, /*Sleep Time*/
{ (const char*) SettingsDescriptions[3], { settings_setShutdownTime }, {
settings_displayShutdownTime } }, /*Shutdown Time*/
{ (const char*) SettingsDescriptions[4], { settings_setSensitivity }, {
settings_displaySensitivity } }, /* Motion Sensitivity*/
{ NULL, { NULL }, { NULL } } // end of menu marker. DO NOT REMOVE
{ (const char*) SettingsDescriptions[1], settings_setSleepTemp,
settings_displaySleepTemp }, /*Sleep Temp*/
{ (const char*) SettingsDescriptions[2], settings_setSleepTime,
settings_displaySleepTime }, /*Sleep Time*/
{ (const char*) SettingsDescriptions[3], settings_setShutdownTime,
settings_displayShutdownTime }, /*Shutdown Time*/
{ (const char*) SettingsDescriptions[4], settings_setSensitivity,
settings_displaySensitivity }, /* Motion Sensitivity*/
{ NULL, NULL, NULL } // end of menu marker. DO NOT REMOVE
};
const menuitem advancedMenu[] = {
/*
* Power limit enable
* Power limit
* Detailed IDLE
* Detailed Soldering
@@ -221,34 +211,25 @@ const menuitem advancedMenu[] = {
* Reset Settings
* Power Pulse
*/
{ (const char*) SettingsDescriptions[21], { settings_setPowerLimitEnable }, {
settings_displayPowerLimitEnable } }, /*Power limit enable*/
{ (const char*) SettingsDescriptions[22], { settings_setPowerLimit }, {
settings_displayPowerLimit } }, /*Power limit*/
{ (const char*) SettingsDescriptions[6], { settings_setAdvancedIDLEScreens }, {
settings_displayAdvancedIDLEScreens } }, /* Advanced idle screen*/
{ (const char*) SettingsDescriptions[15],
{ settings_setAdvancedSolderingScreens }, {
settings_displayAdvancedSolderingScreens } }, /* Advanced soldering screen*/
{ (const char*) SettingsDescriptions[13], { settings_setResetSettings }, {
settings_displayResetSettings } }, /*Resets settings*/
{ (const char*) SettingsDescriptions[12], { settings_setCalibrate }, {
settings_displayCalibrate } }, /*Calibrate tip*/
{ (const char*) SettingsDescriptions[14], { settings_setCalibrateVIN }, {
settings_displayCalibrateVIN } }, /*Voltage input cal*/
{ (const char*) SettingsDescriptions[26], { settings_setPowerPulse }, {
settings_displayPowerPulse } }, /*Power Pulse adjustment */
{ (const char*) SettingsDescriptions[27], { settings_setTipGain }, {
settings_displayTipGain } }, /*TipGain*/
{ NULL, { NULL }, { NULL } } // end of menu marker. DO NOT REMOVE
{ (const char*) SettingsDescriptions[20], settings_setPowerLimit,
settings_displayPowerLimit }, /*Power limit*/
{ (const char*) SettingsDescriptions[6], settings_setAdvancedIDLEScreens,
settings_displayAdvancedIDLEScreens }, /* Advanced idle screen*/
{ (const char*) SettingsDescriptions[14], settings_setAdvancedSolderingScreens,
settings_displayAdvancedSolderingScreens }, /* Advanced soldering screen*/
{ (const char*) SettingsDescriptions[12], settings_setResetSettings,
settings_displayResetSettings }, /*Resets settings*/
{ (const char*) SettingsDescriptions[11], settings_setCalibrate,
settings_displayCalibrate }, /*Calibrate tip*/
{ (const char*) SettingsDescriptions[13], settings_setCalibrateVIN,
settings_displayCalibrateVIN }, /*Voltage input cal*/
{ (const char*) SettingsDescriptions[24], settings_setPowerPulse,
settings_displayPowerPulse }, /*Power Pulse adjustment */
{ (const char*) SettingsDescriptions[25], settings_setTipGain,
settings_displayTipGain }, /*TipGain*/
{ NULL, NULL, NULL } // end of menu marker. DO NOT REMOVE
};
static void printShortDescriptionSingleLine(uint32_t shortDescIndex) {
OLED::setFont(0);
OLED::setCharCursor(0, 0);
OLED::print(SettingsShortNames[shortDescIndex][0]);
}
static void printShortDescriptionDoubleLine(uint32_t shortDescIndex) {
OLED::setFont(1);
OLED::setCharCursor(0, 0);
@@ -267,11 +248,7 @@ static void printShortDescriptionDoubleLine(uint32_t shortDescIndex) {
static void printShortDescription(uint32_t shortDescIndex,
uint16_t cursorCharPosition) {
// print short description (default single line, explicit double line)
if (SettingsShortNameType == SHORT_NAME_DOUBLE_LINE) {
printShortDescriptionDoubleLine(shortDescIndex);
} else {
printShortDescriptionSingleLine(shortDescIndex);
}
// prepare cursor for value
OLED::setFont(0);
@@ -329,10 +306,11 @@ static int userConfirmation(const char *message) {
return 0;
}
#ifdef MODEL_TS100
static void settings_setInputVRange(void) {
static bool settings_setInputVRange(void) {
systemSettings.cutoutSetting = (systemSettings.cutoutSetting + 1) % 5;
if (systemSettings.cutoutSetting)
systemSettings.powerLimitEnable = 0; // disable power limit if switching to a lipo power source
systemSettings.powerLimit = 0; // disable power limit if switching to a lipo power source
return systemSettings.cutoutSetting == 4;
}
static void settings_displayInputVRange(void) {
@@ -346,14 +324,15 @@ static void settings_displayInputVRange(void) {
}
}
#else
static void settings_setInputPRange(void) {
static bool settings_setInputPRange(void) {
systemSettings.cutoutSetting = (systemSettings.cutoutSetting + 1) % 2;
return false;
}
static void settings_displayInputPRange(void) {
printShortDescription(0, 5);
//0 = 9V, 1=12V (Fixed Voltages, these imply 1.5A limits)
/// TODO TS80P
// These are only used in QC3.0 modes
switch (systemSettings.cutoutSetting) {
case 0:
OLED::printNumber(9, 2);
@@ -370,19 +349,21 @@ static void settings_displayInputPRange(void) {
}
#endif
static void settings_setSleepTemp(void) {
static bool settings_setSleepTemp(void) {
// If in C, 10 deg, if in F 20 deg
#ifdef ENABLED_FAHRENHEIT_SUPPORT
if (systemSettings.temperatureInF) {
systemSettings.SleepTemp += 20;
if (systemSettings.SleepTemp > 580)
systemSettings.SleepTemp = 60;
return systemSettings.SleepTemp == 580;
} else
#endif
{
systemSettings.SleepTemp += 10;
if (systemSettings.SleepTemp > 300)
systemSettings.SleepTemp = 10;
return systemSettings.SleepTemp == 300;
}
}
@@ -391,7 +372,7 @@ static void settings_displaySleepTemp(void) {
OLED::printNumber(systemSettings.SleepTemp, 3);
}
static void settings_setSleepTime(void) {
static bool settings_setSleepTime(void) {
systemSettings.SleepTime++; // Go up 1 minute at a time
if (systemSettings.SleepTime >= 16) {
systemSettings.SleepTime = 0; // can't set time over 10 mins
@@ -399,6 +380,7 @@ static void settings_setSleepTime(void) {
// Remember that ^ is the time of no movement
if (PCBVersion == 3)
systemSettings.SleepTime = 0; // Disable sleep on no accel
return systemSettings.SleepTime == 15;
}
static void settings_displaySleepTime(void) {
@@ -414,13 +396,14 @@ static void settings_displaySleepTime(void) {
}
}
static void settings_setShutdownTime(void) {
static bool settings_setShutdownTime(void) {
systemSettings.ShutdownTime++;
if (systemSettings.ShutdownTime > 60) {
systemSettings.ShutdownTime = 0; // wrap to off
}
if (PCBVersion == 3)
systemSettings.ShutdownTime = 0; // Disable shutdown on no accel
return systemSettings.ShutdownTime == 60;
}
static void settings_displayShutdownTime(void) {
@@ -433,7 +416,7 @@ static void settings_displayShutdownTime(void) {
}
}
#ifdef ENABLED_FAHRENHEIT_SUPPORT
static void settings_setTempF(void) {
static bool settings_setTempF(void) {
systemSettings.temperatureInF = !systemSettings.temperatureInF;
if (systemSettings.temperatureInF) {
// Change sleep, boost and soldering temps to the F equiv
@@ -457,6 +440,7 @@ static void settings_setTempF(void) {
systemSettings.SolderingTemp *= 10;
systemSettings.SleepTemp = systemSettings.SleepTemp / 10;
systemSettings.SleepTemp *= 10;
return false;
}
static void settings_displayTempF(void) {
@@ -466,9 +450,10 @@ static void settings_displayTempF(void) {
}
#endif
static void settings_setSensitivity(void) {
static bool settings_setSensitivity(void) {
systemSettings.sensitivity++;
systemSettings.sensitivity = systemSettings.sensitivity % 10;
return systemSettings.sensitivity == 9;
}
static void settings_displaySensitivity(void) {
@@ -476,18 +461,20 @@ static void settings_displaySensitivity(void) {
OLED::printNumber(systemSettings.sensitivity, 1, false);
}
static void settings_setAdvancedSolderingScreens(void) {
static bool settings_setAdvancedSolderingScreens(void) {
systemSettings.detailedSoldering = !systemSettings.detailedSoldering;
return false;
}
static void settings_displayAdvancedSolderingScreens(void) {
printShortDescription(15, 7);
printShortDescription(14, 7);
OLED::drawCheckbox(systemSettings.detailedSoldering);
}
static void settings_setAdvancedIDLEScreens(void) {
static bool settings_setAdvancedIDLEScreens(void) {
systemSettings.detailedIDLE = !systemSettings.detailedIDLE;
return false;
}
static void settings_displayAdvancedIDLEScreens(void) {
@@ -496,42 +483,39 @@ static void settings_displayAdvancedIDLEScreens(void) {
OLED::drawCheckbox(systemSettings.detailedIDLE);
}
static void settings_setPowerLimitEnable(void) {
systemSettings.powerLimitEnable = !systemSettings.powerLimitEnable;
}
static void settings_displayPowerLimitEnable(void) {
printShortDescription(21, 7);
OLED::drawCheckbox(systemSettings.powerLimitEnable);
}
static void settings_setPowerLimit(void) {
if (systemSettings.powerLimit >= MAX_POWER_LIMIT)
systemSettings.powerLimit = POWER_LIMIT_STEPS;
else
static bool settings_setPowerLimit(void) {
systemSettings.powerLimit += POWER_LIMIT_STEPS;
if (systemSettings.powerLimit > MAX_POWER_LIMIT)
systemSettings.powerLimit = 0;
return systemSettings.powerLimit + POWER_LIMIT_STEPS > MAX_POWER_LIMIT;
}
static void settings_displayPowerLimit(void) {
printShortDescription(22, 5);
printShortDescription(20, 5);
if (systemSettings.powerLimit == 0) {
OLED::print(OffString);
} else {
OLED::printNumber(systemSettings.powerLimit, 2);
OLED::print(SymbolWatts);
}
}
static void settings_setScrollSpeed(void) {
static bool settings_setScrollSpeed(void) {
if (systemSettings.descriptionScrollSpeed == 0)
systemSettings.descriptionScrollSpeed = 1;
else
systemSettings.descriptionScrollSpeed = 0;
return false;
}
static void settings_displayScrollSpeed(void) {
printShortDescription(16, 7);
printShortDescription(15, 7);
OLED::print(
(systemSettings.descriptionScrollSpeed) ?
SettingFastChar : SettingSlowChar);
}
static void settings_setDisplayRotation(void) {
static bool settings_setDisplayRotation(void) {
systemSettings.OrientationMode++;
systemSettings.OrientationMode = systemSettings.OrientationMode % 3;
switch (systemSettings.OrientationMode) {
@@ -547,6 +531,7 @@ static void settings_setDisplayRotation(void) {
default:
break;
}
return systemSettings.OrientationMode == 2;
}
static void settings_displayDisplayRotation(void) {
@@ -568,45 +553,53 @@ static void settings_displayDisplayRotation(void) {
}
}
static void settings_setBoostModeEnabled(void) {
systemSettings.boostModeEnabled = !systemSettings.boostModeEnabled;
}
static void settings_displayBoostModeEnabled(void) {
printShortDescription(8, 7);
OLED::drawCheckbox(systemSettings.boostModeEnabled);
}
static void settings_setBoostTemp(void) {
static bool settings_setBoostTemp(void) {
#ifdef ENABLED_FAHRENHEIT_SUPPORT
if (systemSettings.temperatureInF) {
if (systemSettings.BoostTemp == 0) {
systemSettings.BoostTemp = 480; // loop back at 480
} else {
systemSettings.BoostTemp += 20; // Go up 20F at a time
if (systemSettings.BoostTemp > 850) {
systemSettings.BoostTemp = 480; // loop back at 250
}
if (systemSettings.BoostTemp > 850) {
systemSettings.BoostTemp = 0; // jump to off
}
return systemSettings.BoostTemp == 840;
} else
#endif
{
systemSettings.BoostTemp += 10; // Go up 10C at a time
if (systemSettings.BoostTemp > 450) {
if (systemSettings.BoostTemp == 0) {
systemSettings.BoostTemp = 250; // loop back at 250
} else {
systemSettings.BoostTemp += 10; // Go up 10C at a time
}
if (systemSettings.BoostTemp > 450) {
systemSettings.BoostTemp = 0; //Go to off state
}
return systemSettings.BoostTemp == 450;
}
}
static void settings_displayBoostTemp(void) {
printShortDescription(9, 5);
printShortDescription(8, 5);
if (systemSettings.BoostTemp) {
OLED::printNumber(systemSettings.BoostTemp, 3);
} else {
OLED::print(OffString);
}
}
static void settings_setAutomaticStartMode(void) {
static bool settings_setAutomaticStartMode(void) {
systemSettings.autoStartMode++;
systemSettings.autoStartMode %= 4;
return systemSettings.autoStartMode == 3;
}
static void settings_displayAutomaticStartMode(void) {
printShortDescription(10, 7);
printShortDescription(9, 7);
switch (systemSettings.autoStartMode) {
case 0:
@@ -627,17 +620,18 @@ static void settings_displayAutomaticStartMode(void) {
}
}
static void settings_setCoolingBlinkEnabled(void) {
static bool settings_setCoolingBlinkEnabled(void) {
systemSettings.coolingTempBlink = !systemSettings.coolingTempBlink;
return false;
}
static void settings_displayCoolingBlinkEnabled(void) {
printShortDescription(11, 7);
printShortDescription(10, 7);
OLED::drawCheckbox(systemSettings.coolingTempBlink);
}
static void settings_setResetSettings(void) {
static bool settings_setResetSettings(void) {
if (userConfirmation(SettingsResetWarning)) {
resetSettings();
@@ -648,10 +642,11 @@ static void settings_setResetSettings(void) {
waitForButtonPressOrTimeout(2000); // 2 second timeout
}
return false;
}
static void settings_displayResetSettings(void) {
printShortDescription(13, 7);
printShortDescription(12, 7);
}
static void setTipOffset() {
@@ -686,20 +681,21 @@ static void setTipOffset() {
//Provide the user the option to tune their own tip if custom is selected
//If not only do single point tuning as per usual
static void settings_setCalibrate(void) {
static bool settings_setCalibrate(void) {
if (userConfirmation(SettingsCalibrationWarning)) {
// User confirmed
// So we now perform the actual calculation
setTipOffset();
}
return false;
}
static void settings_displayCalibrate(void) {
printShortDescription(12, 5);
printShortDescription(11, 5);
}
static void settings_setCalibrateVIN(void) {
static bool settings_setCalibrateVIN(void) {
// Jump to the voltage calibration subscreen
OLED::setFont(0);
OLED::clearScreen();
@@ -732,8 +728,7 @@ static void settings_setCalibrateVIN(void) {
OLED::printNumber(systemSettings.voltageDiv, 3);
OLED::refresh();
waitForButtonPressOrTimeout(1000);
return;
break;
return false;
case BUTTON_NONE:
default:
break;
@@ -757,9 +752,10 @@ static void settings_setCalibrateVIN(void) {
}
#endif
}
return false;
}
static void settings_setTipGain(void) {
static bool settings_setTipGain(void) {
OLED::setFont(0);
OLED::clearScreen();
@@ -783,8 +779,7 @@ static void settings_setTipGain(void) {
case BUTTON_F_LONG:
case BUTTON_B_LONG:
saveSettings();
return;
break;
return false;
case BUTTON_NONE:
default:
break;
@@ -800,57 +795,64 @@ static void settings_setTipGain(void) {
systemSettings.TipGain = 300;
}
}
return false;
}
static void settings_displayTipGain(void) {
printShortDescription(27, 5);
printShortDescription(25, 5);
}
static void settings_setReverseButtonTempChangeEnabled(void) {
static bool settings_setReverseButtonTempChangeEnabled(void) {
systemSettings.ReverseButtonTempChangeEnabled =
!systemSettings.ReverseButtonTempChangeEnabled;
return false;
}
static void settings_displayReverseButtonTempChangeEnabled(void) {
printShortDescription(23, 7);
printShortDescription(21, 7);
OLED::drawCheckbox(systemSettings.ReverseButtonTempChangeEnabled);
}
static void settings_setTempChangeShortStep(void) {
static bool settings_setTempChangeShortStep(void) {
systemSettings.TempChangeShortStep += TEMP_CHANGE_SHORT_STEP;
if (systemSettings.TempChangeShortStep > TEMP_CHANGE_SHORT_STEP_MAX) {
systemSettings.TempChangeShortStep = TEMP_CHANGE_SHORT_STEP; // loop back at TEMP_CHANGE_SHORT_STEP_MAX
}
return systemSettings.TempChangeShortStep == TEMP_CHANGE_SHORT_STEP_MAX;
}
static void settings_displayTempChangeShortStep(void) {
printShortDescription(24, 6);
printShortDescription(22, 6);
OLED::printNumber(systemSettings.TempChangeShortStep, 2);
}
static void settings_setTempChangeLongStep(void) {
static bool settings_setTempChangeLongStep(void) {
systemSettings.TempChangeLongStep += TEMP_CHANGE_LONG_STEP;
if (systemSettings.TempChangeLongStep > TEMP_CHANGE_LONG_STEP_MAX) {
systemSettings.TempChangeLongStep = TEMP_CHANGE_LONG_STEP; // loop back at TEMP_CHANGE_LONG_STEP_MAX
}
return systemSettings.TempChangeLongStep == TEMP_CHANGE_LONG_STEP_MAX;
}
static void settings_displayTempChangeLongStep(void) {
printShortDescription(25, 6);
printShortDescription(23, 6);
OLED::printNumber(systemSettings.TempChangeLongStep, 2);
}
static void settings_setPowerPulse(void) {
static bool settings_setPowerPulse(void) {
systemSettings.KeepAwakePulse += POWER_PULSE_INCREMENT;
systemSettings.KeepAwakePulse %= POWER_PULSE_MAX;
return systemSettings.KeepAwakePulse == POWER_PULSE_MAX - 1;
}
static void settings_displayPowerPulse(void) {
printShortDescription(26, 5);
printShortDescription(24, 5);
if (systemSettings.KeepAwakePulse) {
OLED::printNumber(systemSettings.KeepAwakePulse / 10, 1);
OLED::print(SymbolDot);
OLED::printNumber(systemSettings.KeepAwakePulse % 10, 1);
} else {
OLED::drawCheckbox(false);
OLED::print(OffString);
}
}
@@ -868,31 +870,35 @@ static void displayMenu(size_t index) {
}
static void settings_displayCalibrateVIN(void) {
printShortDescription(14, 5);
printShortDescription(13, 5);
}
static void settings_displaySolderingMenu(void) {
displayMenu(0);
}
static void settings_enterSolderingMenu(void) {
static bool settings_enterSolderingMenu(void) {
gui_Menu(solderingMenu);
return false;
}
static void settings_displayPowerMenu(void) {
displayMenu(1);
}
static void settings_enterPowerMenu(void) {
static bool settings_enterPowerMenu(void) {
gui_Menu(PowerMenu);
return false;
}
static void settings_displayUIMenu(void) {
displayMenu(2);
}
static void settings_enterUIMenu(void) {
static bool settings_enterUIMenu(void) {
gui_Menu(UIMenu);
return false;
}
static void settings_displayAdvancedMenu(void) {
displayMenu(3);
}
static void settings_enterAdvancedMenu(void) {
static bool settings_enterAdvancedMenu(void) {
gui_Menu(advancedMenu);
return false;
}
void gui_Menu(const menuitem *menu) {
@@ -908,13 +914,15 @@ void gui_Menu(const menuitem *menu) {
static bool enterGUIMenu = true;
enterGUIMenu = true;
uint8_t scrollContentSize = 0;
bool scrollBlink = false;
bool lastValue = false;
for (uint8_t i = 0; menu[i].draw.func != NULL; i++) {
for (uint8_t i = 0; menu[i].draw != NULL; i++) {
scrollContentSize += 1;
}
// Animated menu opening.
if (menu[currentScreen].draw.func != NULL) {
if (menu[currentScreen].draw != NULL) {
// This menu is drawn in a secondary framebuffer.
// Then we play a transition from the current primary
// framebuffer to the new buffer.
@@ -923,12 +931,12 @@ void gui_Menu(const menuitem *menu) {
OLED::setFont(0);
OLED::setCursor(0, 0);
OLED::clearScreen();
menu[currentScreen].draw.func();
menu[currentScreen].draw();
OLED::useSecondaryFramebuffer(false);
OLED::transitionSecondaryFramebuffer(true);
}
while ((menu[currentScreen].draw.func != NULL) && earlyExit == false) {
while ((menu[currentScreen].draw != NULL) && earlyExit == false) {
OLED::setFont(0);
OLED::setCursor(0, 0);
// If the user has hesitated for >=3 seconds, show the long text
@@ -936,9 +944,12 @@ void gui_Menu(const menuitem *menu) {
if ((xTaskGetTickCount() - lastButtonTime < 3000)
|| menu[currentScreen].description == NULL) {
OLED::clearScreen();
menu[currentScreen].draw.func();
menu[currentScreen].draw();
uint8_t indicatorHeight = OLED_HEIGHT / scrollContentSize;
uint8_t position = OLED_HEIGHT * currentScreen / scrollContentSize;
if (lastValue)
scrollBlink = !scrollBlink;
if (!lastValue || !scrollBlink)
OLED::drawScrollIndicator(position, indicatorHeight);
lastOffset = -1;
lcdRefresh = true;
@@ -978,16 +989,16 @@ void gui_Menu(const menuitem *menu) {
case BUTTON_F_SHORT:
// increment
if (descriptionStart == 0) {
if (menu[currentScreen].incrementHandler.func != NULL) {
if (menu[currentScreen].incrementHandler != NULL) {
enterGUIMenu = false;
menu[currentScreen].incrementHandler.func();
lastValue = menu[currentScreen].incrementHandler();
if (enterGUIMenu) {
OLED::useSecondaryFramebuffer(true);
OLED::setFont(0);
OLED::setCursor(0, 0);
OLED::clearScreen();
menu[currentScreen].draw.func();
menu[currentScreen].draw();
OLED::useSecondaryFramebuffer(false);
OLED::transitionSecondaryFramebuffer(false);
}
@@ -999,16 +1010,23 @@ void gui_Menu(const menuitem *menu) {
descriptionStart = 0;
break;
case BUTTON_B_SHORT:
if (descriptionStart == 0)
if (descriptionStart == 0) {
currentScreen++;
else
lastValue = false;
} else
descriptionStart = 0;
break;
case BUTTON_F_LONG:
if (xTaskGetTickCount() - autoRepeatTimer + autoRepeatAcceleration >
if ((int) (xTaskGetTickCount() - autoRepeatTimer
+ autoRepeatAcceleration) >
PRESS_ACCEL_INTERVAL_MAX) {
menu[currentScreen].incrementHandler.func();
autoRepeatTimer = xTaskGetTickCount();
if ((lastValue = menu[currentScreen].incrementHandler()))
autoRepeatTimer = 1000;
else
autoRepeatTimer = 0;
autoRepeatTimer += xTaskGetTickCount();
descriptionStart = 0;
autoRepeatAcceleration += PRESS_ACCEL_STEP;

View File

@@ -12,8 +12,6 @@
#include "Settings.h"
#include "cmsis_os.h"
uint8_t PCBVersion = 0;
// File local variables
bool usb_pd_available = false;
bool settingsWereReset = false;
// FreeRTOS variables
@@ -32,44 +30,17 @@ uint32_t MOVTaskBuffer[MOVTaskStackSize];
osStaticThreadDef_t MOVTaskControlBlock;
// End FreeRTOS
// Main sets up the hardware then hands over to the FreeRTOS kernel
int main(void) {
preRToSInit();
setTipX10Watts(0); // force tip off
resetWatchdog();
OLED::initialize(); // start up the LCD
OLED::setFont(0); // default to bigger font
// Testing for which accelerometer is mounted
resetWatchdog();
usb_pd_available = usb_pd_detect();
resetWatchdog();
settingsWereReset = restoreSettings(); // load the settings from flash
#ifdef ACCEL_MMA
if (MMA8652FC::detect()) {
PCBVersion = 1;
MMA8652FC::initalize(); // this sets up the I2C registers
} else
#endif
#ifdef ACCEL_LIS
if (LIS2DH12::detect()) {
PCBVersion = 2;
// Setup the ST Accelerometer
LIS2DH12::initalize(); // startup the accelerometer
} else
#endif
{
PCBVersion = 3;
systemSettings.SleepTime = 0;
systemSettings.ShutdownTime = 0; // No accel -> disable sleep
systemSettings.sensitivity = 0;
}
resetWatchdog();
/* Create the thread(s) */
/* definition and creation of GUITask */
osThreadStaticDef(GUITask, startGUITask, osPriorityBelowNormal, 0,
GUITaskStackSize, GUITaskBuffer, &GUITaskControlBlock);
GUITaskHandle = osThreadCreate(osThread(GUITask), NULL);

View File

@@ -439,7 +439,7 @@ static void gui_solderingMode(uint8_t jumpToSleep) {
break;
case BUTTON_F_LONG:
// if boost mode is enabled turn it on
if (systemSettings.boostModeEnabled)
if (systemSettings.BoostTemp)
boostModeOn = true;
break;
case BUTTON_F_SHORT:
@@ -632,6 +632,7 @@ void showDebugMenu(void) {
uint8_t idleScreenBGF[sizeof(idleScreenBG)];
/* StartGUITask function */
void startGUITask(void const *argument __unused) {
OLED::initialize(); // start up the LCD
uint8_t tempWarningState = 0;
bool buttonLockout = false;

View File

@@ -23,8 +23,34 @@
uint8_t accelInit = 0;
uint32_t lastMovementTime = 0;
void startMOVTask(void const *argument __unused) {
OLED::setRotation(systemSettings.OrientationMode & 1);
#ifdef ACCEL_MMA
if (MMA8652FC::detect()) {
PCBVersion = 1;
MMA8652FC::initalize(); // this sets up the I2C registers
} else
#endif
#ifdef ACCEL_LIS
if (LIS2DH12::detect()) {
PCBVersion = 2;
// Setup the ST Accelerometer
LIS2DH12::initalize(); // startup the accelerometer
} else
#endif
{
PCBVersion = 3;
systemSettings.SleepTime = 0;
systemSettings.ShutdownTime = 0; // No accel -> disable sleep
systemSettings.sensitivity = 0;
}
postRToSInit();
OLED::setRotation(systemSettings.OrientationMode & 1);
if ((PCBVersion == 1
|| PCBVersion == 2)
&& (systemSettings.autoStartMode == 2
|| systemSettings.autoStartMode == 3))
osDelay(2000);
lastMovementTime = 0;
int16_t datax[MOVFilter] = { 0 };
int16_t datay[MOVFilter] = { 0 };

View File

@@ -20,8 +20,7 @@ TaskHandle_t pidTaskNotification = NULL;
uint32_t currentTempTargetDegC = 0; // Current temperature target in C
/* StartPIDTask function */
void startPIDTask(void const *argument __unused)
{
void startPIDTask(void const *argument __unused) {
/*
* We take the current tip temperature & evaluate the next step for the tip
* control PWM.
@@ -35,27 +34,22 @@ void startPIDTask(void const *argument __unused)
// be over-ridden rapidly
pidTaskNotification = xTaskGetCurrentTaskHandle();
uint32_t PIDTempTarget = 0;
for (;;)
{
for (;;) {
if (ulTaskNotifyTake(pdTRUE, 2000))
{
if (ulTaskNotifyTake(pdTRUE, 2000)) {
// This is a call to block this thread until the ADC does its samples
int32_t x10WattsOut = 0;
// Do the reading here to keep the temp calculations churning along
uint32_t currentTipTempInC = TipThermoModel::getTipInC(true);
PIDTempTarget = currentTempTargetDegC;
if (PIDTempTarget)
{
if (PIDTempTarget) {
// Cap the max set point to 450C
if (PIDTempTarget > (450))
{
if (PIDTempTarget > (450)) {
//Maximum allowed output
PIDTempTarget = (450);
}
//Safety check that not aiming higher than current tip can measure
if (PIDTempTarget > TipThermoModel::getTipMaxInC())
{
if (PIDTempTarget > TipThermoModel::getTipMaxInC()) {
PIDTempTarget = TipThermoModel::getTipMaxInC();
}
// Convert the current tip to degree's C
@@ -95,41 +89,38 @@ void startPIDTask(void const *argument __unused)
// and counters extra power if the iron is no longer losing temp.
// basically: temp - lastTemp
// Unfortunately, our temp signal is too noisy to really help.
}
//If the user turns on the option of using an occasional pulse to keep the power bank on
if (systemSettings.KeepAwakePulse)
{
if (systemSettings.KeepAwakePulse) {
if (xTaskGetTickCount() - lastPowerPulseStart > powerPulseRate)
{
if (xTaskGetTickCount() - lastPowerPulseStart
> powerPulseRate) {
lastPowerPulseStart = xTaskGetTickCount();
lastPowerPulseEnd = lastPowerPulseStart + powerPulseDuration;
lastPowerPulseEnd = lastPowerPulseStart
+ powerPulseDuration;
}
//If current PID is less than the pulse level, check if we want to constrain to the pulse as the floor
if (x10WattsOut < systemSettings.KeepAwakePulse && xTaskGetTickCount() < lastPowerPulseEnd)
{
if (x10WattsOut < systemSettings.KeepAwakePulse
&& xTaskGetTickCount() < lastPowerPulseEnd) {
x10WattsOut = systemSettings.KeepAwakePulse;
}
}
//Secondary safety check to forcefully disable header when within ADC noise of top of ADC
if (getTipRawTemp(0) > (0x7FFF - 150))
{
if (getTipRawTemp(0) > (0x7FFF - 150)) {
x10WattsOut = 0;
}
if (systemSettings.powerLimitEnable && x10WattsOut > (systemSettings.powerLimit * 10))
{
if (systemSettings.powerLimit
&& x10WattsOut > (systemSettings.powerLimit * 10)) {
setTipX10Watts(systemSettings.powerLimit * 10);
}
else
{
} else {
setTipX10Watts(x10WattsOut);
}
resetWatchdog();
}
else
{
} else {
//ADC interrupt timeout
setTipPWM(0);
}