This commit is contained in:
mulbric1
2024-06-04 10:22:35 +00:00
parent 60175861db
commit 5bd1eee633
23 changed files with 1213 additions and 18 deletions

24
src/Dezibot.cpp Normal file
View File

@@ -0,0 +1,24 @@
/**
* @file Dezibot.cpp
* @author Anton Jacker, Hans Haupt, Saskia Duebener
* @brief
* @version 0.1
* @date 2023-11-26
*
* @copyright Copyright (c) 2023
*
*/
#include "Dezibot.h"
Dezibot::Dezibot():multiColorLight(),motionDetection(){
};
void Dezibot::begin(void) {
motion.begin();
multiColorLight.begin();
lightDetection.begin();
motionDetection.begin();
};

51
src/Dezibot.h Normal file
View File

@@ -0,0 +1,51 @@
/**
* @file Dezibot.h
* @author your name (you@domain.com)
* @brief
* @version 0.1
* @date 2023-11-19
*
* @copyright Copyright (c) 2023
*
*/
#ifndef Dezibot_h
#define Dezibot_h
#include "motion/Motion.h"
#include "lightDetection/LightDetection.h"
#include "colorDetection/ColorDetection.h"
#include "multiColorLight/MultiColorLight.h"
#include "motionDetection/MotionDetection.h"
class Dezibot {
protected:
public:
Dezibot();
Motion motion;
LightDetection lightDetection;
ColorDetection colorDetection;
MultiColorLight multiColorLight;
MotionDetection motionDetection;
void begin(void);
/*
Display display
IRCommuncation irCommuncation (beinhaltet Kommuniaktion / Annhärung...)
Battery battery
Extension extension
WiFi wifi //wie wird WiFi geschrieben?
//nur lesender Zugriff, in dieser Klasse sind andere Instanzen mit dem Dezibotinterface gekapselt
Friends friends
OperatingSystem operatingSystem
USBCommunication usbCommunication
Button button
//nicht unique, initzial Dezibot
String robotName
*/
};
#endif //Dezibot_h

View File

@@ -0,0 +1,7 @@
#ifndef ColorDetection_h
#define ColorDetection_h
class ColorDetection{
};
#endif //ColorDetection_h

View File

@@ -0,0 +1,114 @@
#include "LightDetection.h"
void LightDetection::begin(void){
LightDetection::beginInfrared();
LightDetection::beginDaylight();
};
uint16_t LightDetection::getValue(photoTransistors sensor){
uint16_t result;
switch(sensor){
//Fall Through intended
case IR_FRONT:
case IR_LEFT:
case IR_RIGHT:
case IR_BACK:
return readIRPT(sensor);
case DL_BOTTOM:
case DL_FRONT:
return readDLPT(sensor);
}
};
photoTransistors LightDetection::getBrightest(ptType type){
photoTransistors maxSensor;
uint16_t maxReading = 0;
uint16_t currentReading = 0;
if (type == IR){
for(const auto pt : allIRPTs){
currentReading = LightDetection::getValue(pt);
if (currentReading > maxReading){
maxReading = currentReading;
maxSensor = pt;
}
}
} else {
for(const auto pt : allDLPTs){
currentReading = LightDetection::getValue(pt);
if (currentReading > maxReading){
maxReading = currentReading;
maxSensor = pt;
}
}
}
return maxSensor;
};
uint32_t LightDetection::getAverageValue(photoTransistors sensor, uint32_t measurments, uint32_t timeBetween){
TickType_t xLastWakeTime = xTaskGetTickCount();
TickType_t frequency = timeBetween / portTICK_PERIOD_MS;
uint64_t cumulatedResult = 0;
for(int i = 0; i < measurments; i++){
cumulatedResult += LightDetection::getValue(sensor);
xTaskDelayUntil(&xLastWakeTime,frequency);
}
return cumulatedResult/measurments;
};
void LightDetection::beginInfrared(void){
pinMode(IR_PT_ENABLE, OUTPUT);
pinMode(IR_PT_FRONT_ADC, INPUT);
pinMode(IR_PT_LEFT_ADC, INPUT);
pinMode(IR_PT_RIGHT_ADC, INPUT);
pinMode(IR_PT_BACK_ADC, INPUT);
};
void LightDetection::beginDaylight(void){
pinMode(DL_PT_ENABLE, OUTPUT);
pinMode(DL_PT_BOTTOM_ADC, INPUT);
pinMode(DL_PT_FRONT_ADC, INPUT );
};
uint16_t LightDetection::readIRPT(photoTransistors sensor){
digitalWrite(IR_PT_ENABLE,HIGH);
uint16_t result = 0;
switch (sensor)
{
case IR_FRONT:
result = analogRead(IR_PT_FRONT_ADC);
break;
case IR_LEFT:
result = analogRead(IR_PT_LEFT_ADC);
break;
case IR_RIGHT:
result = analogRead(IR_PT_RIGHT_ADC);
break;
case IR_BACK:
result = analogRead(IR_PT_BACK_ADC);
break;
default:
break;
}
digitalWrite(IR_PT_ENABLE,LOW);
return result;
};
uint16_t LightDetection::readDLPT(photoTransistors sensor){
digitalWrite(DL_PT_ENABLE,HIGH);
uint16_t result = 0;
switch (sensor)
{
case DL_FRONT:
result = analogRead(DL_PT_FRONT_ADC);
break;
case DL_BOTTOM:
result = analogRead(DL_PT_BOTTOM_ADC);
break;
default:
break;
}
digitalWrite(DL_PT_ENABLE,LOW);
return result;
};

