Prusa MINI Firmware overview
hwio_a3ides_2209_02.c File Reference
#include "hwio_a3ides.h"
#include <inttypes.h>
#include "config.h"
#include "stm32f4xx_hal.h"
#include "cmsis_os.h"
#include "gpio.h"
#include "adc.h"
#include "sim_nozzle.h"
#include "sim_bed.h"
#include "sim_motion.h"
#include "Arduino.h"
#include "timer_defaults.h"
#include "hwio_pindef.h"
#include "filament_sensor.h"
#include "bsod.h"

Macros

#define HWIO_ERR_UNINI_DIG_RD   0x01
 
#define HWIO_ERR_UNINI_DIG_WR   0x02
 
#define HWIO_ERR_UNINI_ANA_RD   0x03
 
#define HWIO_ERR_UNINI_ANA_WR   0x04
 
#define HWIO_ERR_UNDEF_DIG_RD   0x05
 
#define HWIO_ERR_UNDEF_DIG_WR   0x06
 
#define HWIO_ERR_UNDEF_ANA_RD   0x07
 
#define HWIO_ERR_UNDEF_ANA_WR   0x08
 
#define _DI_CNT   (sizeof(_di_pin32) / sizeof(uint32_t))
 
#define _DO_CNT   (sizeof(_do_pin32) / sizeof(uint32_t))
 
#define _ADC_CNT   (sizeof(_adc_pin32) / sizeof(uint32_t))
 
#define _DAC_CNT   (sizeof(_dac_pin32) / sizeof(uint32_t))
 
#define _FAN_ID_MIN   HWIO_PWM_FAN1
 
#define _FAN_ID_MAX   HWIO_PWM_FAN
 
#define _FAN_CNT   (_FAN_ID_MAX - _FAN_ID_MIN + 1)
 
#define _HEATER_ID_MIN   HWIO_PWM_HEATER_BED
 
#define _HEATER_ID_MAX   HWIO_PWM_HEATER_0
 
#define _HEATER_CNT   (_HEATER_ID_MAX - _HEATER_ID_MIN + 1)
 
#define _PWM_CNT   (sizeof(_pwm_pin32) / sizeof(uint32_t))
 

Functions

void Error_Handler (void)
 This function is executed in case of error occurrence. More...
 
void __pwm_set_val (TIM_HandleTypeDef *htim, uint32_t chan, int val)
 
void _hwio_pwm_analogWrite_set_val (int i_pwm, int val)
 
void _hwio_pwm_set_val (int i_pwm, int val)
 
uint32_t _pwm_get_chan (int i_pwm)
 
TIM_HandleTypeDef_pwm_get_htim (int i_pwm)
 
int is_pwm_id_valid (int i_pwm)
 
int hwio_di_get_cnt (void)
 
int hwio_di_get_val (int i_di)
 
int hwio_do_get_cnt (void)
 
int hwio_do_get_val (int i_do)
 
void hwio_do_set_val (int i_do, int val)
 
int hwio_adc_get_cnt (void)
 
int hwio_adc_get_max (int i_adc)
 
int hwio_adc_get_val (int i_adc)
 
int hwio_dac_get_cnt (void)
 
int hwio_dac_get_max (int i_dac)
 
void hwio_dac_set_val (int i_dac, int val)
 
int hwio_pwm_get_cnt (void)
 
int hwio_pwm_get_max (int i_pwm)
 
void hwio_pwm_set_period_us (int i_pwm, int T_us)
 
int hwio_pwm_get_period_us (int i_pwm)
 
void hwio_pwm_set_prescaler (int i_pwm, int prescaler)
 
int hwio_pwm_get_prescaler (int i_pwm)
 
void hwio_pwm_set_prescaler_exp2 (int i_pwm, int exp)
 
int hwio_pwm_get_prescaler_log2 (int i_pwm)
 
void hwio_pwm_set_val (int i_pwm, int val)
 
int hwio_fan_get_cnt (void)
 
void hwio_fan_set_pwm (int i_fan, int val)
 
int hwio_heater_get_cnt (void)
 
void hwio_heater_set_pwm (int i_heater, int val)
 
void hwio_jogwheel_enable (void)
 
void hwio_jogwheel_disable (void)
 
float hwio_beeper_get_vol (void)
 
void hwio_beeper_set_vol (float vol)
 
void hwio_beeper_set_pwm (uint32_t per, uint32_t pul)
 
void hwio_beeper_tone (float frq, uint32_t del)
 
void hwio_beeper_tone2 (float frq, uint32_t del, float vol)
 
void hwio_beeper_notone (void)
 
void hwio_update_1ms (void)
 
void adc_ready (uint8_t index)
 
uint8_t adc_seq2idx (uint8_t seq)
 
void hwio_arduino_error (int err, uint32_t pin32)
 
int hwio_arduino_digitalRead (uint32_t ulPin)
 
void hwio_arduino_digitalWrite (uint32_t ulPin, uint32_t ulVal)
 
void hwio_arduino_digitalToggle (uint32_t ulPin)
 
uint32_t hwio_arduino_analogRead (uint32_t ulPin)
 
void hwio_arduino_analogWrite (uint32_t ulPin, uint32_t ulValue)
 
void hwio_arduino_pinMode (uint32_t ulPin, uint32_t ulMode)
 

Variables

int HAL_GPIO_Initialized
 
int HAL_ADC_Initialized
 
int HAL_PWM_Initialized
 
TIM_HandleTypeDef htim1
 
TIM_HandleTypeDef htim2
 
TIM_HandleTypeDef htim3
 
const uint32_t _di_pin32 []
 
const uint32_t _do_pin32 []
 
const uint32_t _adc_pin32 []
 
const int _adc_max [] = { 4095, 4095, 4095, 4095, 4095 }
 
int _adc_val [] = { 0, 0, 0, 0, 0 }
 
const uint32_t _dac_pin32 [] = {}
 
const int _dac_max [] = { 0 }
 
int _tim1_period_us = GEN_PERIOD_US(TIM1_default_Prescaler, TIM1_default_Period)
 
int _tim3_period_us = GEN_PERIOD_US(TIM3_default_Prescaler, TIM3_default_Period)
 
const uint32_t _pwm_pin32 []
 
const uint32_t _pwm_chan []
 
TIM_HandleTypeDef_pwm_p_htim []
 
int *const _pwm_period_us []
 
const int _pwm_max [] = { TIM3_default_Period, TIM3_default_Period, TIM1_default_Period, TIM1_default_Period }
 
const TIM_OC_InitTypeDef sConfigOC_default
 
const int _pwm_analogWrite_max [_PWM_CNT] = { 0xff, 0xff, 0xff, 0xff }
 
int _pwm_analogWrite_val [_PWM_CNT] = { 0, 0, 0, 0 }
 
const int * _fan_max = &_pwm_analogWrite_max[_FAN_ID_MIN]
 
int * _fan_val = &_pwm_analogWrite_val[_FAN_ID_MIN]
 
const int * _heater_max = &_pwm_analogWrite_max[_HEATER_ID_MIN]
 
int * _heater_val = &_pwm_analogWrite_val[_HEATER_ID_MIN]
 
int hwio_jogwheel_enabled = 0
 
float hwio_beeper_vol = 1.0F
 
