ESP32 will not output PWM signal

andy_wharton_uk
Posts: 7
Joined: Sat Nov 30, 2024 2:29 pm

ESP32 will not output PWM signal

Postby andy_wharton_uk » Sun Dec 01, 2024 3:33 pm

Hi,

I have a project developed using the Arduino IDE and an Arduino Nano to drive motors on an ROV. This code has been working for a couple of years in various versions. I now need to upgrade to an ESP32-WROOM-32 and, to drive the motors, have delved into the latest mcpwm API. It's taken my brain cell a while to figure it out but I have successfully got the ESP32 to output exactly the PWM I needed - 16kHz PWM with 1024 steps - and I can see this on my scope AND it worked with the new H-Bridge devices (DBH-12V) which I have.

However, after porting the rest of the Arduino Nano code over into my working mcpwm code I checked back and I now have no PWM output at all shown on the scope. Backtracking to just the mcpwm code to try and identify the reason hasn't worked - still no PWM signal. I've also now tested the same ESP32 with ESPHome, trying to output a PWM signal, and again, nothing. I've tried my code on a second ESP32 (which I also used during the porting) but nothing there either.

I can get the same pin to blink an LED both directly and using ESPHome but using ESPHome PWM also does not work.

I've attached the code below but maybe there is a "problem" with the ESP32s which is stopping this from working - I suspect that, during the porting of the remaining Arduino code, I've either damaged something or turned something off inadvertently on both devices.

I would be very grateful for any guidance or suggestions.

Thanks
Andy

Code: Select all

// Test code to identify the configuration and control of motors using MCPWM on an ESP32-WROOM-32
// This code uses the LATEST mcpwm_prelude.h driver code as the old mcpwm.h has been depreciated.
//   Definitely hurt my brain to understand this so apologies if this is not the right way.
//   The code is to drive FOUR motors via TWO DBH-12V H-Bridges
/*
   Andy Wharton - November 2024

*/
#include "driver/mcpwm_prelude.h"

#define VERSION 1.20

/*-----( Declare Constants and Pin Numbers )-----*/
#define DEBUG_SETUP          true
#define DEBUG_LOOP           true

// Motor GPIO pin assignments
#define GPIO_PWM0A_OUT 16   // Define GPIO 16 as PWM0A - Motor 0  H-Bridge 1  Test on 13
#define GPIO_PWM0B_OUT 17   // Define GPIO 17 as PWM0B - Motor 1  H-Bridge 2  Test on 32
#define GPIO_PWM1A_OUT 18   // Define GPIO 18 as PWM1A - Motor 2  H-Bridge 2
#define GPIO_PWM1B_OUT 19   // Define GPIO 19 as PWM1B - Motor 3  H-Bridge 1

#define ZERO 0
#define MAINDELAY 5000


// We need the folowing for the DBH-12V H-Bridge...
//   PWM frequency of 16kHz
//   Duty Cycle in steps of 100 - MAX 98% though so limit at 95% for extra safety
//   PWM outputs from each Operator are symmetric but independent
//   Use the same timer for both Operators - MCPWM_UNIT_0
#define PWM_FREQUENCY0 16384
#define PWM_DUTY_STEPS0 950   // Period of each step = 1/PWM_FREQUENCY0 (approx 61us @ 16kHz)

// Define an instance of the timer config structure and set values for the Main Motors
mcpwm_timer_config_t timer_config0 = {
   .group_id = 0,
   .clk_src = MCPWM_TIMER_CLK_SRC_DEFAULT,
   .resolution_hz = PWM_FREQUENCY0,
   .count_mode = MCPWM_TIMER_COUNT_MODE_UP,                       // Count Up
   .period_ticks = PWM_DUTY_STEPS0,
   .flags = {
       .update_period_on_empty = false,
       .update_period_on_sync = true,
   },
};

// Define all the instances for MCPWM
// Timers, one for the main motors and one for the side motors
mcpwm_timer_handle_t timer0;

// Define instances of the operator config structures.  Sets them to the same group as the timer
mcpwm_operator_config_t operator_config0 = {
	.group_id = 0,   // operator must be in the same group to the timer.  Everything else defaults
};

// Operators - one each for the Main motor pairs and one for the Side motors
mcpwm_oper_handle_t operator0, operator1;

// Create Comparator configurations - only 1 needed as they are all the same
mcpwm_comparator_config_t comparator_config= {
     .flags = {
       .update_cmp_on_tep = 1,  // This is a uint32_1 value which is used as the duty cycle peak.  In our case 0-980
    },
};

// Comparators for the main motors
mcpwm_cmpr_handle_t comparator1, comparator2, comparator3, comparator4;

// Generators - One generator per PWM
// define instances of their configurations - only the GPIO assignments change
mcpwm_generator_config_t generator_config1 = {
	.gen_gpio_num = GPIO_PWM0A_OUT,
};

mcpwm_generator_config_t generator_config2 = {
	.gen_gpio_num = GPIO_PWM0B_OUT,
};

mcpwm_generator_config_t generator_config3 = {
	.gen_gpio_num = GPIO_PWM1A_OUT,
};

mcpwm_generator_config_t generator_config4 = {
	.gen_gpio_num = GPIO_PWM1B_OUT,
};

// FOUR generators for the main motors
mcpwm_gen_handle_t generator1, generator2, generator3, generator4;

/*-----( Declare User-written Functions )-----*/
//<<<<<<<<<<<<<<<<<<<<>>>>>>>>>>>>>>>>>>>
// COMPLETE - TESTED
void wait_a_bit(int period) {
  unsigned long time_now = millis();
  while(millis() < time_now + period) {
    ; //  Wait for period
  }
}