View File

@@ -0,0 +1,103 @@
/**
* @file LightDetection.h
* @author Hans Haupt (hans.haupt@dezibot.de)
* @brief Class for Reading the values of the different Phototransistors, both IR, and DaylightSensors are supported.
* @version 0.1
* @date 2024-04-26
*
* @copyright Copyright (c) 2024
*
*/
#ifndef LightDetection_h
#define LightDetection_h
#include <stdint.h>
#include <Arduino.h>
enum photoTransistors{
IR_LEFT,
IR_RIGHT,
IR_FRONT,
IR_BACK,
DL_FRONT,
DL_BOTTOM
};
struct averageMeasurement {
photoTransistors sensor;
uint32_t measurementAmount;
uint32_t timeBetween;
uint16_t result;
bool done;
};
enum ptType{
IR,
DAYLIGHT
};
static const photoTransistors allIRPTs[] = {IR_FRONT,IR_LEFT,IR_RIGHT,IR_BACK};
static const photoTransistors allDLPTs[] = {DL_BOTTOM,DL_FRONT};
class LightDetection{
public:
/**
* @brief initialize the Lightdetection Compnent, must be called before the other methods are used.
*
*/
static void begin(void);
/**
* @brief reads the Value of the specified sensor
*
* @param sensor which sensor to read
* @return uint the reading of the sensor. between 0-4095
*/
static uint16_t getValue(photoTransistors sensor);
/**
* @brief can be used to determine which sensor is exposed to the greatest amount of light
* Can distingish between IR and Daylight
*
* @param type select which PTTransistors to compare
* @return photoTransistors which sensor is exposed to the greatest amount of light
*/
static photoTransistors getBrightest(ptType type);
/**
* @brief Get the Average of multiple measurments of a single PT
*
* @param sensor Which Phototransistor should be read
* @param measurments how many measurements should be taken
* @param timeBetween which time should elapse between
* @return the average of all taken meaurments
*/
static uint32_t getAverageValue(photoTransistors sensor, uint32_t measurments, uint32_t timeBetween);
protected:
static const uint8_t IR_PT_FRONT_ADC = 3;
static const uint8_t IR_PT_LEFT_ADC = 4;
static const uint8_t IR_PT_RIGHT_ADC = 5;
static const uint8_t IR_PT_BACK_ADC = 6;
static const uint8_t DL_PT_FRONT_ADC = 7;
static const uint8_t DL_PT_BOTTOM_ADC = 8;
static const uint8_t DL_PT_ENABLE = 41;
static const uint8_t IR_PT_ENABLE = 40;
static void beginInfrared(void);
static void beginDaylight(void);
static uint16_t readIRPT(photoTransistors sensor);
static uint16_t readDLPT(photoTransistors sensor);
static void averageMeasurmentTask(void * args);
};
#endif //LightDetection_h

90
src/motion/Motion.cpp Normal file
View File

