added PseudoSensorControl plus lots of symlinks and organization

This commit is contained in:
Aditya Pulipaka
2025-11-20 15:13:19 -06:00
parent b404f6846d
commit 1e9fcfa1af
15 changed files with 242 additions and 6 deletions

View File

@@ -0,0 +1,95 @@
#include "PseudoSensorControl.hpp"
#include <Arduino.h>
// CONTROLLER CONSTANTS
float MAX_INTEGRAL_TERM = 1e4;
PinPair pinMap[4] = {{dirFL, pwmFL}, {dirFR, pwmFR}, {dirBL, pwmBL}, {dirBR, pwmBR}};
void PseudoSensorController::update() {
Left.readMM();
Right.readMM();
Front.readMM();
Back.readMM(); // read and update dists/oor for all sensors.
oor = Left.oor || Right.oor || Front.oor || Back.oor;
control();
for (uint8_t i = 0; i < 4; i++) {
PWMs[i] = slewLimit(PWMs[i], Prevs[i]);
Prevs[i] = PWMs[i];
}
}
void PseudoSensorController::zeroPWMs() {
memset(PWMs, 0, sizeof(PWMs));
}
void PseudoSensorController::sendOutputs() {
if (!outputOn) zeroPWMs();
for (uint8_t i = 0; i < 4; i++) {
// The following assumes 0 direction drives repulsion and 1 direction drives attraction.
digitalWrite(pinMap[i].dir, PWMs[i] < 0);
analogWrite(pinMap[i].pwm, abs(PWMs[i]));
}
}
void PseudoSensorController::control() {
float avg = (Left.mmVal + Right.mmVal + Front.mmVal + Back.mmVal) * 0.25f;
float pseudos[4] = {Front.mmVal + Left.mmVal - avg,
Front.mmVal + Right.mmVal - avg,
Back.mmVal + Left.mmVal - avg,
Back.mmVal + Right.mmVal - avg};
for (uint8_t i = 0; i < 4; i++) {
float eCurr = Refs[i] - pseudos[i]; // Above reference is positive error.
errors[i].eDiff = (eCurr - errors[i].e); // rise over run
errors[i].eInt += eCurr;
errors[i].eInt = constrain(errors[i].eInt, -MAX_INTEGRAL_TERM, MAX_INTEGRAL_TERM);
errors[i].e = eCurr;
PWMs[i] = pwmFunc(Consts, errors[i]);
}
}
int16_t PseudoSensorController::pwmFunc(K_MAP consts, Errors errs) {
if (oor) return 0;
Constants constants = (errs.e < 0) ? consts.attracting : consts.repelling;
return (int)constrain(constants.K*(errs.e + constants.ki*errs.eInt + constants.kd*errs.eDiff), -(float)CAP,(float)CAP);
}
int16_t PseudoSensorController::slewLimit(int16_t target, int16_t prev) {
int16_t delta = target - prev;
if (abs(delta) <= slewRateLimit) return target;
return prev + (delta > 0 ? slewRateLimit : -slewRateLimit);
}
void PseudoSensorController::report() {
Serial.print("CONTROL ON - ");
Serial.print(outputOn);
Serial.print("\n");
Serial.print("SENSORS - Left: ");
Serial.print(Left.mmVal);
Serial.print("mm, Right: ");
Serial.print(Right.mmVal);
Serial.print("mm, Front: ");
Serial.print(Front.mmVal);
Serial.print("mm, Back: ");
Serial.print(Back.mmVal);
Serial.print("mm,\n");
Serial.print("PWMS - FL_PWM: ");
Serial.print(PWMs[0]);
Serial.print(", FR_PWM: ");
Serial.print(PWMs[1]);
Serial.print("BL_PWM: ");
Serial.print(PWMs[2]);
Serial.print("BR_PWM: ");
Serial.print(PWMs[3]);
Serial.print("\n");
}

View File

@@ -0,0 +1,81 @@
#ifndef PSEUDOSENSORCONTROLLER_HPP
#define PSEUDOSENSORCONTROLLER_HPP
#include <stdint.h>
#include <Vector.h>
#include "IndSensorMap.hpp"
// PIN MAPPING
#define dirFR 2
#define pwmFR 3
#define dirBR 4
#define pwmBR 5
#define pwmFL 6
#define dirFL 7
#define dirBL 8
#define pwmBL 9
typedef struct PinPair {
const uint8_t dir;
const uint8_t pwm;
} PinPair;
extern PinPair pinMap[4];
// FL, FR, BL, BR
#define CAP 200
typedef struct Constants {
float K;
float ki;
float kd;
} Constants;
typedef struct K_MAP {
Constants repelling;
Constants attracting;
} K_MAP;
typedef struct Errors {
float e;
float eDiff;
float eInt;
} Errors;
class PseudoSensorController {
public:
bool oor;
bool outputOn;
PseudoSensorController(IndSensor& l, IndSensor& r, IndSensor& f, IndSensor& b,
K_MAP consts, float* refs, uint16_t slewRate) : Left(l), Right(r), Front(f),
Back(b), Refs(refs), errors{}, Consts(consts), oor(false), outputOn(false),
Prevs{}, slewRateLimit(slewRate) {}
void update();
void zeroPWMs();
void sendOutputs();
void report();
private:
void control();
int16_t pwmFunc(K_MAP consts, Errors errs);
int16_t slewLimit(int16_t target, int16_t prev);
IndSensor& Front;
IndSensor& Back;
IndSensor& Right;
IndSensor& Left;
K_MAP Consts;
Errors errors[4]; // FL FR BL BR
float* Refs; // length 4 FL FR BL BR
uint16_t slewRateLimit;
int16_t PWMs[4]; // FL FR BL BR
int16_t Prevs[4]; // FL FR BL BR
};
#endif // PSEUDOSENSORCONTROLLER_HPP