void setup_Main_Motors()
{
  if (DEBUG_SETUP) {
    Serial.print(F("Create Timers.")); 
    Serial.println("     ");
  }  

  // MCPWM Initialise the timer
  ESP_ERROR_CHECK(mcpwm_new_timer(&timer_config0, &timer0));  // Main Motors

  if (DEBUG_SETUP) {
    Serial.print(F("Create Operators.")); 
    Serial.println("     ");
  } 
  // Initialise the Operators
  ESP_ERROR_CHECK(mcpwm_new_operator(&operator_config0, &operator0)); // Main Motors Same config
  ESP_ERROR_CHECK(mcpwm_new_operator(&operator_config0, &operator1)); // Main motors Same config
  
  if (DEBUG_SETUP) {
    Serial.print(F("Connect Timers and Operators.")); 
    Serial.println("     ");
  } 

  // Connect the Operators to the single Timer
  ESP_ERROR_CHECK(mcpwm_operator_connect_timer(operator0, timer0));  // Main  Motors
  ESP_ERROR_CHECK(mcpwm_operator_connect_timer(operator1, timer0));  // Main Motors

  if (DEBUG_SETUP) {
    Serial.print(F("Create Comparators.")); 
    Serial.println("     ");
  } 

  // Create the comparators which define the duty cycle.
  // Set the duty cycle using mcpwm_comparator_set_compare_value()
  // One comparator per Operator
  // Main Motors
  ESP_ERROR_CHECK(mcpwm_new_comparator(operator0, &comparator_config, &comparator1));
  ESP_ERROR_CHECK(mcpwm_new_comparator(operator0, &comparator_config, &comparator2));
  ESP_ERROR_CHECK(mcpwm_new_comparator(operator1, &comparator_config, &comparator3));
  ESP_ERROR_CHECK(mcpwm_new_comparator(operator1, &comparator_config, &comparator4));

  if (DEBUG_SETUP) {
    Serial.print(F("Create Generators.")); 
    Serial.println("     ");
  } 

  // Create the generators 
  // Main Motors
  ESP_ERROR_CHECK(mcpwm_new_generator(operator0, &generator_config1, &generator1));
  ESP_ERROR_CHECK(mcpwm_new_generator(operator0, &generator_config2, &generator2));
  ESP_ERROR_CHECK(mcpwm_new_generator(operator1, &generator_config3, &generator3));
  ESP_ERROR_CHECK(mcpwm_new_generator(operator1, &generator_config4, &generator4));

  if (DEBUG_SETUP) {
    Serial.print(F("Set the generator event actions.")); 
    Serial.println("     ");
  } 

  // Now set the generators to carry out the correct actions based on their direction and the timer event
  // Each generator will get an event when it's operator/comparator hits the duty_cycle
  // >> Main Motors <<
  // Generator 1
  // First go high when the counter is empty
  ESP_ERROR_CHECK(mcpwm_generator_set_action_on_timer_event(generator1, 
         MCPWM_GEN_TIMER_EVENT_ACTION(MCPWM_TIMER_DIRECTION_UP, MCPWM_TIMER_EVENT_EMPTY, MCPWM_GEN_ACTION_HIGH)));

  // Then go LOW when the counter hits the duty cycle threshold.
  ESP_ERROR_CHECK(mcpwm_generator_set_action_on_compare_event(generator1, 
         MCPWM_GEN_COMPARE_EVENT_ACTION(MCPWM_TIMER_DIRECTION_UP, comparator1, MCPWM_GEN_ACTION_LOW)));

  // Generator 2
  // First go high when the counter is empty
  ESP_ERROR_CHECK(mcpwm_generator_set_action_on_timer_event(generator2, 
         MCPWM_GEN_TIMER_EVENT_ACTION(MCPWM_TIMER_DIRECTION_UP, MCPWM_TIMER_EVENT_EMPTY, MCPWM_GEN_ACTION_HIGH)));

  // Then go LOW when the counter hits the duty cycle threshold.
  ESP_ERROR_CHECK(mcpwm_generator_set_action_on_compare_event(generator2, 
         MCPWM_GEN_COMPARE_EVENT_ACTION(MCPWM_TIMER_DIRECTION_UP, comparator2, MCPWM_GEN_ACTION_LOW)));

  // Generator 3
  // First go high when the counter is empty
  ESP_ERROR_CHECK(mcpwm_generator_set_action_on_timer_event(generator3, 
         MCPWM_GEN_TIMER_EVENT_ACTION(MCPWM_TIMER_DIRECTION_UP, MCPWM_TIMER_EVENT_EMPTY, MCPWM_GEN_ACTION_HIGH)));

  // Then go LOW when the counter hits the duty cycle threshold.
  ESP_ERROR_CHECK(mcpwm_generator_set_action_on_compare_event(generator3, 
         MCPWM_GEN_COMPARE_EVENT_ACTION(MCPWM_TIMER_DIRECTION_UP, comparator3, MCPWM_GEN_ACTION_LOW)));

  // Generator 4
  // First go high when the counter is empty
  ESP_ERROR_CHECK(mcpwm_generator_set_action_on_timer_event(generator4, 
         MCPWM_GEN_TIMER_EVENT_ACTION(MCPWM_TIMER_DIRECTION_UP, MCPWM_TIMER_EVENT_EMPTY, MCPWM_GEN_ACTION_HIGH)));

  // Then go LOW when the counter hits the duty cycle threshold.
  ESP_ERROR_CHECK(mcpwm_generator_set_action_on_compare_event(generator4, 
         MCPWM_GEN_COMPARE_EVENT_ACTION(MCPWM_TIMER_DIRECTION_UP, comparator4, MCPWM_GEN_ACTION_LOW)));

  if (DEBUG_SETUP) {
    Serial.print(F("Enable and Start Timer.")); 
    Serial.println("     ");
  } 

  // Enable the timers and start them
  // >> Main Motors <<
  ESP_ERROR_CHECK(mcpwm_timer_enable(timer0));
  ESP_ERROR_CHECK(mcpwm_timer_start_stop(timer0, MCPWM_TIMER_START_NO_STOP));

  if (DEBUG_SETUP) {
    Serial.print(F("Set the duty cycle to 0 (Stop).")); 
    Serial.println("     ");
  } 

  // Set the initial duty cycle to ZERO for all motors
  // >> Main Motors <<
  ESP_ERROR_CHECK(mcpwm_comparator_set_compare_value(comparator1, ZERO));
  ESP_ERROR_CHECK(mcpwm_comparator_set_compare_value(comparator2, ZERO));
  ESP_ERROR_CHECK(mcpwm_comparator_set_compare_value(comparator3, ZERO));
  ESP_ERROR_CHECK(mcpwm_comparator_set_compare_value(comparator4, ZERO));
}

