mirror of
https://gitlab.dit.htwk-leipzig.de/phillip.kuehne/dezibot.git
synced 2025-08-24 10:48:37 +02:00
Merge branch 'feature/#5-motion' into feature/#14-implement-motion-detection
This commit is contained in:
@@ -16,5 +16,6 @@ Dezibot::Dezibot():multiColorLight(),motionDetection(){
|
||||
|
||||
};
|
||||
void Dezibot::begin(void) {
|
||||
motion.begin();
|
||||
multiColorLight.begin();
|
||||
};
|
||||
|
81
src/motion/Motion.cpp
Normal file
81
src/motion/Motion.cpp
Normal file
@@ -0,0 +1,81 @@
|
||||
/**
|
||||
* @file Motion.cpp
|
||||
* @author Jonathan Schulze, Nick Hübenthal, Hans Haupt
|
||||
* @brief Implementation of the Motion class.
|
||||
* @version 0.1
|
||||
* @date 2023-12-13
|
||||
*
|
||||
* @copyright Copyright (c) 2023
|
||||
*
|
||||
*/
|
||||
|
||||
#include "Motion.h"
|
||||
|
||||
TaskHandle_t xMoveTaskHandle = NULL;
|
||||
TaskHandle_t xClockwiseTaskHandle = NULL;
|
||||
TaskHandle_t xAntiClockwiseTaskHandle = NULL;
|
||||
|
||||
// Initialize the movement component.
|
||||
void Motion::begin(void) {
|
||||
|
||||
};
|
||||
void Motion::moveTask(void * args) {
|
||||
analogWrite(MOTOR_LEFT_PIN, LEFT_MOTOR_DUTY);
|
||||
analogWrite(MOTOR_RIGHT_PIN, RIGHT_MOTOR_DUTY);
|
||||
vTaskDelay((uint32_t) args / portTICK_PERIOD_MS);
|
||||
analogWrite(MOTOR_LEFT_PIN, 0);
|
||||
analogWrite(MOTOR_RIGHT_PIN, 0);
|
||||
vTaskDelete(xMoveTaskHandle);
|
||||
};
|
||||
|
||||
// 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{
|
||||
analogWrite(MOTOR_LEFT_PIN, LEFT_MOTOR_DUTY);
|
||||
analogWrite(MOTOR_RIGHT_PIN, RIGHT_MOTOR_DUTY);
|
||||
}
|
||||
};
|
||||
|
||||
void Motion::leftMotorTask(void * args) {
|
||||
analogWrite(MOTOR_LEFT_PIN, LEFT_MOTOR_DUTY);
|
||||
analogWrite(MOTOR_RIGHT_PIN, 0);
|
||||
vTaskDelay((uint32_t) args / portTICK_PERIOD_MS);
|
||||
analogWrite(MOTOR_LEFT_PIN, 0);
|
||||
vTaskDelete(xClockwiseTaskHandle);
|
||||
};
|
||||
|
||||
// Rotate clockwise for a certain amount of time.
|
||||
void Motion::rotateClockwise(uint32_t rotateForMs) {
|
||||
if (rotateForMs > 0){
|
||||
xTaskCreate(leftMotorTask, "LeftMotor", 4096, (void*)rotateForMs, 10, &xClockwiseTaskHandle);
|
||||
} else {
|
||||
analogWrite(MOTOR_LEFT_PIN,LEFT_MOTOR_DUTY);
|
||||
analogWrite(MOTOR_RIGHT_PIN,0);
|
||||
}
|
||||
};
|
||||
|
||||
void Motion::rightMotorTask(void * args) {
|
||||
analogWrite(MOTOR_RIGHT_PIN, RIGHT_MOTOR_DUTY);
|
||||
analogWrite(MOTOR_LEFT_PIN,0);
|
||||
vTaskDelay((uint32_t) args / portTICK_PERIOD_MS);
|
||||
analogWrite(MOTOR_RIGHT_PIN, 0);
|
||||
vTaskDelete(xAntiClockwiseTaskHandle);
|
||||
};
|
||||
|
||||
// Rotate anticlockwise for a certain amount of time.
|
||||
void Motion::rotateAntiClockwise(uint32_t rotateForMs) {
|
||||
if(rotateForMs > 0){
|
||||
xTaskCreate(rightMotorTask, "RightMotor", 4096, (void*)rotateForMs, 10, &xAntiClockwiseTaskHandle);
|
||||
} else {
|
||||
analogWrite(MOTOR_RIGHT_PIN,RIGHT_MOTOR_DUTY);
|
||||
analogWrite(MOTOR_LEFT_PIN,0);
|
||||
}
|
||||
};
|
||||
|
||||
void Motion::stop(void){
|
||||
analogWrite(MOTOR_LEFT_PIN,0);
|
||||
analogWrite(MOTOR_RIGHT_PIN,0);
|
||||
}
|
||||
|
@@ -1,7 +1,64 @@
|
||||
/**
|
||||
* @file Motion.h
|
||||
* @author Jonathan Schulze, Nick Hübenthal
|
||||
* @brief This component controls the ability to rotate and change position.
|
||||
* @version 0.1
|
||||
* @date 2023-12-13
|
||||
*
|
||||
* @copyright Copyright (c) 2023
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef Motion_h
|
||||
#define Motion_h
|
||||
#include <stdint.h>
|
||||
#include <Arduino.h>
|
||||
#include <freertos/FreeRTOS.h>
|
||||
#include <freertos/task.h>
|
||||
|
||||
class Motion{
|
||||
protected:
|
||||
static const uint8_t RIGHT_MOTOR_DUTY = 128;
|
||||
static const uint8_t LEFT_MOTOR_DUTY = 128;
|
||||
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);
|
||||
|
||||
public:
|
||||
/**
|
||||
* @brief Initialize the movement component.
|
||||
*
|
||||
*/
|
||||
void begin(void);
|
||||
|
||||
/**
|
||||
* @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().
|
||||
* @param moveForMs Representing the duration of forward moving in milliseconds.
|
||||
*/
|
||||
static void move(uint32_t moveForMs=0);
|
||||
|
||||
/**
|
||||
* @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.
|
||||
*/
|
||||
static void rotateClockwise(uint32_t rotateForMs=0);
|
||||
|
||||
/**
|
||||
* @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.
|
||||
*/
|
||||
static void rotateAntiClockwise(uint32_t rotateForMs=0);
|
||||
|
||||
/**
|
||||
* @brief stops any current movement, no matter if timebased or endless
|
||||
*
|
||||
*/
|
||||
static void stop(void);
|
||||
|
||||
};
|
||||
#endif //Motion_h
|
Reference in New Issue
Block a user