Improvements
This commit is contained in:
parent
7c68558d80
commit
b2914e437b
10
Motor.cpp
10
Motor.cpp
@ -1,15 +1,9 @@
|
|||||||
#include "Motor.h"
|
#include "Motor.h"
|
||||||
#include <time.h>
|
#include <time.h>
|
||||||
|
|
||||||
// #include <Arduino.h>
|
Motor::Motor() { type = (int)Thing::UncontrolledMotorType; }
|
||||||
|
|
||||||
Motor::Motor() {
|
float Motor::GetSpeed() { return this->currentTargetSpeed; }
|
||||||
type = Thing::MotorType;
|
|
||||||
}
|
|
||||||
|
|
||||||
float Motor::GetSpeed() {
|
|
||||||
return this->currentTargetSpeed;
|
|
||||||
}
|
|
||||||
|
|
||||||
void Motor::SetSpeed(float targetSpeed) {
|
void Motor::SetSpeed(float targetSpeed) {
|
||||||
this->currentTargetSpeed = targetSpeed;
|
this->currentTargetSpeed = targetSpeed;
|
||||||
|
20
Perception.cpp
Normal file
20
Perception.cpp
Normal file
@ -0,0 +1,20 @@
|
|||||||
|
#include "Perception.h"
|
||||||
|
#include "Angle.h"
|
||||||
|
#include <Arduino.h>
|
||||||
|
|
||||||
|
DistanceSensor *Perception::GetSensor(float angle) {
|
||||||
|
angle = Angle::Normalize(angle);
|
||||||
|
|
||||||
|
for (unsigned int ix = 0; ix < this->sensorCount; ix++) {
|
||||||
|
Placement placement = this->sensorPlacements[ix];
|
||||||
|
if (abs(placement.direction.y - angle) < 0.01F)
|
||||||
|
return (DistanceSensor *)placement.thing;
|
||||||
|
}
|
||||||
|
|
||||||
|
DistanceSensor *distanceSensor = new DistanceSensor();
|
||||||
|
Serial.printf("New sensor ADDED %f \n", angle);
|
||||||
|
Placement *newPlacement = new Placement(distanceSensor, angle);
|
||||||
|
AddSensors(newPlacement, 1);
|
||||||
|
|
||||||
|
return distanceSensor;
|
||||||
|
}
|
@ -3,8 +3,13 @@
|
|||||||
namespace Passer {
|
namespace Passer {
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
|
||||||
using Perception = Sensing;
|
// using Perception = Sensing;
|
||||||
|
|
||||||
}
|
class Perception : public Sensing {
|
||||||
|
public:
|
||||||
|
DistanceSensor *GetSensor(float angle);
|
||||||
|
};
|
||||||
|
|
||||||
|
} // namespace RoboidControl
|
||||||
} // namespace Passer
|
} // namespace Passer
|
||||||
using namespace Passer::RoboidControl;
|
using namespace Passer::RoboidControl;
|
@ -33,9 +33,7 @@ void Propulsion::AddQuadcopter(Quadcopter* quadcopter) {
|
|||||||
this->quadcopter = quadcopter;
|
this->quadcopter = quadcopter;
|
||||||
}
|
}
|
||||||
|
|
||||||
unsigned int Propulsion::GetMotorCount() {
|
unsigned int Propulsion::GetMotorCount() { return this->motorCount; }
|
||||||
return this->motorCount;
|
|
||||||
}
|
|
||||||
|
|
||||||
Motor *Propulsion::GetMotor(unsigned int motorId) {
|
Motor *Propulsion::GetMotor(unsigned int motorId) {
|
||||||
if (motorId >= this->motorCount)
|
if (motorId >= this->motorCount)
|
||||||
@ -48,12 +46,18 @@ Motor* Propulsion::GetMotor(unsigned int motorId) {
|
|||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
|
|
||||||
void Propulsion::Update(float currentTimeMs) {
|
Placement *Propulsion::GetMotorPlacement(unsigned int motorId) {
|
||||||
// time_t currentTime = time(NULL);
|
if (motorId >= this->motorCount)
|
||||||
// float timeStep =
|
return nullptr;
|
||||||
// currentTimeMs -
|
|
||||||
// this->lastUpdateTime; // difftime(currentTime, this->lastUpdateTime);
|
|
||||||
|
|
||||||
|
Placement *placement = &this->placement[motorId];
|
||||||
|
if ((placement->thing->type & Thing::MotorType) != 0)
|
||||||
|
return placement;
|
||||||
|
|
||||||
|
return nullptr;
|
||||||
|
}
|
||||||
|
|
||||||
|
void Propulsion::Update(float currentTimeMs) {
|
||||||
for (unsigned int motorIx = 0; motorIx < this->motorCount; motorIx++) {
|
for (unsigned int motorIx = 0; motorIx < this->motorCount; motorIx++) {
|
||||||
Thing *thing = placement[motorIx].thing;
|
Thing *thing = placement[motorIx].thing;
|
||||||
if (thing->type == Thing::ControlledMotorType) {
|
if (thing->type == Thing::ControlledMotorType) {
|
||||||
@ -64,9 +68,7 @@ void Propulsion::Update(float currentTimeMs) {
|
|||||||
this->lastUpdateTime = currentTimeMs;
|
this->lastUpdateTime = currentTimeMs;
|
||||||
}
|
}
|
||||||
|
|
||||||
void Propulsion::SetMaxSpeed(float maxSpeed) {
|
void Propulsion::SetMaxSpeed(float maxSpeed) { this->maxSpeed = abs(maxSpeed); }
|
||||||
this->maxSpeed = abs(maxSpeed);
|
|
||||||
}
|
|
||||||
|
|
||||||
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++) {
|
||||||
@ -139,16 +141,13 @@ void Propulsion::SetTwistVelocity(float forwardVelocity,
|
|||||||
SetDiffDriveVelocities(leftVelocity, rightVelocity);
|
SetDiffDriveVelocities(leftVelocity, rightVelocity);
|
||||||
}
|
}
|
||||||
|
|
||||||
void Propulsion::SetLinearSpeed(Vector3 velocity,
|
void Propulsion::SetLinearSpeed(Vector3 velocity, float yawSpeed,
|
||||||
float yawSpeed,
|
|
||||||
float rollSpeed) {
|
float rollSpeed) {
|
||||||
if (quadcopter != nullptr)
|
if (quadcopter != nullptr)
|
||||||
quadcopter->LinearMotion(velocity, yawSpeed, rollSpeed);
|
quadcopter->LinearMotion(velocity, yawSpeed, rollSpeed);
|
||||||
}
|
}
|
||||||
|
|
||||||
Quadcopter* Propulsion::GetQuadcopter() {
|
Quadcopter *Propulsion::GetQuadcopter() { return quadcopter; }
|
||||||
return quadcopter;
|
|
||||||
}
|
|
||||||
|
|
||||||
/// @brief Odometer returns the total distance traveled since start
|
/// @brief Odometer returns the total distance traveled since start
|
||||||
/// @return The total distance
|
/// @return The total distance
|
||||||
|
@ -22,6 +22,7 @@ class Propulsion {
|
|||||||
|
|
||||||
unsigned int GetMotorCount();
|
unsigned int GetMotorCount();
|
||||||
Motor *GetMotor(unsigned int motorIx);
|
Motor *GetMotor(unsigned int motorIx);
|
||||||
|
Placement *GetMotorPlacement(unsigned int motorIx);
|
||||||
|
|
||||||
/// @brief Set the maximum linear speed.
|
/// @brief Set the maximum linear speed.
|
||||||
/// @param maxSpeed The new maximum linear speed
|
/// @param maxSpeed The new maximum linear speed
|
||||||
@ -41,8 +42,7 @@ class Propulsion {
|
|||||||
void SetTwistVelocity(float forward, float yaw);
|
void SetTwistVelocity(float forward, float yaw);
|
||||||
|
|
||||||
// Think: drones
|
// Think: drones
|
||||||
void SetLinearSpeed(Vector3 direction,
|
void SetLinearSpeed(Vector3 direction, float yawSpeed = 0.0F,
|
||||||
float yawSpeed = 0.0F,
|
|
||||||
float rollSpeed = 0.0F);
|
float rollSpeed = 0.0F);
|
||||||
|
|
||||||
// Position control (or actually, distance control)
|
// Position control (or actually, distance control)
|
||||||
|
17
Sensing.cpp
17
Sensing.cpp
@ -37,9 +37,7 @@ void Sensing::AddSensors(Placement* things, unsigned int thingCount) {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
unsigned int Sensing::GetSensorCount() {
|
unsigned int Sensing::GetSensorCount() { return this->sensorCount; }
|
||||||
return this->sensorCount;
|
|
||||||
}
|
|
||||||
|
|
||||||
Sensor *Sensing::GetSensor(unsigned int sensorId) {
|
Sensor *Sensing::GetSensor(unsigned int sensorId) {
|
||||||
if (sensorId >= this->sensorCount)
|
if (sensorId >= this->sensorCount)
|
||||||
@ -78,7 +76,7 @@ float Sensing::DistanceLeft(float angle) {
|
|||||||
continue;
|
continue;
|
||||||
|
|
||||||
DistanceSensor *distanceSensor = (DistanceSensor *)placement.thing;
|
DistanceSensor *distanceSensor = (DistanceSensor *)placement.thing;
|
||||||
float sensorAngle = placement.direction.x;
|
float sensorAngle = placement.direction.y;
|
||||||
// Serial.printf(" distance sensor: %f %f 0\n", -angle, sensorAngle);
|
// Serial.printf(" distance sensor: %f %f 0\n", -angle, sensorAngle);
|
||||||
if (sensorAngle < 0 && sensorAngle > -angle) {
|
if (sensorAngle < 0 && sensorAngle > -angle) {
|
||||||
minDistance = fmin(minDistance, distanceSensor->GetDistance());
|
minDistance = fmin(minDistance, distanceSensor->GetDistance());
|
||||||
@ -89,15 +87,16 @@ float Sensing::DistanceLeft(float angle) {
|
|||||||
|
|
||||||
float Sensing::DistanceRight(float angle) {
|
float Sensing::DistanceRight(float angle) {
|
||||||
float minDistance = INFINITY;
|
float minDistance = INFINITY;
|
||||||
|
Serial.printf(" distance sensor count: %d\n", sensorCount);
|
||||||
for (unsigned int sensorIx = 0; sensorIx < this->sensorCount; sensorIx++) {
|
for (unsigned int sensorIx = 0; sensorIx < this->sensorCount; sensorIx++) {
|
||||||
Placement placement = sensorPlacements[sensorIx];
|
Placement placement = sensorPlacements[sensorIx];
|
||||||
Sensor *sensor = (Sensor *)placement.thing;
|
Sensor *sensor = (Sensor *)placement.thing;
|
||||||
if (sensor->type & Thing::DistanceSensorType != 0)
|
if (sensor->type != Thing::DistanceSensorType)
|
||||||
continue;
|
continue;
|
||||||
|
|
||||||
DistanceSensor *distanceSensor = (DistanceSensor *)placement.thing;
|
DistanceSensor *distanceSensor = (DistanceSensor *)placement.thing;
|
||||||
float sensorAngle = placement.direction.x;
|
float sensorAngle = placement.direction.y;
|
||||||
// Serial.printf(" distance sensor: 0 %f %f\n", sensorAngle, angle);
|
Serial.printf(" distance sensor: 0 %f %f\n", sensorAngle, angle);
|
||||||
if (sensorAngle > 0 && sensorAngle < angle) {
|
if (sensorAngle > 0 && sensorAngle < angle) {
|
||||||
minDistance = fmin(minDistance, distanceSensor->GetDistance());
|
minDistance = fmin(minDistance, distanceSensor->GetDistance());
|
||||||
}
|
}
|
||||||
@ -201,9 +200,7 @@ void Sensing::SetRange(float min, float max) {
|
|||||||
this->rangeMaximum = max;
|
this->rangeMaximum = max;
|
||||||
}
|
}
|
||||||
|
|
||||||
float* Sensing::GetDepthMap() {
|
float *Sensing::GetDepthMap() { return this->depthMap; }
|
||||||
return this->depthMap;
|
|
||||||
}
|
|
||||||
|
|
||||||
void Sensing::SetDepthMap(float angle, float distance) {
|
void Sensing::SetDepthMap(float angle, float distance) {
|
||||||
if (angle < rangeMinimum || angle > rangeMaximum)
|
if (angle < rangeMinimum || angle > rangeMaximum)
|
||||||
|
Loading…
x
Reference in New Issue
Block a user