Working controlled motor
This commit is contained in:
parent
140138977a
commit
8620023277
@ -18,7 +18,7 @@ class DRV8833 : public Thing {
|
|||||||
int AIn2;
|
int AIn2;
|
||||||
int BIn1;
|
int BIn1;
|
||||||
int BIn2;
|
int BIn2;
|
||||||
int standby;
|
int standby = 255;
|
||||||
};
|
};
|
||||||
|
|
||||||
/// @brief Setup a DRV8833 motor controller
|
/// @brief Setup a DRV8833 motor controller
|
||||||
|
@ -7,7 +7,8 @@ namespace Arduino {
|
|||||||
|
|
||||||
#pragma region Digital input
|
#pragma region Digital input
|
||||||
|
|
||||||
DigitalInput::DigitalInput(unsigned char pin, Thing* parent) : Thing(Type::Undetermined, parent) {
|
DigitalInput::DigitalInput(unsigned char pin, Thing* parent)
|
||||||
|
: Thing(Type::Undetermined, parent) {
|
||||||
this->pin = pin;
|
this->pin = pin;
|
||||||
pinMode(this->pin, INPUT);
|
pinMode(this->pin, INPUT);
|
||||||
std::cout << "digital input start\n";
|
std::cout << "digital input start\n";
|
||||||
@ -46,13 +47,15 @@ DigitalInput::RelativeEncoder::RelativeEncoder(Configuration config,
|
|||||||
|
|
||||||
void DigitalInput::RelativeEncoder::Start() {
|
void DigitalInput::RelativeEncoder::Start() {
|
||||||
// We support up to 2 pulse counters
|
// We support up to 2 pulse counters
|
||||||
if (interruptCount == 0)
|
if (interruptCount == 0) {
|
||||||
|
std::cout << "pin interrupt 1 activated" << std::endl;
|
||||||
attachInterrupt(digitalPinToInterrupt(digitalInput.pin), PulseInterrupt0,
|
attachInterrupt(digitalPinToInterrupt(digitalInput.pin), PulseInterrupt0,
|
||||||
RISING);
|
RISING);
|
||||||
else if (interruptCount == 1)
|
} else if (interruptCount == 1) {
|
||||||
|
std::cout << "pin interrupt 2 activated" << std::endl;
|
||||||
attachInterrupt(digitalPinToInterrupt(digitalInput.pin), PulseInterrupt1,
|
attachInterrupt(digitalPinToInterrupt(digitalInput.pin), PulseInterrupt1,
|
||||||
RISING);
|
RISING);
|
||||||
else {
|
} else {
|
||||||
// maximum interrupt count reached
|
// maximum interrupt count reached
|
||||||
std::cout << "DigitalInput::RelativeEncoder: max. # counters of 2 reached"
|
std::cout << "DigitalInput::RelativeEncoder: max. # counters of 2 reached"
|
||||||
<< std::endl;
|
<< std::endl;
|
||||||
@ -85,14 +88,17 @@ void DigitalInput::RelativeEncoder::Update(bool recursive) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
float timeStep = (float)(currentTimeMs - this->lastUpdateTime) / 1000.0f;
|
float timeStep = (float)(currentTimeMs - this->lastUpdateTime) / 1000.0f;
|
||||||
|
if (timeStep <= 0)
|
||||||
|
return;
|
||||||
|
|
||||||
int pulseCount = GetPulseCount();
|
int pulseCount = GetPulseCount();
|
||||||
netPulseCount += pulseCount;
|
netPulseCount += pulseCount;
|
||||||
|
|
||||||
this->pulseFrequency = pulseCount / timeStep;
|
this->pulseFrequency = pulseCount / timeStep;
|
||||||
this->rotationSpeed = pulseFrequency / pulsesPerRevolution;
|
this->rotationSpeed = pulseFrequency / pulsesPerRevolution;
|
||||||
|
|
||||||
// std::cout << "pulses: " << pulseCount << " per second " << pulseFrequency
|
std::cout << "pulses: " << pulseCount << " per second " << pulseFrequency
|
||||||
// << " timestep " << timeStep << std::endl;
|
<< " timestep " << timeStep << std::endl;
|
||||||
|
|
||||||
this->lastUpdateTime = currentTimeMs;
|
this->lastUpdateTime = currentTimeMs;
|
||||||
}
|
}
|
||||||
|
@ -9,8 +9,8 @@ namespace Arduino {
|
|||||||
UltrasonicSensor::UltrasonicSensor(Configuration config, Thing* parent)
|
UltrasonicSensor::UltrasonicSensor(Configuration config, Thing* parent)
|
||||||
: Thing(Type::Undetermined, parent) {
|
: Thing(Type::Undetermined, parent) {
|
||||||
this->name = "Ultrasonic sensor";
|
this->name = "Ultrasonic sensor";
|
||||||
this->pinTrigger = config.triggerPin;
|
this->pinTrigger = config.trigger;
|
||||||
this->pinEcho = config.echoPin;
|
this->pinEcho = config.echo;
|
||||||
|
|
||||||
pinMode(pinTrigger, OUTPUT); // configure the trigger pin to output mode
|
pinMode(pinTrigger, OUTPUT); // configure the trigger pin to output mode
|
||||||
pinMode(pinEcho, INPUT); // configure the echo pin to input mode
|
pinMode(pinEcho, INPUT); // configure the echo pin to input mode
|
||||||
|
@ -9,8 +9,8 @@ namespace Arduino {
|
|||||||
class UltrasonicSensor : Thing {
|
class UltrasonicSensor : Thing {
|
||||||
public:
|
public:
|
||||||
struct Configuration {
|
struct Configuration {
|
||||||
int triggerPin;
|
int trigger;
|
||||||
int echoPin;
|
int echo;
|
||||||
};
|
};
|
||||||
|
|
||||||
UltrasonicSensor(Configuration config, Thing* parent = Thing::LocalRoot());
|
UltrasonicSensor(Configuration config, Thing* parent = Thing::LocalRoot());
|
||||||
|
@ -1,4 +1,5 @@
|
|||||||
#include "ControlledMotor.h"
|
#include "ControlledMotor.h"
|
||||||
|
#include "LinearAlgebra/FloatSingle.h"
|
||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
|
||||||
@ -7,9 +8,10 @@ ControlledMotor::ControlledMotor(Motor* motor,
|
|||||||
Thing* parent)
|
Thing* parent)
|
||||||
: Motor(parent), motor(motor), encoder(encoder) {
|
: Motor(parent), motor(motor), encoder(encoder) {
|
||||||
this->type = Type::ControlledMotor;
|
this->type = Type::ControlledMotor;
|
||||||
// encoder.SetParent(*this);
|
//encoder->SetParent(null);
|
||||||
// Thing parent = motor.GetParent();
|
// Thing parent = motor.GetParent();
|
||||||
// this->SetParent(parent);
|
// this->SetParent(parent);
|
||||||
|
this->integral = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
void ControlledMotor::SetTargetVelocity(float velocity) {
|
void ControlledMotor::SetTargetVelocity(float velocity) {
|
||||||
@ -19,22 +21,34 @@ void ControlledMotor::SetTargetVelocity(float velocity) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void ControlledMotor::Update(bool recurse) {
|
void ControlledMotor::Update(bool recurse) {
|
||||||
encoder->Update(false);
|
|
||||||
|
|
||||||
this->actualVelocity = (int)rotationDirection * encoder->rotationSpeed;
|
|
||||||
|
|
||||||
unsigned long currentTimeMs = GetTimeMs();
|
unsigned long currentTimeMs = GetTimeMs();
|
||||||
float timeStep = (currentTimeMs - this->lastUpdateTime) / 1000.0f;
|
float timeStep = (currentTimeMs - this->lastUpdateTime) / 1000.0f;
|
||||||
this->lastUpdateTime = currentTimeMs;
|
this->lastUpdateTime = currentTimeMs;
|
||||||
|
if (timeStep <= 0)
|
||||||
|
return;
|
||||||
|
|
||||||
|
// encoder->Update(false);
|
||||||
|
|
||||||
|
this->actualVelocity = (int)rotationDirection * encoder->rotationSpeed;
|
||||||
|
|
||||||
float error = this->targetVelocity - this->actualVelocity;
|
float error = this->targetVelocity - this->actualVelocity;
|
||||||
float acceleration =
|
float p_term = error * pidP;
|
||||||
error * timeStep * pidP; // Just P is used at this moment
|
this->integral += error * timeStep;
|
||||||
std::cout << "motor acc. " << acceleration << std::endl;
|
float i_term = pidI * this->integral;
|
||||||
motor->SetTargetVelocity(targetVelocity +
|
float d_term = pidD * (error - this->lastError) / timeStep;
|
||||||
acceleration); // or something like that
|
this->lastError = error;
|
||||||
|
|
||||||
motor->Update(false);
|
float output = p_term + i_term + d_term;
|
||||||
|
std::cout << "target " << this->targetVelocity << " actual "
|
||||||
|
<< this->actualVelocity << " output = " << output << std::endl;
|
||||||
|
// float acceleration =
|
||||||
|
// error * timeStep * pidP; // Just P is used at this moment
|
||||||
|
// std::cout << "motor acc. " << acceleration << std::endl;
|
||||||
|
|
||||||
|
// float newTargetVelocity = motor->targetVelocity + acceleration;
|
||||||
|
output = LinearAlgebra::Float::Clamp(output, -1, 1);
|
||||||
|
motor->SetTargetVelocity(output); // or something like that
|
||||||
|
//motor->Update(false);
|
||||||
}
|
}
|
||||||
|
|
||||||
// float ControlledMotor::GetActualVelocity() {
|
// float ControlledMotor::GetActualVelocity() {
|
||||||
|
@ -12,9 +12,9 @@ class ControlledMotor : public Motor {
|
|||||||
public:
|
public:
|
||||||
ControlledMotor(Motor* motor, RelativeEncoder* encoder, Thing* parent = Thing::LocalRoot());
|
ControlledMotor(Motor* motor, RelativeEncoder* encoder, Thing* parent = Thing::LocalRoot());
|
||||||
|
|
||||||
float pidP = 1;
|
float pidP = 0.5;
|
||||||
float pidD = 0;
|
float pidD = 0;
|
||||||
float pidI = 0;
|
float pidI = 0.2;
|
||||||
|
|
||||||
/// @brief The actual velocity in revolutions per second
|
/// @brief The actual velocity in revolutions per second
|
||||||
float actualVelocity;
|
float actualVelocity;
|
||||||
@ -32,6 +32,8 @@ class ControlledMotor : public Motor {
|
|||||||
RelativeEncoder* encoder;
|
RelativeEncoder* encoder;
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
float integral = 0;
|
||||||
|
float lastError = 0;
|
||||||
float lastUpdateTime;
|
float lastUpdateTime;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -14,14 +14,14 @@ class RelativeEncoder : public Thing {
|
|||||||
/// full rotation
|
/// full rotation
|
||||||
/// @param distancePerRevolution The distance a wheel travels per full
|
/// @param distancePerRevolution The distance a wheel travels per full
|
||||||
/// rotation
|
/// rotation
|
||||||
RelativeEncoder(Participant* owner);
|
//RelativeEncoder(Participant* owner);
|
||||||
// RelativeEncoder(Thing* parent);
|
// RelativeEncoder(Thing* parent);
|
||||||
RelativeEncoder(Thing* parent = Thing::LocalRoot());
|
RelativeEncoder(Thing* parent = Thing::LocalRoot());
|
||||||
|
|
||||||
/// @brief Get the rotation speed
|
/// @brief Get the rotation speed
|
||||||
/// @return The speed in revolutions per second
|
/// @return The speed in revolutions per second
|
||||||
virtual float GetRotationSpeed();
|
virtual float GetRotationSpeed();
|
||||||
float rotationSpeed;
|
float rotationSpeed = 0;
|
||||||
|
|
||||||
/// @brief Function used to generate binary data for this touch sensor
|
/// @brief Function used to generate binary data for this touch sensor
|
||||||
/// @param buffer The byte array for thw binary data
|
/// @param buffer The byte array for thw binary data
|
||||||
|
Loading…
x
Reference in New Issue
Block a user