mirror of
https://gitlab.dit.htwk-leipzig.de/phillip.kuehne/dezibot.git
synced 2025-05-19 02:51:47 +02:00
Merge commit 'bb338d31be6bd5d71db175c6243401b71725b41d' into power_management
This commit is contained in:
commit
ff11ad95b0
@ -23,6 +23,7 @@
|
|||||||
#define CHANNEL_LEFT LEDC_CHANNEL_3
|
#define CHANNEL_LEFT LEDC_CHANNEL_3
|
||||||
#define CHANNEL_RIGHT LEDC_CHANNEL_4
|
#define CHANNEL_RIGHT LEDC_CHANNEL_4
|
||||||
#define DUTY_RES LEDC_TIMER_13_BIT // Set duty resolution to 13 bits
|
#define DUTY_RES LEDC_TIMER_13_BIT // Set duty resolution to 13 bits
|
||||||
|
#define PHASE_180_DEG (1 << (DUTY_RES))/2 // (2**DUTY_RES)/2 Set phase to 180 degrees
|
||||||
#define FREQUENCY (5000) // Frequency in Hertz. Set frequency at 5 kHz
|
#define FREQUENCY (5000) // Frequency in Hertz. Set frequency at 5 kHz
|
||||||
#define DEFAULT_BASE_VALUE 3900
|
#define DEFAULT_BASE_VALUE 3900
|
||||||
|
|
||||||
@ -32,7 +33,7 @@
|
|||||||
|
|
||||||
class Motor{
|
class Motor{
|
||||||
public:
|
public:
|
||||||
Motor(uint8_t pin, ledc_timer_t timer, ledc_channel_t channel);
|
Motor(uint8_t pin, ledc_timer_t timer, ledc_channel_t channel, int phase=0);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Initializes the motor
|
* @brief Initializes the motor
|
||||||
@ -80,12 +81,17 @@ class Motor{
|
|||||||
ledc_channel_t channel;
|
ledc_channel_t channel;
|
||||||
Power* powerManager;
|
Power* powerManager;
|
||||||
uint16_t duty;
|
uint16_t duty;
|
||||||
|
// The phase of the pwm signal, expressed as a number betweeen 0 and
|
||||||
|
// the maximum value representable by the pwm timer resolution.
|
||||||
|
int phase;
|
||||||
};
|
};
|
||||||
|
|
||||||
class Motion{
|
class Motion{
|
||||||
protected:
|
protected:
|
||||||
static inline uint16_t RIGHT_MOTOR_DUTY = DEFAULT_BASE_VALUE;
|
static inline uint16_t RIGHT_MOTOR_DUTY = DEFAULT_BASE_VALUE;
|
||||||
static inline uint16_t LEFT_MOTOR_DUTY = DEFAULT_BASE_VALUE;
|
static inline uint16_t LEFT_MOTOR_DUTY = DEFAULT_BASE_VALUE;
|
||||||
|
static inline int LEFT_MOTOR_PHASE = 0;
|
||||||
|
static inline int RIGHT_MOTOR_PHASE = PHASE_180_DEG;
|
||||||
static const int MOTOR_RIGHT_PIN = 11;
|
static const int MOTOR_RIGHT_PIN = 11;
|
||||||
static const int MOTOR_LEFT_PIN = 12;
|
static const int MOTOR_LEFT_PIN = 12;
|
||||||
static void moveTask(void * args);
|
static void moveTask(void * args);
|
||||||
@ -101,8 +107,8 @@ protected:
|
|||||||
|
|
||||||
public:
|
public:
|
||||||
//Instances of the motors, so they can also be used from outside to set values for the motors directly.
|
//Instances of the motors, so they can also be used from outside to set values for the motors directly.
|
||||||
static inline Motor left = Motor(MOTOR_LEFT_PIN,TIMER,CHANNEL_LEFT);
|
static inline Motor left = Motor(MOTOR_LEFT_PIN,TIMER,CHANNEL_LEFT,LEFT_MOTOR_PHASE);
|
||||||
static inline Motor right = Motor(MOTOR_RIGHT_PIN,TIMER,CHANNEL_RIGHT);
|
static inline Motor right = Motor(MOTOR_RIGHT_PIN,TIMER,CHANNEL_RIGHT,RIGHT_MOTOR_PHASE);
|
||||||
|
|
||||||
//MotionDetection instance, for motion Correction and user (access with dezibot.motion.detection)
|
//MotionDetection instance, for motion Correction and user (access with dezibot.motion.detection)
|
||||||
static inline MotionDetection detection;
|
static inline MotionDetection detection;
|
||||||
|
@ -4,24 +4,27 @@
|
|||||||
#define MOTOR_LEFT_PIN 12
|
#define MOTOR_LEFT_PIN 12
|
||||||
#define MOTOR_RIGHT_PIN 11
|
#define MOTOR_RIGHT_PIN 11
|
||||||
|
|
||||||
Motor::Motor(uint8_t pin, ledc_timer_t timer, ledc_channel_t channel) {
|
Motor::Motor(uint8_t pin, ledc_timer_t timer, ledc_channel_t channel, int phase){
|
||||||
this->pin = pin;
|
this->pin = pin;
|
||||||
this->channel = channel;
|
this->channel = channel;
|
||||||
this->timer = timer;
|
this->timer = timer;
|
||||||
this->duty = 0;
|
this->duty = 0;
|
||||||
|
this->phase = phase;
|
||||||
};
|
};
|
||||||
|
|
||||||
void Motor::begin(void) {
|
void Motor::begin(void){
|
||||||
pinMode(this->pin, OUTPUT);
|
pinMode(this->pin,OUTPUT);
|
||||||
ledc_channel_config_t channelConfig = {.gpio_num = this->pin,
|
ledc_channel_config_t channelConfig = {
|
||||||
.speed_mode = LEDC_MODE,
|
.gpio_num = this->pin,
|
||||||
.channel = this->channel,
|
.speed_mode = LEDC_MODE,
|
||||||
.intr_type = LEDC_INTR_DISABLE,
|
.channel = this->channel,
|
||||||
.timer_sel = this->timer,
|
.intr_type = LEDC_INTR_DISABLE,
|
||||||
.duty = 0, // Set duty to 0%
|
.timer_sel = this->timer,
|
||||||
.hpoint = 0};
|
.duty = 0, // Set duty to 0%
|
||||||
ledc_channel_config(&channelConfig);
|
.hpoint = this->phase
|
||||||
Serial.println("Motor begin done");
|
};
|
||||||
|
ledc_channel_config(&channelConfig);
|
||||||
|
Serial.println("Motor begin done");
|
||||||
};
|
};
|
||||||
|
|
||||||
bool Motor::setSpeed(uint16_t duty) {
|
bool Motor::setSpeed(uint16_t duty) {
|
||||||
|
Loading…
x
Reference in New Issue
Block a user