mirror of
https://gitlab.dit.htwk-leipzig.de/phillip.kuehne/dezibot.git
synced 2025-08-24 18:58:36 +02:00
Merged MotionCorrection into Release (including InterfaceChange from motionDetection to motion.detection
This commit is contained in:
@@ -11,11 +11,10 @@
|
||||
|
||||
#include "Motion.h"
|
||||
|
||||
TaskHandle_t xMoveTaskHandle = NULL;
|
||||
TaskHandle_t xClockwiseTaskHandle = NULL;
|
||||
TaskHandle_t xAntiClockwiseTaskHandle = NULL;
|
||||
|
||||
// Initialize the movement component.
|
||||
|
||||
|
||||
void Motion::begin(void) {
|
||||
ledc_timer_config_t motor_timer = {
|
||||
.speed_mode = LEDC_MODE,
|
||||
@@ -27,37 +26,118 @@ void Motion::begin(void) {
|
||||
ledc_timer_config(&motor_timer);
|
||||
Motion::left.begin();
|
||||
Motion::right.begin();
|
||||
detection.begin();
|
||||
};
|
||||
void Motion::moveTask(void * args) {
|
||||
uint32_t runtime = (uint32_t)args;
|
||||
|
||||
Motion::left.setSpeed(LEFT_MOTOR_DUTY);
|
||||
Motion::right.setSpeed(RIGHT_MOTOR_DUTY);
|
||||
vTaskDelay((uint32_t) args / portTICK_PERIOD_MS);
|
||||
Motion::left.setSpeed(0);
|
||||
Motion::right.setSpeed(0);
|
||||
vTaskDelete(xMoveTaskHandle);
|
||||
};
|
||||
Motion::xLastWakeTime = xTaskGetTickCount();
|
||||
while(1){
|
||||
if(runtime>40||runtime==0){
|
||||
vTaskDelayUntil(&xLastWakeTime,40);
|
||||
runtime -= 40;
|
||||
//calc new parameters
|
||||
//set new parameters
|
||||
int fifocount = detection.getDataFromFIFO(buffer);
|
||||
int rightCounter = 0;
|
||||
int leftCounter = 0;
|
||||
int changerate = 0;
|
||||
for(int i = 0;i<fifocount;i++){
|
||||
if(buffer[i].gyro.z>correctionThreshold){
|
||||
rightCounter++;
|
||||
} else if(buffer[i].gyro.z<-correctionThreshold){
|
||||
leftCounter++;
|
||||
}
|
||||
}
|
||||
int difference = abs(leftCounter-rightCounter);
|
||||
if (difference>25){
|
||||
changerate = 200;
|
||||
} else if(difference>20){
|
||||
changerate = 100;
|
||||
} else if(difference >15){
|
||||
changerate = 50;
|
||||
} else if(difference > 10){
|
||||
changerate = 20;
|
||||
} else{
|
||||
changerate = 5;
|
||||
}
|
||||
|
||||
// Move forward for a certain amount of time.
|
||||
void Motion::move(uint32_t moveForMs) {
|
||||
if (moveForMs > 0){
|
||||
xTaskCreate(moveTask, "Move", 4096, (void*)moveForMs, 10, &xMoveTaskHandle);
|
||||
} else{
|
||||
Motion::left.setSpeed(LEFT_MOTOR_DUTY);
|
||||
Motion::right.setSpeed(RIGHT_MOTOR_DUTY);
|
||||
if(leftCounter>rightCounter){ //rotates anticlock
|
||||
LEFT_MOTOR_DUTY+=changerate;
|
||||
RIGHT_MOTOR_DUTY-=changerate;
|
||||
} else if(leftCounter<rightCounter){
|
||||
LEFT_MOTOR_DUTY-=changerate;
|
||||
RIGHT_MOTOR_DUTY+=changerate;
|
||||
}
|
||||
|
||||
Motion::left.setSpeed(LEFT_MOTOR_DUTY);
|
||||
Motion::right.setSpeed(RIGHT_MOTOR_DUTY);
|
||||
} else {
|
||||
vTaskDelayUntil(&xLastWakeTime,runtime);
|
||||
Motion::left.setSpeed(0);
|
||||
Motion::right.setSpeed(0);
|
||||
vTaskDelete(xMoveTaskHandle);
|
||||
}
|
||||
}
|
||||
};
|
||||
|
||||
// Move forward for a certain amount of time.
|
||||
void Motion::move(uint32_t moveForMs, uint baseValue) {
|
||||
if(xMoveTaskHandle){
|
||||
vTaskDelete(xMoveTaskHandle);
|
||||
xMoveTaskHandle = NULL;
|
||||
}
|
||||
if(xClockwiseTaskHandle){
|
||||
|
||||
vTaskDelete(xClockwiseTaskHandle);
|
||||
xClockwiseTaskHandle = NULL;
|
||||
}
|
||||
if(xAntiClockwiseTaskHandle){
|
||||
vTaskDelete(xAntiClockwiseTaskHandle);
|
||||
xAntiClockwiseTaskHandle = NULL;
|
||||
|
||||
}
|
||||
LEFT_MOTOR_DUTY = baseValue;
|
||||
RIGHT_MOTOR_DUTY = baseValue;
|
||||
xTaskCreate(moveTask, "Move", 4096, (void*)moveForMs, 10, &xMoveTaskHandle);
|
||||
|
||||
};
|
||||
|
||||
void Motion::leftMotorTask(void * args) {
|
||||
Motion::left.setSpeed(LEFT_MOTOR_DUTY);
|
||||
uint32_t runtime = (uint32_t)args;
|
||||
if(xMoveTaskHandle){
|
||||
vTaskDelete(xMoveTaskHandle);
|
||||
xMoveTaskHandle = NULL;
|
||||
}
|
||||
if(xAntiClockwiseTaskHandle){
|
||||
vTaskDelete(xAntiClockwiseTaskHandle);
|
||||
xAntiClockwiseTaskHandle = NULL;
|
||||
}
|
||||
Motion::right.setSpeed(0);
|
||||
vTaskDelay((uint32_t) args / portTICK_PERIOD_MS);
|
||||
Motion::left.setSpeed(0);
|
||||
vTaskDelete(xClockwiseTaskHandle);
|
||||
Motion::left.setSpeed(LEFT_MOTOR_DUTY);
|
||||
while(1){
|
||||
if((runtime>40)||(runtime==0)){
|
||||
vTaskDelayUntil(&xLastWakeTime,40);
|
||||
runtime -=40;
|
||||
} else {
|
||||
vTaskDelayUntil(&xLastWakeTime,runtime);
|
||||
Motion::left.setSpeed(0);
|
||||
vTaskDelete(xClockwiseTaskHandle);
|
||||
}
|
||||
vTaskDelayUntil(&xLastWakeTime,40);
|
||||
}
|
||||
};
|
||||
|
||||
// Rotate clockwise for a certain amount of time.
|
||||
void Motion::rotateClockwise(uint32_t rotateForMs) {
|
||||
void Motion::rotateClockwise(uint32_t rotateForMs,uint baseValue) {
|
||||
LEFT_MOTOR_DUTY = baseValue;
|
||||
RIGHT_MOTOR_DUTY = baseValue;
|
||||
if (rotateForMs > 0){
|
||||
if(xClockwiseTaskHandle){
|
||||
vTaskDelete(xClockwiseTaskHandle);
|
||||
}
|
||||
xTaskCreate(leftMotorTask, "LeftMotor", 4096, (void*)rotateForMs, 10, &xClockwiseTaskHandle);
|
||||
} else {
|
||||
Motion::left.setSpeed(LEFT_MOTOR_DUTY);
|
||||
@@ -66,16 +146,37 @@ void Motion::rotateClockwise(uint32_t rotateForMs) {
|
||||
};
|
||||
|
||||
void Motion::rightMotorTask(void * args) {
|
||||
uint32_t runtime = (uint32_t)args;
|
||||
if(xMoveTaskHandle){
|
||||
vTaskDelete(xMoveTaskHandle);
|
||||
xMoveTaskHandle = NULL;
|
||||
}
|
||||
if(xClockwiseTaskHandle){
|
||||
vTaskDelete(xClockwiseTaskHandle);
|
||||
xClockwiseTaskHandle = NULL;
|
||||
}
|
||||
Motion::right.setSpeed(RIGHT_MOTOR_DUTY);
|
||||
Motion::left.setSpeed(0);
|
||||
vTaskDelay((uint32_t) args / portTICK_PERIOD_MS);
|
||||
Motion::right.setSpeed(0);
|
||||
vTaskDelete(xAntiClockwiseTaskHandle);
|
||||
while(1){
|
||||
if(runtime>40||runtime==0){
|
||||
vTaskDelayUntil(&xLastWakeTime,40);
|
||||
runtime -= 40;
|
||||
} else {
|
||||
vTaskDelayUntil(&xLastWakeTime,runtime);
|
||||
Motion::right.setSpeed(0);
|
||||
vTaskDelete(xAntiClockwiseTaskHandle);
|
||||
}
|
||||
}
|
||||
};
|
||||
|
||||
// Rotate anticlockwise for a certain amount of time.
|
||||
void Motion::rotateAntiClockwise(uint32_t rotateForMs) {
|
||||
void Motion::rotateAntiClockwise(uint32_t rotateForMs,uint baseValue) {
|
||||
LEFT_MOTOR_DUTY = baseValue;
|
||||
RIGHT_MOTOR_DUTY = baseValue;
|
||||
if(rotateForMs > 0){
|
||||
if(xAntiClockwiseTaskHandle){
|
||||
vTaskDelete(xAntiClockwiseTaskHandle);
|
||||
}
|
||||
xTaskCreate(rightMotorTask, "RightMotor", 4096, (void*)rotateForMs, 10, &xAntiClockwiseTaskHandle);
|
||||
} else {
|
||||
Motion::right.setSpeed(RIGHT_MOTOR_DUTY);
|
||||
@@ -84,6 +185,18 @@ void Motion::rotateAntiClockwise(uint32_t rotateForMs) {
|
||||
};
|
||||
|
||||
void Motion::stop(void){
|
||||
if(xMoveTaskHandle){
|
||||
vTaskDelete(xMoveTaskHandle);
|
||||
xMoveTaskHandle = NULL;
|
||||
}
|
||||
if(xAntiClockwiseTaskHandle){
|
||||
vTaskDelete(xAntiClockwiseTaskHandle);
|
||||
xAntiClockwiseTaskHandle = NULL;
|
||||
}
|
||||
if(xClockwiseTaskHandle){
|
||||
vTaskDelete(xClockwiseTaskHandle);
|
||||
xClockwiseTaskHandle = NULL;
|
||||
}
|
||||
Motion::left.setSpeed(0);
|
||||
Motion::right.setSpeed(0);
|
||||
}
|
||||
|
@@ -16,17 +16,37 @@
|
||||
#include <freertos/FreeRTOS.h>
|
||||
#include <freertos/task.h>
|
||||
#include "driver/ledc.h"
|
||||
#include "motionDetection/MotionDetection.h"
|
||||
#define LEDC_MODE LEDC_LOW_SPEED_MODE
|
||||
#define TIMER LEDC_TIMER_2
|
||||
#define CHANNEL_LEFT LEDC_CHANNEL_3
|
||||
#define CHANNEL_RIGHT LEDC_CHANNEL_4
|
||||
#define DUTY_RES LEDC_TIMER_13_BIT // Set duty resolution to 13 bits
|
||||
#define FREQUENCY (5000) // Frequency in Hertz. Set frequency at 5 kHz
|
||||
#define DEFAULT_BASE_VALUE 3900
|
||||
class Motor{
|
||||
public:
|
||||
Motor(uint8_t pin, ledc_timer_t timer, ledc_channel_t channel);
|
||||
|
||||
/**
|
||||
* @brief Initializes the motor
|
||||
*/
|
||||
void begin(void);
|
||||
|
||||
/**
|
||||
* @brief Set the Speed by changing the pwm. To avoid current peaks, a linear ramp-up is used.
|
||||
*
|
||||
* @attention it is requried at any time to use that method to access the motors or methods of the motionclass to avoid such peaks.
|
||||
*
|
||||
* @param duty the duty cyle that should be set, can be between 0-8192
|
||||
*/
|
||||
void setSpeed(uint16_t duty);
|
||||
|
||||
/**
|
||||
* @brief returns the currently activ speed
|
||||
*
|
||||
* @return current speedvalue of the motor
|
||||
*/
|
||||
uint16_t getSpeed(void);
|
||||
protected:
|
||||
uint8_t pin;
|
||||
@@ -38,18 +58,28 @@ class Motor{
|
||||
|
||||
class Motion{
|
||||
protected:
|
||||
static const uint16_t RIGHT_MOTOR_DUTY = 4096;
|
||||
static const uint16_t LEFT_MOTOR_DUTY = 4096;
|
||||
static inline uint16_t RIGHT_MOTOR_DUTY = DEFAULT_BASE_VALUE;
|
||||
static inline uint16_t LEFT_MOTOR_DUTY = DEFAULT_BASE_VALUE;
|
||||
static const int MOTOR_RIGHT_PIN = 11;
|
||||
static const int MOTOR_LEFT_PIN = 12;
|
||||
static void moveTask(void * args);
|
||||
static void leftMotorTask(void * args);
|
||||
static void rightMotorTask(void * args);
|
||||
static inline TaskHandle_t xMoveTaskHandle = NULL;
|
||||
static inline TaskHandle_t xClockwiseTaskHandle = NULL;
|
||||
static inline TaskHandle_t xAntiClockwiseTaskHandle = NULL;
|
||||
static inline TickType_t xLastWakeTime;
|
||||
|
||||
static inline FIFO_Package* buffer = new FIFO_Package[64];
|
||||
static inline int correctionThreshold = 150;
|
||||
|
||||
public:
|
||||
//Shared Timer to sync movement
|
||||
//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 right = Motor(MOTOR_RIGHT_PIN,TIMER,CHANNEL_RIGHT);
|
||||
|
||||
//MotionDetection instance, for motion Correction and user (access with dezibot.motion.detection)
|
||||
static inline MotionDetection detection;
|
||||
|
||||
/**
|
||||
* @brief Initialize the movement component.
|
||||
@@ -60,23 +90,30 @@ public:
|
||||
/**
|
||||
* @brief Move forward for a certain amount of time.
|
||||
* Call with moveForMs 0 will start movement, that must be stopped explicit by call to stop().
|
||||
* The function applys a basic algorithm to improve the straigthness of the movement.
|
||||
* Lifting the robot from the desk may corrupt the results and is not recommended.
|
||||
*
|
||||
* @param moveForMs Representing the duration of forward moving in milliseconds.
|
||||
* @param baseValue The value that is used to start with the calibrated movement. Defaults to 3900.
|
||||
* If the Dezibot is not moving forward at all increasing the value may help. If the robot is just jumping up and down but not forward, try a lower value.
|
||||
*/
|
||||
static void move(uint32_t moveForMs=0);
|
||||
static void move(uint32_t moveForMs=0,uint baseValue=DEFAULT_BASE_VALUE);
|
||||
|
||||
/**
|
||||
* @brief Rotate clockwise for a certain amount of time.
|
||||
* Call with moveForMs 0 will start movement, that must be stopped explicit by call to stop().
|
||||
* @param rotateForMs Representing the duration of rotating clockwise in milliseconds.
|
||||
* @param rotateForMs Representing the duration of rotating clockwise in milliseconds, or 0 to rotate until another movecmd is issued. Default is 0
|
||||
* @param baseValue The value that is used to start with the calibrated movement (not released yet, currently just the used value)
|
||||
*/
|
||||
static void rotateClockwise(uint32_t rotateForMs=0);
|
||||
static void rotateClockwise(uint32_t rotateForMs=0,uint baseValue=DEFAULT_BASE_VALUE);
|
||||
|
||||
/**
|
||||
* @brief Rotate anticlockwise for a certain amount of time.
|
||||
* Call with moveForMs 0 will start movement, that must be stopped explicit by call to stop().
|
||||
* @param rotateForMs Representing the duration of rotating anticlockwise in milliseconds.
|
||||
* @param rotateForMs Representing the duration of rotating anticlockwise in milliseconds or 0 to let the robot turn until another movecommand is issued. Default is 0.
|
||||
* @param baseValue The value that is used to start with the calibrated movement (not released yet, currently just the used value).
|
||||
*/
|
||||
static void rotateAntiClockwise(uint32_t rotateForMs=0);
|
||||
static void rotateAntiClockwise(uint32_t rotateForMs=0,uint baseValue=DEFAULT_BASE_VALUE);
|
||||
|
||||
/**
|
||||
* @brief stops any current movement, no matter if timebased or endless
|
||||
@@ -84,6 +121,14 @@ public:
|
||||
*/
|
||||
static void stop(void);
|
||||
|
||||
/**
|
||||
* @brief Does the same as the move function, but this function does not apply any kind of algorithm to improve the result.
|
||||
*
|
||||
* @param moveForMs how many ms should the robot move, or 0 to let the robot move until another move command is mentioned, default is 0
|
||||
* @param baseValue the duty value that is used for the movement, default is 0
|
||||
*/
|
||||
static void moveWithoutCorrection(uint32_t moveForMs=0, uint baseValue = DEFAULT_BASE_VALUE);
|
||||
|
||||
};
|
||||
|
||||
|
||||
|
@@ -23,9 +23,24 @@ void Motor::begin(void){
|
||||
};
|
||||
|
||||
void Motor::setSpeed(uint16_t duty){
|
||||
this->duty = duty;
|
||||
ledc_set_duty(LEDC_MODE,this->channel,duty);
|
||||
ledc_update_duty(LEDC_MODE,this->channel);
|
||||
|
||||
int difference = duty-this->getSpeed();
|
||||
if (difference > 0){
|
||||
for(int i = 0;i<difference;i+=difference/20){
|
||||
this->duty += difference/20;
|
||||
ledc_set_duty(LEDC_MODE,this->channel,duty);
|
||||
ledc_update_duty(LEDC_MODE,this->channel);
|
||||
delayMicroseconds(5);
|
||||
}
|
||||
} else {
|
||||
for(int i = 0;i>difference;i-=abs(difference/20)){
|
||||
this->duty -= abs(difference/20);
|
||||
ledc_set_duty(LEDC_MODE,this->channel,duty);
|
||||
ledc_update_duty(LEDC_MODE,this->channel);
|
||||
delayMicroseconds(5);
|
||||
}
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
uint16_t Motor::getSpeed(void){
|
||||
|
Reference in New Issue
Block a user