@@ -0,0 +1,90 @@
/**
* @file Motion.cpp
* @author Jonathan Schulze, Nick Hübenthal, Hans Haupt
* @brief Implementation of the Motion class.
* @version 0.2
* @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) {
ledc_timer_config_t motor_timer = {
.speed_mode = LEDC_MODE,
.duty_resolution = DUTY_RES,
.timer_num = TIMER,
.freq_hz = FREQUENCY,
.clk_cfg = LEDC_AUTO_CLK
};
ledc_timer_config(&motor_timer);
Motion::left.begin();
Motion::right.begin();
};
void Motion::moveTask(void * 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);
};
// 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);
}
};
void Motion::leftMotorTask(void * args) {
Motion::left.setSpeed(LEFT_MOTOR_DUTY);
Motion::right.setSpeed(0);
vTaskDelay((uint32_t) args / portTICK_PERIOD_MS);
Motion::left.setSpeed(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 {
Motion::left.setSpeed(LEFT_MOTOR_DUTY);
Motion::right.setSpeed(0);
}
};
void Motion::rightMotorTask(void * args) {
Motion::right.setSpeed(RIGHT_MOTOR_DUTY);
Motion::left.setSpeed(0);
vTaskDelay((uint32_t) args / portTICK_PERIOD_MS);
Motion::right.setSpeed(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 {
Motion::right.setSpeed(RIGHT_MOTOR_DUTY);
Motion::left.setSpeed(0);
}
};
void Motion::stop(void){
Motion::left.setSpeed(0);
Motion::right.setSpeed(0);
}

90
src/motion/Motion.h Normal file
View File

@@ -0,0 +1,90 @@
/**
* @file Motion.h
* @author Jonathan Schulze, Nick Hübenthal, Hans Haupt
* @brief This component controls the ability to rotate and change position.
* @version 0.2
* @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>
#include "driver/ledc.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
class Motor{
public:
Motor(uint8_t pin, ledc_timer_t timer, ledc_channel_t channel);
void begin(void);
void setSpeed(uint16_t duty);
uint16_t getSpeed(void);
protected:
uint8_t pin;
ledc_timer_t timer;
ledc_channel_t channel;
uint16_t duty;
};
class Motion{
protected:
static const uint16_t RIGHT_MOTOR_DUTY = 4096;
static const uint16_t LEFT_MOTOR_DUTY = 4096;
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:
//Shared Timer to sync movement
static inline Motor left = Motor(MOTOR_LEFT_PIN,TIMER,CHANNEL_LEFT);
static inline Motor right = Motor(MOTOR_RIGHT_PIN,TIMER,CHANNEL_RIGHT);
/**
* @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

33
src/motion/Motor.cpp Normal file
View File

@@ -0,0 +1,33 @@
#include "Motion.h"
Motor::Motor(uint8_t pin, ledc_timer_t timer, ledc_channel_t channel){
this->pin = pin;
this->channel = channel;
this->timer = timer;
this->duty = 0;
};
void Motor::begin(void){
pinMode(this->pin,OUTPUT);
ledc_channel_config_t channelConfig = {
.gpio_num = this->pin,
.speed_mode = LEDC_MODE,
.channel = this->channel,
.intr_type = LEDC_INTR_DISABLE,
.timer_sel = this->timer,
.duty = 0, // Set duty to 0%
.hpoint = 0
};
ledc_channel_config(&channelConfig);
Serial.println("Motor begin done");
};
void Motor::setSpeed(uint16_t duty){
this->duty = duty;
ledc_set_duty(LEDC_MODE,this->channel,duty);
ledc_update_duty(LEDC_MODE,this->channel);
};
uint16_t Motor::getSpeed(void){
return this->duty;
};

View File

@@ -0,0 +1,77 @@
#include "MotionDetection.h"
MotionDetection::MotionDetection(){//:handler(FSPI){
handler = new SPIClass(FSPI);
};
void MotionDetection::begin(void){
pinMode(34,OUTPUT);
digitalWrite(34,HIGH);
handler->begin(36,37,35,34);
handler->beginTransaction(SPISettings(frequency,SPI_MSBFIRST,SPI_MODE0));
digitalWrite(34,LOW);
// set Accel and Gyroscop to Low Noise
handler->transfer(0x1F);
handler->transfer(0x0F);
//busy Wait for startup
delayMicroseconds(200);
digitalWrite(34,HIGH);
handler->endTransaction();
};
void MotionDetection::end(void){
handler->beginTransaction(SPISettings(frequency,SPI_MSBFIRST,SPI_MODE0));
digitalWrite(34,LOW);
handler->transfer(cmdWrite(PWR_MGMT0));
//turn Accel and Gyroscope off
handler->transfer(0x00);
digitalWrite(34,HIGH);
handler->end();
};
IMUResult MotionDetection::getAcceleration(){
IMUResult result;
result.x = readRegister(ACCEL_DATA_X_HIGH)<<8;
result.x |= readRegister(ACCEL_DATA_X_LOW);
result.y = readRegister(ACCEL_DATA_Y_HIGH)<<8;
result.y |= readRegister(ACCEL_DATA_Y_LOW);
result.z = readRegister(ACCEL_DATA_Z_HIGH)<<8;
result.z |= readRegister(ACCEL_DATA_Z_LOW);
return result;
};
IMUResult MotionDetection::getRotation(){
IMUResult result;
result.x = readRegister(GYRO_DATA_X_HIGH) <<8;
result.x |= readRegister(GYRO_DATA_X_LOW);
result.y = readRegister(GYRO_DATA_Y_HIGH)<<8;
result.y |= readRegister(GYRO_DATA_Y_LOW);
result.z = readRegister(GYRO_DATA_Z_HIGH)<<8;
result.z |= readRegister(GYRO_DATA_Z_LOW);
return result;
};
float MotionDetection::getTemperature(){
int16_t raw_temperatur = readRegister(REG_TEMP_HIGH)<<8;
raw_temperatur |= readRegister(REG_TEMP_LOW);
return raw_temperatur/128 +25;
};
int8_t MotionDetection::getWhoAmI(){
return readRegister(WHO_AM_I);
};
uint8_t MotionDetection::cmdRead(uint8_t reg){
return (CMD_READ | (reg & ADDR_MASK));
};
uint8_t MotionDetection::cmdWrite(uint8_t reg){
return (CMD_WRITE | (reg & ADDR_MASK));
};
int8_t MotionDetection::readRegister(uint8_t reg){
handler->beginTransaction(SPISettings(frequency,SPI_MSBFIRST,SPI_MODE0));
digitalWrite(34,LOW);
uint8_t result;
result = handler->transfer(cmdRead(reg));
result = handler->transfer(0x00);
digitalWrite(34,HIGH);
handler->endTransaction();
return result;
};

View File

@@ -0,0 +1,110 @@
/**
* @file MotionDetection.h
* @author Hans Haupt
* @brief This component controls the IMU (Accelerometer & Gyroscope) ICM-42670-P
* @version 0.1
* @date 2023-12-15
*
* @copyright Copyright (c) 2023
*
*/
#ifndef MotionDetection_h
#define MotionDetection_h
#include <SPI.h>
#include <Arduino.h>
struct IMUResult{
int16_t x;
int16_t y;
int16_t z;
};
class MotionDetection{
protected:
static const uint8_t CMD_READ = 0x80;
static const uint8_t CMD_WRITE = 0x00;
static const uint8_t ADDR_MASK = 0x7F;
//Registers
static const uint8_t REG_TEMP_LOW = 0x0A;
static const uint8_t REG_TEMP_HIGH = 0X09;
static const uint8_t ACCEL_DATA_X_HIGH = 0x0B;
static const uint8_t ACCEL_DATA_X_LOW = 0x0C;
static const uint8_t ACCEL_DATA_Y_HIGH = 0x0D;
static const uint8_t ACCEL_DATA_Y_LOW = 0x0E;
static const uint8_t ACCEL_DATA_Z_HIGH = 0x0F;
static const uint8_t ACCEL_DATA_Z_LOW = 0x10;
static const uint8_t GYRO_DATA_X_HIGH = 0x11;
static const uint8_t GYRO_DATA_X_LOW = 0x12;
static const uint8_t GYRO_DATA_Y_HIGH = 0x13;
static const uint8_t GYRO_DATA_Y_LOW = 0x14;
static const uint8_t GYRO_DATA_Z_HIGH = 0x15;
static const uint8_t GYRO_DATA_Z_LOW = 0x16;
static const uint8_t PWR_MGMT0 = 0x1F;
static const uint8_t WHO_AM_I = 0x75;
static const uint frequency = 10000000;
uint16_t cmdRead(uint8_t regHigh,uint8_t regLow);
uint16_t cmdWrite(uint8_t regHigh,uint8_t regLow);
uint8_t cmdRead(uint8_t reg);
uint8_t cmdWrite(uint8_t reg);
int8_t readRegister(uint8_t reg);
int16_t readDoubleRegister(uint8_t lowerReg);
SPIClass * handler = NULL;
public:
MotionDetection();
/**
* @brief initialized the IMU Component.
* Wakes the IMU from Standby
* Set configuration
*
*/
void begin(void);
/**
* @brief stops the component
* Sets the IMU to Low-Power-Mode
*
*/
void end(void);
/**
* @brief Triggers a new Reading of the accelerationvalues and reads them from the IMU
*
* @return IMUResult that contains the new read values
*/
IMUResult getAcceleration();
/**
* @brief Triggers a new reading of the gyroscope and reads the values from the imu
*
* @return IMUResult
*/
IMUResult getRotation();
/**
* @brief Reads the current On Chip temperature of the IMU
*
* @return normalized temperature in degree Centigrade
*/
float getTemperature();
/**
* @brief Returns the value of reading the whoAmI register
* When IMU working correctly, value should be 0x67
*
* @return the value of the whoami register of the ICM-42670
*/
int8_t getWhoAmI();
};
#endif //MotionDetection

