/
InitializePwmOutput()

InitializePwmOutput()

Purpose

Enables the use of a PWM pin by initializing it with information relating to its characteristics.

When to use

Once for each PWM Pin used on the board. If you connect anything to a PWM pin, its mode should be set.

Where to use

At the beginning of your code execution, in the void setup() part of your .ino file, so that the pin is initialized before it is referred to by your code.

Click here to learn more on the PWM outputs of the CrcDuino board. It explains in particular why PWM port #1 to #4 can only be used with power motor controller.

CrcLib Error mode is triggered if a given PWM pin is initialized more than once. Make sure to only use InitializePwmOutput() in void setup()!

This function requires the use of the following functions at some point of your .ino file in order to work properly:

Returns

This function does not return a value once it has completed its tasks.

Main prototype and parameters

static void CrcLib::InitializePwmOutput(unsigned char pin, int minPulseWidth, int maxPulseWidth, bool reverse)

The following parameters must be passed to the function for it to work properly:

  • pin: The name of the PWM pin you want to initialize. Must be of the type unsigned char.

  • minPulseWidth: The minimum pulse width, in µs, of your servo motor. Must be of the type int.

  • maxPulseWidth: The maximum pulse width, in µs, of your servo motor. Must be of the type int.

  • reverse: Whether or not to invert the rotation direction of the servo. Must be of the type bool.

Overloads

#1: Using default pulse width values, without the reverse feature

static void CrcLib::InitializePwmOutput(unsigned char pin)

It is the easiest, minimal way to use this function. A 1000µs min pulse width and 2000µs max pulse width will be used by default. The following parameters must be passed to the function for it to work properly:

  • pin: The name of the PWM pin you want to initialize. Must be of the type unsigned char.

#2: Using default pulse width values, with the reverse feature

static void CrcLib::InitializePwmOutput(unsigned char pin, bool reverse)

A 1000µs min pulse width and 2000µs max pulse width will be used by default. The following parameters must be passed to the function for it to work properly:

  • pin: The name of the PWM pin you want to set. Must be of the type unsigned char.

  • reverse: Whether or not to invert the rotation direction of the servo. Must be of the type bool.

#3: Setting pulse width values, without the reverse feature

static void CrcLib::InitializePwmOutput(unsigned char pin, int minPulseWidth, int maxPulseWidth)

The following parameters must be passed to the function for it to work properly:

  • pin: The name of the PWM pin you want to initialize. Must be of the type unsigned char.

  • minPulseWidth: The minimum pulse width, in µs, of your servo motor. Must be of the type int.

  • maxPulseWidth: The maximum pulse width, in µs, of your servo motor. Must be of the type int.

Examples

#include <CrcLib.h> #define RIGHT_FEEDER_MOTOR CRC_PWM_5 void setup() { CrcLib::Initialize(); CrcLib::InitializePwmOutput(RIGHT_FEEDER_MOTOR); CrcLib::InitializePwmOutput(CRC_PWM_6, true); /* The rest of your setup code ... */ } void loop() { CrcLib::Update(); /* The rest of your looping code ... */ }
#include <CrcLib.h> void setup() { CrcLib::Initialize(); CrcLib::InitializePwmOutput(CRC_PWM_12, 500, 2500); /* The rest of your setup code ... */ } void loop() { CrcLib::Update(); /* The rest of your looping code ... */ }

 

More on this function

Related articles

Related content

SetPwmOutput()
More like this
Debugging - CrcLib Error Codes
Debugging - CrcLib Error Codes
More like this
MoveArcade()
More like this
GetAnalogInput()
GetAnalogInput()
Read with this
InitializePwmOutput() {FR}
InitializePwmOutput() {FR}
More like this
IsCommValid()
Read with this