uint32_t hwio_beeper_del = 0
 
const uint8_t adc_seq [18] = { 4, 1, 4, 1, 4, 0, 4, 1, 4, 1, 4, 2, 4, 1, 4, 1, 4, 3 }
 

Macro Definition Documentation

◆ HWIO_ERR_UNINI_DIG_RD

#define HWIO_ERR_UNINI_DIG_RD   0x01

◆ HWIO_ERR_UNINI_DIG_WR

#define HWIO_ERR_UNINI_DIG_WR   0x02

◆ HWIO_ERR_UNINI_ANA_RD

#define HWIO_ERR_UNINI_ANA_RD   0x03

◆ HWIO_ERR_UNINI_ANA_WR

#define HWIO_ERR_UNINI_ANA_WR   0x04

◆ HWIO_ERR_UNDEF_DIG_RD

#define HWIO_ERR_UNDEF_DIG_RD   0x05

◆ HWIO_ERR_UNDEF_DIG_WR

#define HWIO_ERR_UNDEF_DIG_WR   0x06

◆ HWIO_ERR_UNDEF_ANA_RD

#define HWIO_ERR_UNDEF_ANA_RD   0x07

◆ HWIO_ERR_UNDEF_ANA_WR

#define HWIO_ERR_UNDEF_ANA_WR   0x08

◆ _DI_CNT

#define _DI_CNT   (sizeof(_di_pin32) / sizeof(uint32_t))

◆ _DO_CNT

#define _DO_CNT   (sizeof(_do_pin32) / sizeof(uint32_t))

◆ _ADC_CNT

#define _ADC_CNT   (sizeof(_adc_pin32) / sizeof(uint32_t))

◆ _DAC_CNT

#define _DAC_CNT   (sizeof(_dac_pin32) / sizeof(uint32_t))

◆ _FAN_ID_MIN

#define _FAN_ID_MIN   HWIO_PWM_FAN1

◆ _FAN_ID_MAX

#define _FAN_ID_MAX   HWIO_PWM_FAN

◆ _FAN_CNT

#define _FAN_CNT   (_FAN_ID_MAX - _FAN_ID_MIN + 1)

◆ _HEATER_ID_MIN

#define _HEATER_ID_MIN   HWIO_PWM_HEATER_BED

◆ _HEATER_ID_MAX

#define _HEATER_ID_MAX   HWIO_PWM_HEATER_0

◆ _HEATER_CNT

#define _HEATER_CNT   (_HEATER_ID_MAX - _HEATER_ID_MIN + 1)

◆ _PWM_CNT

#define _PWM_CNT   (sizeof(_pwm_pin32) / sizeof(uint32_t))

Function Documentation

◆ Error_Handler()

void Error_Handler ( void  )

This function is executed in case of error occurrence.

Return values
None
1057  {
1058  /* USER CODE BEGIN Error_Handler_Debug */
1059  /* User can add his own implementation to report the HAL error return state */
1060  app_error();
1061  /* USER CODE END Error_Handler_Debug */
1062 }
Here is the caller graph for this function:

◆ __pwm_set_val()

