Initial attempt for scripting
This commit is contained in:
parent
afa459b120
commit
28ee532700
@ -7,11 +7,26 @@ class Accelerometer : public Sensor {
|
|||||||
public:
|
public:
|
||||||
Accelerometer(){};
|
Accelerometer(){};
|
||||||
|
|
||||||
/// @brief This gives the gravity direciton relative to the down direction.
|
/// @brief Returns the direction of the acceleration in the horizontal plane
|
||||||
/// @param forward the forward direction, negative is backward, positive is forward
|
/// @return The direction of the acceleration, negative is left, positive is
|
||||||
/// @param sideward the sideward direction, negative is left, positive is to the right
|
/// 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
|
/// @note the units (degrees, radians, -1..1, ...) depend on the sensor
|
||||||
void GetAccelerationDirection(float* forward, float* sideward);
|
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.
|
/// @brief The magnitude of the gravity field.
|
||||||
/// @return The magnitude. This value is never negative.
|
/// @return The magnitude. This value is never negative.
|
||||||
/// @note the unity (m/s^2, 0..1) depends on the sensor.
|
/// @note the unity (m/s^2, 0..1) depends on the sensor.
|
||||||
|
@ -1,20 +1,23 @@
|
|||||||
#include "ControlledMotor.h"
|
#include "ControlledMotor.h"
|
||||||
|
|
||||||
ControlledMotor::ControlledMotor() {}
|
ControlledMotor::ControlledMotor() {
|
||||||
|
this->isControlledMotor = true;
|
||||||
|
}
|
||||||
|
|
||||||
ControlledMotor::ControlledMotor(Motor* motor, Encoder* encoder) {
|
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;
|
||||||
}
|
}
|
||||||
|
|
||||||
void ControlledMotor::Update(float timeStep) {
|
void ControlledMotor::Update(float timeStep) {
|
||||||
float velocity = GetActualVelocity();
|
float velocity = GetActualSpeed();
|
||||||
float error = targetVelocity - velocity;
|
float error = targetVelocity - velocity;
|
||||||
|
|
||||||
float acceleration = error * timeStep * pidP; // Just P is used at this moment
|
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
|
||||||
}
|
}
|
@ -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();
|
||||||
@ -16,17 +19,36 @@ class ControlledMotor : public Thing {
|
|||||||
|
|
||||||
void Update(float timeStep);
|
void Update(float timeStep);
|
||||||
|
|
||||||
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() {
|
||||||
|
return (int)rotationDirection * encoder->GetRevolutionsPerSecond();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Drive(float distance) {
|
||||||
|
if (!driving) {
|
||||||
|
targetDistance = distance;
|
||||||
|
encoder->StartCountingRevolutions();
|
||||||
|
driving = true;
|
||||||
|
} else
|
||||||
|
targetDistance -= encoder->RestartCountingRevolutions();
|
||||||
|
|
||||||
|
return (targetDistance <= 0);
|
||||||
|
}
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
float targetVelocity;
|
float targetVelocity;
|
||||||
Motor* motor;
|
Motor* motor;
|
||||||
Encoder* encoder;
|
Encoder* encoder;
|
||||||
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;
|
||||||
};
|
};
|
@ -20,7 +20,7 @@ void Encoder::InterruptHandler() {
|
|||||||
transitionCount++;
|
transitionCount++;
|
||||||
}
|
}
|
||||||
|
|
||||||
float Encoder::GetRotationsPerSecond() {
|
float Encoder::GetRevolutionsPerSecond() {
|
||||||
return rps;
|
return rps;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -42,3 +42,9 @@ void Encoder::Update(float timeStep) {
|
|||||||
// float rps = distanceThisUpdate * timeStep;
|
// float rps = distanceThisUpdate * timeStep;
|
||||||
distance += distanceThisUpdate;
|
distance += distanceThisUpdate;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void Encoder::StartCountingRevolutions() {}
|
||||||
|
|
||||||
|
float Encoder::RestartCountingRevolutions() {
|
||||||
|
return 0;
|
||||||
|
}
|
@ -5,17 +5,20 @@ class Encoder {
|
|||||||
Encoder();
|
Encoder();
|
||||||
Encoder(unsigned char pin, unsigned char transitionsPerRotation);
|
Encoder(unsigned char pin, unsigned char transitionsPerRotation);
|
||||||
|
|
||||||
float GetRotationsPerSecond();
|
float GetPulsesPerSecond();
|
||||||
|
float GetRevolutionsPerSecond();
|
||||||
|
|
||||||
void ResetDistance();
|
void ResetDistance();
|
||||||
float GetRotationDistance();
|
float GetRotationDistance();
|
||||||
|
|
||||||
void Update(float timeStep);
|
void Update(float timeStep);
|
||||||
|
|
||||||
|
virtual void StartCountingRevolutions();
|
||||||
|
virtual float RestartCountingRevolutions();
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
static void InterruptHandler();
|
static void InterruptHandler();
|
||||||
static volatile unsigned char transitionCount;
|
static volatile unsigned char transitionCount;
|
||||||
|
|
||||||
unsigned char transitionsPerRotation;
|
unsigned char transitionsPerRotation;
|
||||||
float rps;
|
float rps;
|
||||||
|
|
||||||
|
3
Motor.h
3
Motor.h
@ -6,8 +6,7 @@ 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);
|
||||||
|
@ -77,7 +77,8 @@ void Propulsion::SetDiffDriveSpeed(float leftSpeed, float rightSpeed) {
|
|||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
|
||||||
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 +89,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);
|
||||||
@ -109,13 +111,16 @@ void Propulsion::SetTwistSpeed(Vector3 linear, float yaw) {
|
|||||||
quadcopter->SetTwistSpeed(linear, yaw);
|
quadcopter->SetTwistSpeed(linear, 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 +128,21 @@ void Propulsion::SetLinearSpeed(Vector3 velocity, float yawSpeed, float rollSpee
|
|||||||
Quadcopter* Propulsion::GetQuadcopter() {
|
Quadcopter* Propulsion::GetQuadcopter() {
|
||||||
return quadcopter;
|
return quadcopter;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// bool Propulsion::Drive(Roboid* roboid, float forwardDistance) {
|
||||||
|
// bool finished = true;
|
||||||
|
// for (unsigned int motorIx = 0; motorIx < roboid->propulsion->motorCount;
|
||||||
|
// motorIx++) {
|
||||||
|
// Motor* motor = (Motor*)roboid->placement[motorIx].thing;
|
||||||
|
// if (motor == nullptr)
|
||||||
|
// continue;
|
||||||
|
// if (motor->isControlledMotor == false)
|
||||||
|
// continue;
|
||||||
|
|
||||||
|
// ControlledMotor* controlledMotor = (ControlledMotor*)motor;
|
||||||
|
// bool motorFinished = controlledMotor->Drive(forwardDistance);
|
||||||
|
// if (motorFinished == false)
|
||||||
|
// finished = false;
|
||||||
|
// }
|
||||||
|
// return finished;
|
||||||
|
// }
|
||||||
|
32
Propulsion.h
32
Propulsion.h
@ -1,17 +1,10 @@
|
|||||||
#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 <list>
|
||||||
|
|
||||||
//struct MotorPlacement {
|
|
||||||
// Motor* motor;
|
|
||||||
// ControlledMotor* controlledMotor;
|
|
||||||
// Vector2 position;
|
|
||||||
//};
|
|
||||||
|
|
||||||
class Propulsion {
|
class Propulsion {
|
||||||
public:
|
public:
|
||||||
@ -20,13 +13,14 @@ class Propulsion {
|
|||||||
|
|
||||||
void Update();
|
void Update();
|
||||||
|
|
||||||
//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,22 @@ 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)
|
||||||
|
// void Drive(float forwardDistance);
|
||||||
|
// void Turn(float turnDistance);
|
||||||
|
|
||||||
|
// void Update();
|
||||||
|
|
||||||
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;
|
||||||
};
|
};
|
||||||
|
17
Roboid.cpp
17
Roboid.cpp
@ -12,3 +12,20 @@ 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(float forwardDistance) {
|
||||||
|
bool finished = true;
|
||||||
|
for (unsigned int motorIx = 0; motorIx < propulsion.motorCount; motorIx++) {
|
||||||
|
Motor* motor = (Motor*)propulsion.placement[motorIx].thing;
|
||||||
|
if (motor == nullptr)
|
||||||
|
continue;
|
||||||
|
if (motor->isControlledMotor == false)
|
||||||
|
continue;
|
||||||
|
|
||||||
|
ControlledMotor* controlledMotor = (ControlledMotor*)motor;
|
||||||
|
bool motorFinished = controlledMotor->Drive(forwardDistance);
|
||||||
|
if (motorFinished == false)
|
||||||
|
finished = false;
|
||||||
|
}
|
||||||
|
return finished;
|
||||||
|
}
|
||||||
|
4
Roboid.h
4
Roboid.h
@ -7,7 +7,7 @@
|
|||||||
|
|
||||||
class Acceleration {
|
class Acceleration {
|
||||||
public:
|
public:
|
||||||
float GetMagnitude() { return 0;};
|
float GetMagnitude() { return 0; };
|
||||||
};
|
};
|
||||||
|
|
||||||
class Roboid {
|
class Roboid {
|
||||||
@ -21,4 +21,6 @@ class Roboid {
|
|||||||
|
|
||||||
Placement* configuration;
|
Placement* configuration;
|
||||||
unsigned int thingCount;
|
unsigned int thingCount;
|
||||||
|
|
||||||
|
bool Drive(float forwardDistance);
|
||||||
};
|
};
|
Loading…
x
Reference in New Issue
Block a user