From 238d26b63fb88fe77042055bb410a387f18f9a49 Mon Sep 17 00:00:00 2001 From: askuric Date: Thu, 29 Feb 2024 12:54:32 +0100 Subject: [PATCH] better error messages --- .../hardware_specific/teensy/teensy4_mcu.cpp | 15 +++++++-------- .../hardware_specific/teensy/teensy_mcu.cpp | 1 + 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/src/drivers/hardware_specific/teensy/teensy4_mcu.cpp b/src/drivers/hardware_specific/teensy/teensy4_mcu.cpp index 6815c10f..0e7953ff 100644 --- a/src/drivers/hardware_specific/teensy/teensy4_mcu.cpp +++ b/src/drivers/hardware_specific/teensy/teensy4_mcu.cpp @@ -87,7 +87,8 @@ void xbar_init() { IMXRT_FLEXPWM_t* get_flexpwm(uint8_t pin){ const struct pwm_pin_info_struct *info; - if (pin >= CORE_NUM_DIGITAL) { + info = pwm_pin_info + pin; + if (pin >= CORE_NUM_DIGITAL || info->type == 2) { #ifdef SIMPLEFOC_TEENSY_DEBUG char s[60]; sprintf (s, "TEENSY-DRV: ERR: Pin: %d not Flextimer pin!", pin); @@ -95,7 +96,6 @@ IMXRT_FLEXPWM_t* get_flexpwm(uint8_t pin){ #endif return nullptr; } - info = pwm_pin_info + pin; // FlexPWM pin IMXRT_FLEXPWM_t *flexpwm; switch ((info->module >> 4) & 3) { @@ -236,17 +236,16 @@ int get_submodule(uint8_t pin, uint8_t pin1){ // 1 - A // 2 - B int get_channel(uint8_t pin){ - const struct pwm_pin_info_struct *info; - if (pin >= CORE_NUM_DIGITAL){ + info = pwm_pin_info + pin; + if (pin >= CORE_NUM_DIGITAL || info->type == 2){ #ifdef SIMPLEFOC_TEENSY_DEBUG - char s[60]; + char s[90]; sprintf (s, "TEENSY-DRV: ERR: Pin: %d not Flextimer pin!", pin); SIMPLEFOC_DEBUG(s); #endif return -1; } - info = pwm_pin_info + pin; #ifdef SIMPLEFOC_TEENSY_DEBUG char s[60]; sprintf (s, "TEENSY-DRV: Pin: %d on channel %s.", pin, info->channel==0 ? "X" : info->channel==1 ? "A" : "B"); @@ -598,7 +597,7 @@ void write_pwm_on_pin(IMXRT_FLEXPWM_t *p, unsigned int submodule, uint8_t channe // we can configure the center-aligned pwm if((flexpwmA != nullptr) && (flexpwmB != nullptr) && (flexpwmC != nullptr) && (channelA > 0) && (channelB > 0) && (channelC > 0) ){ #ifdef SIMPLEFOC_TEENSY_DEBUG - SIMPLEFOC_DEBUG("TEENSY-DRV: All pins on Flexpwm A or B submodules - Configuring center-aligned pwm!"); + SIMPLEFOC_DEBUG("TEENSY-DRV: All pins on Flexpwm A or B channels - Configuring center-aligned pwm!"); #endif // Configure FlexPWM units @@ -645,7 +644,7 @@ void write_pwm_on_pin(IMXRT_FLEXPWM_t *p, unsigned int submodule, uint8_t channe return params; }else{ #ifdef SIMPLEFOC_TEENSY_DEBUG - SIMPLEFOC_DEBUG("TEENSY-DRV: Not all pins on Flexpwm A and B submodules - cannot configure center-aligned pwm!"); + SIMPLEFOC_DEBUG("TEENSY-DRV: Not all pins on Flexpwm A and B channels - cannot configure center-aligned pwm!"); #endif return SIMPLEFOC_DRIVER_INIT_FAILED; } diff --git a/src/drivers/hardware_specific/teensy/teensy_mcu.cpp b/src/drivers/hardware_specific/teensy/teensy_mcu.cpp index 2ad5f57c..196f07fd 100644 --- a/src/drivers/hardware_specific/teensy/teensy_mcu.cpp +++ b/src/drivers/hardware_specific/teensy/teensy_mcu.cpp @@ -61,6 +61,7 @@ void* _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const in if(p != SIMPLEFOC_DRIVER_INIT_FAILED){ return p; // if center aligned pwm is available return the params }else{ // if center aligned pwm is not available use fast pwm + SIMPLEFOC_DEBUG("TEENSY-DRV: Configuring 3PWM with fast pwm. Please consider using center aligned pwm for better performance!"); _setHighFrequency(pwm_frequency, pinA); _setHighFrequency(pwm_frequency, pinB); _setHighFrequency(pwm_frequency, pinC);