void setup()
{
    // Start the built-in serial port, probably to Serial Monitor
  if (DEBUG_SETUP) {
    Serial.begin(9600);
    wait_a_bit(200);
    Serial.print(F("ESP32 MCPWM Debug Output - V"));
    Serial.println(VERSION);
  }

  // Now set up PWM on the 4 main motors
  setup_Main_Motors();

}

void cycle_Motor_UP(int MotorID, int Cycle)
{
  // Loop and ramp the motors up then down

  if (DEBUG_LOOP) {
    Serial.print(F("Cycle UP - Motor  Steps"));
    Serial.println(F("             "));
    Serial.print(MotorID); 
    Serial.print("    ");
    Serial.print(Cycle);
    Serial.println("     ");
  }

  // Motor Ramp UP
  for (int duty_Cycle = 0; duty_Cycle <= Cycle; duty_Cycle = duty_Cycle + 10 ) 
  {
    if (DEBUG_LOOP) {
      Serial.print(F("Motor - ")); 
      Serial.print(MotorID);
      Serial.print(F("   Duty Cycle = ")); 
      Serial.print(duty_Cycle);
      Serial.println("     ");
    }

    // Set the initial duty cycle to the required duty cycle
    switch(MotorID) {
      case 1:
        ESP_ERROR_CHECK(mcpwm_comparator_set_compare_value(comparator1, duty_Cycle));
        break;
      case 2:
        ESP_ERROR_CHECK(mcpwm_comparator_set_compare_value(comparator2, duty_Cycle));
        break;
      case 3:
        ESP_ERROR_CHECK(mcpwm_comparator_set_compare_value(comparator3, duty_Cycle));
        break;
      case 4:
        ESP_ERROR_CHECK(mcpwm_comparator_set_compare_value(comparator4, duty_Cycle));
        break;
      default:
        break; // Do nothing
    }

    wait_a_bit(100);  // Delay 100ms
  }

}

void cycle_Motor_DOWN(int MotorID, int Cycle)
{
  // Loop and ramp the motors up then down

  if (DEBUG_LOOP) {
    Serial.println(F("Cycle DOWN - Motor   Steps"));
    Serial.print(F("             "));
    Serial.print(MotorID); 
    Serial.print("    ");
    Serial.print(Cycle);
    Serial.println("     ");
  }

  // Motor Ramp DOWN
  for (int duty_Cycle = Cycle; duty_Cycle >= 0; duty_Cycle = duty_Cycle - 10 ) 
  {
    if (DEBUG_LOOP) {
      Serial.print(F("Motor - ")); 
      Serial.print(MotorID);
      Serial.print(F("   Duty Cycle = ")); 
      Serial.print(duty_Cycle);
      Serial.println("     ");
    }

    // Set the initial duty cycle to the required duty cycle
    switch(MotorID) {
      case 0:
        ESP_ERROR_CHECK(mcpwm_comparator_set_compare_value(comparator1, duty_Cycle));
        break;
      case 1:
        ESP_ERROR_CHECK(mcpwm_comparator_set_compare_value(comparator2, duty_Cycle));
        break;
      case 2:
        ESP_ERROR_CHECK(mcpwm_comparator_set_compare_value(comparator3, duty_Cycle));
        break;
      case 3:
        ESP_ERROR_CHECK(mcpwm_comparator_set_compare_value(comparator4, duty_Cycle));
        break;
      default:
        break; // Do nothing
    }
    wait_a_bit(100);  // Delay 100ms
  }

}

void loop()
{
  wait_a_bit(5000);  // Delay 5s
 
  // Call Loops to ramp the motors up then down one at a time

  if (DEBUG_LOOP) {
    Serial.print(F("Motor 0, GP16")); 
    Serial.println("     ");
  }
  cycle_Motor_UP(0, PWM_DUTY_STEPS0);

  wait_a_bit(MAINDELAY);  // Delay 5s 

  cycle_Motor_DOWN(0, PWM_DUTY_STEPS0);

  wait_a_bit(MAINDELAY);  // Delay 10s  - allows me to move my scope probes

  if (DEBUG_LOOP) {
    Serial.print(F("Motor 1, GP17")); 
    Serial.println("     ");
  }
  cycle_Motor_UP(1, PWM_DUTY_STEPS0);

  wait_a_bit(MAINDELAY);  // Delay 5s

  cycle_Motor_DOWN(1, PWM_DUTY_STEPS0);

  wait_a_bit(MAINDELAY);  // Delay 10s  - allows me to move my scope probes

  if (DEBUG_LOOP) {
    Serial.print(F("Motor 2, GP18")); 
    Serial.println("     ");
  }
  cycle_Motor_UP(2, PWM_DUTY_STEPS0);

  wait_a_bit(MAINDELAY);  // Delay 5s

  cycle_Motor_DOWN(2, PWM_DUTY_STEPS0);

  wait_a_bit(MAINDELAY);  // Delay 10s - allows me to move my scope probes

  if (DEBUG_LOOP) {
    Serial.print(F("Motor 3, GP19")); 
    Serial.println("     ");
  }
  cycle_Motor_UP(3, PWM_DUTY_STEPS0);

  wait_a_bit(MAINDELAY);  // Delay 5s

  cycle_Motor_DOWN(3, PWM_DUTY_STEPS0);

  wait_a_bit(MAINDELAY);  // Delay 10s - allows me to move my scope probes
}