View File

@@ -0,0 +1,9 @@
static const uint32_t RED = 0xFF0000;
static const uint32_t GREEN = 0x00FF00;
static const uint32_t BLUE = 0x0000FF;
static const uint32_t WHITE = 0xFFFFFF;
static const uint32_t ORANGE = 0x961E00;
static const uint32_t YELLOW = 0x965000;
static const uint32_t TURQUOISE = 0x005064;
static const uint32_t PURPEL = 0x320064;
static const uint32_t PINK = 0x960064;

View File

@@ -0,0 +1,107 @@
#include "MultiColorLight.h"
MultiColorLight::MultiColorLight():rgbLeds(ledAmount,ledPin){
};
void MultiColorLight::begin(void){
rgbLeds.begin();
};
void MultiColorLight::setLed(uint8_t index , uint32_t color){
if (index > ledAmount-1){
//TODO: logging
}
rgbLeds.setPixelColor(index, normalizeColor(color));
rgbLeds.show();
};
void MultiColorLight::setLed(leds leds, uint32_t color){
switch (leds){
case TOP_LEFT:
MultiColorLight::setLed(1,color);break;
case TOP_RIGHT:
MultiColorLight::setLed(0,color);break;
case BOTTOM:
MultiColorLight::setLed(2,color);break;
case TOP:
for (int index = 0; index<2; index++){
MultiColorLight::setLed(index,color);
}break;
case ALL:
for (int index = 0; index<ledAmount; index++){
MultiColorLight::setLed(index,color);
}break;
default:
//TODO logging
break;
}
};
void MultiColorLight::setLed(leds leds, uint8_t red, uint8_t green, uint8_t blue){
MultiColorLight::setLed(leds, MultiColorLight::color(red,green,blue));
};
void MultiColorLight::setTopLeds(uint32_t color){
MultiColorLight::setLed(TOP,color);
};
void MultiColorLight::setTopLeds(uint8_t red, uint8_t green, uint8_t blue){
MultiColorLight::setTopLeds(MultiColorLight::color(red,green,blue));
};
void MultiColorLight::blink(uint16_t amount,uint32_t color, leds leds, uint32_t interval){
for(uint16_t index = 0; index < amount;index++){
MultiColorLight::setLed(leds, color);
vTaskDelay(interval);
MultiColorLight::turnOffLed(leds);
vTaskDelay(interval);
}
};
void MultiColorLight::turnOffLed(leds leds){
switch (leds){
case TOP_LEFT:
MultiColorLight::setLed(1,0);break;
case TOP_RIGHT:
MultiColorLight::setLed(0,0);break;
case BOTTOM:
MultiColorLight::setLed(2,0);break;
case TOP:
for (int index = 0; index<2; index++){
MultiColorLight::setLed(index,0);
}break;
case ALL:
for (int index = 0; index<3; index++){
MultiColorLight::setLed(index,0);
}break;
default:
//TODO logging
break;
}
};
uint32_t MultiColorLight::color(uint8_t r, uint8_t g, uint8_t b){
return rgbLeds.Color(r,g,b);
};
//PRIVATE
uint32_t MultiColorLight::normalizeColor(uint32_t color,uint8_t maxBrightness){
uint8_t red = (color&0x00FF0000)>>16;
uint8_t green = (color&0x0000FF00)>>8;
uint8_t blue = (color&0x000000FF);
if (red > maxBrightness){
red = maxBrightness;
}
if(green > maxBrightness-70){
green = maxBrightness-70;
}
if(blue > maxBrightness-50){
blue = maxBrightness-50;
}
return MultiColorLight::color(red,green,blue);
}

