Reduced the use of raw pointers
This commit is contained in:
parent
3f8eadf8cc
commit
5b5513971c
@ -19,13 +19,13 @@ if(ESP_PLATFORM)
|
||||
REQUIRES esp_netif esp_wifi
|
||||
)
|
||||
else()
|
||||
set(CMAKE_CXX_STANDARD 17) # Enable c++11 standard
|
||||
set(CMAKE_POSITION_INDEPENDENT_CODE ON)
|
||||
|
||||
project(RoboidControl)
|
||||
add_subdirectory(LinearAlgebra)
|
||||
add_subdirectory(Examples)
|
||||
|
||||
set(CMAKE_CXX_STANDARD 17) # Enable c++11 standard
|
||||
set(CMAKE_POSITION_INDEPENDENT_CODE ON)
|
||||
|
||||
add_compile_definitions(GTEST)
|
||||
include(FetchContent)
|
||||
FetchContent_Declare(
|
||||
|
@ -9,6 +9,7 @@
|
||||
|
||||
#include <math.h>
|
||||
|
||||
namespace LinearAlgebra {
|
||||
template <typename T>
|
||||
DirectionOf<T>::DirectionOf() {
|
||||
this->horizontal = AngleOf<T>();
|
||||
@ -98,5 +99,6 @@ void DirectionOf<T>::Normalize() {
|
||||
}
|
||||
}
|
||||
|
||||
template class DirectionOf<float>;
|
||||
template class DirectionOf<signed short>;
|
||||
template class LinearAlgebra::DirectionOf<float>;
|
||||
template class LinearAlgebra::DirectionOf<signed short>;
|
||||
}
|
@ -99,6 +99,4 @@ using Direction = DirectionSingle;
|
||||
|
||||
} // namespace LinearAlgebra
|
||||
|
||||
using namespace LinearAlgebra;
|
||||
|
||||
#endif
|
@ -175,5 +175,5 @@ PolarOf<T> PolarOf<T>::Rotate(const PolarOf& v, AngleOf<T> angle) {
|
||||
return r;
|
||||
}
|
||||
|
||||
template class PolarOf<float>;
|
||||
template class PolarOf<signed short>;
|
||||
template class LinearAlgebra::PolarOf<float>;
|
||||
template class LinearAlgebra::PolarOf<signed short>;
|
@ -5,6 +5,8 @@
|
||||
|
||||
#include <math.h>
|
||||
|
||||
namespace LinearAlgebra {
|
||||
|
||||
template <typename T>
|
||||
SphericalOf<T>::SphericalOf() {
|
||||
this->distance = 0.0f;
|
||||
@ -301,3 +303,5 @@ SphericalOf<T> SphericalOf<T>::RotateVertical(const SphericalOf<T>& v,
|
||||
|
||||
template class SphericalOf<float>;
|
||||
template class SphericalOf<signed short>;
|
||||
|
||||
} // namespace LinearAlgebra
|
@ -186,7 +186,6 @@ using Spherical = SphericalSingle;
|
||||
#endif
|
||||
|
||||
} // namespace LinearAlgebra
|
||||
using namespace LinearAlgebra;
|
||||
|
||||
#include "Polar.h"
|
||||
#include "Vector3.h"
|
||||
|
@ -4,6 +4,8 @@
|
||||
|
||||
#include "SwingTwist.h"
|
||||
|
||||
namespace LinearAlgebra {
|
||||
|
||||
template <typename T>
|
||||
SwingTwistOf<T>::SwingTwistOf() {
|
||||
this->swing = DirectionOf<T>(AngleOf<T>(), AngleOf<T>());
|
||||
@ -166,3 +168,5 @@ void SwingTwistOf<T>::Normalize() {
|
||||
|
||||
template class SwingTwistOf<float>;
|
||||
template class SwingTwistOf<signed short>;
|
||||
|
||||
}
|
@ -6,6 +6,8 @@
|
||||
|
||||
#include "Direction.h"
|
||||
|
||||
using namespace LinearAlgebra;
|
||||
|
||||
#define FLOAT_INFINITY std::numeric_limits<float>::infinity()
|
||||
|
||||
TEST(Direction16, Compare) {
|
||||
|
@ -8,6 +8,8 @@ namespace RoboidControl {
|
||||
|
||||
ParticipantRegistry Participant::registry;
|
||||
|
||||
Participant LocalParticipant = Participant("0.0.0.0", 0);
|
||||
|
||||
Participant::Participant(const char* ipAddress, int port) {
|
||||
// make a copy of the ip address string
|
||||
int addressLength = (int)strlen(ipAddress);
|
||||
|
@ -72,6 +72,8 @@ class Participant {
|
||||
/// @brief Destructor for the participant
|
||||
~Participant();
|
||||
|
||||
static Participant LocalParticipant;
|
||||
|
||||
public:
|
||||
#if defined(NO_STD)
|
||||
unsigned char thingCount = 0;
|
||||
|
@ -11,7 +11,7 @@
|
||||
namespace RoboidControl {
|
||||
namespace Posix {
|
||||
|
||||
void Setup(int localPort, const char* remoteIpAddress, int remotePort) {
|
||||
void ParticipantUDP::Setup(int localPort, const char* remoteIpAddress, int remotePort) {
|
||||
#if defined(__unix__) || defined(__APPLE__)
|
||||
|
||||
// Create a UDP socket
|
||||
@ -63,7 +63,7 @@ void Setup(int localPort, const char* remoteIpAddress, int remotePort) {
|
||||
#endif
|
||||
}
|
||||
|
||||
void Receive() {
|
||||
void ParticipantUDP::Receive() {
|
||||
#if defined(__unix__) || defined(__APPLE__)
|
||||
sockaddr_in client_addr;
|
||||
socklen_t len = sizeof(client_addr);
|
||||
@ -90,7 +90,7 @@ void Receive() {
|
||||
#endif
|
||||
}
|
||||
|
||||
bool Send(Participant* remoteParticipant, int bufferSize) {
|
||||
bool ParticipantUDP::Send(Participant* remoteParticipant, int bufferSize) {
|
||||
#if defined(__unix__) || defined(__APPLE__)
|
||||
// std::cout << "Send to " << remoteParticipant->ipAddress << ":" << ntohs(remoteParticipant->port)
|
||||
// << "\n";
|
||||
@ -113,7 +113,7 @@ bool Send(Participant* remoteParticipant, int bufferSize) {
|
||||
return true;
|
||||
}
|
||||
|
||||
bool Publish(IMessage* msg) {
|
||||
bool ParticipantUDP::Publish(IMessage* msg) {
|
||||
#if defined(__unix__) || defined(__APPLE__)
|
||||
int bufferSize = msg->Serialize(this->buffer);
|
||||
if (bufferSize <= 0)
|
||||
|
@ -11,6 +11,11 @@ class ParticipantUDP : public RoboidControl::ParticipantUDP {
|
||||
void Receive();
|
||||
bool Send(Participant* remoteParticipant, int bufferSize);
|
||||
bool Publish(IMessage* msg);
|
||||
|
||||
protected:
|
||||
sockaddr_in remote_addr;
|
||||
sockaddr_in server_addr;
|
||||
sockaddr_in broadcast_addr;
|
||||
};
|
||||
|
||||
} // namespace Posix
|
||||
|
11
Thing.cpp
11
Thing.cpp
@ -20,7 +20,7 @@ namespace RoboidControl {
|
||||
|
||||
#pragma region Init
|
||||
|
||||
Thing Root = Thing(Thing::Type::Undetermined, Root);
|
||||
Thing Thing::Root = Thing(Thing::Type::Undetermined, Root);
|
||||
|
||||
Thing::Thing(unsigned char thingType, Thing& parent) {
|
||||
this->type = thingType;
|
||||
@ -38,6 +38,7 @@ Thing::Thing(unsigned char thingType, Thing& parent) {
|
||||
// << this->owner->ipAddress << ":" << this->owner->port <<
|
||||
// std::endl;
|
||||
this->owner->Add(this, true);
|
||||
this->SetParent(&parent);
|
||||
}
|
||||
|
||||
Thing::Thing(Participant* owner, unsigned char thingType) {
|
||||
@ -63,10 +64,10 @@ Thing::Thing(Participant* owner, unsigned char thingType) {
|
||||
this->owner->Add(this, true);
|
||||
}
|
||||
|
||||
Thing::Thing(Thing* parent, unsigned char thingType) //, unsigned char thingId)
|
||||
: Thing(parent->owner, thingType) { //}, thingId) {
|
||||
this->SetParent(parent);
|
||||
}
|
||||
// Thing::Thing(Thing* parent, unsigned char thingType) //, unsigned char thingId)
|
||||
// : Thing(parent->owner, thingType) { //}, thingId) {
|
||||
// this->SetParent(parent);
|
||||
// }
|
||||
|
||||
Thing Thing::Reconstruct(Participant* owner, unsigned char thingType, unsigned char thingId) {
|
||||
Thing thing = Thing(owner, thingType);
|
||||
|
11
Thing.h
11
Thing.h
@ -41,18 +41,17 @@ class Thing {
|
||||
};
|
||||
|
||||
#pragma region Init
|
||||
static Thing Root; // = Thing(Type::Undetermined, Root);
|
||||
static Thing Root;
|
||||
|
||||
Thing(unsigned char thingType = Type::Undetermined, Thing& parent = Root);
|
||||
Thing(unsigned char thingType = Thing::Type::Undetermined, Thing& parent = Root);
|
||||
|
||||
/// @brief Create a new thing for a participant
|
||||
/// @param owner The owning participant
|
||||
/// @param thingType The type of thing (can use Thing::Type)
|
||||
/// @param thingId The ID of the thing, leave out or set to zero to generate
|
||||
/// an ID
|
||||
Thing(Participant* owner = nullptr,
|
||||
unsigned char thingType = Type::Undetermined);
|
||||
// unsigned char thingId = 0);
|
||||
Thing(Participant* owner,
|
||||
unsigned char thingType = Thing::Type::Undetermined);
|
||||
|
||||
/// @brief Create a new child thing
|
||||
/// @param parent The parent thing
|
||||
@ -60,8 +59,6 @@ class Thing {
|
||||
/// @param thingId The ID of the thing, leave out or set to zero to generate
|
||||
/// an ID
|
||||
/// @note The owner will be the same as the owner of the parent thing
|
||||
Thing(Thing* parent,
|
||||
unsigned char thingType = 0); //, unsigned char thingId = 0);
|
||||
|
||||
static Thing Reconstruct(Participant* owner,
|
||||
unsigned char thingType,
|
||||
|
@ -16,7 +16,11 @@ DifferentialDrive::DifferentialDrive(Participant* owner) : Thing(owner, Type::Di
|
||||
this->leftWheel = new Motor();
|
||||
this->rightWheel = new Motor();
|
||||
}
|
||||
DifferentialDrive::DifferentialDrive(Thing* parent) : Thing(parent, Type::DifferentialDrive) {
|
||||
// DifferentialDrive::DifferentialDrive(Thing* parent) : Thing(parent, Type::DifferentialDrive) {
|
||||
// this->leftWheel = new Motor();
|
||||
// this->rightWheel = new Motor();
|
||||
// }
|
||||
DifferentialDrive::DifferentialDrive(Thing& parent) : Thing(Type::DifferentialDrive, parent) {
|
||||
this->leftWheel = new Motor();
|
||||
this->rightWheel = new Motor();
|
||||
}
|
||||
|
@ -16,13 +16,14 @@ class DifferentialDrive : public Thing {
|
||||
/// @param participant The local participant
|
||||
/// @param thingId The ID of the thing, leave out or set to zero to generate
|
||||
/// an ID
|
||||
DifferentialDrive(Participant* participant = nullptr); //,
|
||||
DifferentialDrive(Participant* participant); //,
|
||||
//unsigned char thingId = 0);
|
||||
/// @brief Create a new child differential drive
|
||||
/// @param parent The parent thing
|
||||
/// @param thingId The ID of the thing, leave out or set to zero to generate
|
||||
/// an ID
|
||||
DifferentialDrive(Thing* parent); //, unsigned char thingId = 0);
|
||||
// DifferentialDrive(Thing* parent); //, unsigned char thingId = 0);
|
||||
DifferentialDrive(Thing& parent = Thing::Root);
|
||||
|
||||
/// @brief Configures the dimensions of the drive
|
||||
/// @param wheelDiameter The diameter of the wheels in meters
|
||||
|
@ -12,7 +12,8 @@ namespace RoboidControl {
|
||||
|
||||
DigitalSensor::DigitalSensor(Participant* owner) : Thing(owner, Type::Switch) {}
|
||||
|
||||
DigitalSensor::DigitalSensor(Thing* parent) : Thing(parent, Type::Switch) {}
|
||||
// DigitalSensor::DigitalSensor(Thing* parent) : Thing(parent, Type::Switch) {}
|
||||
DigitalSensor::DigitalSensor(Thing& parent) : Thing(Type::Switch, parent) {}
|
||||
|
||||
int DigitalSensor::GenerateBinary(char* bytes, unsigned char* ix) {
|
||||
bytes[(*ix)++] = state ? 1 : 0;
|
||||
|
@ -18,7 +18,8 @@ class DigitalSensor : public Thing {
|
||||
/// @param parent The parent thing
|
||||
/// @param thingId The ID of the thing, leave out or set to zero to generate
|
||||
/// an ID
|
||||
DigitalSensor(Thing* parent); //, unsigned char thingId = 0);
|
||||
// DigitalSensor(Thing* parent); //, unsigned char thingId = 0);
|
||||
DigitalSensor(Thing& parent = Thing::Root);
|
||||
|
||||
/// @brief The sigital state
|
||||
bool state = 0;
|
||||
|
@ -1,9 +1,17 @@
|
||||
#include "Motor.h"
|
||||
|
||||
RoboidControl::Motor::Motor(Participant* owner) : Thing(owner, Type::UncontrolledMotor) {}
|
||||
namespace RoboidControl {
|
||||
|
||||
RoboidControl::Motor::Motor(Thing* parent) : Thing(parent, Type::UncontrolledMotor) {}
|
||||
RoboidControl::Motor::Motor(Participant* owner)
|
||||
: Thing(owner, Type::UncontrolledMotor) {}
|
||||
|
||||
// RoboidControl::Motor::Motor(Thing* parent)
|
||||
// : Thing(parent, Type::UncontrolledMotor) {}
|
||||
|
||||
Motor::Motor(Thing& parent) : Thing(Type::UncontrolledMotor, parent) {}
|
||||
|
||||
void RoboidControl::Motor::SetTargetSpeed(float targetSpeed) {
|
||||
this->targetSpeed = targetSpeed;
|
||||
}
|
||||
|
||||
} // namespace RoboidControl
|
@ -6,8 +6,9 @@ namespace RoboidControl {
|
||||
|
||||
class Motor : public Thing {
|
||||
public:
|
||||
Motor(Participant* owner = nullptr);
|
||||
Motor(Thing* parent);
|
||||
Motor(Participant* owner);
|
||||
// Motor(Thing* parent);
|
||||
Motor(Thing& parent = Thing::Root);
|
||||
|
||||
/// @brief Motor turning direction
|
||||
enum class Direction { Clockwise = 1, CounterClockwise = -1 };
|
||||
|
@ -4,8 +4,8 @@ namespace RoboidControl {
|
||||
|
||||
RelativeEncoder::RelativeEncoder(Participant* owner)
|
||||
: Thing(owner, Type::IncrementalEncoder) {}
|
||||
RelativeEncoder::RelativeEncoder(Thing* parent)
|
||||
: Thing(parent, Type::IncrementalEncoder) {}
|
||||
// RelativeEncoder::RelativeEncoder(Thing* parent)
|
||||
// : Thing(parent, Type::IncrementalEncoder) {}
|
||||
|
||||
float RelativeEncoder::GetRotationSpeed() {
|
||||
return rotationSpeed;
|
||||
|
@ -15,7 +15,8 @@ class RelativeEncoder : public Thing {
|
||||
/// @param distancePerRevolution The distance a wheel travels per full
|
||||
/// rotation
|
||||
RelativeEncoder(Participant* owner);
|
||||
RelativeEncoder(Thing* parent);
|
||||
// RelativeEncoder(Thing* parent);
|
||||
RelativeEncoder(Thing& parent);
|
||||
|
||||
/// @brief Get the rotation speed
|
||||
/// @return The speed in revolutions per second
|
||||
|
@ -10,7 +10,9 @@ namespace RoboidControl {
|
||||
|
||||
TemperatureSensor::TemperatureSensor(Participant* owner) : Thing(owner, Type::TemperatureSensor) {}
|
||||
|
||||
TemperatureSensor::TemperatureSensor(Thing* parent) : Thing(parent, Type::TemperatureSensor) {}
|
||||
TemperatureSensor::TemperatureSensor(Thing& parent) : Thing(Type::TemperatureSensor, parent) {}
|
||||
|
||||
// TemperatureSensor::TemperatureSensor(Thing* parent) : Thing(parent, Type::TemperatureSensor) {}
|
||||
|
||||
void TemperatureSensor::SetTemperature(float temp) {
|
||||
this->temperature = temp;
|
||||
|
@ -13,7 +13,8 @@ class TemperatureSensor : public Thing {
|
||||
/// @param networkId The network ID of the sensor
|
||||
/// @param thingId The ID of the thing
|
||||
TemperatureSensor(Participant* participant); //, unsigned char thingId);
|
||||
TemperatureSensor(Thing* parent);
|
||||
// TemperatureSensor(Thing* parent);
|
||||
TemperatureSensor(Thing& parent = Thing::Root);
|
||||
|
||||
/// @brief The measured temperature
|
||||
float temperature = 0;
|
||||
|
@ -15,7 +15,8 @@ namespace RoboidControl {
|
||||
TouchSensor::TouchSensor(Participant* owner)
|
||||
: Thing(owner, Type::TouchSensor) {}
|
||||
|
||||
TouchSensor::TouchSensor(Thing* parent) : Thing(parent, Type::TouchSensor) {}
|
||||
// TouchSensor::TouchSensor(Thing* parent) : Thing(parent, Type::TouchSensor) {}
|
||||
TouchSensor::TouchSensor(Thing& parent) : Thing(Type::TouchSensor, parent) {}
|
||||
|
||||
int TouchSensor::GenerateBinary(char* bytes, unsigned char* ix) {
|
||||
bytes[(*ix)++] = touchedSomething ? 1 : 0;
|
||||
|
@ -14,12 +14,13 @@ class TouchSensor : public Thing {
|
||||
/// @param owner The owning participant
|
||||
/// @param thingId The ID of the thing, leave out or set to zero to generate
|
||||
/// an ID
|
||||
TouchSensor(Participant* owner = nullptr); //, unsigned char thingId = 0);
|
||||
TouchSensor(Participant* owner); //, unsigned char thingId = 0);
|
||||
/// @brief Create a new child touch sensor
|
||||
/// @param parent The parent thing
|
||||
/// @param thingId The ID of the thing, leave out or set to zero to generate
|
||||
/// an ID
|
||||
TouchSensor(Thing* parent); //, unsigned char thingId = 0);
|
||||
// TouchSensor(Thing* parent); //, unsigned char thingId = 0);
|
||||
TouchSensor(Thing& parent = Thing::Root);
|
||||
|
||||
/// @brief Value which is true when the sensor is touching something, false
|
||||
/// otherwise
|
||||
|
@ -17,26 +17,26 @@ using namespace RoboidControl;
|
||||
|
||||
int main() {
|
||||
// The robot's propulsion is a differential drive
|
||||
DifferentialDrive* bb2b = new DifferentialDrive();
|
||||
DifferentialDrive bb2b = DifferentialDrive();
|
||||
// Is has a touch sensor at the front left of the roboid
|
||||
TouchSensor* touchLeft = new TouchSensor(bb2b);
|
||||
TouchSensor touchLeft = TouchSensor(bb2b);
|
||||
// and other one on the right
|
||||
TouchSensor* touchRight = new TouchSensor(bb2b);
|
||||
TouchSensor touchRight = TouchSensor(bb2b);
|
||||
|
||||
// Do forever:
|
||||
while (true) {
|
||||
// The left wheel turns forward when nothing is touched on the right side
|
||||
// and turn backward when the roboid hits something on the right
|
||||
float leftWheelSpeed = (touchRight->touchedSomething) ? -600.0f : 600.0f;
|
||||
float leftWheelSpeed = (touchRight.touchedSomething) ? -600.0f : 600.0f;
|
||||
// The right wheel does the same, but instead is controlled by
|
||||
// touches on the left side
|
||||
float rightWheelSpeed = (touchLeft->touchedSomething) ? -600.0f : 600.0f;
|
||||
float rightWheelSpeed = (touchLeft.touchedSomething) ? -600.0f : 600.0f;
|
||||
// When both sides are touching something, both wheels will turn backward
|
||||
// and the roboid will move backwards
|
||||
bb2b->SetWheelVelocity(leftWheelSpeed, rightWheelSpeed);
|
||||
bb2b.SetWheelVelocity(leftWheelSpeed, rightWheelSpeed);
|
||||
|
||||
// Update the roboid state
|
||||
bb2b->Update(true);
|
||||
bb2b.Update(true);
|
||||
|
||||
// and sleep for 100ms
|
||||
#if defined(ARDUINO)
|
||||
|
@ -7,6 +7,9 @@
|
||||
#include "Participants/SiteServer.h"
|
||||
#include "Thing.h"
|
||||
|
||||
#include <chrono>
|
||||
#include <thread>
|
||||
|
||||
using namespace RoboidControl;
|
||||
|
||||
TEST(Participant, Participant) {
|
||||
@ -15,7 +18,7 @@ TEST(Participant, Participant) {
|
||||
unsigned long milliseconds = Thing::GetTimeMs();
|
||||
unsigned long startTime = milliseconds;
|
||||
while (milliseconds < startTime + 7000) {
|
||||
participant->Update(milliseconds);
|
||||
participant->Update();
|
||||
|
||||
std::this_thread::sleep_for(std::chrono::milliseconds(100));
|
||||
milliseconds = Thing::GetTimeMs();
|
||||
@ -29,7 +32,7 @@ TEST(Participant, SiteServer) {
|
||||
unsigned long milliseconds = Thing::GetTimeMs();
|
||||
unsigned long startTime = milliseconds;
|
||||
while (milliseconds < startTime + 7000) {
|
||||
siteServer->Update(milliseconds);
|
||||
siteServer->Update();
|
||||
|
||||
std::this_thread::sleep_for(std::chrono::milliseconds(100));
|
||||
milliseconds = Thing::GetTimeMs();
|
||||
@ -44,8 +47,8 @@ TEST(Participant, SiteParticipant) {
|
||||
unsigned long milliseconds = Thing::GetTimeMs();
|
||||
unsigned long startTime = milliseconds;
|
||||
while (milliseconds < startTime + 7000) {
|
||||
siteServer->Update(milliseconds);
|
||||
participant->Update(milliseconds);
|
||||
siteServer->Update();
|
||||
participant->Update();
|
||||
|
||||
std::this_thread::sleep_for(std::chrono::milliseconds(100));
|
||||
milliseconds = Thing::GetTimeMs();
|
||||
@ -63,8 +66,8 @@ TEST(Participant, ThingMsg) {
|
||||
unsigned long milliseconds = Thing::GetTimeMs();
|
||||
unsigned long startTime = milliseconds;
|
||||
while (milliseconds < startTime + 7000) {
|
||||
siteServer->Update(milliseconds);
|
||||
participant->Update(milliseconds);
|
||||
siteServer->Update();
|
||||
participant->Update();
|
||||
|
||||
std::this_thread::sleep_for(std::chrono::milliseconds(100));
|
||||
milliseconds = Thing::GetTimeMs();
|
||||
|
@ -15,7 +15,7 @@ TEST(RoboidControlSuite, HiddenParticipant) {
|
||||
unsigned long milliseconds = Thing::GetTimeMs();
|
||||
unsigned long startTime = milliseconds;
|
||||
while (milliseconds < startTime + 1000) {
|
||||
Thing::UpdateThings(milliseconds);
|
||||
Thing::UpdateThings();
|
||||
|
||||
milliseconds = Thing::GetTimeMs();
|
||||
}
|
||||
@ -29,7 +29,7 @@ TEST(RoboidControlSuite, IsolatedParticipant) {
|
||||
unsigned long milliseconds = Thing::GetTimeMs();
|
||||
unsigned long startTime = milliseconds;
|
||||
while (milliseconds < startTime + 1000) {
|
||||
participant->Update(milliseconds);
|
||||
participant->Update();
|
||||
|
||||
milliseconds = Thing::GetTimeMs();
|
||||
}
|
||||
|
Loading…
x
Reference in New Issue
Block a user