MicroController
Posts: 1818
Joined: Mon Oct 17, 2022 7:38 pm
Location: Europe, Germany

Re: ESP32 will not output PWM signal

Postby MicroController » Mon Dec 02, 2024 9:07 am

Any logging output?

Code: Select all

void wait_a_bit(int period) {
  unsigned long time_now = millis();
  while(millis() < time_now + period) {
    ; //  Wait for period
  }
}
should be

Code: Select all

void wait_a_bit(int period) {
  delay(period);
}

andy_wharton_uk
Posts: 7
Joined: Sat Nov 30, 2024 2:29 pm

Re: ESP32 will not output PWM signal

Postby andy_wharton_uk » Mon Dec 02, 2024 9:20 am

Hi,

Historical as the code was ported from Arduino where delay() is a blocking function. I didn't know it was non-blocking on ESP32 so thanks.

All my debug output indicates that the code is working, just no PWM signal:

09:26:55.314 -> ESP32 MCPWM Debug Output - V1.20
09:26:55.751 -> Create Timers.
09:26:55.751 -> Create Operators.
09:26:55.783 -> Connect Timers and Operators.
09:26:55.816 -> Create Comparators.
09:26:55.848 -> Create Generators.
09:26:55.880 -> Set the generator event actions.
09:26:55.912 -> Enable and Start Timer.
09:26:55.944 -> Set the duty cycle to 0 (Stop).
09:27:00.956 -> Motor 0, GP16
09:27:00.989 -> Cycle UP - Motor Steps
09:27:01.021 -> 0 950
09:27:01.021 -> Motor - 0 Duty Cycle = 0
09:27:01.053 -> Motor - 0 Duty Cycle = 10
09:27:01.153 -> Motor - 0 Duty Cycle = 20
09:27:01.253 -> Motor - 0 Duty Cycle = 30
09:27:01.354 -> Motor - 0 Duty Cycle = 40
:
etc up to 950 then down again.

Andy

MicroController
Posts: 1818
Joined: Mon Oct 17, 2022 7:38 pm
Location: Europe, Germany

Re: ESP32 will not output PWM signal

Postby MicroController » Tue Dec 03, 2024 1:41 pm

Code: Select all

//   PWM frequency of 16kHz
//   Duty Cycle in steps of 100 - MAX 98% though so limit at 95% for extra safety

#define PWM_FREQUENCY0 16384
#define PWM_DUTY_STEPS0 950   // Period of each step = 1/PWM_FREQUENCY0 (approx 61us @ 16kHz)

// Define an instance of the timer config structure and set values for the Main Motors
mcpwm_timer_config_t timer_config0 = {
...
   .resolution_hz = PWM_FREQUENCY0,
...
   .period_ticks = PWM_DUTY_STEPS0,
...
};
This doesn't look right. You set the resolution to 16k and the period to 950, i.e. the PWM frequency would be 16384/950 ~ 17Hz. And setting the period to 950 means that you get 100% duty cycle at a comparator value of ~950; you probably want something like a period of 1000 and limit the comparator values to 950.
Last edited by MicroController on Thu Dec 12, 2024 8:48 pm, edited 1 time in total.

andy_wharton_uk
Posts: 7
Joined: Sat Nov 30, 2024 2:29 pm

Re: ESP32 will not output PWM signal

Postby andy_wharton_uk » Tue Dec 03, 2024 3:52 pm

Hi,

Many thanks for your help.

I never was great at the maths side of programming :-). Re-reading the Programming Guide I can see that the "tick resolution is set in resolution_hz" so that makes sense with what you are saying - in my case each period_tick is 950/16384 ~ 0.058 ~ 17Hz. I would still expect to see this on my scope though - I did before.

My DBH-12V H-Bridge specifies a "normal" motor frequency of 16kHz (see image below) and I should really have period_ticks at 1024 and use 1000 as the max duty cycle.

If that means I need 1024/resolution_hz = 16384Hz it makes resolution_hz around 16MHz? That sounds way too high as the H-Bridge also specifies 80kHz for a coreless motor which would mean a resolution_hz of 77MHz! The PWM frequency on an Arduino Nano I found quoted at around 500Hz which would give a resolution_hz of around 475kHz which sounds more reasonable. Either way I'm not sure where the 16kHz H-Bridge requirement fits in?

I did have my ESP32 with the above code/numbers attached to the H-Bridge and it worked - the motors ran well enough although I did think they sounded a little ragged so increasing the "frequency" might help. At the moment I get nothing at all which is my problem. I can adjust the numbers fine but with no output at all I'm struggling. It's as if I have somehow inadvertently disabled or broken PWM within the ESP32 as neither LEDC or MCPWM output anything but I can blink an LED from the same pin?

I have some new ESP32's on order just in case so can try my code on them when they arrive.

Thanks again.
Andy
Attachments
DBH_12V Specification.jpg
DBH_12V Specification.jpg (55.04 KiB) Viewed 2039 times

