Skip to content

Commit

Permalink
Enhancement: Fixed a Bug
Browse files Browse the repository at this point in the history
- handled the case where value is greater than 255
- added doc strings for documentation
  • Loading branch information
Witty-Wizard committed Nov 28, 2024
1 parent a8f2aa2 commit b5a53b4
Show file tree
Hide file tree
Showing 2 changed files with 40 additions and 18 deletions.
13 changes: 3 additions & 10 deletions src/HBridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,15 +12,8 @@ void HBridge::begin()

void HBridge::write(int16_t value)
{
value = value % 256;
if (value >= 0)
{
digitalWrite(_dir_pin, LOW);
}
else
{
digitalWrite(_dir_pin, HIGH);
value = 255 + value;
}
value = constrain(value, -255, 255);
digitalWrite(_dir_pin, (value > 0) ? LOW : HIGH);
value = (value > 0) ? value : 255 + value;
analogWrite(_pin, value);
}
45 changes: 37 additions & 8 deletions src/HBridge.h
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
/**
* @file HBridge.h
* @brief Header file for the HBridge class.
* @brief Header file for the HBridge class, which controls an H-Bridge motor driver.
*/

#pragma once
Expand All @@ -9,13 +9,42 @@

#include "DriveMaster.h"

class HBridge : public DriveMaster{
private:

/**
* @class HBridge
* @brief A class to control an H-Bridge motor driver.
*
* The HBridge class provides methods to initialize and control the speed and direction
* of a motor using an H-Bridge. It inherits from the DriveMaster base class, which
* provides the control pins.
*/
class HBridge : public DriveMaster {
public:
explicit HBridge(int pin, int dir_pin);
void begin() override;
void write(int16_t value) override;
/**
* @brief Constructs an HBridge object with specified control pins.
*
* @param pin The PWM pin used for controlling motor speed (inherited from DriveMaster).
* @param dir_pin The direction control pin (inherited from DriveMaster).
*/
explicit HBridge(int pin, int dir_pin);

/**
* @brief Initializes the H-Bridge driver.
*
* Sets up the necessary pin modes for motor control.
*/
void begin() override;

/**
* @brief Writes a speed value to the motor.
*
* The value controls both the speed and direction of the motor.
* Positive values set forward direction, while negative values set reverse direction.
* The value is constrained between -255 and 255.
*
* @param value The speed value to write, where 0 is stopped, 255 is full forward,
* and -255 is full reverse.
*/
void write(int16_t value) override;
};

#endif
#endif // HBRIDGE_H

0 comments on commit b5a53b4

Please sign in to comment.