Drop C-style 'void' argument

This commit is contained in:
Scott Lahteine
2019-09-16 20:31:08 -05:00
parent 7d8c38693f
commit f01f0d1956
174 changed files with 864 additions and 864 deletions

View File

@@ -39,15 +39,15 @@ uint16_t HAL_adc_result;
/* VGPV Done with defines
// disable interrupts
void cli(void) { noInterrupts(); }
void cli() { noInterrupts(); }
// enable interrupts
void sei(void) { interrupts(); }
void sei() { interrupts(); }
*/
void HAL_clear_reset_source(void) { __HAL_RCC_CLEAR_RESET_FLAGS(); }
void HAL_clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); }
uint8_t HAL_get_reset_source(void) {
uint8_t HAL_get_reset_source() {
if (__HAL_RCC_GET_FLAG(RCC_FLAG_IWDGRST) != RESET) return RST_WATCHDOG;
if (__HAL_RCC_GET_FLAG(RCC_FLAG_SFTRST) != RESET) return RST_SOFTWARE;
if (__HAL_RCC_GET_FLAG(RCC_FLAG_PINRST) != RESET) return RST_EXTERNAL;
@@ -91,6 +91,6 @@ extern "C" {
void HAL_adc_start_conversion(const uint8_t adc_pin) { HAL_adc_result = analogRead(adc_pin); }
uint16_t HAL_adc_get_result(void) { return HAL_adc_result; }
uint16_t HAL_adc_get_result() { return HAL_adc_result; }
#endif // STM32GENERIC && (STM32F4 || STM32F7)

View File

@@ -150,19 +150,19 @@ extern uint16_t HAL_adc_result;
// Memory related
#define __bss_end __bss_end__
inline void HAL_init(void) { }
inline void HAL_init() { }
// Clear reset reason
void HAL_clear_reset_source(void);
void HAL_clear_reset_source();
// Reset reason
uint8_t HAL_get_reset_source(void);
uint8_t HAL_get_reset_source();
void _delay_ms(const int delay);
/*
extern "C" {
int freeMemory(void);
int freeMemory();
}
*/
@@ -179,7 +179,7 @@ int freeMemory() {
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-function"
static inline int freeMemory(void) {
static inline int freeMemory() {
volatile char top;
return &top - reinterpret_cast<char*>(_sbrk(0));
}
@@ -205,14 +205,14 @@ void eeprom_update_block (const void *__src, void *__dst, size_t __n);
#define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT)
inline void HAL_adc_init(void) {}
inline void HAL_adc_init() {}
#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
#define HAL_READ_ADC() HAL_adc_result
#define HAL_ADC_READY() true
void HAL_adc_start_conversion(const uint8_t adc_pin);
uint16_t HAL_adc_get_result(void);
uint16_t HAL_adc_get_result();
#define GET_PIN_MAP_PIN(index) index
#define GET_PIN_MAP_INDEX(pin) pin

View File

@@ -71,7 +71,7 @@ static SPISettings spiConfig;
*
* @details Only configures SS pin since libmaple creates and initialize the SPI object
*/
void spiBegin(void) {
void spiBegin() {
#if !defined(SS_PIN) || SS_PIN < 0
#error SS_PIN not defined!
#endif
@@ -103,7 +103,7 @@ void spiInit(uint8_t spiRate) {
*
* @details
*/
uint8_t spiRec(void) {
uint8_t spiRec() {
SPI.beginTransaction(spiConfig);
uint8_t returnByte = SPI.transfer(0xFF);
SPI.endTransaction();

View File

@@ -82,10 +82,10 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
}
extern "C" void TIM5_IRQHandler() {
((void(*)(void))TimerHandle[0].callback)();
((void(*)())TimerHandle[0].callback)();
}
extern "C" void TIM7_IRQHandler() {
((void(*)(void))TimerHandle[1].callback)();
((void(*)())TimerHandle[1].callback)();
}
void HAL_timer_enable_interrupt(const uint8_t timer_num) {

View File

@@ -226,7 +226,7 @@ void TMC26XStepper::setSpeed(uint16_t whatSpeed) {
this->next_step_time = this->last_step_time + this->step_delay;
}
uint16_t TMC26XStepper::getSpeed(void) { return this->speed; }
uint16_t TMC26XStepper::getSpeed() { return this->speed; }
/**
* Moves the motor steps_to_move steps.
@@ -246,7 +246,7 @@ char TMC26XStepper::step(int16_t steps_to_move) {
return -1;
}
char TMC26XStepper::move(void) {
char TMC26XStepper::move() {
// decrement the number of steps, moving one step each time:
if (this->steps_left > 0) {
uint32_t time = micros();
@@ -277,11 +277,11 @@ char TMC26XStepper::move(void) {
return 0;
}
char TMC26XStepper::isMoving(void) { return this->steps_left > 0; }
char TMC26XStepper::isMoving() { return this->steps_left > 0; }
uint16_t TMC26XStepper::getStepsLeft(void) { return this->steps_left; }
uint16_t TMC26XStepper::getStepsLeft() { return this->steps_left; }
char TMC26XStepper::stop(void) {
char TMC26XStepper::stop() {
//note to self if the motor is currently moving
char state = isMoving();
//stop the motor
@@ -334,7 +334,7 @@ void TMC26XStepper::setCurrent(uint16_t current) {
}
}
uint16_t TMC26XStepper::getCurrent(void) {
uint16_t TMC26XStepper::getCurrent() {
// Calculate the current according to the datasheet to be on the safe side.
// This is not the fastest but the most accurate and illustrative way.
float result = (float)(stallguard2_current_register_value & CURRENT_SCALING_PATTERN),
@@ -361,7 +361,7 @@ void TMC26XStepper::setStallGuardThreshold(char stallguard_threshold, char stall
if (started) send262(stallguard2_current_register_value);
}
char TMC26XStepper::getStallGuardThreshold(void) {
char TMC26XStepper::getStallGuardThreshold() {
uint32_t stallguard_threshold = stallguard2_current_register_value & STALL_GUARD_VALUE_PATTERN;
//shift it down to bit 0
stallguard_threshold >>= 8;
@@ -374,7 +374,7 @@ char TMC26XStepper::getStallGuardThreshold(void) {
return result;
}
char TMC26XStepper::getStallGuardFilter(void) {
char TMC26XStepper::getStallGuardFilter() {
if (stallguard2_current_register_value & STALL_GUARD_FILTER_ENABLED)
return -1;
return 0;
@@ -421,7 +421,7 @@ void TMC26XStepper::setMicrosteps(const int16_t in_steps) {
/**
* returns the effective number of microsteps at the moment
*/
int16_t TMC26XStepper::getMicrosteps(void) { return microsteps; }
int16_t TMC26XStepper::getMicrosteps() { return microsteps; }
/**
* constant_off_time: The off time setting controls the minimum chopper frequency.
@@ -623,7 +623,7 @@ void TMC26XStepper::setCoolStepEnabled(boolean enabled) {
if (started) send262(cool_step_register_value);
}
boolean TMC26XStepper::isCoolStepEnabled(void) { return this->cool_step_enabled; }
boolean TMC26XStepper::isCoolStepEnabled() { return this->cool_step_enabled; }
uint16_t TMC26XStepper::getCoolStepLowerSgThreshold() {
// We return our internally stored value - in order to provide the correct setting even if cool step is not enabled
@@ -684,7 +684,7 @@ void TMC26XStepper::readStatus(char read_value) {
send262(driver_configuration_register_value);
}
int16_t TMC26XStepper::getMotorPosition(void) {
int16_t TMC26XStepper::getMotorPosition() {
//we read it out even if we are not started yet - perhaps it is useful information for somebody
readStatus(TMC26X_READOUT_POSITION);
return getReadoutValue();
@@ -692,7 +692,7 @@ int16_t TMC26XStepper::getMotorPosition(void) {
//reads the StallGuard setting from last status
//returns -1 if StallGuard information is not present
int16_t TMC26XStepper::getCurrentStallGuardReading(void) {
int16_t TMC26XStepper::getCurrentStallGuardReading() {
//if we don't yet started there cannot be a StallGuard value
if (!started) return -1;
//not time optimal, but solution optiomal:
@@ -701,7 +701,7 @@ int16_t TMC26XStepper::getCurrentStallGuardReading(void) {
return getReadoutValue();
}
uint8_t TMC26XStepper::getCurrentCSReading(void) {
uint8_t TMC26XStepper::getCurrentCSReading() {
//if we don't yet started there cannot be a StallGuard value
if (!started) return 0;
//not time optimal, but solution optiomal:
@@ -710,7 +710,7 @@ uint8_t TMC26XStepper::getCurrentCSReading(void) {
return (getReadoutValue() & 0x1F);
}
uint16_t TMC26XStepper::getCurrentCurrent(void) {
uint16_t TMC26XStepper::getCurrentCurrent() {
float result = (float)getCurrentCSReading(),
resistor_value = (float)this->resistor,
voltage = (driver_configuration_register_value & VSENSE)? 0.165 : 0.31;
@@ -721,7 +721,7 @@ uint16_t TMC26XStepper::getCurrentCurrent(void) {
/**
* Return true if the StallGuard threshold has been reached
*/
boolean TMC26XStepper::isStallGuardOverThreshold(void) {
boolean TMC26XStepper::isStallGuardOverThreshold() {
if (!this->started) return false;
return (driver_status_result & STATUS_STALL_GUARD_STATUS);
}
@@ -732,7 +732,7 @@ boolean TMC26XStepper::isStallGuardOverThreshold(void) {
* OVER_TEMPERATURE_SHUTDOWN if the temperature is so hot that the driver is shut down
* Any of those levels are not too good.
*/
char TMC26XStepper::getOverTemperature(void) {
char TMC26XStepper::getOverTemperature() {
if (!this->started) return 0;
if (driver_status_result & STATUS_OVER_TEMPERATURE_SHUTDOWN)
@@ -745,44 +745,44 @@ char TMC26XStepper::getOverTemperature(void) {
}
// Is motor channel A shorted to ground
boolean TMC26XStepper::isShortToGroundA(void) {
boolean TMC26XStepper::isShortToGroundA() {
if (!this->started) return false;
return (driver_status_result & STATUS_SHORT_TO_GROUND_A);
}
// Is motor channel B shorted to ground
boolean TMC26XStepper::isShortToGroundB(void) {
boolean TMC26XStepper::isShortToGroundB() {
if (!this->started) return false;
return (driver_status_result & STATUS_SHORT_TO_GROUND_B);
}
// Is motor channel A connected
boolean TMC26XStepper::isOpenLoadA(void) {
boolean TMC26XStepper::isOpenLoadA() {
if (!this->started) return false;
return (driver_status_result & STATUS_OPEN_LOAD_A);
}
// Is motor channel B connected
boolean TMC26XStepper::isOpenLoadB(void) {
boolean TMC26XStepper::isOpenLoadB() {
if (!this->started) return false;
return (driver_status_result & STATUS_OPEN_LOAD_B);
}
// Is chopper inactive since 2^20 clock cycles - defaults to ~0,08s
boolean TMC26XStepper::isStandStill(void) {
boolean TMC26XStepper::isStandStill() {
if (!this->started) return false;
return (driver_status_result & STATUS_STAND_STILL);
}
//is chopper inactive since 2^20 clock cycles - defaults to ~0,08s
boolean TMC26XStepper::isStallGuardReached(void) {
boolean TMC26XStepper::isStallGuardReached() {
if (!this->started) return false;
return (driver_status_result & STATUS_STALL_GUARD_STATUS);
}
//reads the StallGuard setting from last status
//returns -1 if StallGuard information is not present
int16_t TMC26XStepper::getReadoutValue(void) {
int16_t TMC26XStepper::getReadoutValue() {
return (int)(driver_status_result >> 10);
}
@@ -794,7 +794,7 @@ boolean TMC26XStepper::isCurrentScalingHalfed() {
/**
* version() returns the version of the library:
*/
int16_t TMC26XStepper::version(void) { return 1; }
int16_t TMC26XStepper::version() { return 1; }
void TMC26XStepper::debugLastStatus() {
#ifdef TMC_DEBUG1

View File

@@ -150,7 +150,7 @@ class TMC26XStepper {
* \brief Report the currently selected speed in RPM.
* \sa setSpeed()
*/
uint16_t getSpeed(void);
uint16_t getSpeed();
/*!
* \brief Set the number of microsteps in 2^i values (rounded) up to 256
@@ -170,7 +170,7 @@ class TMC26XStepper {
*
* \sa setMicrosteps()
*/
int16_t getMicrosteps(void);
int16_t getMicrosteps();
/*!
* \brief Initiate a movement with the given number of steps. Positive values move in one direction, negative in the other.
@@ -204,7 +204,7 @@ class TMC26XStepper {
* It is recommended to call this using a hardware timer to ensure regular invocation.
* \sa step()
*/
char move(void);
char move();
/*!
* \brief Check whether the last movement command is done.
@@ -213,13 +213,13 @@ class TMC26XStepper {
* Used to determine if the motor is ready for new movements.
*\sa step(), move()
*/
char isMoving(void);
char isMoving();
/*!
* \brief Get the number of steps left in the current movement.
* \return The number of steps left in the movement. Always positive.
*/
uint16_t getStepsLeft(void);
uint16_t getStepsLeft();
/*!
* \brief Stop the motor immediately.
@@ -227,7 +227,7 @@ class TMC26XStepper {
*
* This method directly and abruptly stops the motor and may be used as an emergency stop.
*/
char stop(void);
char stop();
/*!
* \brief Set and configure the classical Constant Off Timer Chopper
@@ -309,7 +309,7 @@ class TMC26XStepper {
* \return the maximum motor current in milli amps
* \sa getCurrentCurrent()
*/
uint16_t getCurrent(void);
uint16_t getCurrent();
/*!
* \brief set the StallGuard threshold in order to get sensible StallGuard readings.
@@ -332,13 +332,13 @@ class TMC26XStepper {
* \brief reads out the StallGuard threshold
* \return a number between -64 and 63.
*/
char getStallGuardThreshold(void);
char getStallGuardThreshold();
/*!
* \brief returns the current setting of the StallGuard filter
* \return 0 if not set, -1 if set
*/
char getStallGuardFilter(void);
char getStallGuardFilter();
/*!
* \brief This method configures the CoolStep smart energy operation. You must have a proper StallGuard configuration for the motor situation (current, voltage, speed) in rder to use this feature.
@@ -411,7 +411,7 @@ class TMC26XStepper {
*
* Keep in mind that this routine reads and writes a value via SPI - so this may take a bit time.
*/
int16_t getMotorPosition(void);
int16_t getMotorPosition();
/*!
* \brief Reads the current StallGuard value.
@@ -419,14 +419,14 @@ class TMC26XStepper {
* Keep in mind that this routine reads and writes a value via SPI - so this may take a bit time.
* \sa setStallGuardThreshold() for tuning the readout to sensible ranges.
*/
int16_t getCurrentStallGuardReading(void);
int16_t getCurrentStallGuardReading();
/*!
* \brief Reads the current current setting value as fraction of the maximum current
* Returns values between 0 and 31, representing 1/32 to 32/32 (=1)
* \sa setCoolStepConfiguration()
*/
uint8_t getCurrentCSReading(void);
uint8_t getCurrentCSReading();
/*!
@@ -442,7 +442,7 @@ class TMC26XStepper {
* may not be the fastest.
* \sa getCurrentCSReading(), getResistor(), isCurrentScalingHalfed(), getCurrent()
*/
uint16_t getCurrentCurrent(void);
uint16_t getCurrentCurrent();
/*!
* \brief checks if there is a StallGuard warning in the last status
@@ -452,7 +452,7 @@ class TMC26XStepper {
*
* \sa setStallGuardThreshold() for tuning the readout to sensible ranges.
*/
boolean isStallGuardOverThreshold(void);
boolean isStallGuardOverThreshold();
/*!
* \brief Return over temperature status of the last status readout
@@ -460,7 +460,7 @@ class TMC26XStepper {
* Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
* You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
*/
char getOverTemperature(void);
char getOverTemperature();
/*!
* \brief Is motor channel A shorted to ground detected in the last status readout.
@@ -469,7 +469,7 @@ class TMC26XStepper {
* You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
*/
boolean isShortToGroundA(void);
boolean isShortToGroundA();
/*!
* \brief Is motor channel B shorted to ground detected in the last status readout.
@@ -477,14 +477,14 @@ class TMC26XStepper {
* Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
* You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
*/
boolean isShortToGroundB(void);
boolean isShortToGroundB();
/*!
* \brief iIs motor channel A connected according to the last statu readout.
* \return true is yes, false if not.
* Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
* You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
*/
boolean isOpenLoadA(void);
boolean isOpenLoadA();
/*!
* \brief iIs motor channel A connected according to the last statu readout.
@@ -492,7 +492,7 @@ class TMC26XStepper {
* Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
* You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
*/
boolean isOpenLoadB(void);
boolean isOpenLoadB();
/*!
* \brief Is chopper inactive since 2^20 clock cycles - defaults to ~0,08s
@@ -500,7 +500,7 @@ class TMC26XStepper {
* Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
* You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
*/
boolean isStandStill(void);
boolean isStandStill();
/*!
* \brief checks if there is a StallGuard warning in the last status
@@ -513,7 +513,7 @@ class TMC26XStepper {
*
* \sa setStallGuardThreshold() for tuning the readout to sensible ranges.
*/
boolean isStallGuardReached(void);
boolean isStallGuardReached();
/*!
*\brief enables or disables the motor driver bridges. If disabled the motor can run freely. If enabled not.
@@ -549,13 +549,13 @@ class TMC26XStepper {
* \brief Prints out all the information that can be found in the last status read out - it does not force a status readout.
* The result is printed via Serial
*/
void debugLastStatus(void);
void debugLastStatus();
/*!
* \brief library version
* \return the version number as int.
*/
int16_t version(void);
int16_t version();
private:
uint16_t steps_left; // The steps the motor has to do to complete the movement

View File

@@ -86,10 +86,10 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
//forward the interrupt
extern "C" void TIM5_IRQHandler() {
((void(*)(void))timerConfig[0].callback)();
((void(*)())timerConfig[0].callback)();
}
extern "C" void TIM7_IRQHandler() {
((void(*)(void))timerConfig[1].callback)();
((void(*)())timerConfig[1].callback)();
}
void HAL_timer_set_compare(const uint8_t timer_num, const uint32_t compare) {

View File

@@ -62,7 +62,7 @@ uint16_t VirtAddVarTab[NB_OF_VAR];
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
static HAL_StatusTypeDef EE_Format(void);
static HAL_StatusTypeDef EE_Format();
static uint16_t EE_FindValidPage(uint8_t Operation);
static uint16_t EE_VerifyPageFullWriteVariable(uint16_t VirtAddress, uint16_t Data);
static uint16_t EE_PageTransfer(uint16_t VirtAddress, uint16_t Data);
@@ -75,7 +75,7 @@ static uint16_t EE_VerifyPageFullyErased(uint32_t Address);
* @retval - Flash error code: on write Flash error
* - FLASH_COMPLETE: on success
*/
uint16_t EE_Initialize(void) {
uint16_t EE_Initialize() {
/* Get Page0 and Page1 status */
uint16_t PageStatus0 = (*(__IO uint16_t*)PAGE0_BASE_ADDRESS),
PageStatus1 = (*(__IO uint16_t*)PAGE1_BASE_ADDRESS);
@@ -331,7 +331,7 @@ uint16_t EE_WriteVariable(uint16_t VirtAddress, uint16_t Data) {
* @retval Status of the last operation (Flash write or erase) done during
* EEPROM formating
*/
static HAL_StatusTypeDef EE_Format(void) {
static HAL_StatusTypeDef EE_Format() {
FLASH_EraseInitTypeDef pEraseInit;
pEraseInit.TypeErase = FLASH_TYPEERASE_SECTORS;
pEraseInit.Sector = PAGE0_ID;

View File

@@ -108,7 +108,7 @@
#define NB_OF_VAR uint16_t(4096)
/* Exported functions ------------------------------------------------------- */
uint16_t EE_Initialize(void);
uint16_t EE_Initialize();
uint16_t EE_ReadVariable(uint16_t VirtAddress, uint16_t* Data);
uint16_t EE_WriteVariable(uint16_t VirtAddress, uint16_t Data);

View File

@@ -25,9 +25,9 @@
#include "../../module/endstops.h"
// One ISR for all EXT-Interrupts
void endstop_ISR(void) { endstops.update(); }
void endstop_ISR() { endstops.update(); }
void setup_endstop_interrupts(void) {
void setup_endstop_interrupts() {
#if HAS_X_MAX
attachInterrupt(X_MAX_PIN, endstop_ISR, CHANGE);
#endif