MicroController
Posts: 1818
Joined: Mon Oct 17, 2022 7:38 pm
Location: Europe, Germany

Re: ESP32 will not output PWM signal

Postby MicroController » Tue Dec 03, 2024 6:01 pm

andy_wharton_uk wrote:
Tue Dec 03, 2024 3:52 pm
If that means I need 1024/resolution_hz = 16384Hz it makes resolution_hz around 16MHz? That sounds way too high as the H-Bridge also specifies 80kHz for a coreless motor which would mean a resolution_hz of 77MHz!
Those numbers sound about right. However, you should determine what granularity of the duty cycle you actually want/need and go from there. Say you want 16kHz PWM frequency, and be able to control the duty cycle only in increments of 10%, i.e. 10 steps, then you need only 16kHz*10=160kHz for resolution; 1.6MHz for 100 steps @ 16kHz &c.
At the moment I get nothing at all which is my problem. I can adjust the numbers fine but with no output at all I'm struggling. It's as if I have somehow inadvertently disabled or broken PWM within the ESP32 as neither LEDC or MCPWM output anything but I can blink an LED from the same pin?
Looking at your code I did not find anything wrong. - But I'm not too familiar with the details of using the MCPWM, so that doesn't mean all that much.
If you can blink an LED on the same pins you set the MCPWM to the hardware should be fine.
Can you blink the LED via LEDC or MCPWM?

andy_wharton_uk
Posts: 7
Joined: Sat Nov 30, 2024 2:29 pm

Re: ESP32 will not output PWM signal

Postby andy_wharton_uk » Tue Dec 03, 2024 7:02 pm

Hi,

Thanks again, this is really helping.

OK, I guess the numbers are right. Since my ESP-WROOM-32 only has a 40MHz clock I need to think practical so 100 steps would be fine putting resolution_hz at 1.6MHz and period_ticks at 100.

I tried the same ESP32 with a simple blink LED automation using ESPHome via my Home Assistant and that worked fine. Using similar automation with ESPHome useing LEDC gave me nothing on the LED or on the scope and I just tried the code below which also gave me a flat line (disconnecting the scope probe I can see mains hum so it's as if it's shorted to GND).

I'll try the same code on the new ESPs when they arrive and post the result.

It's good to know my MCPWM code looks OK. Pretty much all of the examples I could find used the now depreciated mcpwm.h code so it took me a while to crack it. I had some failures along the way and couldn't get timers in different groups to work so eventually kept it as simple as I could.

Code: Select all

#include "driver/ledc.h"

//configure GPIO pins to connect motor driver
int enable1Pin = 16;

// Setting PWM properties
const int freq = 1638400;
const int pwmChannel = 0;
const int resolution = 100;

void setup()
{
  Serial.begin(9600);
  delay(200);

  // sets the pins as outputs:
  pinMode(enable1Pin, OUTPUT);

  //Configure LED PWM functionalities
  ledcAttachChannel(enable1Pin, pwmChannel, freq, resolution);

  Serial.println("Dump IO Config");

  gpio_dump_io_configuration(stdout, (1ULL <<16));

  delay(5000);

  Serial.println("Testing DC Motor...");
}

void loop()
{
  // Run up to and down from 95% of the available duty cycle.
  for (int duty_Cycle = 0; duty_Cycle <= (resolution * .95); duty_Cycle++ ) 
  {
    Serial.print("Speed increasing with duty cycle: ");
    Serial.println(duty_Cycle);
    ledcWrite(pwmChannel, duty_Cycle); 

    delay(200);
  }

  delay(5000);

  for (int duty_Cycle = (resolution * 0.95); duty_Cycle >= 0; duty_Cycle-- )  
  {
    Serial.print("Speed decreasing with duty cycle: ");
    Serial.println(duty_Cycle);
    ledcWrite(pwmChannel, duty_Cycle); 

    delay(200);
  }

  delay(5000);
}

andy_wharton_uk
Posts: 7
Joined: Sat Nov 30, 2024 2:29 pm

Re: ESP32 will not output PWM signal

Postby andy_wharton_uk » Wed Dec 11, 2024 4:20 pm

Hi,

Update on this....

I've tried a brand new device and still got nothing however, in re-trying my original MCPWM code I now have the code generating a PWM signal from GPIO16 but ONLY when ramping DOWN from peak to 0 Duty cycle. It's the same call to ESP_ERROR_CHECK(mcpwm_comparator_set_compare_value(comparator1, duty_Cycle)); ramping up and down so no idea why one works and one does not.

This proves my hardware IS working and I havn't fried it and perhaps points me in the direction of an incorrect value/setting somewhere in the definitions. Code which is doing this is below...

Andy

Code: Select all

// Test code to identify the configuration and control of motors using MCPWM on an ESP32-WROOM-32
// This code uses the LATEST mcpwm_prelude.h driver code as the old mcpwm.h has been depreciated.
//   Definitely hurt my brain to understand this so apologies if this is not the right way.
//   The code is to drive FOUR motors via TWO DBH-12V H-Bridges
/*
   Andy Wharton - November 2024

*/
#include "driver/mcpwm_prelude.h"

#define VERSION 1.20

/*-----( Declare Constants and Pin Numbers )-----*/
#define DEBUG_SETUP          true
#define DEBUG_LOOP           true

// Motor GPIO pin assignments
#define GPIO_PWM0A_OUT 16   // Define GPIO 16 as PWM0A - Motor 0  H-Bridge 1  Test on 13
#define GPIO_PWM0B_OUT 17   // Define GPIO 17 as PWM0B - Motor 1  H-Bridge 2  Test on 32
#define GPIO_PWM1A_OUT 18   // Define GPIO 18 as PWM1A - Motor 2  H-Bridge 2
#define GPIO_PWM1B_OUT 19   // Define GPIO 19 as PWM1B - Motor 3  H-Bridge 1

