trajectory using propulsion
This commit is contained in:
parent
d2b240a514
commit
ae5ed79700
23
Motor.cpp
23
Motor.cpp
@ -4,30 +4,9 @@
|
|||||||
#include <Arduino.h>
|
#include <Arduino.h>
|
||||||
|
|
||||||
Motor::Motor() {
|
Motor::Motor() {
|
||||||
// this->isMotor = true;
|
|
||||||
type = Type::Motor;
|
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;
|
||||||
}
|
}
|
||||||
@ -48,6 +27,6 @@ bool Motor::Drive(float distance) {
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
SetSpeed(distance < 0 ? -1 : 1);
|
SetSpeed(distance < 0 ? -1 : 1); // max speed
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
@ -3,6 +3,8 @@
|
|||||||
|
|
||||||
#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;
|
||||||
@ -112,6 +114,8 @@ 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,
|
void Propulsion::SetTwistVelocity(float forwardVelocity,
|
||||||
@ -132,20 +136,23 @@ Quadcopter* Propulsion::GetQuadcopter() {
|
|||||||
return quadcopter;
|
return quadcopter;
|
||||||
}
|
}
|
||||||
|
|
||||||
// bool Propulsion::Drive(Roboid* roboid, float forwardDistance) {
|
bool Propulsion::Drive(Vector3 point, float rotation) {
|
||||||
// bool finished = true;
|
if (!this->driving) {
|
||||||
// for (unsigned int motorIx = 0; motorIx < roboid->propulsion->motorCount;
|
this->startTime = time(NULL);
|
||||||
// motorIx++) {
|
this->targetDistance = point.magnitude();
|
||||||
// Motor* motor = (Motor*)roboid->placement[motorIx].thing;
|
this->driving = true;
|
||||||
// if (motor == nullptr)
|
}
|
||||||
// continue;
|
double duration = difftime(time(NULL), this->startTime);
|
||||||
// if (motor->isControlledMotor == false)
|
if (duration >= this->targetDistance) {
|
||||||
// continue;
|
this->driving = false;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
// ControlledMotor* controlledMotor = (ControlledMotor*)motor;
|
if (rotation > 0)
|
||||||
// bool motorFinished = controlledMotor->Drive(forwardDistance);
|
rotation = 1;
|
||||||
// if (motorFinished == false)
|
if (rotation < 0)
|
||||||
// finished = false;
|
rotation = -1;
|
||||||
// }
|
SetTwistSpeed(point.normalized(), rotation);
|
||||||
// return finished;
|
|
||||||
// }
|
return false;
|
||||||
|
}
|
@ -4,7 +4,7 @@
|
|||||||
#include "Quadcopter.h"
|
#include "Quadcopter.h"
|
||||||
#include "Vector2.h"
|
#include "Vector2.h"
|
||||||
|
|
||||||
// #include <list>
|
#include <time.h>
|
||||||
|
|
||||||
class Propulsion {
|
class Propulsion {
|
||||||
public:
|
public:
|
||||||
@ -35,10 +35,7 @@ class Propulsion {
|
|||||||
float rollSpeed = 0.0F);
|
float rollSpeed = 0.0F);
|
||||||
|
|
||||||
// Position control (or actually, distance control)
|
// Position control (or actually, distance control)
|
||||||
// void Drive(float forwardDistance);
|
bool Drive(Vector3 point, float rotation);
|
||||||
// void Turn(float turnDistance);
|
|
||||||
|
|
||||||
// void Update();
|
|
||||||
|
|
||||||
Placement* placement = nullptr;
|
Placement* placement = nullptr;
|
||||||
unsigned int motorCount = 0;
|
unsigned int motorCount = 0;
|
||||||
@ -48,4 +45,5 @@ class Propulsion {
|
|||||||
|
|
||||||
bool driving = false;
|
bool driving = false;
|
||||||
float targetDistance = 0;
|
float targetDistance = 0;
|
||||||
|
time_t startTime;
|
||||||
};
|
};
|
||||||
|
50
Roboid.cpp
50
Roboid.cpp
@ -13,56 +13,8 @@ Roboid::Roboid(Placement configuration[], unsigned int 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++)
|
|
||||||
// {
|
|
||||||
// bool motorFinished = false;
|
|
||||||
// Thing* thing = propulsion.placement[motorIx].thing;
|
|
||||||
|
|
||||||
// switch (thing->type) {
|
|
||||||
// case Thing::Type::ControlledMotor: {
|
|
||||||
// ControlledMotor* controlledMotor = (ControlledMotor*)thing;
|
|
||||||
// motorFinished = controlledMotor->Drive(forwardDistance);
|
|
||||||
// break;
|
|
||||||
// }
|
|
||||||
// case Thing::Type::Motor: {
|
|
||||||
// Motor* motor = (Motor*)thing;
|
|
||||||
// motorFinished = motor->Drive(forwardDistance);
|
|
||||||
// break;
|
|
||||||
// }
|
|
||||||
// default:
|
|
||||||
// break;
|
|
||||||
// }
|
|
||||||
// if (motorFinished == false)
|
|
||||||
// finished = false;
|
|
||||||
// }
|
|
||||||
// return finished;
|
|
||||||
// }
|
|
||||||
|
|
||||||
bool Roboid::Drive(Waypoint* waypoint) {
|
bool Roboid::Drive(Waypoint* waypoint) {
|
||||||
bool finished = true;
|
bool finished = propulsion.Drive(waypoint->point, waypoint->rotation);
|
||||||
for (unsigned int motorIx = 0; motorIx < propulsion.motorCount; motorIx++) {
|
|
||||||
bool motorFinished = false;
|
|
||||||
Thing* thing = propulsion.placement[motorIx].thing;
|
|
||||||
|
|
||||||
switch (thing->type) {
|
|
||||||
case Thing::Type::ControlledMotor: {
|
|
||||||
ControlledMotor* controlledMotor = (ControlledMotor*)thing;
|
|
||||||
motorFinished = controlledMotor->Drive(waypoint->point.z);
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
case Thing::Type::Motor: {
|
|
||||||
Motor* motor = (Motor*)thing;
|
|
||||||
motorFinished = motor->Drive(waypoint->point.z);
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
default:
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
if (motorFinished == false)
|
|
||||||
finished = false;
|
|
||||||
}
|
|
||||||
return finished;
|
return finished;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
x
Reference in New Issue
Block a user