void __pwm_set_val ( TIM_HandleTypeDef htim,
uint32_t  chan,
int  val 
)
410 {
411  if (htim->Init.Period) {
413  if (val)
414  sConfigOC.Pulse = val;
415  else {
416  sConfigOC.Pulse = htim->Init.Period;
417  if (sConfigOC.OCPolarity == TIM_OCPOLARITY_HIGH)
418  sConfigOC.OCPolarity = TIM_OCPOLARITY_LOW;
419  else
420  sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH;
421  }
422  if (HAL_TIM_PWM_ConfigChannel(htim, &sConfigOC, pchan) != HAL_OK) {
423  Error_Handler();
424  }
425  HAL_TIM_PWM_Start(htim, pchan);
426  } else
427  HAL_TIM_PWM_Stop(htim, pchan);
Here is the call graph for this function:
Here is the caller graph for this function:

◆ _hwio_pwm_analogWrite_set_val()

void _hwio_pwm_analogWrite_set_val ( int  i_pwm,
int  val 
)
430  {
431  if (!is_pwm_id_valid(i_pwm))
432  return;
433 
434  if (_pwm_analogWrite_val[i_pwm] != val) {
435  int32_t pwm_max = hwio_pwm_get_max(i_pwm);
436  uint32_t pulse = (val * pwm_max) / _pwm_analogWrite_max[i_pwm];
437  hwio_pwm_set_val(i_pwm, pulse);
438  _pwm_analogWrite_val[i_pwm] = val;
439  }
Here is the call graph for this function:
Here is the caller graph for this function:

◆ _hwio_pwm_set_val()

void _hwio_pwm_set_val ( int  i_pwm,
int  val 
)
399 {
400  uint32_t chan = _pwm_get_chan(i_pwm);
401  TIM_HandleTypeDef *htim = _pwm_get_htim(i_pwm);
402  if ((chan == -1) || htim->Instance == 0) {
403  return;
404  }
405 
406  __pwm_set_val(htim, chan, val);
Here is the call graph for this function:
Here is the caller graph for this function:

◆ _pwm_get_chan()

uint32_t _pwm_get_chan ( int  i_pwm)
364  {
365  if (!is_pwm_id_valid(i_pwm))
366  return -1;
367  return _pwm_chan[i_pwm];
Here is the call graph for this function:
Here is the caller graph for this function:

◆ _pwm_get_htim()

TIM_HandleTypeDef * _pwm_get_htim ( int  i_pwm)
370  {
371  if (!is_pwm_id_valid(i_pwm))
372  i_pwm = 0;
373 
374  return _pwm_p_htim[i_pwm];
Here is the call graph for this function:
Here is the caller graph for this function:

◆ is_pwm_id_valid()

int is_pwm_id_valid ( int  i_pwm)
270  {
271  return ((i_pwm >= 0) && (i_pwm < _PWM_CNT));
Here is the caller graph for this function:

◆ hwio_di_get_cnt()

int hwio_di_get_cnt ( void  )
195 { return _DI_CNT; }

◆ hwio_di_get_val()

int hwio_di_get_val ( int  i_di)
198 {
199  if ((i_di >= 0) && (i_di < _DI_CNT))
200  return gpio_get(_di_pin32[i_di]);
201  /* {
202  uint32_t pin32 = ;
203  GPIO_TypeDef* gpio = (GPIO_TypeDef*)_gpio[pin32 >> 4];
204  uint16_t msk = (1 << (pin32 & 0x0f));
205  return HAL_GPIO_ReadPin(gpio, msk)?1:0;
206  }*/
207  //else //TODO: check
208  return 0;
Here is the call graph for this function:
Here is the caller graph for this function:

◆ hwio_do_get_cnt()

int hwio_do_get_cnt ( void  )
215 { return _DO_CNT; }

◆ hwio_do_get_val()

int hwio_do_get_val ( int  i_do)
218 {
219  if ((i_do >= 0) && (i_do < _DO_CNT))
220  return gpio_get(_do_pin32[i_do]);
221  return INT32_MAX; // undefined state
Here is the call graph for this function:
Here is the caller graph for this function:

◆ hwio_do_set_val()

void hwio_do_set_val ( int  i_do,
int  val 
)
225 {
226  if ((i_do >= 0) && (i_do < _DO_CNT))
227  gpio_set(_do_pin32[i_do], val);
228  /* {
229  uint32_t pin32 = _do_pin32[i_do];
230  GPIO_TypeDef* gpio = (GPIO_TypeDef*)_gpio[pin32 >> 4];
231  uint16_t msk = (1 << (pin32 & 0x0f));
232  HAL_GPIO_WritePin(gpio, msk, val?GPIO_PIN_SET:GPIO_PIN_RESET);
233  }*/
234  //else //TODO: check
Here is the call graph for this function:
Here is the caller graph for this function:

◆ hwio_adc_get_cnt()

int hwio_adc_get_cnt ( void  )
241 { return _ADC_CNT; }

◆ hwio_adc_get_max()

int hwio_adc_get_max ( int  i_adc)
244 { return _adc_max[i_adc]; }

◆ hwio_adc_get_val()

int hwio_adc_get_val ( int  i_adc)
247 {
248  if ((i_adc >= 0) && (i_adc < _ADC_CNT))
249  return _adc_val[i_adc];
250  //else //TODO: check
251  return 0;
Here is the caller graph for this function:

◆ hwio_dac_get_cnt()

int hwio_dac_get_cnt ( void  )
258 { return _DAC_CNT; }

◆ hwio_dac_get_max()

int hwio_dac_get_max ( int  i_dac)
261 { return _dac_max[i_dac]; }

◆ hwio_dac_set_val()

void hwio_dac_set_val ( int  i_dac,
int  val 
)
264 {

◆ hwio_pwm_get_cnt()

int hwio_pwm_get_cnt ( void  )
275 { return _PWM_CNT; }

◆ hwio_pwm_get_max()

int hwio_pwm_get_max ( int  i_pwm)
278 {
279  if (!is_pwm_id_valid(i_pwm))
280  return -1;
281  return _pwm_max[i_pwm];
Here is the call graph for this function:
Here is the caller graph for this function:

◆ hwio_pwm_set_period_us()

void hwio_pwm_set_period_us ( int  i_pwm,
int  T_us 
)
287 {
288  if (!is_pwm_id_valid(i_pwm))
289  return;
290  int *ptr_period_us = _pwm_period_us[i_pwm];
291 
292  if (T_us == *ptr_period_us)
293  return;
294 
295  int prescaler = T_us * (int32_t)TIM_BASE_CLK_MHZ / (_pwm_max[i_pwm] + 1) - 1;
296  hwio_pwm_set_prescaler(i_pwm, prescaler);
297  //actualize seconds
298  *ptr_period_us = T_us;
Here is the call graph for this function:

◆ hwio_pwm_get_period_us()

int hwio_pwm_get_period_us ( int  i_pwm)
301  {
302  if (!is_pwm_id_valid(i_pwm))
303  return -1;
304  return *_pwm_period_us[i_pwm];
Here is the call graph for this function:

◆ hwio_pwm_set_prescaler()

void hwio_pwm_set_prescaler ( int  i_pwm,
int  prescaler 
)
307  {
308  if (hwio_pwm_get_prescaler(i_pwm) == prescaler)
309  return;
310 
311  TIM_HandleTypeDef *htim = _pwm_get_htim(i_pwm);
312 
313  //uint32_t chan = _pwm_get_chan(i_pwm);
314  //uint32_t cmp = __HAL_TIM_GET_COMPARE(htim,chan);
315 
316  htim->Init.Prescaler = prescaler;
317  //__pwm_set_val(htim, chan, cmp);
318 
319  __HAL_TIM_SET_PRESCALER(htim, prescaler);
320 
321  //calculate micro seconds
322  int T_us = GEN_PERIOD_US(prescaler, htim->Init.Period);
323  //actualize micro
324  int *ptr_period_us = _pwm_period_us[i_pwm];
325  *ptr_period_us = T_us;
Here is the call graph for this function:
Here is the caller graph for this function:

◆ hwio_pwm_get_prescaler()

int hwio_pwm_get_prescaler ( int  i_pwm)
328  {
329  if (!is_pwm_id_valid(i_pwm))
330  return -1;
331  TIM_HandleTypeDef *htim = _pwm_get_htim(i_pwm);
332  return htim->Init.Prescaler;
Here is the call graph for this function:
Here is the caller graph for this function:

◆ hwio_pwm_set_prescaler_exp2()

void hwio_pwm_set_prescaler_exp2 ( int  i_pwm,
int  exp 
)
344  {
345  uint32_t prescaler = (1 << (exp)) - 1;
346  hwio_pwm_set_prescaler(i_pwm, prescaler);
Here is the call graph for this function:
Here is the caller graph for this function:

◆ hwio_pwm_get_prescaler_log2()

int hwio_pwm_get_prescaler_log2 ( int  i_pwm)
350  {
351  if (!is_pwm_id_valid(i_pwm))
352  return -1;
353  uint32_t prescaler = hwio_pwm_get_prescaler(i_pwm) + 1;
354  int index = 0;
355 
356  while (prescaler != 0) {
357  ++index;
358  prescaler = prescaler >> 1;
359  }
360 
361  return index - 1;
Here is the call graph for this function:
Here is the caller graph for this function:

◆ hwio_pwm_set_val()

void hwio_pwm_set_val ( int  i_pwm,
int  val 
)
378 {
379  if (!is_pwm_id_valid(i_pwm))
380  return;
381 
382  uint32_t chan = _pwm_get_chan(i_pwm);
383  TIM_HandleTypeDef *htim = _pwm_get_htim(i_pwm);
384  uint32_t cmp = __HAL_TIM_GET_COMPARE(htim, chan);
385 
386  if ((_pwm_analogWrite_val[i_pwm] ^ val) || (cmp != val)) {
387  _hwio_pwm_set_val(i_pwm, val);
388 
389  //actualize _pwm_analogWrite_val
390  int pwm_max = hwio_pwm_get_max(i_pwm);
391  int pwm_analogWrite_max = _pwm_analogWrite_max[i_pwm];
392 
393  uint32_t pulse = (val * pwm_analogWrite_max) / pwm_max;
394  _pwm_analogWrite_val[i_pwm] = pulse; //arduino compatible
395  }
Here is the call graph for this function:
Here is the caller graph for this function:

◆ hwio_fan_get_cnt()

int hwio_fan_get_cnt ( void  )
446 { return _FAN_CNT; }
Here is the caller graph for this function:

◆ hwio_fan_set_pwm()

void hwio_fan_set_pwm ( int  i_fan,
int  val 
)
448  {
449  i_fan += _FAN_ID_MIN;
450  if ((i_fan >= _FAN_ID_MIN) && (i_fan <= _FAN_ID_MAX))
451  _hwio_pwm_analogWrite_set_val(i_fan, val);
Here is the call graph for this function:
Here is the caller graph for this function:

◆ hwio_heater_get_cnt()

int hwio_heater_get_cnt ( void  )
458 { return _HEATER_CNT; }
Here is the caller graph for this function:

◆ hwio_heater_set_pwm()

void hwio_heater_set_pwm ( int  i_heater,
int  val 
)
460  {
461  i_heater += _HEATER_ID_MIN;
462  if ((i_heater >= _HEATER_ID_MIN) && (i_heater <= _HEATER_ID_MAX))
463  _hwio_pwm_analogWrite_set_val(i_heater, val);
Here is the call graph for this function:
Here is the caller graph for this function:

◆ hwio_jogwheel_enable()

void hwio_jogwheel_enable ( void  )
469  {
Here is the caller graph for this function:

◆ hwio_jogwheel_disable()

void hwio_jogwheel_disable ( void  )
473  {
Here is the caller graph for this function:

◆ hwio_beeper_get_vol()

float hwio_beeper_get_vol ( void  )
480  {
481  return hwio_beeper_vol;

◆ hwio_beeper_set_vol()

void hwio_beeper_set_vol ( float  vol)
484  {
485  if (vol < 0)
486  vol *= -1;
487  if (vol > 1)
488  vol = 1;
489  hwio_beeper_vol = vol;
Here is the caller graph for this function:

◆ hwio_beeper_set_pwm()

void hwio_beeper_set_pwm ( uint32_t  per,
uint32_t  pul 
)
492  {
493  TIM_OC_InitTypeDef sConfigOC = { 0 };
494  if (per) {
495  htim2.Init.Prescaler = 0;
497  htim2.Init.Period = per;
500  sConfigOC.OCMode = TIM_OCMODE_PWM1;
501  if (pul) {
502  sConfigOC.Pulse = pul;
503  sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH;
504  } else {
505  sConfigOC.Pulse = per;
506  sConfigOC.OCPolarity = TIM_OCPOLARITY_LOW;
507  }
508  sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
511  } else
Here is the call graph for this function:
Here is the caller graph for this function:

◆ hwio_beeper_tone()

void hwio_beeper_tone ( float  frq,
uint32_t  del 
)
515  {
516  uint32_t per;
517  uint32_t pul;
518  if (frq && del && hwio_beeper_vol) {
519  if (frq < 0)
520  frq *= -1;
521  if (frq > 100000)
522  frq = 100000;
523  per = (uint32_t)(84000000.0F / frq);
524  pul = (uint32_t)(per * hwio_beeper_vol / 2);
525  hwio_beeper_set_pwm(per, pul);
526  hwio_beeper_del = del;
527  } else
528  hwio_beeper_set_pwm(0, 0);
Here is the call graph for this function:
Here is the caller graph for this function:

◆ hwio_beeper_tone2()

void hwio_beeper_tone2 ( float  frq,
uint32_t  del,
float  vol 
)
531  {
532  hwio_beeper_set_vol(vol);
533  hwio_beeper_tone(frq, del);
Here is the call graph for this function:
Here is the caller graph for this function:

◆ hwio_beeper_notone()

void hwio_beeper_notone ( void  )
536  {
537  hwio_beeper_set_pwm(0, 0);
Here is the call graph for this function:

◆ hwio_update_1ms()

void hwio_update_1ms ( void  )
540  {
541  if ((hwio_beeper_del) && ((--hwio_beeper_del) == 0))
542  hwio_beeper_set_pwm(0, 0);
Here is the call graph for this function:
Here is the caller graph for this function:

◆ adc_ready()

void adc_ready ( uint8_t  index)
549  {
550  _adc_val[index] = adc_val[index] >> 4;

◆ adc_seq2idx()

uint8_t adc_seq2idx ( uint8_t  seq)
554  { 4, 1, 4, 1, 4, 0, 4, 1, 4, 1, 4, 2, 4, 1, 4, 1, 4, 3 };
556  return adc_seq[seq];
557  // return 2;
558  // if ((seq % 3) != 2) return 2;
559  // if (seq != 8) return 0;
560  // return 1;

◆ hwio_arduino_error()

void hwio_arduino_error ( int  err,
uint32_t  pin32 
)
566  {
567  char text[64];
568  if ((err == HWIO_ERR_UNINI_DIG_WR) && (pin32 == PIN_BEEPER))
569  return; //ignore BEEPER write
570  strcat(text, "HWIO error\n");
571  switch (err) {
576  strcat(text, "uninitialized\n");
577  break;
582  strcat(text, "undefined\n");
583  break;
584  }
585  sprintf(text + strlen(text), "pin #%u (0x%02x)\n", (int)pin32, (uint8_t)pin32);
586  switch (err) {
591  strcat(text, "digital ");
592  break;
597  strcat(text, "analog ");
598  break;
599  }
600  switch (err) {
605  strcat(text, "read");
606  break;
611  strcat(text, "write");
612  break;
613  }
614  bsod(text);
Here is the caller graph for this function:

◆ hwio_arduino_digitalRead()

int hwio_arduino_digitalRead ( uint32_t  ulPin)
620  {
621  if (HAL_GPIO_Initialized) {
622  switch (ulPin) {
623 #ifdef SIM_MOTION
624  case PIN_Z_MIN:
625  return sim_motion_get_min_end(2);
626  case PIN_E_DIAG:
627  return sim_motion_get_diag(3);
628  case PIN_Y_DIAG:
629  return sim_motion_get_diag(1);
630  case PIN_X_DIAG:
631  return sim_motion_get_diag(0);
632  case PIN_Z_DIAG:
633  return sim_motion_get_diag(2);
634 #else //SIM_MOTION
635  case PIN_Z_MIN:
636  return hwio_di_get_val(_DI_Z_MIN);
637  case PIN_E_DIAG:
638  return hwio_di_get_val(_DI_E_DIAG);
639  case PIN_Y_DIAG:
640  return hwio_di_get_val(_DI_Y_DIAG);
641  case PIN_X_DIAG:
642  return hwio_di_get_val(_DI_X_DIAG);
643  case PIN_Z_DIAG:
644  return hwio_di_get_val(_DI_Z_DIAG);
645 #endif //SIM_MOTION
646  case PIN_BTN_ENC:
648  case PIN_BTN_EN1:
650  case PIN_BTN_EN2:
652  case PIN_Z_DIR:
653  return hwio_do_get_val(_DO_Z_DIR);
654  default:
655  hwio_arduino_error(HWIO_ERR_UNDEF_DIG_RD, ulPin); //error: undefined pin digital read
656  }
657  } else
658  hwio_arduino_error(HWIO_ERR_UNINI_DIG_RD, ulPin); //error: uninitialized digital read
659  return 0;
Here is the call graph for this function:
Here is the caller graph for this function:

◆ hwio_arduino_digitalWrite()

void hwio_arduino_digitalWrite ( uint32_t  ulPin,
uint32_t  ulVal 
)
662  {
663  if (HAL_GPIO_Initialized) {
664  switch (ulPin) {
665  case PIN_BEEPER:
666  return;
667  case PIN_HEATER_BED:
668  //hwio_heater_set_pwm(_HEATER_BED, ulVal?255:0);
669 #ifdef SIM_HEATER_BED_ADC
670  if (adc_sim_msk & (1 << SIM_HEATER_BED_ADC))
671  sim_bed_set_power(ulVal ? 100 : 0);
672  else
673 #endif //SIM_HEATER_BED_ADC
675  return;
676  case PIN_HEATER_0:
677  //hwio_heater_set_pwm(_HEATER_0, ulVal?255:0);
678 #ifdef SIM_HEATER_NOZZLE_ADC
679  if (adc_sim_msk & (1 << SIM_HEATER_NOZZLE_ADC))
680  sim_nozzle_set_power(ulVal ? 40 : 0);
681  else
682 #endif //SIM_HEATER_NOZZLE_ADC
684  return;
685  case PIN_FAN1:
686  //hwio_fan_set_pwm(_FAN1, ulVal?255:0);
687  //_hwio_pwm_analogWrite_set_val(HWIO_PWM_FAN1, ulVal ? _pwm_analogWrite_max[HWIO_PWM_FAN1] : 0);
689  return;
690  case PIN_FAN:
692  return;
693 #ifdef SIM_MOTION
694  case PIN_X_DIR:
695  sim_motion_set_dir(0, ulVal ? 1 : 0);
696  return;
697  case PIN_X_STEP:
698  sim_motion_set_stp(0, ulVal ? 1 : 0);
699  return;
700  case PIN_Z_ENABLE:
701  sim_motion_set_ena(2, ulVal ? 1 : 0);
702  return;
703  case PIN_X_ENABLE:
704  sim_motion_set_ena(0, ulVal ? 1 : 0);
705  return;
706  case PIN_Z_STEP:
707  sim_motion_set_stp(2, ulVal ? 1 : 0);
708  return;
709  case PIN_E_DIR:
710  sim_motion_set_dir(3, ulVal ? 1 : 0);
711  return;
712  case PIN_E_STEP:
713  sim_motion_set_stp(3, ulVal ? 1 : 0);
714  return;
715  case PIN_E_ENABLE:
716  sim_motion_set_ena(3, ulVal ? 1 : 0);
717  return;
718  case PIN_Y_DIR:
719  sim_motion_set_dir(1, ulVal ? 1 : 0);
720  return;
721  case PIN_Y_STEP:
722  sim_motion_set_stp(1, ulVal ? 1 : 0);
723  return;
724  case PIN_Y_ENABLE:
725  sim_motion_set_ena(1, ulVal ? 1 : 0);
726  return;
727  case PIN_Z_DIR:
728  sim_motion_set_dir(2, ulVal ? 1 : 0);
729  return;
730 #else //SIM_MOTION
731  case PIN_X_DIR:
732  hwio_do_set_val(_DO_X_DIR, ulVal ? 1 : 0);
733  return;
734  case PIN_X_STEP:
735  hwio_do_set_val(_DO_X_STEP, ulVal ? 1 : 0);
736  return;
737  case PIN_Z_ENABLE:
738  hwio_do_set_val(_DO_Z_ENABLE, ulVal ? 1 : 0);
739  return;
740  case PIN_X_ENABLE:
741  hwio_do_set_val(_DO_X_ENABLE, ulVal ? 1 : 0);
742  return;
743  case PIN_Z_STEP:
744  hwio_do_set_val(_DO_Z_STEP, ulVal ? 1 : 0);
745  return;
746  case PIN_E_DIR:
747  hwio_do_set_val(_DO_E_DIR, ulVal ? 1 : 0);
748  return;
749  case PIN_E_STEP:
750  hwio_do_set_val(_DO_E_STEP, ulVal ? 1 : 0);
751  return;
752  case PIN_E_ENABLE:
753  hwio_do_set_val(_DO_E_ENABLE, ulVal ? 1 : 0);
754  return;
755  case PIN_Y_DIR:
756  hwio_do_set_val(_DO_Y_DIR, ulVal ? 1 : 0);
757  return;
758  case PIN_Y_STEP:
759  hwio_do_set_val(_DO_Y_STEP, ulVal ? 1 : 0);
760  return;
761  case PIN_Y_ENABLE:
762  hwio_do_set_val(_DO_Y_ENABLE, ulVal ? 1 : 0);
763  return;
764  case PIN_Z_DIR:
765  hwio_do_set_val(_DO_Z_DIR, ulVal ? 1 : 0);
766  return;
767 #endif //SIM_MOTION
768  default:
769  hwio_arduino_error(HWIO_ERR_UNDEF_DIG_WR, ulPin); //error: undefined pin digital write
770  }
771  } else
772  hwio_arduino_error(HWIO_ERR_UNINI_DIG_WR, ulPin); //error: uninitialized digital write
Here is the call graph for this function:
Here is the caller graph for this function:

◆ hwio_arduino_digitalToggle()

void hwio_arduino_digitalToggle ( uint32_t  ulPin)
775  {
777  // TODO test me
Here is the call graph for this function:
Here is the caller graph for this function:

◆ hwio_arduino_analogRead()

uint32_t hwio_arduino_analogRead ( uint32_t  ulPin)
780  {
781  if (HAL_ADC_Initialized) {
782  switch (ulPin) {
783  case PIN_TEMP_BED:
785  case PIN_TEMP_0:
787  case PIN_TEMP_HEATBREAK:
789  default:
790  hwio_arduino_error(HWIO_ERR_UNDEF_ANA_RD, ulPin); //error: undefined pin analog read
791  }
792  } else
793  hwio_arduino_error(HWIO_ERR_UNINI_ANA_RD, ulPin); //error: uninitialized analog read
794  return 0;
Here is the call graph for this function:
Here is the caller graph for this function:

◆ hwio_arduino_analogWrite()

void hwio_arduino_analogWrite ( uint32_t  ulPin,
uint32_t  ulValue 
)
797  {
798  if (HAL_PWM_Initialized) {
799  switch (ulPin) {
800  case PIN_FAN1:
801  //hwio_fan_set_pwm(_FAN1, ulValue);
803  return;
804  case PIN_FAN:
805  //hwio_fan_set_pwm(_FAN, ulValue);
807  return;
808  case PIN_HEATER_BED:
810  return;
811  case PIN_HEATER_0:
813  return;
814  default:
815  hwio_arduino_error(HWIO_ERR_UNDEF_ANA_WR, ulPin); //error: undefined pin analog write
816  }
817  } else
818  hwio_arduino_error(HWIO_ERR_UNINI_ANA_WR, ulPin); //error: uninitialized analog write
Here is the call graph for this function:
Here is the caller graph for this function:

◆ hwio_arduino_pinMode()

void hwio_arduino_pinMode ( uint32_t  ulPin,
uint32_t  ulMode 
)
821  {
822  // not supported, all pins are configured with Cube
Here is the caller graph for this function:

Variable Documentation

◆ HAL_GPIO_Initialized

int HAL_GPIO_Initialized

◆ HAL_ADC_Initialized

int HAL_ADC_Initialized

◆ HAL_PWM_Initialized

int HAL_PWM_Initialized

◆ htim1

◆ htim2

◆ htim3

◆ _di_pin32

const uint32_t _di_pin32[]

◆ _do_pin32

◆ _adc_pin32

const uint32_t _adc_pin32[]

◆ _adc_max

const int _adc_max[] = { 4095, 4095, 4095, 4095, 4095 }

◆ _adc_val

int _adc_val[] = { 0, 0, 0, 0, 0 }

◆ _dac_pin32

const uint32_t _dac_pin32[] = {}

◆ _dac_max

const int _dac_max[] = { 0 }

◆ _tim1_period_us

◆ _tim3_period_us

◆ _pwm_pin32

const uint32_t _pwm_pin32[]
Initial value:

◆ _pwm_chan

const uint32_t _pwm_chan[]

◆ _pwm_p_htim

TIM_HandleTypeDef* _pwm_p_htim[]
Initial value:
= {
&htim3,
&htim3,
&htim1,
&htim1,
}

◆ _pwm_period_us

int* const _pwm_period_us[]

◆ _pwm_max

◆ sConfigOC_default

◆ _pwm_analogWrite_max

const int _pwm_analogWrite_max[_PWM_CNT] = { 0xff, 0xff, 0xff, 0xff }

◆ _pwm_analogWrite_val

int _pwm_analogWrite_val[_PWM_CNT] = { 0, 0, 0, 0 }

◆ _fan_max

◆ _fan_val

int* _fan_val = &_pwm_analogWrite_val[_FAN_ID_MIN]

◆ _heater_max

◆ _heater_val

int* _heater_val = &_pwm_analogWrite_val[_HEATER_ID_MIN]

◆ hwio_jogwheel_enabled

int hwio_jogwheel_enabled = 0

◆ hwio_beeper_vol

float hwio_beeper_vol = 1.0F

◆ hwio_beeper_del

uint32_t hwio_beeper_del = 0

◆ adc_seq

const uint8_t adc_seq[18] = { 4, 1, 4, 1, 4, 0, 4, 1, 4, 1, 4, 2, 4, 1, 4, 1, 4, 3 }
is_pwm_id_valid
int is_pwm_id_valid(int i_pwm)
Definition: hwio_a3ides_2209_02.c:269
_DO_Z_STEP
#define _DO_Z_STEP
Definition: hwio_a3ides.h:23
PIN_X_DIR
#define PIN_X_DIR
Definition: hwio_pindef.h:18
PIN_E_DIR
#define PIN_E_DIR
Definition: hwio_pindef.h:33
_DI_BTN_ENC
#define _DI_BTN_ENC
Definition: hwio_a3ides.h:14
PIN_E_ENABLE
#define PIN_E_ENABLE
Definition: hwio_pindef.h:35
sim_motion_get_min_end
int sim_motion_get_min_end(uint8_t axis)
PIN_FAN
#define PIN_FAN
Definition: hwio_pindef.h:39
_DI_X_DIAG
#define _DI_X_DIAG
Definition: hwio_a3ides.h:12
PIN_TEMP_0
#define PIN_TEMP_0
Definition: hwio_pindef.h:16
TIM_Base_InitTypeDef::Period
uint32_t Period
Definition: stm32f4xx_hal_tim.h:71
HAL_PWM_Initialized
int HAL_PWM_Initialized
Definition: main.c:106
HWIO_PWM_HEATER_0
#define HWIO_PWM_HEATER_0
Definition: hwio_a3ides.h:55
TIM_OCNPOLARITY_HIGH
#define TIM_OCNPOLARITY_HIGH
Definition: stm32f4xx_hal_tim.h:395
_adc_val
int _adc_val[]
Definition: hwio_a3ides_2209_02.c:85
HAL_TIM_Base_Init
HAL_StatusTypeDef HAL_TIM_Base_Init(TIM_HandleTypeDef *htim)
sim_motion_get_diag
int sim_motion_get_diag(uint8_t axis)
_pwm_max
const int _pwm_max[]
Definition: hwio_a3ides_2209_02.c:135
HAL_OK
Definition: stm32f4xx_hal_def.h:57
__pwm_set_val
void __pwm_set_val(TIM_HandleTypeDef *htim, uint32_t chan, int val)
Definition: hwio_a3ides_2209_02.c:408
PIN_Z_DIAG
#define PIN_Z_DIAG
Definition: hwio_pindef.h:31
Error_Handler
void Error_Handler(void)
This function is executed in case of error occurrence.
Definition: main.c:1057
TIM_OCFAST_DISABLE
#define TIM_OCFAST_DISABLE
Definition: stm32f4xx_hal_tim.h:377
HAL_TIM_PWM_ConfigChannel
HAL_StatusTypeDef HAL_TIM_PWM_ConfigChannel(TIM_HandleTypeDef *htim, TIM_OC_InitTypeDef *sConfig, uint32_t Channel)
_DI_Z_MIN
#define _DI_Z_MIN
Definition: hwio_a3ides.h:9
hwio_beeper_tone
void hwio_beeper_tone(float frq, uint32_t del)
Definition: hwio_a3ides_2209_02.c:514
_DI_Y_DIAG
#define _DI_Y_DIAG
Definition: hwio_a3ides.h:11
adc_seq
const uint8_t adc_seq[18]
Definition: hwio_a3ides_2209_02.c:553
_PWM_CNT
#define _PWM_CNT
Definition: hwio_a3ides_2209_02.c:136
_hwio_pwm_analogWrite_set_val
void _hwio_pwm_analogWrite_set_val(int i_pwm, int val)
Definition: hwio_a3ides_2209_02.c:429
hwio_do_set_val
void hwio_do_set_val(int i_do, int val)
Definition: hwio_a3ides_2209_02.c:223
app_error
void app_error(void)
Definition: appmain.cpp:145
HWIO_ERR_UNDEF_ANA_RD
#define HWIO_ERR_UNDEF_ANA_RD
Definition: hwio_a3ides_2209_02.c:27
TIM_Base_InitTypeDef::ClockDivision
uint32_t ClockDivision
Definition: stm32f4xx_hal_tim.h:75
PIN_HEATER_0
#define PIN_HEATER_0
Definition: hwio_pindef.h:14
_HEATER_ID_MAX
#define _HEATER_ID_MAX
Definition: hwio_a3ides_2209_02.c:98
PIN_BTN_EN2
#define PIN_BTN_EN2
Definition: hwio_pindef.h:42
hwio_pwm_set_val
void hwio_pwm_set_val(int i_pwm, int val)
Definition: hwio_a3ides_2209_02.c:376
_do_pin32
const uint32_t _do_pin32[]
Definition: hwio_a3ides_2209_02.c:57
_DO_Y_STEP
#define _DO_Y_STEP
Definition: hwio_a3ides.h:28
HWIO_ERR_UNDEF_DIG_WR
#define HWIO_ERR_UNDEF_DIG_WR
Definition: hwio_a3ides_2209_02.c:26
hwio_jogwheel_enabled
int hwio_jogwheel_enabled
Definition: hwio_a3ides_2209_02.c:176
TIM_OC_InitTypeDef::OCPolarity
uint32_t OCPolarity
Definition: stm32f4xx_hal_tim.h:100
_DI_CNT
#define _DI_CNT
Definition: hwio_a3ides_2209_02.c:54
_ADC_TEMP_HEATBREAK
#define _ADC_TEMP_HEATBREAK
Definition: hwio_a3ides.h:36
hwio_di_get_val
int hwio_di_get_val(int i_di)
Definition: hwio_a3ides_2209_02.c:196
_adc_max
const int _adc_max[]
Definition: hwio_a3ides_2209_02.c:82
htim2
TIM_HandleTypeDef htim2
Definition: main.c:86
_HEATER_ID_MIN
#define _HEATER_ID_MIN
Definition: hwio_a3ides_2209_02.c:97
TIM_OCIDLESTATE_RESET
#define TIM_OCIDLESTATE_RESET
Definition: stm32f4xx_hal_tim.h:405
TIM_OC_InitTypeDef::OCFastMode
uint32_t OCFastMode
Definition: stm32f4xx_hal_tim.h:107
_DO_X_STEP
#define _DO_X_STEP
Definition: hwio_a3ides.h:20
HWIO_ERR_UNDEF_ANA_WR
#define HWIO_ERR_UNDEF_ANA_WR
Definition: hwio_a3ides_2209_02.c:28
sim_motion_set_dir
void sim_motion_set_dir(uint8_t axis, int state)
htim1
TIM_HandleTypeDef htim1
Definition: main.c:85
PIN_TEMP_BED
#define PIN_TEMP_BED
Definition: hwio_pindef.h:8
hwio_beeper_set_pwm
void hwio_beeper_set_pwm(uint32_t per, uint32_t pul)
Definition: hwio_a3ides_2209_02.c:491
TIM_Base_InitTypeDef::CounterMode
uint32_t CounterMode
Definition: stm32f4xx_hal_tim.h:68
_ADC_CNT
#define _ADC_CNT
Definition: hwio_a3ides_2209_02.c:83
_DO_Y_DIR
#define _DO_Y_DIR
Definition: hwio_a3ides.h:27
HAL_ADC_Initialized
int HAL_ADC_Initialized
Definition: main.c:105
TIM_OCMODE_PWM1
#define TIM_OCMODE_PWM1
Definition: stm32f4xx_hal_tim.h:365
hwio_beeper_vol
float hwio_beeper_vol
Definition: hwio_a3ides_2209_02.c:178
TIM_OC_InitTypeDef
TIM Output Compare Configuration Structure definition.
Definition: stm32f4xx_hal_tim.h:92
F
#define F(str)
Definition: UHS_macros.h:164
TIM_CHANNEL_3
#define TIM_CHANNEL_3
Definition: stm32f4xx_hal_tim.h:424
_DO_CNT
#define _DO_CNT
Definition: hwio_a3ides_2209_02.c:71
HAL_GPIO_Initialized
int HAL_GPIO_Initialized
Definition: main.c:104
hwio_arduino_digitalRead
int hwio_arduino_digitalRead(uint32_t ulPin)
Definition: hwio_a3ides_2209_02.c:619
_DI_BTN_EN2
#define _DI_BTN_EN2
Definition: hwio_a3ides.h:16
PIN_Z_MIN
#define PIN_Z_MIN
Definition: hwio_pindef.h:11
HWIO_ERR_UNINI_DIG_WR
#define HWIO_ERR_UNINI_DIG_WR
Definition: hwio_a3ides_2209_02.c:22
gpio_get
static int gpio_get(uint8_t pin8)
Definition: gpio.h:94
_DI_Z_DIAG
#define _DI_Z_DIAG
Definition: hwio_a3ides.h:13
TIM_CLOCKDIVISION_DIV1
#define TIM_CLOCKDIVISION_DIV1
Definition: stm32f4xx_hal_tim.h:351
HWIO_PWM_HEATER_BED
#define HWIO_PWM_HEATER_BED
Definition: hwio_a3ides.h:54
PIN_HW_IDENTIFY
#define PIN_HW_IDENTIFY
Definition: hwio_pindef.h:7
_DO_Z_DIR
#define _DO_Z_DIR
Definition: hwio_a3ides.h:30
_tim1_period_us
int _tim1_period_us
Definition: hwio_a3ides_2209_02.c:102
PIN_BTN_EN1
#define PIN_BTN_EN1
Definition: hwio_pindef.h:41
HAL_TIM_PWM_Start
HAL_StatusTypeDef HAL_TIM_PWM_Start(TIM_HandleTypeDef *htim, uint32_t Channel)
PIN_BEEPER
#define PIN_BEEPER
Definition: hwio_pindef.h:6
hwio_arduino_error
void hwio_arduino_error(int err, uint32_t pin32)
Definition: hwio_a3ides_2209_02.c:565
_FAN_CNT
#define _FAN_CNT
Definition: hwio_a3ides_2209_02.c:95
sim_motion_set_ena
void sim_motion_set_ena(uint8_t axis, int state)
PIN_Z_ENABLE
#define PIN_Z_ENABLE
Definition: hwio_pindef.h:30
hwio_adc_get_val
int hwio_adc_get_val(int i_adc)
Definition: hwio_a3ides_2209_02.c:245
hwio_do_get_val
int hwio_do_get_val(int i_do)
Definition: hwio_a3ides_2209_02.c:216
PIN_Y_DIAG
#define PIN_Y_DIAG
Definition: hwio_pindef.h:26
hwio_pwm_set_prescaler
void hwio_pwm_set_prescaler(int i_pwm, int prescaler)
Definition: hwio_a3ides_2209_02.c:306
_DO_Y_ENABLE
#define _DO_Y_ENABLE
Definition: hwio_a3ides.h:29
_hwio_pwm_set_val
void _hwio_pwm_set_val(int i_pwm, int val)
Definition: hwio_a3ides_2209_02.c:397
sim_nozzle_set_power
void sim_nozzle_set_power(float P)
Definition: sim_nozzle.c:57
hwio_arduino_digitalWrite
void hwio_arduino_digitalWrite(uint32_t ulPin, uint32_t ulVal)
Definition: hwio_a3ides_2209_02.c:661
PIN_TEMP_HEATBREAK
#define PIN_TEMP_HEATBREAK
Definition: hwio_pindef.h:10
sim_motion_set_stp
void sim_motion_set_stp(uint8_t axis, int state)
HWIO_PWM_FAN1
#define HWIO_PWM_FAN1
Definition: hwio_a3ides.h:56
TIM_CHANNEL_2
#define TIM_CHANNEL_2
Definition: stm32f4xx_hal_tim.h:423
adc_val
uint32_t adc_val[ADC_CHAN_CNT]
Definition: adc.c:17
_HEATER_CNT
#define _HEATER_CNT
Definition: hwio_a3ides_2209_02.c:99
sim_bed_set_power
void sim_bed_set_power(float P)
Definition: sim_bed.c:51
TIM_CHANNEL_4
#define TIM_CHANNEL_4
Definition: stm32f4xx_hal_tim.h:425
PIN_Z_STEP
#define PIN_Z_STEP
Definition: hwio_pindef.h:29
TIM_OCNIDLESTATE_RESET
#define TIM_OCNIDLESTATE_RESET
Definition: stm32f4xx_hal_tim.h:414
_DO_E_DIR
#define _DO_E_DIR
Definition: hwio_a3ides.h:24
TIM_HandleTypeDef::Instance
TIM_TypeDef * Instance
Definition: stm32f4xx_hal_tim.h:289
_FAN_ID_MIN
#define _FAN_ID_MIN
Definition: hwio_a3ides_2209_02.c:93
TIM_COUNTERMODE_DOWN
#define TIM_COUNTERMODE_DOWN
Definition: stm32f4xx_hal_tim.h:340
TIM_CHANNEL_1
#define TIM_CHANNEL_1
Definition: stm32f4xx_hal_tim.h:422
PIN_HEATER_BED
#define PIN_HEATER_BED
Definition: hwio_pindef.h:13
PIN_Y_STEP
#define PIN_Y_STEP
Definition: hwio_pindef.h:24
_pwm_chan
const uint32_t _pwm_chan[]
Definition: hwio_a3ides_2209_02.c:113
_tim3_period_us
int _tim3_period_us
Definition: hwio_a3ides_2209_02.c:103
sConfigOC_default
const TIM_OC_InitTypeDef sConfigOC_default
Definition: hwio_a3ides_2209_02.c:138
PIN_Y_DIR
#define PIN_Y_DIR
Definition: hwio_pindef.h:23
HWIO_PWM_FAN
#define HWIO_PWM_FAN
Definition: hwio_a3ides.h:57
uint8_t
const uint8_t[]
Definition: 404_html.c:3
PIN_X_ENABLE
#define PIN_X_ENABLE
Definition: hwio_pindef.h:20
_dac_max
const int _dac_max[]
Definition: hwio_a3ides_2209_02.c:90
PIN_Y_ENABLE
#define PIN_Y_ENABLE
Definition: hwio_pindef.h:25
TIM_Base_InitTypeDef::Prescaler
uint32_t Prescaler
Definition: stm32f4xx_hal_tim.h:65
_pwm_get_chan
uint32_t _pwm_get_chan(int i_pwm)
Definition: hwio_a3ides_2209_02.c:363
_DO_X_ENABLE
#define _DO_X_ENABLE
Definition: hwio_a3ides.h:22
TIM_OC_InitTypeDef::Pulse
uint32_t Pulse
Definition: stm32f4xx_hal_tim.h:97
PIN_E_STEP
#define PIN_E_STEP
Definition: hwio_pindef.h:34
TIM_OC_InitTypeDef::OCMode
uint32_t OCMode
Definition: stm32f4xx_hal_tim.h:94
PIN_X_STEP
#define PIN_X_STEP
Definition: hwio_pindef.h:19
_pwm_analogWrite_val
int _pwm_analogWrite_val[_PWM_CNT]
Definition: hwio_a3ides_2209_02.c:151
_FAN_ID_MAX
#define _FAN_ID_MAX
Definition: hwio_a3ides_2209_02.c:94
hwio_pwm_get_max
int hwio_pwm_get_max(int i_pwm)
Definition: hwio_a3ides_2209_02.c:276
PIN_THERM2
#define PIN_THERM2
Definition: hwio_pindef.h:9
TIM_OCPOLARITY_HIGH
#define TIM_OCPOLARITY_HIGH
Definition: stm32f4xx_hal_tim.h:386
HAL_TIM_PWM_Stop
HAL_StatusTypeDef HAL_TIM_PWM_Stop(TIM_HandleTypeDef *htim, uint32_t Channel)
PIN_E_DIAG
#define PIN_E_DIAG
Definition: hwio_pindef.h:36
hwio_beeper_del
uint32_t hwio_beeper_del
Definition: hwio_a3ides_2209_02.c:179
gpio_set
static void gpio_set(uint8_t pin8, int state)
Definition: gpio.h:98
TIM_OCPOLARITY_LOW
#define TIM_OCPOLARITY_LOW
Definition: stm32f4xx_hal_tim.h:387
bsod
#define bsod(fmt,...)
Definition: bsod.h:20
TIM_HandleTypeDef
TIM Time Base Handle Structure definition.
Definition: stm32f4xx_hal_tim.h:287
PIN_X_DIAG
#define PIN_X_DIAG
Definition: hwio_pindef.h:21
_DO_Z_ENABLE
#define _DO_Z_ENABLE
Definition: hwio_a3ides.h:21
_DAC_CNT
#define _DAC_CNT
Definition: hwio_a3ides_2209_02.c:91
PIN_FAN1
#define PIN_FAN1
Definition: hwio_pindef.h:38
htim3
TIM_HandleTypeDef htim3
Definition: main.c:87
TIM_HandleTypeDef::Init
TIM_Base_InitTypeDef Init
Definition: stm32f4xx_hal_tim.h:290
__HAL_TIM_GET_COMPARE
#define __HAL_TIM_GET_COMPARE(__HANDLE__, __CHANNEL__)
Gets the TIM Capture Compare Register value on runtime.
Definition: stm32f4xx_hal_tim.h:1132
_DO_E_STEP
#define _DO_E_STEP
Definition: hwio_a3ides.h:25
_ADC_TEMP_0
#define _ADC_TEMP_0
Definition: hwio_a3ides.h:37
hwio_pwm_get_prescaler
int hwio_pwm_get_prescaler(int i_pwm)
Definition: hwio_a3ides_2209_02.c:327
HWIO_ERR_UNINI_DIG_RD
#define HWIO_ERR_UNINI_DIG_RD
Definition: hwio_a3ides_2209_02.c:21
HWIO_ERR_UNINI_ANA_RD
#define HWIO_ERR_UNINI_ANA_RD
Definition: hwio_a3ides_2209_02.c:23
_di_pin32
const uint32_t _di_pin32[]
Definition: hwio_a3ides_2209_02.c:44
_ADC_TEMP_BED
#define _ADC_TEMP_BED
Definition: hwio_a3ides.h:34
_DI_BTN_EN1
#define _DI_BTN_EN1
Definition: hwio_a3ides.h:15
PIN_Z_DIR
#define PIN_Z_DIR
Definition: hwio_pindef.h:28
GEN_PERIOD_US
#define GEN_PERIOD_US(prescaler, period)
Definition: timer_defaults.h:16
__HAL_TIM_SET_PRESCALER
#define __HAL_TIM_SET_PRESCALER(__HANDLE__, __PRESC__)
Set the TIM Prescaler on runtime.
Definition: stm32f4xx_hal_tim.h:1077
adc_seq2idx
uint8_t adc_seq2idx(uint8_t seq)
Definition: hwio_a3ides_2209_02.c:554
adc_sim_msk
uint32_t adc_sim_msk
Definition: adc.c:24
TIM_BASE_CLK_MHZ
#define TIM_BASE_CLK_MHZ
Definition: timer_defaults.h:6
HWIO_ERR_UNINI_ANA_WR
#define HWIO_ERR_UNINI_ANA_WR
Definition: hwio_a3ides_2209_02.c:24
HWIO_ERR_UNDEF_DIG_RD
#define HWIO_ERR_UNDEF_DIG_RD
Definition: hwio_a3ides_2209_02.c:25
_pwm_get_htim
TIM_HandleTypeDef * _pwm_get_htim(int i_pwm)
Definition: hwio_a3ides_2209_02.c:369
_DI_E_DIAG
#define _DI_E_DIAG
Definition: hwio_a3ides.h:10
_DO_X_DIR
#define _DO_X_DIR
Definition: hwio_a3ides.h:19
PIN_BTN_ENC
#define PIN_BTN_ENC
Definition: hwio_pindef.h:40
_DO_E_ENABLE
#define _DO_E_ENABLE
Definition: hwio_a3ides.h:26
_pwm_p_htim
TIM_HandleTypeDef * _pwm_p_htim[]
Definition: hwio_a3ides_2209_02.c:120
_pwm_analogWrite_max
const int _pwm_analogWrite_max[_PWM_CNT]
Definition: hwio_a3ides_2209_02.c:149
_pwm_period_us
int *const _pwm_period_us[]
Definition: hwio_a3ides_2209_02.c:127
hwio_beeper_set_vol
void hwio_beeper_set_vol(float vol)
Definition: hwio_a3ides_2209_02.c:483