#define ZERO 0
#define MAINDELAY 5000

// We need the folowing for the DBH-12V H-Bridge...
//   PWM frequency of 16kHz
//   Duty Cycle in steps of 100 - MAX 98% though so limit at 95% for extra safety
//   PWM outputs from each Operator are symmetric but independent
//   Use the same timer for both Operators - MCPWM_UNIT_0
#define PWM_FREQUENCY0 16384 * 100   // 1.6MHz resolution_hz value
#define PWM_DUTY_STEPS0 100          // and period_ticks of 100 gives a Frequency of 100/1.6MHz = 16kHz

// Define all the instances for MCPWM
// Timers, one for the main motors and one for the side motors
mcpwm_timer_handle_t timer0;

// Define an instance of the timer config structure and set values for the Main Motors
mcpwm_timer_config_t timer_config0 = {
   .group_id = 0,
   .clk_src = MCPWM_TIMER_CLK_SRC_DEFAULT,
   .resolution_hz = PWM_FREQUENCY0,
   .count_mode = MCPWM_TIMER_COUNT_MODE_UP,                       // Count Up
   .period_ticks = PWM_DUTY_STEPS0,
   .flags = {
       .update_period_on_empty = false,
       .update_period_on_sync = true,
   },
};

// Operators - one each for the Main motor pairs
mcpwm_oper_handle_t operator0, operator1;

// Define instances of the operator config structures.  Sets them to the same group as the timer
mcpwm_operator_config_t operator_config0 = {
	.group_id = 0,   // operator must be in the same group to the timer.  Everything else defaults
};
mcpwm_operator_config_t operator_config1 = {
	.group_id = 0,   // operator must be in the same group to the timer.  Everything else defaults
};

// Comparators for the main motors
mcpwm_cmpr_handle_t comparator1, comparator2, comparator3, comparator4;

// Create Comparator configurations - only 1 needed as they are all the same
mcpwm_comparator_config_t comparator_config1 = {
     .flags = {
        .update_cmp_on_tep = 1,  // Update compare threshold when timer counts to peak
    },
};
mcpwm_comparator_config_t comparator_config2 = {
     .flags = {
       .update_cmp_on_tep = 1,  // Update compare threshold when timer counts to peak
    },
};
mcpwm_comparator_config_t comparator_config3 = {
     .flags = {
       .update_cmp_on_tep = 1,  // Update compare threshold when timer counts to peak
    },
};
mcpwm_comparator_config_t comparator_config4 = {
     .flags = {
       .update_cmp_on_tep = 1,  // Update compare threshold when timer counts to peak
    },
};

// FOUR generators for the main motors
mcpwm_gen_handle_t generator1, generator2, generator3, generator4;

// Generators - One generator per PWM
// define instances of their configurations - only the GPIO assignments change
mcpwm_generator_config_t generator_config1 = {
	.gen_gpio_num = GPIO_PWM0A_OUT,
};

mcpwm_generator_config_t generator_config2 = {
	.gen_gpio_num = GPIO_PWM0B_OUT,
};

mcpwm_generator_config_t generator_config3 = {
	.gen_gpio_num = GPIO_PWM1A_OUT,
};

mcpwm_generator_config_t generator_config4 = {
	.gen_gpio_num = GPIO_PWM1B_OUT,
};

/*-----( Declare User-written Functions )-----*/
//<<<<<<<<<<<<<<<<<<<<>>>>>>>>>>>>>>>>>>>

