controlled motor support improved
This commit is contained in:
parent
ae5ed79700
commit
5a6c4fcaef
@ -1,24 +1,45 @@
|
|||||||
#include "ControlledMotor.h"
|
#include "ControlledMotor.h"
|
||||||
|
#include <Arduino.h>
|
||||||
ControlledMotor::ControlledMotor() {
|
ControlledMotor::ControlledMotor() {
|
||||||
// this->isControlledMotor = true;
|
|
||||||
this->type = Type::ControlledMotor;
|
this->type = Type::ControlledMotor;
|
||||||
}
|
}
|
||||||
|
|
||||||
ControlledMotor::ControlledMotor(Motor* motor, Encoder* encoder) {
|
ControlledMotor::ControlledMotor(Motor* motor, Encoder* encoder)
|
||||||
|
: ControlledMotor() {
|
||||||
this->motor = motor;
|
this->motor = motor;
|
||||||
this->encoder = encoder;
|
this->encoder = encoder;
|
||||||
}
|
}
|
||||||
|
|
||||||
void ControlledMotor::SetTargetSpeed(float velocity) {
|
void ControlledMotor::SetTargetSpeed(float velocity) {
|
||||||
this->targetVelocity = velocity;
|
this->targetVelocity = velocity;
|
||||||
|
this->rotationDirection = (targetVelocity < 0) ? Direction::Reverse : Direction::Forward;
|
||||||
}
|
}
|
||||||
|
|
||||||
void ControlledMotor::Update(float timeStep) {
|
void ControlledMotor::Update(float currentTimeMs) {
|
||||||
float velocity = GetActualSpeed();
|
actualVelocity = (int)rotationDirection * encoder->GetRevolutionsPerSecond(currentTimeMs);
|
||||||
float error = targetVelocity - velocity;
|
float error = targetVelocity - velocity;
|
||||||
|
|
||||||
|
float timeStep = currentTimeMs - lastUpdateTime;
|
||||||
float acceleration =
|
float acceleration =
|
||||||
error * timeStep * pidP; // Just P is used at this moment
|
error * timeStep * pidP; // Just P is used at this moment
|
||||||
motor->SetSpeed(targetVelocity + acceleration); // or something like that
|
motor->SetSpeed(targetVelocity + acceleration); // or something like that
|
||||||
|
this->lastUpdateTime = currentTimeMs;
|
||||||
|
}
|
||||||
|
|
||||||
|
float ControlledMotor::GetActualSpeed() {
|
||||||
|
return actualVelocity; //(int)rotationDirection * encoder->GetRevolutionsPerSecond(currentTimeMs);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool ControlledMotor::Drive(float distance) {
|
||||||
|
if (!driving) {
|
||||||
|
targetDistance = distance;
|
||||||
|
startDistance = encoder->GetDistance();
|
||||||
|
driving = true;
|
||||||
|
}
|
||||||
|
// else
|
||||||
|
// targetDistance = encoder->GetDistance(); // encoder->RestartCountingRevolutions();
|
||||||
|
float totalDistance = encoder->GetDistance() - startDistance;
|
||||||
|
Serial.printf("total distance = %f\n", totalDistance);
|
||||||
|
bool completed = totalDistance > targetDistance;
|
||||||
|
return completed;
|
||||||
}
|
}
|
@ -17,7 +17,7 @@ class ControlledMotor : public Thing {
|
|||||||
float pidD = 0;
|
float pidD = 0;
|
||||||
float pidI = 0;
|
float pidI = 0;
|
||||||
|
|
||||||
void Update(float timeStep);
|
void Update(float currentTimeMs);
|
||||||
|
|
||||||
/// @brief Set the target speed for the motor controller
|
/// @brief Set the target speed for the motor controller
|
||||||
/// @param speed the target in revolutions per second.
|
/// @param speed the target in revolutions per second.
|
||||||
@ -25,26 +25,22 @@ class ControlledMotor : public Thing {
|
|||||||
|
|
||||||
/// @brief Get the actual speed from the encoder
|
/// @brief Get the actual speed from the encoder
|
||||||
/// @return The speed in revolutions per second
|
/// @return The speed in revolutions per second
|
||||||
float GetActualSpeed() {
|
float GetActualSpeed();
|
||||||
return (int)rotationDirection * encoder->GetRevolutionsPerSecond();
|
|
||||||
}
|
|
||||||
|
|
||||||
bool Drive(float distance) {
|
bool Drive(float distance);
|
||||||
if (!driving) {
|
|
||||||
targetDistance = distance;
|
|
||||||
encoder->StartCountingRevolutions();
|
|
||||||
driving = true;
|
|
||||||
} else
|
|
||||||
targetDistance -= encoder->RestartCountingRevolutions();
|
|
||||||
|
|
||||||
return (targetDistance <= 0);
|
|
||||||
}
|
|
||||||
|
|
||||||
protected:
|
|
||||||
float targetVelocity;
|
|
||||||
Motor* motor;
|
Motor* motor;
|
||||||
Encoder* encoder;
|
Encoder* encoder;
|
||||||
enum Direction { Forward = 1, Reverse = -1 };
|
|
||||||
|
protected:
|
||||||
|
float lastUpdateTime;
|
||||||
|
float targetVelocity;
|
||||||
|
float actualVelocity;
|
||||||
|
float netDistance = 0;
|
||||||
|
float startDistance = 0;
|
||||||
|
|
||||||
|
enum Direction { Forward = 1,
|
||||||
|
Reverse = -1 };
|
||||||
|
|
||||||
Direction rotationDirection;
|
Direction rotationDirection;
|
||||||
|
|
||||||
|
52
Encoder.cpp
52
Encoder.cpp
@ -1,50 +1,26 @@
|
|||||||
#include "Encoder.h"
|
#include "Encoder.h"
|
||||||
|
|
||||||
volatile unsigned char Encoder::transitionCount = 0;
|
|
||||||
|
|
||||||
Encoder::Encoder() {
|
Encoder::Encoder() {
|
||||||
rps = 0;
|
|
||||||
transitionsPerRotation = 1; // to prevent devide by zero
|
transitionsPerRotation = 1; // to prevent devide by zero
|
||||||
distance = 0;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
Encoder::Encoder(unsigned char pin, unsigned char transitionsPerRotation)
|
Encoder::Encoder(unsigned char transitionsPerRotation)
|
||||||
: Encoder::Encoder() {
|
: Encoder::Encoder() {
|
||||||
/// Hmm. Arduino dependent code
|
|
||||||
// pinMode(pin, INPUT_PULLUP);
|
|
||||||
// attachInterrupt(digitalPinToInterrupt(pin), InterruptHandler, CHANGE);
|
|
||||||
this->transitionsPerRotation = transitionsPerRotation;
|
this->transitionsPerRotation = transitionsPerRotation;
|
||||||
}
|
}
|
||||||
|
|
||||||
void Encoder::InterruptHandler() {
|
int Encoder::GetPulseCount() {
|
||||||
transitionCount++;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
float Encoder::GetRevolutionsPerSecond() {
|
float Encoder::GetPulsesPerSecond(float currentTimeMs) {
|
||||||
return rps;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
void Encoder::ResetDistance() {
|
float Encoder::GetDistance() {
|
||||||
distance = 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
float Encoder::GetRotationDistance() {
|
float Encoder::GetRevolutionsPerSecond(float currentTimeMs) {
|
||||||
return distance;
|
|
||||||
}
|
|
||||||
|
|
||||||
void Encoder::Update(float timeStep) {
|
|
||||||
// Hmmm. Arduino-dependent code...
|
|
||||||
// noInterrupts();
|
|
||||||
float distanceThisUpdate = transitionCount / transitionsPerRotation;
|
|
||||||
transitionCount = 0;
|
|
||||||
// interrupts();
|
|
||||||
|
|
||||||
// float rps = distanceThisUpdate * timeStep;
|
|
||||||
distance += distanceThisUpdate;
|
|
||||||
}
|
|
||||||
|
|
||||||
void Encoder::StartCountingRevolutions() {}
|
|
||||||
|
|
||||||
float Encoder::RestartCountingRevolutions() {
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
20
Encoder.h
20
Encoder.h
@ -3,24 +3,14 @@
|
|||||||
class Encoder {
|
class Encoder {
|
||||||
public:
|
public:
|
||||||
Encoder();
|
Encoder();
|
||||||
Encoder(unsigned char pin, unsigned char transitionsPerRotation);
|
Encoder(unsigned char transitionsPerRotation);
|
||||||
|
|
||||||
float GetPulsesPerSecond();
|
virtual int GetPulseCount();
|
||||||
float GetRevolutionsPerSecond();
|
virtual float GetPulsesPerSecond(float currentTimeMs);
|
||||||
|
|
||||||
void ResetDistance();
|
virtual float GetDistance();
|
||||||
float GetRotationDistance();
|
virtual float GetRevolutionsPerSecond(float currentTimeMs);
|
||||||
|
|
||||||
void Update(float timeStep);
|
|
||||||
|
|
||||||
virtual void StartCountingRevolutions();
|
|
||||||
virtual float RestartCountingRevolutions();
|
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
static void InterruptHandler();
|
|
||||||
static volatile unsigned char transitionCount;
|
|
||||||
unsigned char transitionsPerRotation;
|
unsigned char transitionsPerRotation;
|
||||||
float rps;
|
|
||||||
|
|
||||||
float distance; // this is direction agnostic
|
|
||||||
};
|
};
|
||||||
|
@ -10,28 +10,21 @@ Propulsion::Propulsion() {
|
|||||||
this->motorCount = 0;
|
this->motorCount = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
// void Propulsion::AddMotors(MotorPlacement* motors, unsigned int motorCount) {
|
|
||||||
// this->palce = motors;
|
|
||||||
// this->motorCount = motorCount;
|
|
||||||
// }
|
|
||||||
|
|
||||||
void Propulsion::AddMotors(Placement* things, unsigned int thingCount) {
|
void Propulsion::AddMotors(Placement* things, unsigned int thingCount) {
|
||||||
// this->placement = motors;
|
|
||||||
// this->motorCount = motorCount;
|
|
||||||
this->motorCount = 0;
|
this->motorCount = 0;
|
||||||
for (unsigned int thingIx = 0; thingIx < thingCount; thingIx++) {
|
for (unsigned int thingIx = 0; thingIx < thingCount; thingIx++) {
|
||||||
Thing* thing = things[thingIx].thing;
|
Thing* thing = things[thingIx].thing;
|
||||||
// if (thing->isMotor)
|
if (thing->type == Thing::Type::Motor || thing->type == Thing::Type::ControlledMotor)
|
||||||
if (thing->type == Thing::Type::Motor)
|
|
||||||
motorCount++;
|
motorCount++;
|
||||||
|
if (thing->type == Thing::Type::ControlledMotor)
|
||||||
|
hasOdometer = true;
|
||||||
}
|
}
|
||||||
this->placement = new Placement[motorCount];
|
this->placement = new Placement[motorCount];
|
||||||
|
|
||||||
unsigned int motorIx = 0;
|
unsigned int motorIx = 0;
|
||||||
for (unsigned int thingIx = 0; thingIx < thingCount; thingIx++) {
|
for (unsigned int thingIx = 0; thingIx < thingCount; thingIx++) {
|
||||||
Thing* thing = things[thingIx].thing;
|
Thing* thing = things[thingIx].thing;
|
||||||
// if (thing->isMotor)
|
if (thing->type == Thing::Type::Motor || thing->type == Thing::Type::ControlledMotor)
|
||||||
if (thing->type == Thing::Type::Motor)
|
|
||||||
this->placement[motorIx++] = things[thingIx];
|
this->placement[motorIx++] = things[thingIx];
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -56,20 +49,24 @@ Motor* Propulsion::GetMotor(unsigned int motorId) {
|
|||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
|
|
||||||
void Propulsion::Update() {
|
void Propulsion::Update(float currentTimeMs) {
|
||||||
// Hmmm. Arduino dependent code
|
// time_t currentTime = time(NULL);
|
||||||
// unsigned long curMillis = millis();
|
float timeStep = currentTimeMs - this->lastUpdateTime; // difftime(currentTime, this->lastUpdateTime);
|
||||||
// float timeStep = (float)(curMillis - lastMillis) / 1000;
|
|
||||||
// lastMillis = curMillis;
|
|
||||||
|
|
||||||
for (unsigned int motorIx = 0; motorIx < this->motorCount; motorIx++) {
|
for (unsigned int motorIx = 0; motorIx < this->motorCount; motorIx++) {
|
||||||
// Placement placement = placement[motorIx];
|
Thing* thing = placement[motorIx].thing;
|
||||||
// placement.controlledMotor->Update(timeStep);
|
if (thing->type == Thing::Type::ControlledMotor) {
|
||||||
|
ControlledMotor* motor = (ControlledMotor*)thing;
|
||||||
|
motor->Update(currentTimeMs);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
this->lastUpdateTime = currentTimeMs;
|
||||||
|
}
|
||||||
|
|
||||||
void Propulsion::SetDiffDriveSpeed(float leftSpeed, float rightSpeed) {
|
void Propulsion::SetDiffDriveSpeed(float leftSpeed, float rightSpeed) {
|
||||||
for (unsigned int motorIx = 0; motorIx < this->motorCount; motorIx++) {
|
for (unsigned int motorIx = 0; motorIx < this->motorCount; motorIx++) {
|
||||||
|
Thing* thing = placement[motorIx].thing;
|
||||||
|
if (thing->type == Thing::Type::Motor) {
|
||||||
Motor* motor = (Motor*)placement[motorIx].thing;
|
Motor* motor = (Motor*)placement[motorIx].thing;
|
||||||
if (motor == nullptr)
|
if (motor == nullptr)
|
||||||
continue;
|
continue;
|
||||||
@ -79,6 +76,21 @@ void Propulsion::SetDiffDriveSpeed(float leftSpeed, float rightSpeed) {
|
|||||||
motor->SetSpeed(leftSpeed);
|
motor->SetSpeed(leftSpeed);
|
||||||
else if (xPosition > 0)
|
else if (xPosition > 0)
|
||||||
motor->SetSpeed(rightSpeed);
|
motor->SetSpeed(rightSpeed);
|
||||||
|
|
||||||
|
Serial.printf("motor %d, speed = %f\n", motorIx, motor->GetSpeed());
|
||||||
|
} else if (thing->type == Thing::Type::ControlledMotor) {
|
||||||
|
ControlledMotor* motor = (ControlledMotor*)placement[motorIx].thing;
|
||||||
|
if (motor == nullptr)
|
||||||
|
continue;
|
||||||
|
|
||||||
|
float xPosition = placement[motorIx].position.x;
|
||||||
|
if (xPosition < 0)
|
||||||
|
motor->SetTargetSpeed(leftSpeed);
|
||||||
|
else if (xPosition > 0)
|
||||||
|
motor->SetTargetSpeed(rightSpeed);
|
||||||
|
|
||||||
|
Serial.printf("controlled motor %d, speed = %f\n", motorIx, motor->GetActualSpeed());
|
||||||
|
}
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -136,17 +148,40 @@ Quadcopter* Propulsion::GetQuadcopter() {
|
|||||||
return quadcopter;
|
return quadcopter;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool Propulsion::Drive(Vector3 point, float rotation) {
|
float Propulsion::GetOdometer() {
|
||||||
|
float odometer = 0;
|
||||||
|
for (unsigned int motorIx = 0; motorIx < this->motorCount; motorIx++) {
|
||||||
|
Thing* thing = placement[motorIx].thing;
|
||||||
|
if (thing->type == Thing::Type::ControlledMotor) {
|
||||||
|
ControlledMotor* motor = (ControlledMotor*)thing;
|
||||||
|
odometer += motor->encoder->GetDistance() / this->motorCount;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return odometer;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Propulsion::Drive(Vector3 point, float rotation, float currentTimeMs) {
|
||||||
if (!this->driving) {
|
if (!this->driving) {
|
||||||
this->startTime = time(NULL);
|
this->startTime = time(NULL);
|
||||||
this->targetDistance = point.magnitude();
|
this->targetDistance = point.magnitude();
|
||||||
|
if (hasOdometer)
|
||||||
|
this->startOdometer = GetOdometer();
|
||||||
this->driving = true;
|
this->driving = true;
|
||||||
}
|
}
|
||||||
|
if (hasOdometer) {
|
||||||
|
float distance = GetOdometer() - this->startOdometer;
|
||||||
|
Serial.printf("Odometer = %f\n", distance);
|
||||||
|
if (distance >= this->targetDistance) {
|
||||||
|
this->driving = false;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
double duration = difftime(time(NULL), this->startTime);
|
double duration = difftime(time(NULL), this->startTime);
|
||||||
if (duration >= this->targetDistance) {
|
if (duration >= this->targetDistance) {
|
||||||
this->driving = false;
|
this->driving = false;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
if (rotation > 0)
|
if (rotation > 0)
|
||||||
rotation = 1;
|
rotation = 1;
|
||||||
@ -154,5 +189,7 @@ bool Propulsion::Drive(Vector3 point, float rotation) {
|
|||||||
rotation = -1;
|
rotation = -1;
|
||||||
SetTwistSpeed(point.normalized(), rotation);
|
SetTwistSpeed(point.normalized(), rotation);
|
||||||
|
|
||||||
|
Update(currentTimeMs);
|
||||||
|
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
@ -11,7 +11,7 @@ class Propulsion {
|
|||||||
/// @brief Setup sensing
|
/// @brief Setup sensing
|
||||||
Propulsion();
|
Propulsion();
|
||||||
|
|
||||||
void Update();
|
void Update(float currentTimeMs);
|
||||||
|
|
||||||
void AddMotors(Placement* motors, unsigned int motorCount);
|
void AddMotors(Placement* motors, unsigned int motorCount);
|
||||||
void AddQuadcopter(Quadcopter* quadcopter);
|
void AddQuadcopter(Quadcopter* quadcopter);
|
||||||
@ -35,7 +35,9 @@ class Propulsion {
|
|||||||
float rollSpeed = 0.0F);
|
float rollSpeed = 0.0F);
|
||||||
|
|
||||||
// Position control (or actually, distance control)
|
// Position control (or actually, distance control)
|
||||||
bool Drive(Vector3 point, float rotation);
|
bool Drive(Vector3 point, float rotation, float currentTimeMs);
|
||||||
|
|
||||||
|
float GetOdometer();
|
||||||
|
|
||||||
Placement* placement = nullptr;
|
Placement* placement = nullptr;
|
||||||
unsigned int motorCount = 0;
|
unsigned int motorCount = 0;
|
||||||
@ -45,5 +47,8 @@ class Propulsion {
|
|||||||
|
|
||||||
bool driving = false;
|
bool driving = false;
|
||||||
float targetDistance = 0;
|
float targetDistance = 0;
|
||||||
|
bool hasOdometer = false;
|
||||||
|
float startOdometer;
|
||||||
time_t startTime;
|
time_t startTime;
|
||||||
|
float lastUpdateTime;
|
||||||
};
|
};
|
||||||
|
13
Roboid.cpp
13
Roboid.cpp
@ -13,8 +13,8 @@ Roboid::Roboid(Placement configuration[], unsigned int thingCount) {
|
|||||||
propulsion.AddMotors(configuration, thingCount);
|
propulsion.AddMotors(configuration, thingCount);
|
||||||
}
|
}
|
||||||
|
|
||||||
bool Roboid::Drive(Waypoint* waypoint) {
|
bool Roboid::Drive(Waypoint* waypoint, float currentTimeMs) {
|
||||||
bool finished = propulsion.Drive(waypoint->point, waypoint->rotation);
|
bool finished = propulsion.Drive(waypoint->point, waypoint->rotation, currentTimeMs);
|
||||||
return finished;
|
return finished;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -23,18 +23,19 @@ void Roboid::FollowTrajectory(Trajectory* trajectory) {
|
|||||||
this->waypointIx = 0;
|
this->waypointIx = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
void Roboid::Update() {
|
void Roboid::Update(float currentTimeMs) {
|
||||||
if (this->trajectory == nullptr)
|
if (this->trajectory == nullptr)
|
||||||
return;
|
return;
|
||||||
|
|
||||||
Waypoint* waypoint = &this->trajectory->waypoints[this->waypointIx];
|
Waypoint* waypoint = &this->trajectory->waypoints[this->waypointIx];
|
||||||
// Serial.printf("Driving waypoints %d: %f %f\n", this->waypointIx,
|
Serial.printf("Driving waypoints %d: %f %f\n", this->waypointIx,
|
||||||
// waypoint->point.z, waypoint->rotation);
|
waypoint->point.z, waypoint->rotation);
|
||||||
if (Drive(waypoint)) {
|
if (Drive(waypoint, currentTimeMs)) {
|
||||||
this->waypointIx++;
|
this->waypointIx++;
|
||||||
if (this->waypointIx == this->trajectory->waypointCount) {
|
if (this->waypointIx == this->trajectory->waypointCount) {
|
||||||
this->trajectory = nullptr;
|
this->trajectory = nullptr;
|
||||||
this->waypointIx = 0;
|
this->waypointIx = 0;
|
||||||
|
// stop
|
||||||
propulsion.SetTwistSpeed(0, 0);
|
propulsion.SetTwistSpeed(0, 0);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
4
Roboid.h
4
Roboid.h
@ -45,9 +45,9 @@ class Roboid {
|
|||||||
Placement* configuration;
|
Placement* configuration;
|
||||||
unsigned int thingCount;
|
unsigned int thingCount;
|
||||||
|
|
||||||
void Update();
|
void Update(float currentTimeMs);
|
||||||
|
|
||||||
bool Drive(Waypoint* waypoint);
|
bool Drive(Waypoint* waypoint, float currentTimeMs);
|
||||||
void FollowTrajectory(Trajectory* Trajectory);
|
void FollowTrajectory(Trajectory* Trajectory);
|
||||||
|
|
||||||
public:
|
public:
|
||||||
|
Loading…
x
Reference in New Issue
Block a user