Merge branch 'master' of http://gitlab.passervr.com/passer/cpp/roboidcontrol
This commit is contained in:
commit
2d20113355
34
Accelerometer.h
Normal file
34
Accelerometer.h
Normal file
@ -0,0 +1,34 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include "Sensor.h"
|
||||||
|
|
||||||
|
/// @brief A Sensor which can measure the magnetic field
|
||||||
|
class Accelerometer : public Sensor {
|
||||||
|
public:
|
||||||
|
Accelerometer(){};
|
||||||
|
|
||||||
|
/// @brief Returns the direction of the acceleration in the horizontal plane
|
||||||
|
/// @return The direction of the acceleration, negative is left, positive is
|
||||||
|
/// right
|
||||||
|
/// @note The horizontal plane is defined as being orthogonal to the gravity
|
||||||
|
/// vector
|
||||||
|
/// @note the units (degrees, radians, -1..1, ...) depend on the sensor
|
||||||
|
float GetHorizontalAccelerationDirection();
|
||||||
|
/// @brief Returns the magnitude of the acceleration in the horizontal plane
|
||||||
|
/// @return The magnitude. This value is never negative.
|
||||||
|
/// @note the unity (m/s^2, 0..1) depends on the sensor.
|
||||||
|
float GetHorizontalAccelerationMagnitude();
|
||||||
|
|
||||||
|
/// @brief This gives the gravity direciton relative to the down direction.
|
||||||
|
/// @param horizontal the horizontal direction, negative is left, positive is
|
||||||
|
/// right
|
||||||
|
/// @param vertical the vertical direction, negative is down, positive is up
|
||||||
|
/// @note The horizontal plane is defined as being orthogonal to the gravity
|
||||||
|
/// vector
|
||||||
|
/// @note the units (degrees, radians, -1..1, ...) depend on the sensor
|
||||||
|
void GetAccelerationDirection(float* horizontal, float* vertical);
|
||||||
|
/// @brief The magnitude of the gravity field.
|
||||||
|
/// @return The magnitude. This value is never negative.
|
||||||
|
/// @note the unity (m/s^2, 0..1) depends on the sensor.
|
||||||
|
float GetAccelerationMagnitude();
|
||||||
|
};
|
@ -1,20 +1,45 @@
|
|||||||
#include "ControlledMotor.h"
|
#include "ControlledMotor.h"
|
||||||
|
#include <Arduino.h>
|
||||||
|
ControlledMotor::ControlledMotor() {
|
||||||
|
this->type = Type::ControlledMotor;
|
||||||
|
}
|
||||||
|
|
||||||
ControlledMotor::ControlledMotor() {}
|
ControlledMotor::ControlledMotor(Motor* motor, Encoder* encoder)
|
||||||
|
: ControlledMotor() {
|
||||||
ControlledMotor::ControlledMotor(Motor* motor, Encoder* encoder) {
|
|
||||||
this->motor = motor;
|
this->motor = motor;
|
||||||
this->encoder = encoder;
|
this->encoder = encoder;
|
||||||
}
|
}
|
||||||
|
|
||||||
void ControlledMotor::SetTargetVelocity(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 = GetActualVelocity();
|
actualVelocity = (int)rotationDirection * encoder->GetRevolutionsPerSecond(currentTimeMs);
|
||||||
float error = targetVelocity - velocity;
|
float error = targetVelocity - velocity;
|
||||||
|
|
||||||
float acceleration = error * timeStep * pidP; // Just P is used at this moment
|
float timeStep = currentTimeMs - lastUpdateTime;
|
||||||
|
float acceleration =
|
||||||
|
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;
|
||||||
}
|
}
|
@ -3,6 +3,9 @@
|
|||||||
#include "Encoder.h"
|
#include "Encoder.h"
|
||||||
#include "Motor.h"
|
#include "Motor.h"
|
||||||
|
|
||||||
|
/// @brief A motor with speed control
|
||||||
|
/// It uses a feedback loop from an encoder to regulate the speed
|
||||||
|
/// The speed is measured in revolutions per second.
|
||||||
class ControlledMotor : public Thing {
|
class ControlledMotor : public Thing {
|
||||||
public:
|
public:
|
||||||
ControlledMotor();
|
ControlledMotor();
|
||||||
@ -14,19 +17,34 @@ class ControlledMotor : public Thing {
|
|||||||
float pidD = 0;
|
float pidD = 0;
|
||||||
float pidI = 0;
|
float pidI = 0;
|
||||||
|
|
||||||
void Update(float timeStep);
|
void Update(float currentTimeMs);
|
||||||
|
|
||||||
void SetTargetVelocity(float rotationsPerSecond);
|
/// @brief Set the target speed for the motor controller
|
||||||
float GetActualVelocity() {
|
/// @param speed the target in revolutions per second.
|
||||||
return (int)rotationDirection * encoder->GetRotationsPerSecond();
|
void SetTargetSpeed(float speed);
|
||||||
} // in rotations per second
|
|
||||||
|
/// @brief Get the actual speed from the encoder
|
||||||
|
/// @return The speed in revolutions per second
|
||||||
|
float GetActualSpeed();
|
||||||
|
|
||||||
|
bool Drive(float distance);
|
||||||
|
|
||||||
protected:
|
|
||||||
float targetVelocity;
|
|
||||||
Motor* motor;
|
Motor* motor;
|
||||||
Encoder* encoder;
|
Encoder* encoder;
|
||||||
|
|
||||||
|
protected:
|
||||||
|
float lastUpdateTime;
|
||||||
|
float targetVelocity;
|
||||||
|
float actualVelocity;
|
||||||
|
float netDistance = 0;
|
||||||
|
float startDistance = 0;
|
||||||
|
|
||||||
enum Direction { Forward = 1,
|
enum Direction { Forward = 1,
|
||||||
Reverse = -1 };
|
Reverse = -1 };
|
||||||
|
|
||||||
Direction rotationDirection;
|
Direction rotationDirection;
|
||||||
|
|
||||||
|
bool driving = false;
|
||||||
|
float targetDistance = 0;
|
||||||
|
float lastEncoderPosition = 0;
|
||||||
};
|
};
|
36
Encoder.cpp
36
Encoder.cpp
@ -1,44 +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::GetRotationsPerSecond() {
|
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;
|
return 0;
|
||||||
}
|
|
||||||
|
|
||||||
void Encoder::Update(float timeStep) {
|
|
||||||
// Hmmm. Arduino-dependent code...
|
|
||||||
// noInterrupts();
|
|
||||||
float distanceThisUpdate = transitionCount / transitionsPerRotation;
|
|
||||||
transitionCount = 0;
|
|
||||||
// interrupts();
|
|
||||||
|
|
||||||
// float rps = distanceThisUpdate * timeStep;
|
|
||||||
distance += distanceThisUpdate;
|
|
||||||
}
|
}
|
17
Encoder.h
17
Encoder.h
@ -3,21 +3,14 @@
|
|||||||
class Encoder {
|
class Encoder {
|
||||||
public:
|
public:
|
||||||
Encoder();
|
Encoder();
|
||||||
Encoder(unsigned char pin, unsigned char transitionsPerRotation);
|
Encoder(unsigned char transitionsPerRotation);
|
||||||
|
|
||||||
float GetRotationsPerSecond();
|
virtual int GetPulseCount();
|
||||||
|
virtual float GetPulsesPerSecond(float currentTimeMs);
|
||||||
|
|
||||||
void ResetDistance();
|
virtual float GetDistance();
|
||||||
float GetRotationDistance();
|
virtual float GetRevolutionsPerSecond(float currentTimeMs);
|
||||||
|
|
||||||
void Update(float timeStep);
|
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
static void InterruptHandler();
|
|
||||||
static volatile unsigned char transitionCount;
|
|
||||||
|
|
||||||
unsigned char transitionsPerRotation;
|
unsigned char transitionsPerRotation;
|
||||||
float rps;
|
|
||||||
|
|
||||||
float distance; // this is direction agnostic
|
|
||||||
};
|
};
|
||||||
|
23
Magnetometer.h
Normal file
23
Magnetometer.h
Normal file
@ -0,0 +1,23 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include "Sensor.h"
|
||||||
|
|
||||||
|
/// @brief A Sensor which can measure the magnetic field
|
||||||
|
class Magnetometer : public Sensor {
|
||||||
|
public:
|
||||||
|
Magnetometer();
|
||||||
|
|
||||||
|
/// @brief Returns the direction of the magnetic field relative to the forward direction
|
||||||
|
/// @return The direction, negative is to the left, positive is to the right
|
||||||
|
/// @note The actual unit (degrees, radians, -1..1, ...) depends on the sensor.
|
||||||
|
virtual float GetDirection();
|
||||||
|
/// @brief Returns the inclination of the magnetic field relative to the horizontal plane
|
||||||
|
/// @return The direction, negative is downward, positive is upward
|
||||||
|
/// @note The actual unit (degrees, radias, -1..1, ...) depends on the sensor.
|
||||||
|
virtual float GetInclination();
|
||||||
|
|
||||||
|
/// @brief Returns the strength of the magnetic field
|
||||||
|
/// @return The strength. This values should always be positive
|
||||||
|
/// @note The actual unit (tesla, 0..1, ...) depends on the sensor.
|
||||||
|
virtual unsigned float GetMagnitude();
|
||||||
|
}
|
45
Motor.cpp
45
Motor.cpp
@ -1,33 +1,32 @@
|
|||||||
#include "Motor.h"
|
#include "Motor.h"
|
||||||
|
#include <time.h>
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
|
||||||
Motor::Motor() {
|
Motor::Motor() {
|
||||||
this->isMotor = true;
|
type = Type::Motor;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Motor::Motor(uint8_t pinIn1, uint8_t pinIn2) {
|
|
||||||
// this->pinIn1 = pinIn1;
|
|
||||||
// this->pinIn2 = pinIn2;
|
|
||||||
|
|
||||||
// pinMode(pinIn1, OUTPUT); // configure the in1 pin to output mode
|
|
||||||
// pinMode(pinIn2, OUTPUT); // configure the in2 pin to output mode
|
|
||||||
// }
|
|
||||||
|
|
||||||
// void Motor::SetDirection(Direction direction) {
|
|
||||||
// digitalWrite(pinIn1, direction);
|
|
||||||
// digitalWrite(pinIn2, !direction); // This is the opposite of pinIn1
|
|
||||||
// }
|
|
||||||
|
|
||||||
// void Motor::SetSpeed(float speed) { // 0..1
|
|
||||||
// currentSpeed = speed;
|
|
||||||
// uint8_t motorSignal = (uint8_t)(speed * 255);
|
|
||||||
// analogWrite(pinIn1, speed);
|
|
||||||
// analogWrite(pinIn2, 255 - speed);
|
|
||||||
// }
|
|
||||||
|
|
||||||
float Motor::GetSpeed() {
|
float Motor::GetSpeed() {
|
||||||
return this->currentSpeed;
|
return this->currentSpeed;
|
||||||
}
|
}
|
||||||
|
|
||||||
void Motor::SetSpeed(float speed) {
|
void Motor::SetSpeed(float speed) {
|
||||||
this->currentSpeed = speed;
|
this->currentSpeed = speed;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Motor::Drive(float distance) {
|
||||||
|
if (!this->driving) {
|
||||||
|
this->startTime = time(NULL);
|
||||||
|
this->targetDistance = abs(distance);
|
||||||
|
this->driving = true;
|
||||||
|
}
|
||||||
|
double duration = difftime(time(NULL), this->startTime);
|
||||||
|
if (duration >= this->targetDistance) {
|
||||||
|
this->driving = false;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
SetSpeed(distance < 0 ? -1 : 1); // max speed
|
||||||
|
return false;
|
||||||
}
|
}
|
9
Motor.h
9
Motor.h
@ -1,13 +1,13 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include <time.h>
|
||||||
#include "Thing.h"
|
#include "Thing.h"
|
||||||
|
|
||||||
class Motor : public Thing {
|
class Motor : public Thing {
|
||||||
public:
|
public:
|
||||||
Motor();
|
Motor();
|
||||||
/// @brief Turning direction of the motor
|
/// @brief Turning direction of the motor
|
||||||
enum Direction { Forward = 1,
|
enum Direction { Forward = 1, Reverse = -1 };
|
||||||
Reverse = -1 };
|
|
||||||
|
|
||||||
/// @brief Set the turning direction of the motor
|
/// @brief Set the turning direction of the motor
|
||||||
// void SetDirection(Direction direction);
|
// void SetDirection(Direction direction);
|
||||||
@ -15,6 +15,11 @@ class Motor : public Thing {
|
|||||||
virtual void SetSpeed(float speed);
|
virtual void SetSpeed(float speed);
|
||||||
float GetSpeed();
|
float GetSpeed();
|
||||||
|
|
||||||
|
bool Drive(float distance);
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
float currentSpeed = 0;
|
float currentSpeed = 0;
|
||||||
|
bool driving = false;
|
||||||
|
float targetDistance = 0;
|
||||||
|
time_t startTime = 0;
|
||||||
};
|
};
|
||||||
|
128
Propulsion.cpp
128
Propulsion.cpp
@ -3,31 +3,28 @@
|
|||||||
|
|
||||||
#include "FloatSingle.h"
|
#include "FloatSingle.h"
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
|
||||||
Propulsion::Propulsion() {
|
Propulsion::Propulsion() {
|
||||||
this->placement = nullptr;
|
this->placement = nullptr;
|
||||||
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)
|
||||||
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)
|
||||||
this->placement[motorIx++] = things[thingIx];
|
this->placement[motorIx++] = things[thingIx];
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -45,39 +42,60 @@ Motor* Propulsion::GetMotor(unsigned int motorId) {
|
|||||||
return nullptr;
|
return nullptr;
|
||||||
|
|
||||||
Thing* thing = this->placement[motorId].thing;
|
Thing* thing = this->placement[motorId].thing;
|
||||||
if (thing->isMotor)
|
// if (thing->isMotor)
|
||||||
|
if (thing->type == Thing::Type::Motor)
|
||||||
return (Motor*)thing;
|
return (Motor*)thing;
|
||||||
|
|
||||||
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++) {
|
||||||
Motor* motor = (Motor*)placement[motorIx].thing;
|
Thing* thing = placement[motorIx].thing;
|
||||||
if (motor == nullptr)
|
if (thing->type == Thing::Type::Motor) {
|
||||||
continue;
|
Motor* motor = (Motor*)placement[motorIx].thing;
|
||||||
|
if (motor == nullptr)
|
||||||
|
continue;
|
||||||
|
|
||||||
float xPosition = placement[motorIx].position.x;
|
float xPosition = placement[motorIx].position.x;
|
||||||
if (xPosition < 0)
|
if (xPosition < 0)
|
||||||
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());
|
||||||
|
}
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
|
||||||
void Propulsion::SetDiffDriveVelocities(float leftVelocity, float rightVelocity) {
|
void Propulsion::SetDiffDriveVelocities(float leftVelocity,
|
||||||
|
float rightVelocity) {
|
||||||
for (unsigned int motorIx = 0; motorIx < this->motorCount; motorIx++) {
|
for (unsigned int motorIx = 0; motorIx < this->motorCount; motorIx++) {
|
||||||
// Placement placement = placement[motorIx];
|
// Placement placement = placement[motorIx];
|
||||||
// if (placement.position.x < 0)
|
// if (placement.position.x < 0)
|
||||||
@ -88,7 +106,8 @@ void Propulsion::SetDiffDriveVelocities(float leftVelocity, float rightVelocity)
|
|||||||
}
|
}
|
||||||
|
|
||||||
void Propulsion::SetTwistSpeed(float forward, float yaw) {
|
void Propulsion::SetTwistSpeed(float forward, float yaw) {
|
||||||
// This is configuration dependent, a drone will do something completely different...
|
// This is configuration dependent, a drone will do something completely
|
||||||
|
// different...
|
||||||
float leftSpeed = Float::Clamp(forward - yaw, -1, 1);
|
float leftSpeed = Float::Clamp(forward - yaw, -1, 1);
|
||||||
float rightSpeed = Float::Clamp(forward + yaw, -1, 1);
|
float rightSpeed = Float::Clamp(forward + yaw, -1, 1);
|
||||||
SetDiffDriveSpeed(leftSpeed, rightSpeed);
|
SetDiffDriveSpeed(leftSpeed, rightSpeed);
|
||||||
@ -107,15 +126,20 @@ void Propulsion::SetTwistSpeed(float forward, float yaw, float pitch) {
|
|||||||
void Propulsion::SetTwistSpeed(Vector3 linear, float yaw) {
|
void Propulsion::SetTwistSpeed(Vector3 linear, float yaw) {
|
||||||
if (quadcopter != nullptr)
|
if (quadcopter != nullptr)
|
||||||
quadcopter->SetTwistSpeed(linear, yaw);
|
quadcopter->SetTwistSpeed(linear, yaw);
|
||||||
|
else
|
||||||
|
SetTwistSpeed(linear.z, yaw);
|
||||||
}
|
}
|
||||||
|
|
||||||
void Propulsion::SetTwistVelocity(float forwardVelocity, float turningVelocity) {
|
void Propulsion::SetTwistVelocity(float forwardVelocity,
|
||||||
|
float turningVelocity) {
|
||||||
float leftVelocity = Float::Clamp(forwardVelocity - turningVelocity, -1, 1);
|
float leftVelocity = Float::Clamp(forwardVelocity - turningVelocity, -1, 1);
|
||||||
float rightVelocity = Float::Clamp(forwardVelocity + turningVelocity, -1, 1);
|
float rightVelocity = Float::Clamp(forwardVelocity + turningVelocity, -1, 1);
|
||||||
SetDiffDriveVelocities(leftVelocity, rightVelocity);
|
SetDiffDriveVelocities(leftVelocity, rightVelocity);
|
||||||
}
|
}
|
||||||
|
|
||||||
void Propulsion::SetLinearSpeed(Vector3 velocity, float yawSpeed, float rollSpeed) {
|
void Propulsion::SetLinearSpeed(Vector3 velocity,
|
||||||
|
float yawSpeed,
|
||||||
|
float rollSpeed) {
|
||||||
if (quadcopter != nullptr)
|
if (quadcopter != nullptr)
|
||||||
quadcopter->LinearMotion(velocity, yawSpeed, rollSpeed);
|
quadcopter->LinearMotion(velocity, yawSpeed, rollSpeed);
|
||||||
}
|
}
|
||||||
@ -123,3 +147,49 @@ void Propulsion::SetLinearSpeed(Vector3 velocity, float yawSpeed, float rollSpee
|
|||||||
Quadcopter* Propulsion::GetQuadcopter() {
|
Quadcopter* Propulsion::GetQuadcopter() {
|
||||||
return quadcopter;
|
return quadcopter;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
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) {
|
||||||
|
this->startTime = time(NULL);
|
||||||
|
this->targetDistance = point.magnitude();
|
||||||
|
if (hasOdometer)
|
||||||
|
this->startOdometer = GetOdometer();
|
||||||
|
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);
|
||||||
|
if (duration >= this->targetDistance) {
|
||||||
|
this->driving = false;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (rotation > 0)
|
||||||
|
rotation = 1;
|
||||||
|
if (rotation < 0)
|
||||||
|
rotation = -1;
|
||||||
|
SetTwistSpeed(point.normalized(), rotation);
|
||||||
|
|
||||||
|
Update(currentTimeMs);
|
||||||
|
|
||||||
|
return false;
|
||||||
|
}
|
37
Propulsion.h
37
Propulsion.h
@ -1,32 +1,26 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "Quadcopter.h"
|
|
||||||
#include "ControlledMotor.h"
|
#include "ControlledMotor.h"
|
||||||
#include "Placement.h"
|
#include "Placement.h"
|
||||||
|
#include "Quadcopter.h"
|
||||||
#include "Vector2.h"
|
#include "Vector2.h"
|
||||||
|
|
||||||
#include <list>
|
#include <time.h>
|
||||||
|
|
||||||
//struct MotorPlacement {
|
|
||||||
// Motor* motor;
|
|
||||||
// ControlledMotor* controlledMotor;
|
|
||||||
// Vector2 position;
|
|
||||||
//};
|
|
||||||
|
|
||||||
class Propulsion {
|
class Propulsion {
|
||||||
public:
|
public:
|
||||||
/// @brief Setup sensing
|
/// @brief Setup sensing
|
||||||
Propulsion();
|
Propulsion();
|
||||||
|
|
||||||
void Update();
|
void Update(float currentTimeMs);
|
||||||
|
|
||||||
//void AddMotors(MotorPlacement* motors, unsigned int motorCount);
|
|
||||||
void AddMotors(Placement* motors, unsigned int motorCount);
|
void AddMotors(Placement* motors, unsigned int motorCount);
|
||||||
void AddQuadcopter(Quadcopter* quadcopter);
|
void AddQuadcopter(Quadcopter* quadcopter);
|
||||||
|
Quadcopter* GetQuadcopter();
|
||||||
|
|
||||||
unsigned int GetMotorCount();
|
unsigned int GetMotorCount();
|
||||||
Motor* GetMotor(unsigned int motorIx);
|
Motor* GetMotor(unsigned int motorIx);
|
||||||
|
|
||||||
|
// Velocity control
|
||||||
void SetDiffDriveSpeed(float leftSpeed, float rightSpeed);
|
void SetDiffDriveSpeed(float leftSpeed, float rightSpeed);
|
||||||
void SetDiffDriveVelocities(float leftVelocity, float rightVelocity);
|
void SetDiffDriveVelocities(float leftVelocity, float rightVelocity);
|
||||||
|
|
||||||
@ -36,14 +30,25 @@ class Propulsion {
|
|||||||
void SetTwistVelocity(float forward, float yaw);
|
void SetTwistVelocity(float forward, float yaw);
|
||||||
|
|
||||||
// Think: drones
|
// Think: drones
|
||||||
Quadcopter* GetQuadcopter();
|
void SetLinearSpeed(Vector3 direction,
|
||||||
void SetLinearSpeed(Vector3 direction, float yawSpeed = 0.0F, float rollSpeed = 0.0F);
|
float yawSpeed = 0.0F,
|
||||||
|
float rollSpeed = 0.0F);
|
||||||
|
|
||||||
|
// Position control (or actually, distance control)
|
||||||
|
bool Drive(Vector3 point, float rotation, float currentTimeMs);
|
||||||
|
|
||||||
|
float GetOdometer();
|
||||||
|
|
||||||
protected:
|
|
||||||
//unsigned long lastMillis;
|
|
||||||
//MotorPlacement* motors = nullptr;
|
|
||||||
Placement* placement = nullptr;
|
Placement* placement = nullptr;
|
||||||
unsigned int motorCount = 0;
|
unsigned int motorCount = 0;
|
||||||
|
|
||||||
|
protected:
|
||||||
Quadcopter* quadcopter = nullptr;
|
Quadcopter* quadcopter = nullptr;
|
||||||
|
|
||||||
|
bool driving = false;
|
||||||
|
float targetDistance = 0;
|
||||||
|
bool hasOdometer = false;
|
||||||
|
float startOdometer;
|
||||||
|
time_t startTime;
|
||||||
|
float lastUpdateTime;
|
||||||
};
|
};
|
||||||
|
30
Roboid.cpp
30
Roboid.cpp
@ -1,5 +1,5 @@
|
|||||||
#include "Roboid.h"
|
#include "Roboid.h"
|
||||||
|
#include <Arduino.h>
|
||||||
Roboid::Roboid() {
|
Roboid::Roboid() {
|
||||||
this->configuration = nullptr;
|
this->configuration = nullptr;
|
||||||
this->thingCount = 0;
|
this->thingCount = 0;
|
||||||
@ -12,3 +12,31 @@ Roboid::Roboid(Placement configuration[], unsigned int thingCount) {
|
|||||||
perception.AddSensors(configuration, thingCount);
|
perception.AddSensors(configuration, thingCount);
|
||||||
propulsion.AddMotors(configuration, thingCount);
|
propulsion.AddMotors(configuration, thingCount);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool Roboid::Drive(Waypoint* waypoint, float currentTimeMs) {
|
||||||
|
bool finished = propulsion.Drive(waypoint->point, waypoint->rotation, currentTimeMs);
|
||||||
|
return finished;
|
||||||
|
}
|
||||||
|
|
||||||
|
void Roboid::FollowTrajectory(Trajectory* trajectory) {
|
||||||
|
this->trajectory = trajectory;
|
||||||
|
this->waypointIx = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
void Roboid::Update(float currentTimeMs) {
|
||||||
|
if (this->trajectory == nullptr)
|
||||||
|
return;
|
||||||
|
|
||||||
|
Waypoint* waypoint = &this->trajectory->waypoints[this->waypointIx];
|
||||||
|
Serial.printf("Driving waypoints %d: %f %f\n", this->waypointIx,
|
||||||
|
waypoint->point.z, waypoint->rotation);
|
||||||
|
if (Drive(waypoint, currentTimeMs)) {
|
||||||
|
this->waypointIx++;
|
||||||
|
if (this->waypointIx == this->trajectory->waypointCount) {
|
||||||
|
this->trajectory = nullptr;
|
||||||
|
this->waypointIx = 0;
|
||||||
|
// stop
|
||||||
|
propulsion.SetTwistSpeed(0, 0);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
38
Roboid.h
38
Roboid.h
@ -5,6 +5,34 @@
|
|||||||
#include "Placement.h"
|
#include "Placement.h"
|
||||||
#include "Propulsion.h"
|
#include "Propulsion.h"
|
||||||
|
|
||||||
|
class Waypoint {
|
||||||
|
public:
|
||||||
|
Waypoint(float forwardDistance, float rotation) {
|
||||||
|
this->point = Vector3(0, 0, forwardDistance);
|
||||||
|
this->distance = forwardDistance;
|
||||||
|
this->rotation = rotation;
|
||||||
|
}
|
||||||
|
float distance = 0;
|
||||||
|
Vector3 point = Vector3(0, 0, 0);
|
||||||
|
float rotation = 0;
|
||||||
|
};
|
||||||
|
class Trajectory {
|
||||||
|
public:
|
||||||
|
Trajectory(){};
|
||||||
|
Trajectory(Waypoint* waypoints, unsigned int waypointCount) {
|
||||||
|
this->waypoints = waypoints;
|
||||||
|
this->waypointCount = waypointCount;
|
||||||
|
}
|
||||||
|
|
||||||
|
Waypoint* waypoints;
|
||||||
|
unsigned int waypointCount;
|
||||||
|
};
|
||||||
|
|
||||||
|
class Acceleration {
|
||||||
|
public:
|
||||||
|
float GetMagnitude() { return 0; };
|
||||||
|
};
|
||||||
|
|
||||||
class Roboid {
|
class Roboid {
|
||||||
public:
|
public:
|
||||||
Roboid();
|
Roboid();
|
||||||
@ -12,7 +40,17 @@ class Roboid {
|
|||||||
|
|
||||||
Perception perception;
|
Perception perception;
|
||||||
Propulsion propulsion;
|
Propulsion propulsion;
|
||||||
|
Acceleration acceleration;
|
||||||
|
|
||||||
Placement* configuration;
|
Placement* configuration;
|
||||||
unsigned int thingCount;
|
unsigned int thingCount;
|
||||||
|
|
||||||
|
void Update(float currentTimeMs);
|
||||||
|
|
||||||
|
bool Drive(Waypoint* waypoint, float currentTimeMs);
|
||||||
|
void FollowTrajectory(Trajectory* Trajectory);
|
||||||
|
|
||||||
|
public:
|
||||||
|
Trajectory* trajectory;
|
||||||
|
unsigned int waypointIx = 0;
|
||||||
};
|
};
|
13
Sensing.cpp
13
Sensing.cpp
@ -29,7 +29,8 @@ void Sensing::AddSensors(Placement* things, unsigned int thingCount) {
|
|||||||
sensorCount = 0;
|
sensorCount = 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->isSensor)
|
// if (thing->isSensor)
|
||||||
|
if (thing->type == Thing::Type::Sensor)
|
||||||
sensorCount++;
|
sensorCount++;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -38,7 +39,8 @@ void Sensing::AddSensors(Placement* things, unsigned int thingCount) {
|
|||||||
unsigned int sensorIx = 0;
|
unsigned int sensorIx = 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->isSensor)
|
// if (thing->isSensor)
|
||||||
|
if (thing->type == Thing::Type::Sensor)
|
||||||
sensorPlacements[sensorIx++] = things[thingIx];
|
sensorPlacements[sensorIx++] = things[thingIx];
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -52,7 +54,8 @@ Sensor* Sensing::GetSensor(unsigned int sensorId) {
|
|||||||
return nullptr;
|
return nullptr;
|
||||||
|
|
||||||
Thing* thing = this->sensorPlacements[sensorId].thing;
|
Thing* thing = this->sensorPlacements[sensorId].thing;
|
||||||
if (thing->isSensor)
|
// if (thing->isSensor)
|
||||||
|
if (thing->type == Thing::Type::Sensor)
|
||||||
return (Sensor*)thing;
|
return (Sensor*)thing;
|
||||||
|
|
||||||
return nullptr;
|
return nullptr;
|
||||||
@ -167,7 +170,9 @@ bool Sensing::SwitchOn(float fromAngle, float toAngle) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
unsigned int Sensing::ToDepthMapIndex(float angle) {
|
unsigned int Sensing::ToDepthMapIndex(float angle) {
|
||||||
unsigned int depthMapIx = (unsigned int)(((angle - rangeMinimum) / (rangeMaximum - rangeMinimum)) * (float)resolution);
|
unsigned int depthMapIx =
|
||||||
|
(unsigned int)(((angle - rangeMinimum) / (rangeMaximum - rangeMinimum)) *
|
||||||
|
(float)resolution);
|
||||||
return depthMapIx;
|
return depthMapIx;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1,5 +1,6 @@
|
|||||||
#include "Sensor.h"
|
#include "Sensor.h"
|
||||||
|
|
||||||
Sensor::Sensor() {
|
Sensor::Sensor() {
|
||||||
this->isSensor = true;
|
// this->isSensor = true;
|
||||||
|
type = Type::Sensor;
|
||||||
}
|
}
|
1
Sensor.h
1
Sensor.h
@ -2,6 +2,7 @@
|
|||||||
|
|
||||||
#include "Thing.h"
|
#include "Thing.h"
|
||||||
|
|
||||||
|
/// @brief A sensor is a thing which can perform measurements in the environment
|
||||||
class Sensor : public Thing {
|
class Sensor : public Thing {
|
||||||
public:
|
public:
|
||||||
Sensor();
|
Sensor();
|
||||||
|
16
Thing.h
16
Thing.h
@ -1,8 +1,16 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
/// @brief A thing is a functional component on a robot
|
||||||
class Thing {
|
class Thing {
|
||||||
public:
|
public:
|
||||||
Thing() { isSensor = false, isMotor = false; }
|
Thing() {
|
||||||
bool isSensor;
|
type = Type::Undetermined;
|
||||||
bool isMotor;
|
// isSensor = false, isMotor = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
enum class Type { Undetermined, Sensor, Motor, ControlledMotor };
|
||||||
|
Type type = Type::Undetermined;
|
||||||
|
// bool isSensor;
|
||||||
|
// bool isMotor;
|
||||||
|
// bool isControlledMotor;
|
||||||
};
|
};
|
11
library.json
Normal file
11
library.json
Normal file
@ -0,0 +1,11 @@
|
|||||||
|
{
|
||||||
|
"name": "RoboidControl",
|
||||||
|
"version": "0.0",
|
||||||
|
"build": {
|
||||||
|
"srcDir": ".",
|
||||||
|
"flags": [
|
||||||
|
"-I .",
|
||||||
|
"-I ./VectorAlgebra/include"
|
||||||
|
]
|
||||||
|
}
|
||||||
|
}
|
Loading…
x
Reference in New Issue
Block a user