void setup_Main_Motors()
{
  if (DEBUG_SETUP) {
    Serial.print(F("Create Timers.")); 
    Serial.println("     ");
  }  

  // MCPWM Initialise the timer
  ESP_ERROR_CHECK(mcpwm_new_timer(&timer_config0, &timer0));  // Main Motors

  if (DEBUG_SETUP) {
    Serial.print(F("Create Operators.")); 
    Serial.println("     ");
  } 
  // Initialise the Operators
  ESP_ERROR_CHECK(mcpwm_new_operator(&operator_config0, &operator0)); // Main Motors Same config
  ESP_ERROR_CHECK(mcpwm_new_operator(&operator_config1, &operator1)); // Main motors Same config
  
  if (DEBUG_SETUP) {
    Serial.print(F("Connect Timers and Operators.")); 
    Serial.println("     ");
  } 

  // Connect the Operators to the single Timer
  ESP_ERROR_CHECK(mcpwm_operator_connect_timer(operator0, timer0));  // Main  Motors
  ESP_ERROR_CHECK(mcpwm_operator_connect_timer(operator1, timer0));  // Main Motors

  if (DEBUG_SETUP) {
    Serial.print(F("Create Comparators.")); 
    Serial.println("     ");
  } 

  // Create the comparators which define the duty cycle.
  // Set the duty cycle using mcpwm_comparator_set_compare_value()
  // One comparator per Operator
  // Main Motors
  ESP_ERROR_CHECK(mcpwm_new_comparator(operator0, &comparator_config1, &comparator1));
  ESP_ERROR_CHECK(mcpwm_new_comparator(operator0, &comparator_config2, &comparator2));
  ESP_ERROR_CHECK(mcpwm_new_comparator(operator1, &comparator_config3, &comparator3));
  ESP_ERROR_CHECK(mcpwm_new_comparator(operator1, &comparator_config4, &comparator4));

  if (DEBUG_SETUP) {
    Serial.print(F("Create Generators.")); 
    Serial.println("     ");
  } 

  // Create the generators 
  // Main Motors
  ESP_ERROR_CHECK(mcpwm_new_generator(operator0, &generator_config1, &generator1));
  ESP_ERROR_CHECK(mcpwm_new_generator(operator0, &generator_config2, &generator2));
  ESP_ERROR_CHECK(mcpwm_new_generator(operator1, &generator_config3, &generator3));
  ESP_ERROR_CHECK(mcpwm_new_generator(operator1, &generator_config4, &generator4));

  if (DEBUG_SETUP) {
    Serial.print(F("Set the generator event actions.")); 
    Serial.println("     ");
  } 

  // Now set the generators to carry out the correct actions based on their direction and the timer event
  // Each generator will get an event when it's operator/comparator hits the duty_cycle
  // >> Main Motors <<
  // Generator 1
  // First go high when the counter is empty
  ESP_ERROR_CHECK(mcpwm_generator_set_action_on_timer_event(generator1, 
         MCPWM_GEN_TIMER_EVENT_ACTION(MCPWM_TIMER_DIRECTION_UP, MCPWM_TIMER_EVENT_EMPTY, MCPWM_GEN_ACTION_HIGH)));

  // Then go LOW when the counter hits the duty cycle threshold.
  ESP_ERROR_CHECK(mcpwm_generator_set_action_on_compare_event(generator1, 
         MCPWM_GEN_COMPARE_EVENT_ACTION(MCPWM_TIMER_DIRECTION_UP, comparator1, MCPWM_GEN_ACTION_LOW)));

  // Generator 2
  // First go high when the counter is empty
  ESP_ERROR_CHECK(mcpwm_generator_set_action_on_timer_event(generator2, 
         MCPWM_GEN_TIMER_EVENT_ACTION(MCPWM_TIMER_DIRECTION_UP, MCPWM_TIMER_EVENT_EMPTY, MCPWM_GEN_ACTION_HIGH)));

  // Then go LOW when the counter hits the duty cycle threshold.
  ESP_ERROR_CHECK(mcpwm_generator_set_action_on_compare_event(generator2, 
         MCPWM_GEN_COMPARE_EVENT_ACTION(MCPWM_TIMER_DIRECTION_UP, comparator2, MCPWM_GEN_ACTION_LOW)));

  // Generator 3
  // First go high when the counter is empty
  ESP_ERROR_CHECK(mcpwm_generator_set_action_on_timer_event(generator3, 
         MCPWM_GEN_TIMER_EVENT_ACTION(MCPWM_TIMER_DIRECTION_UP, MCPWM_TIMER_EVENT_EMPTY, MCPWM_GEN_ACTION_HIGH)));

  // Then go LOW when the counter hits the duty cycle threshold.
  ESP_ERROR_CHECK(mcpwm_generator_set_action_on_compare_event(generator3, 
         MCPWM_GEN_COMPARE_EVENT_ACTION(MCPWM_TIMER_DIRECTION_UP, comparator3, MCPWM_GEN_ACTION_LOW)));

  // Generator 4
  // First go high when the counter is empty
  ESP_ERROR_CHECK(mcpwm_generator_set_action_on_timer_event(generator4, 
         MCPWM_GEN_TIMER_EVENT_ACTION(MCPWM_TIMER_DIRECTION_UP, MCPWM_TIMER_EVENT_EMPTY, MCPWM_GEN_ACTION_HIGH)));

  // Then go LOW when the counter hits the duty cycle threshold.
  ESP_ERROR_CHECK(mcpwm_generator_set_action_on_compare_event(generator4, 
         MCPWM_GEN_COMPARE_EVENT_ACTION(MCPWM_TIMER_DIRECTION_UP, comparator4, MCPWM_GEN_ACTION_LOW)));

  if (DEBUG_SETUP) {
    Serial.print(F("Enable and Start Timer.")); 
    Serial.println("     ");
  } 

  // Enable the timers and start them
  // >> Main Motors <<
  ESP_ERROR_CHECK(mcpwm_timer_enable(timer0));
  ESP_ERROR_CHECK(mcpwm_timer_start_stop(timer0, MCPWM_TIMER_START_NO_STOP));

  if (DEBUG_SETUP) {
    Serial.print(F("Set the duty cycle to 0 (Stop).")); 
    Serial.println("     ");
  } 

  // Set the initial duty cycle to ZERO for all motors
  // >> Main Motors <<
  ESP_ERROR_CHECK(mcpwm_comparator_set_compare_value(comparator1, ZERO));
  ESP_ERROR_CHECK(mcpwm_comparator_set_compare_value(comparator2, ZERO));
  ESP_ERROR_CHECK(mcpwm_comparator_set_compare_value(comparator3, ZERO));
  ESP_ERROR_CHECK(mcpwm_comparator_set_compare_value(comparator4, ZERO));
}

void setup()
{
    // Start the built-in serial port, probably to Serial Monitor
  if (DEBUG_SETUP) {
    Serial.begin(9600);
    delay(200);
    Serial.print(F("ESP32 MCPWM Debug Output - V"));
    Serial.println(VERSION);
  }

  // Now set up PWM on the 4 main motors
  setup_Main_Motors();

}