View File

@@ -0,0 +1,139 @@
/**
* @file MultiColorLight.h
* @author Saskia Duebener, Hans Haupt
* @brief This component controls the ability to show multicolored light, using the RGB-LEDs
* @version 0.2
* @date 2023-11-25
*
* @copyright Copyright (c) 2023
*
*/
#ifndef MultiColorLight_h
#define MultiColorLight_h
#include <Adafruit_NeoPixel.h>
#include "ColorConstants.h"
/**
* @brief Describes combinations of leds on the Dezibot.
* With the Robot in Front of you, when the robot drives away from you, the left LED is TOP_LEFT
*
*/
enum leds{
TOP_LEFT,
TOP_RIGHT,
BOTTOM,
TOP,
ALL
};
class MultiColorLight{
protected:
static const uint16_t ledAmount = 3;
static const int16_t ledPin = 48;
static const uint8_t maxBrightness = 150;
Adafruit_NeoPixel rgbLeds;
public:
MultiColorLight();
/**
* @brief initialize the multicolor component
*
*/
void begin(void);
/**
* @brief Set the specified led to the passed color
* @param index ranging from 0-2, 0: Right, 1: Left, 2: Bottom
* @param color A 32-bit unsigned integer representing the color in the format
* 0x00RRGGBB, where RR is the red component, GG is the green
* component, and BB is the blue component. Each color can range between 0 to 100
*/
void setLed(uint8_t index , uint32_t color);
/**
* @brief Set the specified leds to the passed color value
*
* @param leds which leds should be updated
* @param color A 32-bit unsigned integer representing the color in the format
* 0x00RRGGBB, where RR is the red component, GG is the green
* component, and BB is the blue component. Each color can range between 0 to 100
*/
void setLed(leds leds, uint32_t color);
/**
* @brief Set the specified leds to the passed color value
*
* @param leds which leds should be updated
* @param red brightness of red, is normalized in the function
* @param green brightness of green, is normalized in the function
* @param blue brightness of blue, is normalized in the function
*/
void setLed(leds leds, uint8_t red, uint8_t green, uint8_t blue);
/**
* @brief sets the two leds on the top of the robot to the specified color
*
* @param color A 32-bit unsigned integer representing the color in the format
* 0x00RRGGBB, where RR is the red component, GG is the green
* component, and BB is the blue component. Each color can range between 0 to 100
*/
void setTopLeds(uint32_t color);
/**
* @brief sets the two leds on the top of the robot to the specified color
*
* @param red brightness of red, is normalized in the function
* @param green brightness of green, is normalized in the function
* @param blue brightness of blue, is normalized in the function
*/
void setTopLeds(uint8_t red, uint8_t green, uint8_t blue);
/**
* @brief Let LEDs blink, returns after all blinks were executed
*
* @param amount how often should the leds blink
* @param color A 32-bit unsigned integer representing the color in the format
* 0x00RRGGBB, where RR is the red component, GG is the green
* component, and BB is the blue component.
* Each color can range between 0 to 100
* Defaults to blue
* @param leds which LEDs should blink, default is TOP
* @param interval how many miliseconds the led is on, defaults to 1s
*/
void blink(uint16_t amount,uint32_t color = 0x00006400,leds leds=TOP, uint32_t interval=1000);
/**
* @brief turn off the given leds
*
* @param leds which leds should be turned off, defaults to ALL
*/
void turnOffLed(leds leds=ALL);
/**
* @brief wrapper to calulate the used colorformat from a rgb-value
*
* @param r red (0-100)
* @param g green (0-100)
* @param b blue (0-100)
* @return A 32-bit unsigned integer representing the color in the format
* 0x00RRGGBB, where RR is the red component, GG is the green
* component, and BB is the blue component.
*/
uint32_t color(uint8_t r, uint8_t g, uint8_t b);
private:
/**
* @brief normalizes every component of color to not exeed the maxBrightness
*
* @param color A 32-bit unsigned integer representing the color in the format
* 0x00RRGGBB, where RR is the red component, GG is the green
* component, and BB is the blue component.
* @param maxBrigthness maximal level of brightness that is allowed for each color
* @return uint32_t A 32-bit unsigned integer representing the color in the format
* 0x00RRGGBB, where RR is the red component, GG is the green
* component, and BB is the blue component. Where each component can be
* between 0 - maxBrightness
*/
uint32_t normalizeColor(uint32_t color, uint8_t maxBrigthness=maxBrightness);
};
#endif //MultiColorLight_h