void cycle_Motor_UP(int MotorID, int Cycle)
{
  // Loop and ramp the motors up then down

  if (DEBUG_LOOP) {
    Serial.print(F("Cycle UP - Motor  Steps"));
    Serial.println(F("             "));
    Serial.print(MotorID); 
    Serial.print("    ");
    Serial.print(Cycle);
    Serial.println("     ");
  }

  // Motor Ramp UP
  for (int duty_Cycle = 0; duty_Cycle <= Cycle; duty_Cycle++ ) 
  {
    if (DEBUG_LOOP) {
      Serial.print(F("Motor - ")); 
      Serial.print(MotorID);
      Serial.print(F("   Duty Cycle = ")); 
      Serial.print(duty_Cycle);
      Serial.println("     ");
    }

    // Set the initial duty cycle to the required duty cycle
    switch(MotorID) {
      case 1:
        ESP_ERROR_CHECK(mcpwm_comparator_set_compare_value(comparator1, duty_Cycle));   // <=== Not working
        break;
      case 2:
        ESP_ERROR_CHECK(mcpwm_comparator_set_compare_value(comparator2, duty_Cycle));
        break;
      case 3:
        ESP_ERROR_CHECK(mcpwm_comparator_set_compare_value(comparator3, duty_Cycle));
        break;
      case 4:
        ESP_ERROR_CHECK(mcpwm_comparator_set_compare_value(comparator4, duty_Cycle));
        break;
      default:
        break; // Do nothing
    }

    delay(200);  // Delay 200ms
  }

}

void cycle_Motor_DOWN(int MotorID, int Cycle)
{
  // Loop and ramp the motors up then down

  if (DEBUG_LOOP) {
    Serial.println(F("Cycle DOWN - Motor   Steps"));
    Serial.print(F("             "));
    Serial.print(MotorID); 
    Serial.print("    ");
    Serial.print(Cycle);
    Serial.println("     ");
  }

  // Motor Ramp DOWN
  for (int duty_Cycle = Cycle; duty_Cycle >= 0; duty_Cycle-- ) 
  {
    if (DEBUG_LOOP) {
      Serial.print(F("Motor - ")); 
      Serial.print(MotorID);
      Serial.print(F("   Duty Cycle = ")); 
      Serial.print(duty_Cycle);
      Serial.println("     ");
    }

    // Set the initial duty cycle to the required duty cycle
    switch(MotorID) {
      case 0:
        ESP_ERROR_CHECK(mcpwm_comparator_set_compare_value(comparator1, duty_Cycle));   // <=== Working???
        break;
      case 1:
        ESP_ERROR_CHECK(mcpwm_comparator_set_compare_value(comparator2, duty_Cycle));
        break;
      case 2:
        ESP_ERROR_CHECK(mcpwm_comparator_set_compare_value(comparator3, duty_Cycle));
        break;
      case 3:
        ESP_ERROR_CHECK(mcpwm_comparator_set_compare_value(comparator4, duty_Cycle));
        break;
      default:
        break; // Do nothing
    }
    delay(100);  // Delay 100ms
  }

}

void loop()
{
  delay(5000);  // Delay 5s
 
  // Call Loops to ramp the motors up then down one at a time
  // Max Duty Cycle of 95% of the available steps

  if (DEBUG_LOOP) {
    Serial.print(F("Motor 0, GP16")); 
    Serial.println("     ");
  }
  cycle_Motor_UP(0, PWM_DUTY_STEPS0 * 0.95);

  delay(MAINDELAY);  // Delay 5s 

  cycle_Motor_DOWN(0, PWM_DUTY_STEPS0 * 0.95);

  delay(MAINDELAY);  // Delay 10s  - allows me to move my scope probes

  if (DEBUG_LOOP) {
    Serial.print(F("Motor 1, GP17")); 
    Serial.println("     ");
  }
  //cycle_Motor_UP(1, PWM_DUTY_STEPS0 * 0.95);

  //delay(MAINDELAY);  // Delay 5s

  //cycle_Motor_DOWN(1, PWM_DUTY_STEPS0 * 0.95);

  //delay(MAINDELAY);  // Delay 10s  - allows me to move my scope probes

  if (DEBUG_LOOP) {
    Serial.print(F("Motor 2, GP18")); 
    Serial.println("     ");
  }
  //cycle_Motor_UP(2, PWM_DUTY_STEPS0 * 0.95);

  //delay(MAINDELAY);  // Delay 5s

  //cycle_Motor_DOWN(2, PWM_DUTY_STEPS0 * 0.95);

  //delay(MAINDELAY);  // Delay 10s - allows me to move my scope probes

  if (DEBUG_LOOP) {
    Serial.print(F("Motor 3, GP19")); 
    Serial.println("     ");
  }
  //cycle_Motor_UP(3, PWM_DUTY_STEPS0 * 0.95);

  //delay(MAINDELAY);  // Delay 5s

  //cycle_Motor_DOWN(3, PWM_DUTY_STEPS0 * 0.95);

  //delay(MAINDELAY);  // Delay 10s - allows me to move my scope probes
}





andy_wharton_uk
Posts: 7
Joined: Sat Nov 30, 2024 2:29 pm

Re: ESP32 will not output PWM signal

Postby andy_wharton_uk » Wed Dec 11, 2024 8:31 pm

Hi,

I added more GPIO captures in and eventually spotted I had my case statements wrong - UP was 1, 2, 3,4 and DOWN is 0, 1, 2, 3. Doh!!

I have working PWM signals now.

I'm still unsure why or how I managed to lose them in the first place but at least I have something to work with now.

I will go and stand in the corner for a while!!

Many Thanks
Andy

MicroController
Posts: 1818
Joined: Mon Oct 17, 2022 7:38 pm
Location: Europe, Germany

Re: ESP32 will not output PWM signal

Postby MicroController » Thu Dec 12, 2024 1:06 pm

andy_wharton_uk wrote:
Wed Dec 11, 2024 8:31 pm
I added more GPIO captures in and eventually spotted I had my case statements wrong - UP was 1, 2, 3,4 and DOWN is 0, 1, 2, 3. Doh!!
Sneaky... ;)

Btw, instead of that switch statement you could also use an array to hold the comparator handles, like mcpwm_cmpr_handle_t comps[4], then mcpwm_comparator_set_compare_value( comps[ MotorID ], duty_Cycle );

Who is online

Users browsing this forum: Google [Bot] and 36 guests