Compare commits

..

9 Commits

84 changed files with 1326 additions and 1818 deletions

View File

@ -1,30 +1,28 @@
#include "ArduinoParticipant.h"
#if !defined(NO_STD)
#include <iostream>
#endif
#if defined(ARDUINO)
#if defined(ARDUINO_ARCH_ESP8266)
#define HAS_WIFI 1
#include <ESP8266WiFi.h>
#elif defined(ESP32)
#define HAS_WIFI 1
#include <WiFi.h>
#elif defined(UNO_R4)
#define HAS_WIFI 1
#include <WiFi.h>
#elif defined(ARDUINO_ARCH_RP2040) // not functional, for future use
#define HAS_WIFI 1
#include <WifiNINA.h>
#endif
#endif
namespace RoboidControl {
namespace Arduino {
#if defined(ARDUINO) && defined(HAS_WIFI)
WiFiUDP* udp;
#if HAS_WIFI
WiFiUDP udp;
#endif
void ParticipantUDP::Setup() {
@ -33,9 +31,7 @@ void ParticipantUDP::Setup() {
#if defined(UNO_R4)
if (WiFi.status() == WL_NO_MODULE) {
#if !defined(NO_STD)
std::cout << "No network available!\n";
#endif
return;
}
#else
@ -44,16 +40,13 @@ void ParticipantUDP::Setup() {
return;
}
#endif
std::cout << "starting udp \n";
udp = new WiFiUDP();
udp->begin(this->port);
udp.begin(this->port);
#if !defined(NO_STD)
std::cout << "Wifi sync started local " << this->port;
if (this->remoteSite != nullptr)
std::cout << ", remote " << this->remoteSite->ipAddress << ":"
<< this->remoteSite->port << "\n";
#endif
std::cout << "Wifi sync started local " << this->port << ", remote "
<< this->remoteSite->ipAddress << ":" << this->remoteSite->port
<< "\n";
#endif
}
@ -65,68 +58,63 @@ void ParticipantUDP::GetBroadcastAddress() {
this->broadcastIpAddress = new char[broadcastIpString.length() + 1];
broadcastIpString.toCharArray(this->broadcastIpAddress,
broadcastIpString.length() + 1);
#if !defined(NO_STD)
std::cout << "Broadcast address: " << broadcastIpAddress << "\n";
#endif
#endif
}
void ParticipantUDP::Receive() {
#if defined(ARDUINO) && defined(HAS_WIFI)
int packetSize = udp->parsePacket();
int packetSize = udp.parsePacket();
while (packetSize > 0) {
udp->read(buffer, packetSize);
udp.read(buffer, packetSize);
String senderAddress = udp->remoteIP().toString();
String senderAddress = udp.remoteIP().toString();
char sender_ipAddress[16];
senderAddress.toCharArray(sender_ipAddress, 16);
unsigned int sender_port = udp->remotePort();
unsigned int sender_port = udp.remotePort();
// std::cout << "receiving " << packetSize << " bytes, msgId "
// << (int)this->buffer[0] << "\n";
ReceiveData(packetSize, sender_ipAddress, sender_port);
packetSize = udp->parsePacket();
packetSize = udp.parsePacket();
}
#endif
#endif // ARDUINO && HAS_WIFI
}
bool ParticipantUDP::Send(Participant* remoteParticipant, int bufferSize) {
#if defined(ARDUINO) && defined(HAS_WIFI)
// std::cout << "Sending to:\n " << remoteParticipant->ipAddress << ":"
// << remoteParticipant->port << "\n";
// << remoteParticipant->port << "\n";
int n = 0;
int r = 0;
do {
if (n > 0) {
#if !defined(NO_STD)
std::cout << "Retry sending\n";
#endif
delay(10);
}
n++;
udp.beginPacket(remoteParticipant->ipAddress, remoteParticipant->port);
udp.write((unsigned char*)buffer, bufferSize);
} while (udp.endPacket() == 0 && n < 10);
udp->beginPacket(remoteParticipant->ipAddress, remoteParticipant->port);
udp->write((unsigned char*)buffer, bufferSize);
r = udp->endPacket();
// On an Uno R4 WiFi, endPacket blocks for 10 seconds the first time
// It is not cleary yet why
} while (r == 0 && n < 10);
#endif
#endif // ARDUINO && HAS_WIFI
return true;
}
bool ParticipantUDP::Publish(IMessage* msg) {
#if defined(ARDUINO) && defined(HAS_WIFI)
// std::cout << "Publish to " << this->broadcastIpAddress << ":"
// << this->remoteSite->port << "\n";
int bufferSize = msg->Serialize((char*)this->buffer);
if (bufferSize <= 0)
return true;
udp->beginPacket(this->broadcastIpAddress, this->port);
udp->write((unsigned char*)buffer, bufferSize);
udp->endPacket();
udp.beginPacket(this->broadcastIpAddress, this->remoteSite->port);
udp.write((unsigned char*)buffer, bufferSize);
udp.endPacket();
// std::cout << "Publish to " << this->broadcastIpAddress << ":"
// << this->remotePort << "\n";
#endif
return true;
};

View File

@ -2,19 +2,31 @@
#include "Participants/ParticipantUDP.h"
// #if defined(ARDUINO_ARCH_ESP8266) || defined(ESP32) || defined(UNO_R4) || \
// defined(ARDUINO_ARCH_RP2040)
// #define HAS_WIFI 1
// #endif
// #if defined(HAS_WIFI)
// #include <WiFiUdp.h>
// #endif
namespace RoboidControl {
namespace Arduino {
class ParticipantUDP : public RoboidControl::ParticipantUDP {
public:
void Setup();
void Setup(); // const char* remoteIpAddress, int remotePort);
void Receive();
bool Send(Participant* remoteParticipant, int bufferSize);
bool Publish(IMessage* msg);
protected:
//#if defined(HAS_WIFI)
char* broadcastIpAddress = nullptr;
//#endif
void GetBroadcastAddress();
};

View File

@ -45,9 +45,6 @@ struct NssServer {
bool StartWifi(const char* wifiSsid,
const char* wifiPassword,
bool hotspotFallback) {
#if !defined(HAS_WIFI)
return false;
#else
#if defined(UNO_R4) || defined(ARDUINO_ARCH_RP2040)
if (WiFi.status() == WL_NO_MODULE) {
Serial.println("WiFi not present, WiFiSync is disabled");
@ -150,13 +147,9 @@ bool StartWifi(const char* wifiSsid,
}
return (!hotSpotEnabled);
#endif
}
void CheckFirmware(String url, String FIRMWARE_NAME, int FIRMWARE_VERSION) {
#if !defined(HAS_WIFI)
return;
#else
#if defined(UNO_R4) // Uno R4 Wifi does not support this kind of firmware
// update (as far as I know)
return;
@ -213,6 +206,5 @@ void CheckFirmware(String url, String FIRMWARE_NAME, int FIRMWARE_VERSION) {
Serial.println(httpCode);
}
#endif
#endif
}
#endif

View File

@ -5,81 +5,49 @@
namespace RoboidControl {
namespace Arduino {
#pragma region DRV8833
DRV8833::DRV8833(Configuration config, Thing* parent) : Thing(Type::Undetermined, parent) {
this->pinStandby = config.standby;
if (pinStandby != 255)
pinMode(pinStandby, OUTPUT);
this->motorA = new DRV8833Motor(this, config.AIn1, config.AIn2);
this->motorA->SetName("Motor A");
this->motorB = new DRV8833Motor(this, config.BIn1, config.BIn2);
this->motorB->SetName("Motor B");
}
#pragma endregion DRV8833
#pragma region Differential drive
DRV8833::DifferentialDrive::DifferentialDrive(DRV8833::Configuration config,
Thing* parent)
: RoboidControl::DifferentialDrive(this->drv8833.motorA,
this->drv8833.motorB,
parent),
drv8833(config, this) {}
void DRV8833::DifferentialDrive::Update(bool recurse) {
RoboidControl::DifferentialDrive::Update(recurse);
this->drv8833.Update(false);
}
#pragma endregion Differential drive
#pragma region Motor
#if (ESP32)
uint8_t DRV8833Motor::nextAvailablePwmChannel = 0;
#endif
DRV8833Motor::DRV8833Motor(DRV8833* driver,
unsigned char pinIn1,
unsigned char pinIn2,
bool reverse)
: Motor() {
this->SetParent(driver);
DRV8833Motor::DRV8833Motor(Participant* participant, unsigned char pinIn1, unsigned char pinIn2, bool reverse)
: Thing(participant) {
this->pinIn1 = pinIn1;
this->pinIn2 = pinIn2;
#if (ESP32)
in1Ch = DRV8833Motor::nextAvailablePwmChannel++;
in1Ch = nextAvailablePwmChannel++;
ledcSetup(in1Ch, 500, 8);
ledcAttachPin(pinIn1, in1Ch);
in2Ch = DRV8833Motor::nextAvailablePwmChannel++;
in2Ch = nextAvailablePwmChannel++;
ledcSetup(in2Ch, 500, 8);
ledcAttachPin(pinIn2, in2Ch);
#else
pinMode(pinIn1, OUTPUT); // configure the in1 pin to output mode
pinMode(pinIn2, OUTPUT); // configure the in1 pin to output mode
#endif
// this->reverse = reverse;
this->reverse = reverse;
}
// void DRV8833Motor::SetMaxRPM(unsigned int rpm) {
// this->maxRpm = rpm;
// }
void DRV8833Motor::SetMaxRPM(unsigned int rpm) {
this->maxRpm = rpm;
}
void DRV8833Motor::SetTargetVelocity(float motorSpeed) {
Motor::SetTargetVelocity(motorSpeed);
void DRV8833Motor::SetAngularVelocity(Spherical velocity) {
Thing::SetAngularVelocity(velocity);
// ignoring rotation axis for now.
// Spherical angularVelocity = this->GetAngularVelocity();
float angularSpeed = velocity.distance; // in degrees/sec
uint8_t motorSignal =
(uint8_t)(motorSpeed > 0 ? motorSpeed * 255 : -motorSpeed * 255);
float rpm = angularSpeed / 360 * 60;
float motorSpeed = rpm / this->maxRpm;
// std::cout << "moto speed " << this->name << " = " << motorSpeed
uint8_t motorSignal = (uint8_t)(motorSpeed * 255);
// if (direction == RotationDirection::CounterClockwise)
// speed = -speed;
// Determine the rotation direction
if (velocity.direction.horizontal.InDegrees() < 0)
motorSpeed = -motorSpeed;
if (this->reverse)
motorSpeed = -motorSpeed;
// std::cout << "ang speed " << this->name << " = " << angularSpeed << " rpm " << rpm
// << ", motor signal = " << (int)motorSignal << "\n";
#if (ESP32)
@ -129,7 +97,24 @@ void DRV8833Motor::SetTargetVelocity(float motorSpeed) {
#endif
}
#pragma endregion Motor
DRV8833::DRV8833(Participant* participant,
unsigned char pinAIn1,
unsigned char pinAIn2,
unsigned char pinBIn1,
unsigned char pinBIn2,
unsigned char pinStandby,
bool reverseA,
bool reverseB)
: Thing(participant) {
this->pinStandby = pinStandby;
if (pinStandby != 255)
pinMode(pinStandby, OUTPUT);
this->motorA = new DRV8833Motor(participant, pinAIn1, pinAIn2, reverseA);
this->motorA->name = "Motor A";
this->motorB = new DRV8833Motor(participant, pinBIn1, pinBIn2, reverseB);
this->motorB->name = "Motor B";
}
} // namespace Arduino
} // namespace RoboidControl

View File

@ -1,76 +1,35 @@
#pragma once
#include <Arduino.h>
#include "Participants/IsolatedParticipant.h"
#include "Thing.h"
#include "Things/DifferentialDrive.h"
#include "Things/Motor.h"
namespace RoboidControl {
namespace Arduino {
class DRV8833Motor;
class DRV8833 : public Thing {
public:
struct Configuration {
int AIn1;
int AIn2;
int BIn1;
int BIn2;
int standby = 255;
};
/// @brief Setup a DRV8833 motor controller
DRV8833(Configuration config, Thing* parent = Thing::LocalRoot());
DRV8833Motor* motorA = nullptr;
DRV8833Motor* motorB = nullptr;
protected:
unsigned char pinStandby = 255;
public:
class DifferentialDrive;
};
#pragma region Differential drive
class DRV8833::DifferentialDrive : public RoboidControl::DifferentialDrive {
public:
DifferentialDrive(DRV8833::Configuration config, Thing* parent = Thing::LocalRoot());
virtual void Update(bool recurse = false) override;
protected:
DRV8833 drv8833;
};
#pragma endregion Differential drive
#pragma region Motor
/// @brief Support for a DRV8833 motor controller
class DRV8833Motor : public Motor {
class DRV8833Motor : public Thing {
public:
/// @brief Motor turning direction
enum class RotationDirection { Clockwise = 1, CounterClockwise = -1 };
/// @brief Setup the DC motor
/// @param pinIn1 the pin number for the in1 signal
/// @param pinIn2 the pin number for the in2 signal
/// @param direction the forward turning direction of the motor
DRV8833Motor(DRV8833* driver,
DRV8833Motor(Participant* participant,
unsigned char pinIn1,
unsigned char pinIn2,
bool reverse = false);
// void SetMaxRPM(unsigned int rpm);
void SetMaxRPM(unsigned int rpm);
// virtual void SetAngularVelocity(Spherical velocity) override;
virtual void SetTargetVelocity(float targetSpeed) override;
// bool reverse = false;
virtual void SetAngularVelocity(Spherical velocity) override;
bool reverse = false;
protected:
unsigned char pinIn1 = 255;
unsigned char pinIn2 = 255;
// unsigned int maxRpm = 200;
unsigned int maxRpm = 200;
#if (ESP32)
uint8_t in1Ch;
@ -79,7 +38,32 @@ class DRV8833Motor : public Motor {
#endif
};
#pragma endregion Motor
class DRV8833 : public Thing {
public:
/// @brief Setup a DRV8833 motor controller
/// @param pinAIn1 The pin number connected to the AIn1 port
/// @param pinAIn2 The pin number connected to the AIn2 port
/// @param pinBIn1 The pin number connected to the BIn1 port
/// @param pinBIn2 The pin number connceted to the BIn2 port
/// @param pinStandby The pin number connected to the standby port, 255
/// indicated that the port is not connected
/// @param reverseA The forward turning direction of motor A
/// @param reverseB The forward turning direction of motor B
DRV8833(Participant* participant,
unsigned char pinAIn1,
unsigned char pinAIn2,
unsigned char pinBIn1,
unsigned char pinBIn2,
unsigned char pinStandby = 255,
bool reverseA = false,
bool reverseB = false);
DRV8833Motor* motorA = nullptr;
DRV8833Motor* motorB = nullptr;
protected:
unsigned char pinStandby = 255;
};
} // namespace Arduino
} // namespace RoboidControl

View File

@ -5,125 +5,19 @@
namespace RoboidControl {
namespace Arduino {
#pragma region Digital input
DigitalInput::DigitalInput(unsigned char pin, Thing* parent)
: Thing(Type::Undetermined, parent) {
DigitalInput::DigitalInput(Participant* participant, unsigned char pin)
: TouchSensor(participant) {
this->pin = pin;
pinMode(this->pin, INPUT);
std::cout << "digital input start\n";
pinMode(pin, INPUT);
}
void DigitalInput::Update(bool recursive) {
this->isHigh = digitalRead(this->pin);
this->isLow = !this->isHigh;
Thing::Update(recursive);
void DigitalInput::Update(unsigned long currentTimeMs, bool recursive) {
this->touchedSomething = digitalRead(pin) == LOW;
// std::cout << "DigitalINput pin " << (int)this->pin << ": " <<
// this->touchedSomething << "\n";
Thing::Update(currentTimeMs, recursive);
}
#pragma endregion Digital input
#pragma region Touch sensor
DigitalInput::TouchSensor::TouchSensor(unsigned char pin, Thing* parent)
: RoboidControl::TouchSensor(parent), digitalInput(pin, parent) {}
void DigitalInput::TouchSensor::Update(bool recursive) {
this->touchedSomething = digitalInput.isLow;
}
#pragma endregion Touch sensor
#pragma region Relative encoder
int DigitalInput::RelativeEncoder::interruptCount = 0;
volatile int DigitalInput::RelativeEncoder::pulseCount0 = 0;
volatile int DigitalInput::RelativeEncoder::pulseCount1 = 0;
DigitalInput::RelativeEncoder::RelativeEncoder(Configuration config,
Thing* parent)
: RoboidControl::RelativeEncoder(parent),
digitalInput(config.pin, parent),
pulsesPerRevolution(config.pulsesPerRevolution) {}
void DigitalInput::RelativeEncoder::Start() {
// We support up to 2 pulse counters
if (interruptCount == 0) {
std::cout << "pin interrupt 1 activated" << std::endl;
attachInterrupt(digitalPinToInterrupt(digitalInput.pin), PulseInterrupt0,
RISING);
} else if (interruptCount == 1) {
std::cout << "pin interrupt 2 activated" << std::endl;
attachInterrupt(digitalPinToInterrupt(digitalInput.pin), PulseInterrupt1,
RISING);
} else {
// maximum interrupt count reached
std::cout << "DigitalInput::RelativeEncoder: max. # counters of 2 reached"
<< std::endl;
return;
}
interruptIx = interruptCount;
interruptCount++;
std::cout << "pin ints. " << interruptCount << std::endl;
}
int DigitalInput::RelativeEncoder::GetPulseCount() {
if (interruptIx == 0) {
int pulseCount = pulseCount0;
pulseCount0 = 0;
return pulseCount;
} else if (interruptIx == 1) {
int pulseCount = pulseCount1;
pulseCount1 = 0;
return pulseCount;
}
return 0;
}
void DigitalInput::RelativeEncoder::Update(bool recursive) {
unsigned long currentTimeMs = GetTimeMs();
if (this->lastUpdateTime == 0) {
this->Start();
this->lastUpdateTime = currentTimeMs;
return;
}
float timeStep = (float)(currentTimeMs - this->lastUpdateTime) / 1000.0f;
if (timeStep <= 0)
return;
int pulseCount = GetPulseCount();
netPulseCount += pulseCount;
this->pulseFrequency = pulseCount / timeStep;
this->rotationSpeed = pulseFrequency / pulsesPerRevolution;
std::cout << "pulses: " << pulseCount << " per second " << pulseFrequency
<< " timestep " << timeStep << std::endl;
this->lastUpdateTime = currentTimeMs;
}
#if defined(ESP8266) || defined(ESP32)
void ICACHE_RAM_ATTR DigitalInput::RelativeEncoder::PulseInterrupt0() {
pulseCount0++;
}
#else
void DigitalInput::RelativeEncoder::PulseInterrupt0() {
pulseCount0++;
}
#endif
#if defined(ESP8266) || defined(ESP32)
void IRAM_ATTR DigitalInput::RelativeEncoder::PulseInterrupt1() {
pulseCount1++;
}
#else
void DigitalInput::RelativeEncoder::PulseInterrupt1() {
pulseCount1++;
}
#endif
#pragma endregion Relative encoder
} // namespace Arduino
} // namespace RoboidControl

View File

@ -1,92 +1,26 @@
#pragma once
#include "Things/RelativeEncoder.h"
#include "Things/TouchSensor.h"
namespace RoboidControl {
namespace Arduino {
/// @brief A digital input represents the stat of a digital GPIO pin
class DigitalInput : public Thing {
class DigitalInput : public TouchSensor {
public:
/// @brief Create a new digital input
/// @param participant The participant to use
/// @param pin The digital pin
//DigitalInput(Participant* participant, unsigned char pin);
// DigitalInput(Thing* parent, unsigned char pin);
DigitalInput(unsigned char pin, Thing* parent);
bool isHigh = false;
bool isLow = false;
DigitalInput(Participant* participant, unsigned char pin);
/// @copydoc RoboidControl::Thing::Update(unsigned long currentTimeMs)
virtual void Update(bool recursive = false) override;
virtual void Update(unsigned long currentTimeMs,
bool recursive = false) override;
protected:
/// @brief The pin used for digital input
unsigned char pin = 0;
public:
class TouchSensor;
class RelativeEncoder;
};
#pragma region Touch sensor
class DigitalInput::TouchSensor : public RoboidControl::TouchSensor {
public:
TouchSensor(unsigned char pin, Thing* parent);
/// @copydoc RoboidControl::Thing::Update(unsigned long currentTimeMs)
virtual void Update(bool recurse = false) override;
protected:
DigitalInput digitalInput;
};
#pragma endregion Touch sensor
#pragma region Incremental encoder
class DigitalInput::RelativeEncoder : public RoboidControl::RelativeEncoder {
public:
struct Configuration {
unsigned char pin;
unsigned char pulsesPerRevolution;
};
RelativeEncoder(Configuration config, Thing* parent = Thing::LocalRoot());
unsigned char pulsesPerRevolution;
/// @brief The current pulse frequency in Hz
float pulseFrequency = 0;
/// @copydoc RoboidControl::Thing::Update()
virtual void Update(bool recurse = false) override;
protected:
DigitalInput digitalInput;
int interruptIx = 0;
static int interruptCount;
volatile static int pulseCount0;
static void PulseInterrupt0();
volatile static int pulseCount1;
static void PulseInterrupt1();
int GetPulseCount();
long netPulseCount = 0;
unsigned long lastUpdateTime = 0;
private:
void Start();
};
#pragma endregion Incremental encoder
} // namespace Arduino
} // namespace RoboidControl

View File

@ -1,16 +1,16 @@
#include "UltrasonicSensor.h"
#include <Arduino.h>
#include <iostream>
namespace RoboidControl {
namespace Arduino {
UltrasonicSensor::UltrasonicSensor(Configuration config, Thing* parent)
: Thing(Type::Undetermined, parent) {
this->name = "Ultrasonic sensor";
this->pinTrigger = config.trigger;
this->pinEcho = config.echo;
UltrasonicSensor::UltrasonicSensor(Participant* participant,
unsigned char pinTrigger,
unsigned char pinEcho)
: TouchSensor(participant) {
this->pinTrigger = pinTrigger;
this->pinEcho = pinEcho;
pinMode(pinTrigger, OUTPUT); // configure the trigger pin to output mode
pinMode(pinEcho, INPUT); // configure the echo pin to input mode
@ -19,14 +19,14 @@ UltrasonicSensor::UltrasonicSensor(Configuration config, Thing* parent)
float UltrasonicSensor::GetDistance() {
// Start the ultrasonic 'ping'
digitalWrite(pinTrigger, LOW);
delayMicroseconds(2);
delayMicroseconds(5);
digitalWrite(pinTrigger, HIGH);
delayMicroseconds(10);
digitalWrite(pinTrigger, LOW);
// Measure the duration of the pulse on the echo pin
unsigned long duration_us =
pulseIn(pinEcho, HIGH, 10000); // the result is in microseconds
float duration_us =
pulseIn(pinEcho, HIGH, 100000); // the result is in microseconds
// Calculate the distance:
// * Duration should be divided by 2, because the ping goes to the object
@ -37,38 +37,32 @@ float UltrasonicSensor::GetDistance() {
// * Now we calculate the distance based on the speed of sound (340 m/s):
// distance = duration_sec * 340;
// * The result calculation is therefore:
this->distance = (float)duration_us / 2 / 1000000 * 340;
// Serial.println(this->distance);
// std::cout << "US distance " << this->distance << std::endl;
this->distance = duration_us / 2 / 1000000 * 340;
// Filter faulty measurements. The sensor can often give values > 30 m which
// are not correct
// if (distance > 30)
// distance = 0;
return this->distance;
this->touchedSomething |= (this->distance <= this->touchDistance);
// std::cout << "Ultrasonic " << this->distance << " " <<
// this->touchedSomething << "\n";
return distance;
}
void UltrasonicSensor::Update(bool recursive) {
void UltrasonicSensor::Update(unsigned long currentTimeMs, bool recursive) {
this->touchedSomething = false;
GetDistance();
Thing::Update(recursive);
Thing::Update(currentTimeMs, recursive);
}
#pragma region Touch sensor
UltrasonicSensor::TouchSensor::TouchSensor(Configuration config, Thing* parent)
: RoboidControl::TouchSensor(parent), ultrasonic(config, this) {}
void UltrasonicSensor::TouchSensor::Update(bool recursive) {
RoboidControl::TouchSensor::Update(recursive);
this->ultrasonic.Update(false);
this->touchedSomething |= (this->ultrasonic.distance > 0 &&
this->ultrasonic.distance <= this->touchDistance);
}
#pragma region Touch sensor
// void UltrasonicSensor::ProcessBinary(char* bytes) {
// this->touchedSomething = (bytes[0] == 1);
// if (this->touchedSomething)
// std::cout << "Touching something!\n";
// }
} // namespace Arduino
} // namespace RoboidControl

View File

@ -6,19 +6,20 @@ namespace RoboidControl {
namespace Arduino {
/// @brief An HC-SR04 ultrasonic distance sensor
class UltrasonicSensor : Thing {
class UltrasonicSensor : public TouchSensor {
public:
struct Configuration {
int trigger;
int echo;
};
UltrasonicSensor(Configuration config, Thing* parent = Thing::LocalRoot());
/// @brief Setup an ultrasonic sensor
/// @param participant The participant to use
/// @param pinTrigger The pin number of the trigger signal
/// @param pinEcho The pin number of the echo signal
UltrasonicSensor(Participant* participant,
unsigned char pinTrigger,
unsigned char pinEcho);
// parameters
/// @brief The distance at which the object is considered to be touched
// float touchDistance = 0.2f;
float touchDistance = 0.2f;
// state
@ -30,35 +31,15 @@ class UltrasonicSensor : Thing {
float GetDistance();
/// @copydoc RoboidControl::Thing::Update(unsigned long currentTimeMs)
virtual void Update(bool recursive = false) override;
virtual void Update(unsigned long currentTimeMs,
bool recursive = false) override;
protected:
/// @brief The pin number of the trigger signal
unsigned char pinTrigger = 0;
/// @brief The pin number of the echo signal
unsigned char pinEcho = 0;
public:
class TouchSensor;
};
#pragma region Touch sensor
class UltrasonicSensor::TouchSensor : public RoboidControl::TouchSensor {
public:
TouchSensor(UltrasonicSensor::Configuration config,
Thing* parent = Thing::LocalRoot());
float touchDistance = 0.2f;
/// @copydoc RoboidControl::Thing::Update(unsigned long currentTimeMs)
virtual void Update(bool recursive = false) override;
protected:
UltrasonicSensor ultrasonic;
};
#pragma region Touch sensor
} // namespace Arduino
} // namespace RoboidControl

View File

@ -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(

View File

@ -7,9 +7,9 @@
namespace RoboidControl {
namespace EspIdf {
void ParticipantUDP::Setup(int localPort,
const char* remoteIpAddress,
int remotePort) {
void ParticipantUDP::Setup() {//int localPort,
// const char* remoteIpAddress,
// int remotePort) {
#if defined(IDF_VER)
std::cout << "Set up UDP\n";
GetBroadcastAddress();

View File

@ -11,7 +11,7 @@ namespace EspIdf {
class ParticipantUDP : public RoboidControl::ParticipantUDP {
public:
void Setup(int localPort, const char* remoteIpAddress, int remotePort);
void Setup(); //const char* remoteIpAddress, int remotePort);
void Receive();
bool Send(Participant* remoteParticipant, int bufferSize);
bool Publish(IMessage* msg);

View File

@ -17,26 +17,26 @@ using namespace RoboidControl;
int main() {
// The robot's propulsion is a differential drive
DifferentialDrive bb2b = DifferentialDrive();
DifferentialDrive* bb2b = new DifferentialDrive();
// Is has a touch sensor at the front left of the roboid
TouchSensor touchLeft = TouchSensor(&bb2b);
TouchSensor* touchLeft = new TouchSensor(bb2b);
// and other one on the right
TouchSensor touchRight = TouchSensor(&bb2b);
TouchSensor* touchRight = new 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)

View File

@ -9,7 +9,6 @@
#include <math.h>
namespace LinearAlgebra {
template <typename T>
DirectionOf<T>::DirectionOf() {
this->horizontal = AngleOf<T>();
@ -99,6 +98,5 @@ void DirectionOf<T>::Normalize() {
}
}
template class LinearAlgebra::DirectionOf<float>;
template class LinearAlgebra::DirectionOf<signed short>;
}
template class DirectionOf<float>;
template class DirectionOf<signed short>;

View File

@ -99,4 +99,6 @@ using Direction = DirectionSingle;
} // namespace LinearAlgebra
using namespace LinearAlgebra;
#endif

View File

@ -1,7 +1,5 @@
#include "Matrix.h"
#if !defined(NO_STD)
#include <iostream>
#endif
namespace LinearAlgebra {
@ -63,9 +61,7 @@ Matrix2::Matrix2(const Matrix2& m)
this->data = nullptr;
else {
this->data = new float[this->nValues];
for (int ix = 0; ix < this->nValues; ++ix)
this->data[ix] = m.data[ix];
std::copy(m.data, m.data + nValues, this->data);
}
}
@ -80,8 +76,7 @@ Matrix2& Matrix2::operator=(const Matrix2& m) {
this->data = nullptr;
else {
this->data = new float[this->nValues];
for (int ix = 0; ix < this->nValues; ++ix)
this->data[ix] = m.data[ix];
std::copy(m.data, m.data + this->nValues, this->data);
}
}
return *this;
@ -94,8 +89,7 @@ Matrix2::~Matrix2() {
Matrix2 Matrix2::Clone() const {
Matrix2 r = Matrix2(this->nRows, this->nCols);
for (int ix = 0; ix < this->nValues; ++ix)
r.data[ix] = this->data[ix];
std::copy(this->data, this->data + this->nValues, r.data);
return r;
}
@ -139,7 +133,7 @@ Matrix2 Matrix2::Identity(int size) {
}
Matrix2 Matrix2::Diagonal(float f, int size) {
Matrix2 r = Matrix2::Zero(size, size);
Matrix2 r = Matrix2(size, size);
float* data = r.data;
int valueIx = 0;
for (int ix = 0; ix < size; ix++) {
@ -164,8 +158,8 @@ Matrix2 Matrix2::SkewMatrix(const Vector3& v) {
Matrix2 Matrix2::Transpose() const {
Matrix2 r = Matrix2(this->nCols, this->nRows);
for (int rowIx = 0; rowIx < this->nRows; rowIx++) {
for (int colIx = 0; colIx < this->nCols; colIx++)
for (uint rowIx = 0; rowIx < this->nRows; rowIx++) {
for (uint colIx = 0; colIx < this->nCols; colIx++)
r.data[colIx * this->nCols + rowIx] =
this->data[rowIx * this->nCols + colIx];
}
@ -206,16 +200,16 @@ Matrix2 LinearAlgebra::Matrix2::operator*(const Matrix2& B) const {
int BColOffset = i * BCols; // BColOffset is constant for each row of B
for (int j = 0; j < BCols; ++j) {
float sum = 0;
std::cout << " 0";
// std::cout << " 0";
int BIndex = j;
for (int k = 0; k < ACols; ++k) {
std::cout << " + " << this->data[ARowOffset + k] << " * "
<< B.data[BIndex];
// std::cout << " + " << this->data[ARowOffset + k] << " * "
// << B.data[BIndex];
sum += this->data[ARowOffset + k] * B.data[BIndex];
BIndex += BCols;
}
r.data[BColOffset + j] = sum;
std::cout << " = " << sum << " ix: " << BColOffset + j << "\n";
// std::cout << " = " << sum << " ix: " << BColOffset + j << "\n";
}
}
return r;

View File

@ -175,5 +175,5 @@ PolarOf<T> PolarOf<T>::Rotate(const PolarOf& v, AngleOf<T> angle) {
return r;
}
template class LinearAlgebra::PolarOf<float>;
template class LinearAlgebra::PolarOf<signed short>;
template class PolarOf<float>;
template class PolarOf<signed short>;

View File

@ -5,8 +5,6 @@
#include <math.h>
namespace LinearAlgebra {
template <typename T>
SphericalOf<T>::SphericalOf() {
this->distance = 0.0f;
@ -303,5 +301,3 @@ SphericalOf<T> SphericalOf<T>::RotateVertical(const SphericalOf<T>& v,
template class SphericalOf<float>;
template class SphericalOf<signed short>;
} // namespace LinearAlgebra

View File

@ -186,6 +186,7 @@ using Spherical = SphericalSingle;
#endif
} // namespace LinearAlgebra
using namespace LinearAlgebra;
#include "Polar.h"
#include "Vector3.h"

View File

@ -4,8 +4,6 @@
#include "SwingTwist.h"
namespace LinearAlgebra {
template <typename T>
SwingTwistOf<T>::SwingTwistOf() {
this->swing = DirectionOf<T>(AngleOf<T>(), AngleOf<T>());
@ -167,6 +165,4 @@ void SwingTwistOf<T>::Normalize() {
}
template class SwingTwistOf<float>;
template class SwingTwistOf<signed short>;
}
template class SwingTwistOf<signed short>;

View File

@ -6,8 +6,6 @@
#include "Direction.h"
using namespace LinearAlgebra;
#define FLOAT_INFINITY std::numeric_limits<float>::infinity()
TEST(Direction16, Compare) {

View File

@ -2,7 +2,6 @@
#include <gtest/gtest.h>
#include <limits>
#include <math.h>
#include <chrono>
#include "Polar.h"
#include "Spherical.h"

View File

@ -2,7 +2,6 @@
#include <gtest/gtest.h>
#include <limits>
#include <math.h>
#include <chrono>
#include "Spherical.h"
#include "Vector3.h"

View File

@ -2,7 +2,6 @@
#include <gtest/gtest.h>
#include <limits>
#include <math.h>
#include <chrono>
#include "Spherical.h"

View File

@ -6,8 +6,7 @@ BinaryMsg::BinaryMsg(unsigned char networkId, Thing* thing) {
this->networkId = networkId;
this->thingId = thing->id;
this->thing = thing;
unsigned char ix = 0; //BinaryMsg::length;
this->data = new char[255];
unsigned char ix = BinaryMsg::length;
this->dataLength = this->thing->GenerateBinary(this->data, &ix);
}
@ -41,8 +40,6 @@ unsigned char BinaryMsg::Serialize(char* buffer) {
buffer[ix++] = this->networkId;
buffer[ix++] = this->thingId;
buffer[ix++] = this->dataLength;
for (int dataIx = 0; dataIx < this->dataLength; dataIx++)
buffer[ix++] = this->data[dataIx];
return this->length + this->dataLength;
}

View File

@ -1,17 +1,15 @@
#pragma once
#include "IMessage.h"
#include "Thing.h"
#include "Messages.h"
namespace RoboidControl {
/// @brief A message containing binary data for custom communication
/// @brief Message to send thing-specific data
class BinaryMsg : public IMessage {
public:
/// @brief The message ID
static const unsigned char id = 0xB1;
/// @brief The length of the message in bytes, excluding the binary data
/// For the total size of the message this.bytes.Length should be added to this value.
/// @brief The length of the message without the binary data itslef
static const unsigned length = 4;
/// @brief The network ID of the thing
@ -25,7 +23,7 @@ class BinaryMsg : public IMessage {
/// @brief The binary data which is communicated
char* data = nullptr;
/// @brief Create a BinaryMsg
/// @brief Create a new message for sending
/// @param networkId The network ID of the thing
/// @param thing The thing for which binary data is sent
BinaryMsg(unsigned char networkId, Thing* thing);

View File

@ -2,22 +2,19 @@
namespace RoboidControl {
DestroyMsg::DestroyMsg(unsigned char networkId, Thing* thing) {
DestroyMsg::DestroyMsg(unsigned char networkId, Thing *thing) {
this->networkId = networkId;
this->thingId = thing->id;
}
DestroyMsg::DestroyMsg(char* buffer) {
this->networkId = buffer[1];
this->thingId = buffer[2];
}
DestroyMsg::DestroyMsg(char* buffer) {}
DestroyMsg::~DestroyMsg() {}
unsigned char DestroyMsg::Serialize(char* buffer) {
#if defined(DEBUG)
std::cout << "Send DestroyMsg [" << (int)this->networkId << "/"
<< (int)this->thingId << "] " << std::endl;
unsigned char DestroyMsg::Serialize(char *buffer) {
#if defined(DEBUG)
std::cout << "Send DestroyMsg [" << (int)this->networkId << "/" << (int)this->thingId
<< "] " << std::endl;
#endif
unsigned char ix = 0;
buffer[ix++] = this->id;
@ -26,4 +23,4 @@ unsigned char DestroyMsg::Serialize(char* buffer) {
return ix;
}
} // namespace RoboidControl
} // namespace RoboidControl

View File

@ -1,16 +1,13 @@
#pragma once
#include "IMessage.h"
#include "Thing.h"
#include "Messages.h"
namespace RoboidControl {
/// @brief A Message notifiying that a Thing no longer exists
/// @brief Message notifiying that a Thing no longer exists
class DestroyMsg : public IMessage {
public:
/// @brief The message ID
static const unsigned char id = 0x20;
/// @brief The length of the message in bytes
/// @brief The length of the message
static const unsigned length = 3;
/// @brief The network ID of the thing
unsigned char networkId;

View File

@ -1,16 +0,0 @@
#pragma once
namespace RoboidControl {
/// @brief Root structure for all communcation messages
class IMessage {
public:
IMessage();
/// @brief Serialize the message into a byte array for sending
/// @param buffer The buffer to serilize into
/// @return The length of the message in the buffer
virtual unsigned char Serialize(char* buffer);
};
} // namespace RoboidControl

View File

@ -7,9 +7,9 @@ InvestigateMsg::InvestigateMsg(char* buffer) {
this->networkId = buffer[ix++];
this->thingId = buffer[ix++];
}
InvestigateMsg::InvestigateMsg(unsigned char networkId, Thing* thing) {
InvestigateMsg::InvestigateMsg(unsigned char networkId, unsigned char thingId) {
this->networkId = networkId;
this->thingId = thing->id;
this->thingId = thingId;
}
InvestigateMsg::~InvestigateMsg() {}

View File

@ -1,7 +1,4 @@
#pragma once
#include "IMessage.h"
#include "Thing.h"
#include "Messages.h"
namespace RoboidControl {
@ -17,10 +14,10 @@ class InvestigateMsg : public IMessage {
/// @brief the ID of the thing
unsigned char thingId;
/// @brief Create an investigate message
/// @brief Create a new message for sending
/// @param networkId The network ID for the thing
/// @param thing The thing for which the details are requested
InvestigateMsg(unsigned char networkId, Thing* thing);
/// @param thingId The ID of the thing
InvestigateMsg(unsigned char networkId, unsigned char thingId);
/// @copydoc RoboidControl::IMessage::IMessage(char*)
InvestigateMsg(char* buffer);
/// @brief Destructor for the message

View File

@ -1,5 +1,3 @@
#pragma once
#include "LinearAlgebra/Spherical.h"
#include "LinearAlgebra/SwingTwist.h"
@ -7,18 +5,18 @@ namespace RoboidControl {
class LowLevelMessages {
public:
static void SendAngle8(char* buffer, unsigned char* ix, const float angle);
static Angle8 ReceiveAngle8(const char* buffer, unsigned char* startIndex);
static void SendFloat16(char* buffer, unsigned char* ix, float value);
static float ReceiveFloat16(const char* buffer, unsigned char* startIndex);
static void SendSpherical(char* buffer, unsigned char* ix, Spherical s);
static Spherical ReceiveSpherical(const char* buffer,
unsigned char* startIndex);
static void SendQuat32(char* buffer, unsigned char* ix, SwingTwist q);
static SwingTwist ReceiveQuat32(const char* buffer, unsigned char* ix);
static void SendAngle8(char* buffer, unsigned char* ix, const float angle);
static Angle8 ReceiveAngle8(const char* buffer, unsigned char* startIndex);
static void SendFloat16(char* buffer, unsigned char* ix, float value);
static float ReceiveFloat16(const char* buffer, unsigned char* startIndex);
};
} // namespace RoboidControl

View File

@ -1,4 +1,7 @@
#include "IMessage.h"
#include "Messages.h"
#include "LowLevelMessages.h"
#include "string.h"
namespace RoboidControl {

22
Messages/Messages.h Normal file
View File

@ -0,0 +1,22 @@
#pragma once
#include "LinearAlgebra/Spherical.h"
#include "LinearAlgebra/SwingTwist.h"
#include "Thing.h"
namespace RoboidControl {
class ParticipantUDP;
class IMessage {
public:
IMessage();
virtual unsigned char Serialize(char* buffer);
static unsigned char* ReceiveMsg(unsigned char packetSize);
// bool Publish(ParticipantUDP *participant);
// bool SendTo(ParticipantUDP *participant);
};
} // namespace RoboidControl

View File

@ -1,7 +1,4 @@
#pragma once
#include "IMessage.h"
#include "Thing.h"
#include "Messages.h"
namespace RoboidControl {
@ -29,6 +26,8 @@ class ModelUrlMsg : public IMessage {
ModelUrlMsg(unsigned char networkId, Thing* thing);
/// @copydoc RoboidControl::IMessage::IMessage(char*)
ModelUrlMsg(const char* buffer);
// ModelUrlMsg(unsigned char networkId, unsigned char thingId,
// unsigned char urlLegth, const char *url, float scale = 1);
/// @brief Destructor for the message
virtual ~ModelUrlMsg();

View File

@ -7,16 +7,15 @@ namespace RoboidControl {
NameMsg::NameMsg(unsigned char networkId, Thing* thing) {
this->networkId = networkId;
this->thingId = thing->id;
const char* thingName = thing->GetName();
if (thingName == nullptr)
if (thing->name == nullptr)
this->nameLength = 0;
else
this->nameLength = (unsigned char)strlen(thingName);
this->nameLength = (unsigned char)strlen(thing->name);
// the name string in the buffer is not \0 terminated!
char* name = new char[this->nameLength + 1];
for (int i = 0; i < this->nameLength; i++)
name[i] = thingName[i];
name[i] = thing->name[i];
name[this->nameLength] = '\0';
this->name = name;
}

View File

@ -1,7 +1,4 @@
#pragma once
#include "IMessage.h"
#include "Thing.h"
#include "Messages.h"
namespace RoboidControl {
@ -25,6 +22,9 @@ class NameMsg : public IMessage {
/// @param networkId The network ID of the thing
/// @param thing The ID of the thing
NameMsg(unsigned char networkId, Thing* thing);
// NameMsg(unsigned char networkId, unsigned char thingId, const char *name,
// unsigned char nameLength);
/// @copydoc RoboidControl::IMessage::IMessage(char*)
NameMsg(const char* buffer);
/// @brief Destructor for the message

View File

@ -1,27 +0,0 @@
#include "NetworkIdMsg.h"
#include <iostream>
namespace RoboidControl {
NetworkIdMsg::NetworkIdMsg(const char* buffer) {
this->networkId = buffer[1];
}
NetworkIdMsg::NetworkIdMsg(unsigned char networkId) {
this->networkId = networkId;
}
NetworkIdMsg::~NetworkIdMsg() {}
unsigned char NetworkIdMsg::Serialize(char* buffer) {
#if defined(DEBUG)
std::cout << "Send NetworkIdMsg [" << (int)this->networkId << "] " << std::endl;
#endif
unsigned char ix = 0;
buffer[ix++] = this->id;
buffer[ix++] = this->networkId;
return NetworkIdMsg::length;
}
} // namespace RoboidControl

View File

@ -1,9 +1,5 @@
#include "ParticipantMsg.h"
#if !defined(NO_STD)
#include <iostream>
#endif
namespace RoboidControl {
ParticipantMsg::ParticipantMsg(char networkId) {
@ -17,7 +13,7 @@ ParticipantMsg::ParticipantMsg(const char* buffer) {
ParticipantMsg::~ParticipantMsg() {}
unsigned char ParticipantMsg::Serialize(char* buffer) {
#if defined(DEBUG) && !defined(NO_STD)
#if defined(DEBUG)
std::cout << "Send ParticipantMsg [" << (int)this->networkId << "] "
<< std::endl;
#endif

View File

@ -1,6 +1,6 @@
#pragma once
#include "IMessage.h"
#include "Messages.h"
namespace RoboidControl {

View File

@ -8,11 +8,11 @@ PoseMsg::PoseMsg(unsigned char networkId, Thing* thing, bool force) {
this->thingId = thing->id;
this->poseType = 0;
if (thing->positionUpdated || (force && thing->IsRoot())) {
if (thing->positionUpdated || force) {
this->position = thing->GetPosition();
this->poseType |= Pose_Position;
}
if (thing->orientationUpdated || (force && thing->IsRoot())) {
if (thing->orientationUpdated || force) {
this->orientation = thing->GetOrientation();
this->poseType |= Pose_Orientation;
}
@ -45,7 +45,7 @@ unsigned char PoseMsg::Serialize(char* buffer) {
if (this->poseType == 0)
return 0;
#if defined(DEBUG) && DEBUG > 1
#if defined(DEBUG)
std::cout << "Send PoseMsg [" << (int)this->networkId << "/"
<< (int)this->thingId << "] " << (int)this->poseType << std::endl;
#endif

View File

@ -1,6 +1,4 @@
#pragma once
#include "IMessage.h"
#include "Thing.h"
#include "Messages.h"
namespace RoboidControl {
@ -11,7 +9,7 @@ class PoseMsg : public IMessage {
public:
/// @brief The message ID
static const unsigned char id = 0x10;
/// @brief The length of the message in bytes
/// @brief The length of the message
unsigned char length = 4 + 4 + 4;
/// @brief The network ID of the thing
@ -42,8 +40,7 @@ class PoseMsg : public IMessage {
/// @brief Create a new message for sending
/// @param networkId he network ID of the thing
/// @param thing The thing for which the pose should be sent
/// @param force If true, position and orientation are always included, even when they are not updated
/// @param thing The thing for which the pose shouldbe sent
PoseMsg(unsigned char networkId, Thing* thing, bool force = false);
/// @copydoc RoboidControl::IMessage::IMessage(char*)

25
Messages/SiteMsg.cpp Normal file
View File

@ -0,0 +1,25 @@
#include "SiteMsg.h"
namespace RoboidControl {
SiteMsg::SiteMsg(const char* buffer) {
this->networkId = buffer[1];
}
SiteMsg::SiteMsg(unsigned char networkId) {
this->networkId = networkId;
}
SiteMsg::~SiteMsg() {}
unsigned char SiteMsg::Serialize(char* buffer) {
#if defined(DEBUG)
std::cout << "Send SiteMsg [" << (int)this->networkId << "] " << std::endl;
#endif
unsigned char ix = 0;
buffer[ix++] = this->id;
buffer[ix++] = this->networkId;
return SiteMsg::length;
}
} // namespace RoboidControl

View File

@ -1,11 +1,9 @@
#pragma once
#include "IMessage.h"
#include "Messages.h"
namespace RoboidControl {
/// @brief A message communicating the network ID for that participant
class NetworkIdMsg : public IMessage {
class SiteMsg : public IMessage {
public:
/// @brief The message ID
static const unsigned char id = 0xA1;
@ -16,11 +14,11 @@ public:
/// @brief Create a new message for sending
/// @param networkId The network ID for the participant
NetworkIdMsg(unsigned char networkId);
SiteMsg(unsigned char networkId);
/// @copydoc RoboidControl::IMessage::IMessage(char*)
NetworkIdMsg(const char *buffer);
SiteMsg(const char *buffer);
/// @brief Destructor for the message
virtual ~NetworkIdMsg();
virtual ~SiteMsg();
/// @copydoc RoboidControl::IMessage::Serialize
virtual unsigned char Serialize(char *buffer) override;

View File

@ -1,9 +1,5 @@
#include "TextMsg.h"
#if !defined(NO_STD)
#include <iostream>
#endif
namespace RoboidControl {
TextMsg::TextMsg(const char* text, unsigned char textLength) {
@ -28,7 +24,7 @@ unsigned char TextMsg::Serialize(char* buffer) {
if (this->textLength == 0 || this->text == nullptr)
return 0;
#if defined(DEBUG) && !defined(NO_STD)
#if defined(DEBUG)
std::cout << "Send TextMsg " << (int)this->textLength << " " << this->text << std::endl;
#endif
unsigned char ix = 0;

View File

@ -1,4 +1,4 @@
#include "IMessage.h"
#include "Messages.h"
namespace RoboidControl {
@ -9,6 +9,10 @@ class TextMsg : public IMessage {
static const unsigned char id = 0xB0;
/// @brief The length of the message without the text itself
static const unsigned char length = 2;
/// @brief The network ID of the thing
unsigned char networkId;
/// @brief the ID of the thing
unsigned char thingId;
/// @brief The text without the null terminator
const char* text;
/// @brief The length of the text

View File

@ -14,21 +14,27 @@ ThingMsg::ThingMsg(unsigned char networkId, Thing* thing) {
this->networkId = networkId;
this->thingId = thing->id;
this->thingType = thing->type;
if (thing->IsRoot())
this->parentId = 0;
else {
Thing* parent = thing->GetParent();
Thing* parent = thing->GetParent();
if (parent != nullptr)
this->parentId = parent->id;
}
else
this->parentId = 0;
}
// ThingMsg::ThingMsg(unsigned char networkId, unsigned char thingId,
// unsigned char thingType, unsigned char parentId) {
// this->networkId = networkId;
// this->thingId = thingId;
// this->thingType = thingType;
// this->parentId = parentId;
// }
ThingMsg::~ThingMsg() {}
unsigned char ThingMsg::Serialize(char* buffer) {
#if defined(DEBUG)
std::cout << "Send ThingMsg [" << (int)this->networkId << "/"
<< (int)this->thingId << "] " << (int)this->thingType << " "
<< (int)this->parentId << std::endl;
std::cout << "Send ThingMsg [" << (int)this->networkId << "/" << (int)this->thingId
<< "] " << (int)this->thingType << " " << (int)this->parentId << std::endl;
#endif
unsigned char ix = 0;
buffer[ix++] = this->id;

View File

@ -1,9 +1,8 @@
#include "IMessage.h"
#include "Thing.h"
#include "Messages.h"
namespace RoboidControl {
/// @brief Message providing generic details about a Thing
/// @brief Message providing generic information about a Thing
class ThingMsg : public IMessage {
public:
/// @brief The message ID
@ -14,15 +13,17 @@ class ThingMsg : public IMessage {
unsigned char networkId;
/// @brief The ID of the thing
unsigned char thingId;
/// @brief The type of thing
/// @brief The Thing.Type of the thing
unsigned char thingType;
/// @brief The ID of the parent thing in the hierarchy. This is zero for root things
/// @brief The parent of the thing in the hierarachy. This is null for root Things
unsigned char parentId;
/// @brief Create a message for sending
/// @param networkId The network ID of the thing</param>
/// @param thing The thing
ThingMsg(unsigned char networkId, Thing* thing);
// ThingMsg(unsigned char networkId, unsigned char thingId,
// unsigned char thingType, unsigned char parentId);
/// @copydoc RoboidControl::IMessage::IMessage(char*)
ThingMsg(const char* buffer);

View File

@ -4,30 +4,9 @@
namespace RoboidControl {
#pragma region Participant
ParticipantRegistry Participant::registry;
Participant* Participant::LocalParticipant = new Participant();
void Participant::ReplaceLocalParticipant(Participant& newParticipant) {
LocalParticipant = &newParticipant;
std::cout << "Replaced local participant" << std::endl;
}
Participant::Participant() {
std::cout << "P\n";
//this->root.name = "Isolated";
this->root = new Thing(this);
this->root->name = "Root";
this->Add(this->root);
}
Participant::Participant() {}
Participant::Participant(const char* ipAddress, int port) {
// Add the root thing to the list of things, because we could not do that
// earlier (I think)
this->Add(this->root);
// make a copy of the ip address string
int addressLength = (int)strlen(ipAddress);
int stringLength = addressLength + 1;
@ -45,14 +24,13 @@ Participant::Participant(const char* ipAddress, int port) {
}
Participant::~Participant() {
// registry.Remove(this);
delete[] this->ipAddress;
}
void Participant::Update() {
void Participant::Update(unsigned long currentTimeMs) {
for (Thing* thing : this->things) {
if (thing != nullptr)
thing->Update(true);
thing->Update(currentTimeMs, true);
}
}
@ -61,8 +39,7 @@ Thing* Participant::Get(unsigned char thingId) {
if (thing->id == thingId)
return thing;
}
// std::cout << "Could not find thing " << this->ipAddress << ":" <<
// this->port
// std::cout << "Could not find thing " << this->ipAddress << ":" << this->port
// << "[" << (int)thingId << "]\n";
return nullptr;
}
@ -74,15 +51,7 @@ void Participant::Add(Thing* thing, bool checkId) {
thing->id = this->thingCount + 1;
this->things[this->thingCount++] = thing;
#else
// find highest id
int highestIx = 0;
for (Thing* thing : this->things) {
if (thing == nullptr)
continue;
if (thing->id > highestIx)
highestIx = thing->id;
}
thing->id = highestIx + 1;
thing->id = (unsigned char)this->things.size() + 1;
this->things.push_back(thing);
#endif
// std::cout << "Add thing with generated ID " << this->ipAddress << ":"
@ -95,8 +64,7 @@ void Participant::Add(Thing* thing, bool checkId) {
#else
this->things.push_back(thing);
#endif
// std::cout << "Add thing " << this->ipAddress << ":" << this->port <<
// "["
// std::cout << "Add thing " << this->ipAddress << ":" << this->port << "["
// << (int)thing->id << "]\n";
} else {
// std::cout << "Did not add, existing thing " << this->ipAddress << ":"
@ -121,93 +89,22 @@ void Participant::Remove(Thing* thing) {
this->thingCount = lastThingIx;
#else
this->things.remove_if([thing](Thing* obj) { return obj == thing; });
// std::cout << "Removing [" << (int)thing->networkId << "/" << (int)thing->id
// << "] list size = " << this->things.size() << "\n";
std::cout << "Removing " << thing->networkId << "/" << thing->id
<< " list size = " << this->things.size() << "\n";
#endif
}
#pragma endregion
// void Participant::UpdateAll(unsigned long currentTimeMs) {
// // Not very efficient, but it works for now.
#pragma region ParticipantRegistry
Participant* ParticipantRegistry::Get(const char* ipAddress,
unsigned int port) {
#if !defined(NO_STD)
for (Participant* participant : ParticipantRegistry::participants) {
if (participant == nullptr)
continue;
if (strcmp(participant->ipAddress, ipAddress) == 0 &&
participant->port == port) {
// std::cout << "found participant " << participant->ipAddress << ":"
// << (int)participant->port << std::endl;
return participant;
}
}
std::cout << "Could not find participant " << ipAddress << ":" << (int)port
<< std::endl;
#endif
return nullptr;
}
Participant* ParticipantRegistry::Get(unsigned char participantId) {
#if !defined(NO_STD)
for (Participant* participant : ParticipantRegistry::participants) {
if (participant == nullptr)
continue;
if (participant->networkId == participantId)
return participant;
}
std::cout << "Could not find participant " << (int)participantId << std::endl;
#endif
return nullptr;
}
Participant* ParticipantRegistry::Add(const char* ipAddress,
unsigned int port) {
Participant* participant = new Participant(ipAddress, port);
Add(participant);
return participant;
}
void ParticipantRegistry::Add(Participant* participant) {
Participant* foundParticipant =
Get(participant->ipAddress, participant->port);
if (foundParticipant == nullptr) {
#if defined(NO_STD)
// this->things[this->thingCount++] = thing;
#else
ParticipantRegistry::participants.push_back(participant);
#endif
// std::cout << "Add participant " << participant->ipAddress << ":"
// << participant->port << "[" << (int)participant->networkId
// << "]\n";
// std::cout << "participants " <<
// ParticipantRegistry::participants.size()
// << "\n";
// } else {
// std::cout << "Did not add, existing participant " <<
// participant->ipAddress
// << ":" << participant->port << "[" <<
// (int)participant->networkId
// << "]\n";
}
}
void ParticipantRegistry::Remove(Participant* participant) {
// participants.remove(participant);
}
#if defined(NO_STD)
Participant** ParticipantRegistry::GetAll() const {
return ParticipantRegistry::participants;
}
#else
const std::list<Participant*>& ParticipantRegistry::GetAll() const {
return ParticipantRegistry::participants;
}
#endif
#pragma endregion ParticipantRegistry
// for (Thing* thing : this->things) {
// if (thing != nullptr && thing->GetParent() == nullptr) { // update all
// root things
// // std::cout << " update " << (int)ix << " thingid " << (int)thing->id
// // << "\n";
// thing->Update(currentTimeMs);
// }
// }
// }
} // namespace RoboidControl

View File

@ -1,57 +1,10 @@
#pragma once
#include "Thing.h"
namespace RoboidControl {
constexpr int MAX_THING_COUNT = 256;
/// @brief class which manages all known participants
class ParticipantRegistry {
public:
/// @brief Retrieve a participant by its address
/// @param ipAddress The IP address of the participant
/// @param port The port number of the participant
/// @return The participant or a nullptr when it could not be found
Participant* Get(const char* ipAddress, unsigned int port);
/// @brief Retrieve a participant by its network ID
/// @param networkID The network ID of the participant
/// @return The participant or a nullptr when it could not be found
Participant* Get(unsigned char networkID);
/// @brief Add a participant with the given details
/// @param ipAddress The IP address of the participant
/// @param port The port number of the participant
/// @return The added participant
Participant* Add(const char* ipAddress, unsigned int port);
/// @brief Add a participant
/// @param participant The participant to add
void Add(Participant* participant);
/// @brief Remove a participant
/// @param participant The participant to remove
void Remove(Participant* participant);
private:
#if defined(NO_STD)
public:
Participant** GetAll() const;
int count = 0;
private:
Participant** participants;
#else
public:
/// @brief Get all participants
/// @return All participants
const std::list<Participant*>& GetAll() const;
private:
/// @brief The list of known participants
std::list<Participant*> participants;
#endif
};
/// @brief A participant is a device which manages things.
/// It can communicate with other participant to synchronise the state of
/// things. This class is used to register the things the participant is
@ -60,56 +13,52 @@ class ParticipantRegistry {
/// reference to remote participants.
class Participant {
public:
/// @brief The name of the participant
const char* name = "Participant";
/// @brief The Ip Address of a participant.
/// @brief The Ip Address of a participant. When the participant is local,
/// this contains 0.0.0.0
const char* ipAddress = "0.0.0.0";
/// @brief The port number for UDP communication with the participant.
unsigned int port = 0;
/// @brief The port number for UDP communication with the participant. This is
/// 0 for isolated participants.
int port = 0;
/// @brief The network Id to identify the participant
/// @brief The network Id to identify the participant.
/// @note This field is likely to disappear in future versions
unsigned char networkId = 0;
/// @brief Default constructor
Participant();
/// @brief Create a new participant with the given communcation info
/// @param ipAddress The IP address of the participant
/// @param port The UDP port of the participant
/// @param port The port of the participant
Participant(const char* ipAddress, int port);
/// @brief Destructor for the participant
~Participant();
static Participant* LocalParticipant;
static void ReplaceLocalParticipant(Participant& newParticipant);
virtual void Update(unsigned long currentTimeMs = 0);
Thing* root = new Thing(this);
public:
protected:
#if defined(NO_STD)
unsigned char thingCount = 0;
Thing* things[MAX_THING_COUNT];
#else
/// @brief The things managed by this participant
/// @brief The list of things managed by this participant
std::list<Thing*> things;
#endif
public:
/// @brief Find a thing managed by this participant
/// @param networkId The network ID for the thing
/// @param thingId The ID of the thing
/// @return The thing if found, nullptr when no thing has been found
/// @return The thing if found or nullptr when no thing has been found
/// @note The use of the network ID is likely to disappear in future versions.
Thing* Get(unsigned char thingId);
/// @brief Add a new thing for this participant.
/// @param thing The thing to add
/// @param checkId If true, the thing.id is regenerated if it is zero
/// @param checkId Checks the thing ID of the thing. If it is 0, a new thing
/// Id will be assigned.
void Add(Thing* thing, bool checkId = true);
/// @brief Remove a thing for this participant
/// @param thing The thing to remove
void Remove(Thing* thing);
/// @brief Update all things for this participant
/// @param currentTimeMs The current time in milliseconds (optional)
virtual void Update();
public:
static ParticipantRegistry registry;
};
} // namespace RoboidControl

View File

@ -1,49 +1,44 @@
#include "ParticipantUDP.h"
#include "Participant.h"
#include "Thing.h"
#include "Arduino/ArduinoParticipant.h"
#include "EspIdf/EspIdfParticipant.h"
#include "Posix/PosixParticipant.h"
#if defined(_WIN32) || defined(_WIN64)
#include <winsock2.h>
#include <ws2tcpip.h>
#include "Windows/WindowsParticipant.h"
#pragma comment(lib, "ws2_32.lib")
#elif defined(__unix__) || defined(__APPLE__)
#include <arpa/inet.h>
#include <fcntl.h> // For fcntl
#include <netinet/in.h>
#include <sys/socket.h>
#include <unistd.h>
#include <chrono>
#include "Posix/PosixParticipant.h"
#endif
#include <string.h>
namespace RoboidControl {
#pragma region Init
ParticipantUDP::ParticipantUDP(int port) : Participant("127.0.0.1", port) {
this->name = "ParticipantUDP";
ParticipantUDP::ParticipantUDP(int port) {
this->ipAddress = "0.0.0.0";
this->port = port;
this->remoteSite = nullptr;
if (this->port == 0)
this->isIsolated = true;
Participant::registry.Add(this);
this->root = Thing::LocalRoot(); //::LocalParticipant->root;
this->root->owner = this;
this->root->name = "UDP Root";
this->Add(this->root);
Participant::ReplaceLocalParticipant(*this);
}
ParticipantUDP::ParticipantUDP(const char* ipAddress, int port, int localPort)
: Participant("127.0.0.1", localPort) {
this->name = "ParticipantUDP";
if (this->port == 0)
this->isIsolated = true;
else
this->remoteSite = new Participant(ipAddress, port);
Participant::registry.Add(this);
this->root = Thing::LocalRoot(); // Participant::LocalParticipant->root;
this->root->owner = this;
this->root->name = "UDP Root";
this->Add(this->root);
Participant::ReplaceLocalParticipant(*this);
}
static ParticipantUDP* isolatedParticipant = nullptr;
@ -55,7 +50,7 @@ ParticipantUDP* ParticipantUDP::Isolated() {
}
void ParticipantUDP::begin() {
if (this->isIsolated || this->remoteSite == nullptr)
if (this->isIsolated)
return;
SetupUDP(this->port, this->remoteSite->ipAddress, this->remoteSite->port);
@ -74,27 +69,18 @@ void ParticipantUDP::SetupUDP(int localPort,
#elif defined(ARDUINO)
Arduino::ParticipantUDP* thisArduino =
static_cast<Arduino::ParticipantUDP*>(this);
thisArduino->Setup();
thisArduino->Setup(); // localPort, remoteIpAddress, remotePort);
#elif defined(IDF_VER)
EspIdf::ParticipantUDP* thisEspIdf =
static_cast<EspIdf::ParticipantUDP*>(this);
thisEspIdf->Setup(localPort, remoteIpAddress, remotePort);
thisEspIdf->Setup(); // localPort, remoteIpAddress, remotePort);
#endif
this->connected = true;
}
#pragma endregion Init
#pragma region Update
// The update order
// 1. receive external messages
// 2. update the state
// 3. send out the updated messages
void ParticipantUDP::Update() {
unsigned long currentTimeMs = Thing::GetTimeMs();
PrepMyThings();
void ParticipantUDP::Update(unsigned long currentTimeMs) {
if (currentTimeMs == 0)
currentTimeMs = Thing::GetTimeMs();
if (this->isIsolated == false) {
if (this->connected == false)
@ -114,111 +100,66 @@ void ParticipantUDP::Update() {
this->ReceiveUDP();
}
UpdateMyThings();
UpdateOtherThings();
}
void ParticipantUDP::PrepMyThings() {
for (Thing* thing : this->things) {
if (thing == nullptr)
continue;
thing->PrepareForUpdate();
}
}
void ParticipantUDP::UpdateMyThings() {
// std::cout << this->things.size() << std::endl;
for (Thing* thing : this->things) {
if (thing == nullptr) // || thing->GetParent() != nullptr)
continue;
// std::cout << thing->name << "\n";
if (thing->hierarchyChanged) {
if (!(this->isIsolated || this->networkId == 0)) {
ThingMsg* thingMsg = new ThingMsg(this->networkId, thing);
this->Send(this->remoteSite, thingMsg);
delete thingMsg;
if (thing->nameChanged) {
NameMsg* nameMsg = new NameMsg(this->networkId, thing);
this->Send(this->remoteSite, nameMsg);
delete nameMsg;
}
}
}
// std::cout << "B\n";
// Why don't we do recursive?
// Because when a thing creates a thing in the update,
// that new thing is not sent out (because of hierarchyChanged)
// before it is updated itself: it is immediatedly updated!
thing->Update(false);
// std::cout << "C\n";
if (!(this->isIsolated || this->networkId == 0)) {
if (thing->terminate) {
DestroyMsg* destroyMsg = new DestroyMsg(this->networkId, thing);
this->Send(this->remoteSite, destroyMsg);
delete destroyMsg;
} else {
// Send to remote site
if (thing->nameChanged) {
NameMsg* nameMsg = new NameMsg(this->networkId, thing);
this->Send(this->remoteSite, nameMsg);
delete nameMsg;
}
PoseMsg* poseMsg = new PoseMsg(this->networkId, thing);
this->Send(this->remoteSite, poseMsg);
delete poseMsg;
BinaryMsg* binaryMsg = new BinaryMsg(this->networkId, thing);
this->Send(this->remoteSite, binaryMsg);
delete binaryMsg;
}
}
// std::cout << "D\n";
if (thing->terminate)
this->Remove(thing);
// std::cout << "E\n";
}
}
void ParticipantUDP::UpdateOtherThings() {
#if defined(NO_STD)
Participant** participants = Participant::registry.GetAll();
for (int ix = 0; ix < Participant::registry.count; ix++) {
Participant* participant = participants[ix];
#else
for (Participant* participant : Participant::registry.GetAll()) {
#endif
if (participant == nullptr || participant == this)
continue;
// Call only the Participant version of the Update.
// This is to deal with the function where one of the (remote)
// participants is actually a local participant
participant->Participant::Update();
if (this->isIsolated)
continue;
for (Thing* thing : participant->things) {
PoseMsg* poseMsg = new PoseMsg(participant->networkId, thing);
this->Send(participant, poseMsg);
if (this->isIsolated == false) {
//std::cout << "thingg " << thing->name << " pos upd. " << thing->positionUpdated << std::endl;
PoseMsg* poseMsg = new PoseMsg(this->networkId, thing);
this->Send(thing->owner, poseMsg);
BinaryMsg* binaryMsg = new BinaryMsg(this->networkId, thing);
this->Send(thing->owner, binaryMsg);
delete poseMsg;
BinaryMsg* binaryMsg = new BinaryMsg(participant->networkId, thing);
this->Send(participant, binaryMsg);
delete binaryMsg;
}
thing->Update(currentTimeMs, true);
}
}
// Update
#pragma endregion
void ParticipantUDP::ReceiveUDP() {
#if defined(_WIN32) || defined(_WIN64)
Windows::ParticipantUDP* thisWindows =
static_cast<Windows::ParticipantUDP*>(this);
thisWindows->Receive();
#elif defined(__unix__) || defined(__APPLE__)
Posix::ParticipantUDP* thisPosix = static_cast<Posix::ParticipantUDP*>(this);
thisPosix->Receive();
#elif defined(ARDUINO)
Arduino::ParticipantUDP* thisArduino =
static_cast<Arduino::ParticipantUDP*>(this);
thisArduino->Receive();
#elif defined(IDF_VER)
EspIdf::ParticipantUDP* thisEspIdf =
static_cast<EspIdf::ParticipantUDP*>(this);
thisEspIdf->Receive();
#endif
}
Participant* ParticipantUDP::GetParticipant(const char* ipAddress, int port) {
for (Participant* sender : this->senders) {
if (strcmp(sender->ipAddress, ipAddress) == 0 && sender->port == port)
return sender;
}
return nullptr;
}
Participant* ParticipantUDP::AddParticipant(const char* ipAddress, int port) {
// std::cout << "New Participant " << ipAddress << ":" << port << "\n";
Participant* participant = new Participant(ipAddress, port);
#if defined(NO_STD)
participant->networkId = this->senderCount;
this->senders[this->senderCount++] = participant;
#else
participant->networkId = (unsigned char)this->senders.size();
this->senders.push_back(participant);
#endif
return participant;
}
#pragma region Send
void ParticipantUDP::SendThingInfo(Participant* remoteParticipant,
Thing* thing) {
Thing* thing, bool recurse) {
// std::cout << "Send thing info [" << (int)thing->id << "] \n";
ThingMsg* thingMsg = new ThingMsg(this->networkId, thing);
this->Send(remoteParticipant, thingMsg);
@ -235,6 +176,11 @@ void ParticipantUDP::SendThingInfo(Participant* remoteParticipant,
BinaryMsg* customMsg = new BinaryMsg(this->networkId, thing);
this->Send(remoteParticipant, customMsg);
delete customMsg;
if (recurse) {
for (int childIx = 0; childIx < thing->childCount; childIx++)
SendThingInfo(remoteParticipant, thing->GetChildByIndex(childIx));
}
}
bool ParticipantUDP::Send(Participant* remoteParticipant, IMessage* msg) {
@ -242,9 +188,6 @@ bool ParticipantUDP::Send(Participant* remoteParticipant, IMessage* msg) {
if (bufferSize <= 0)
return true;
// std::cout << "send msg " << (static_cast<int>(this->buffer[0]) & 0xff)
// << " to " << remoteParticipant->ipAddress << std::endl;
#if defined(_WIN32) || defined(_WIN64)
Windows::ParticipantUDP* thisWindows =
static_cast<Windows::ParticipantUDP*>(this);
@ -287,7 +230,6 @@ void ParticipantUDP::PublishThingInfo(Thing* thing) {
}
bool ParticipantUDP::Publish(IMessage* msg) {
// std::cout << "publish msg\n";
#if defined(_WIN32) || defined(_WIN64)
Windows::ParticipantUDP* thisWindows =
static_cast<Windows::ParticipantUDP*>(this);
@ -313,37 +255,14 @@ bool ParticipantUDP::Publish(IMessage* msg) {
#pragma region Receive
void ParticipantUDP::ReceiveUDP() {
#if defined(_WIN32) || defined(_WIN64)
Windows::ParticipantUDP* thisWindows =
static_cast<Windows::ParticipantUDP*>(this);
thisWindows->Receive();
#elif defined(__unix__) || defined(__APPLE__)
Posix::ParticipantUDP* thisPosix = static_cast<Posix::ParticipantUDP*>(this);
thisPosix->Receive();
#elif defined(ARDUINO)
Arduino::ParticipantUDP* thisArduino =
static_cast<Arduino::ParticipantUDP*>(this);
thisArduino->Receive();
#elif defined(IDF_VER)
EspIdf::ParticipantUDP* thisEspIdf =
static_cast<EspIdf::ParticipantUDP*>(this);
thisEspIdf->Receive();
#endif
}
void ParticipantUDP::ReceiveData(unsigned char packetSize,
char* senderIpAddress,
unsigned int senderPort) {
// std::cout << "Receive data from " << senderIpAddress << ":" << senderPort
// << std::endl;
Participant* sender = this->registry.Get(senderIpAddress, senderPort);
Participant* sender = this->GetParticipant(senderIpAddress, senderPort);
if (sender == nullptr) {
sender = this->registry.Add(senderIpAddress, senderPort);
#if !defined(NO_STD)
sender = this->AddParticipant(senderIpAddress, senderPort);
std::cout << "New remote participant " << sender->ipAddress << ":"
<< sender->port << std::endl;
#endif
}
ReceiveData(packetSize, sender);
@ -361,8 +280,8 @@ void ParticipantUDP::ReceiveData(unsigned char bufferSize,
Process(sender, msg);
delete msg;
} break;
case NetworkIdMsg::id: {
NetworkIdMsg* msg = new NetworkIdMsg(this->buffer);
case SiteMsg::id: {
SiteMsg* msg = new SiteMsg(this->buffer);
bufferSize -= msg->length;
Process(sender, msg);
delete msg;
@ -404,11 +323,9 @@ void ParticipantUDP::ReceiveData(unsigned char bufferSize,
} break;
};
// Check if the buffer has been read completely
#if !defined(NO_STD)
// Check if the buffer has been read completely
if (bufferSize > 0)
std::cout << "Buffer not fully read, remaining " << (int)bufferSize << "\n";
#endif
}
void ParticipantUDP::Process(Participant* sender, ParticipantMsg* msg) {
@ -418,18 +335,17 @@ void ParticipantUDP::Process(Participant* sender, ParticipantMsg* msg) {
#endif
}
void ParticipantUDP::Process(Participant* sender, NetworkIdMsg* msg) {
void ParticipantUDP::Process(Participant* sender, SiteMsg* msg) {
#if defined(DEBUG)
std::cout << this->name << ": process NetworkIdMsg " << (int)this->networkId
std::cout << this->name << ": process SiteMsg " << (int)this->networkId
<< " -> " << (int)msg->networkId << "\n";
#endif
if (this->networkId != msg->networkId) {
this->networkId = msg->networkId;
std::cout << this->things.size() << " things\n";
for (Thing* thing : this->things)
this->SendThingInfo(sender, thing);
this->SendThingInfo(sender, thing, false);
}
}
@ -469,15 +385,11 @@ void ParticipantUDP::Process(Participant* sender, NameMsg* msg) {
nameLength); // Leave space for null terminator
#endif
thingName[nameLength] = '\0';
thing->SetName(thingName);
thing->name = thingName;
#if !defined(NO_STD)
std::cout << thing->GetName();
#endif
std::cout << thing->name;
}
#if !defined(NO_STD)
std::cout << std::endl;
#endif
}
void ParticipantUDP::Process(Participant* sender, ModelUrlMsg* msg) {
@ -488,48 +400,26 @@ void ParticipantUDP::Process(Participant* sender, ModelUrlMsg* msg) {
}
void ParticipantUDP::Process(Participant* sender, PoseMsg* msg) {
#if !defined(DEBUG) && !defined(NO_STD)
std::cout << this->name << ": process PoseMsg [" << (int)this->networkId
<< "/" << (int)msg->networkId << "] " << (int)msg->poseType << "\n";
#if defined(DEBUG)
std::cout << this->name << ": process PoseMsg [" << (int)msg->networkId
<< "/" << (int)msg->thingId << "]\n";
#endif
Participant* owner = Participant::registry.Get(msg->networkId);
if (owner == nullptr)
return;
Thing* thing = owner->Get(msg->thingId);
if (thing == nullptr)
return;
if ((msg->poseType & PoseMsg::Pose_Position) != 0)
thing->SetPosition(msg->position);
if ((msg->poseType & PoseMsg::Pose_Orientation) != 0)
thing->SetOrientation(msg->orientation);
if ((msg->poseType & PoseMsg::Pose_LinearVelocity) != 0)
thing->SetLinearVelocity(msg->linearVelocity);
if ((msg->poseType & PoseMsg::Pose_AngularVelocity) != 0)
thing->SetAngularVelocity(msg->angularVelocity);
}
void ParticipantUDP::Process(Participant* sender, BinaryMsg* msg) {
#if defined(DEBUG)
std::cout << this->name << ": process BinaryMsg [" << (int)msg->networkId
<< "/" << (int)msg->thingId << "]\n";
<< "/" << (int)msg->thingId << "] ";
#endif
Participant* owner = Participant::registry.Get(msg->networkId);
if (owner != nullptr) {
Thing* thing = owner->Get(msg->thingId);
if (thing != nullptr)
thing->ProcessBinary(msg->data);
#if !defined(NO_STD)
else {
#if defined(DEBUG)
std::cout << " unknown thing [" << (int)msg->networkId << "/"
<< (int)msg->thingId << "]";
#endif
}
#endif
Thing* thing = sender->Get(msg->thingId);
if (thing != nullptr)
thing->ProcessBinary(msg->data);
else {
std::cout << " unknown thing [" << (int)msg->networkId << "/"
<< (int)msg->thingId << "]";
}
std::cout << std::endl;
}
// Receive

View File

@ -1,13 +1,12 @@
#pragma once
#include "Messages/BinaryMsg.h"
#include "Messages/DestroyMsg.h"
#include "Messages/InvestigateMsg.h"
#include "Messages/ModelUrlMsg.h"
#include "Messages/NameMsg.h"
#include "Messages/ParticipantMsg.h"
#include "Messages/PoseMsg.h"
#include "Messages/NetworkIdMsg.h"
#include "Messages/SiteMsg.h"
#include "Messages/ThingMsg.h"
#include "Participant.h"
@ -30,8 +29,7 @@ namespace RoboidControl {
constexpr int MAX_SENDER_COUNT = 256;
/// @brief A participant using UDP communication
/// A local participant is the local device which can communicate with
/// @brief A local participant is the local device which can communicate with
/// other participants It manages all local things and communcation with other
/// participants. Each application has a local participant which is usually
/// explicit in the code. An participant can be isolated. In that case it is
@ -43,8 +41,6 @@ constexpr int MAX_SENDER_COUNT = 256;
/// RoboidControl::IsolatedParticipant::Isolated().
/// @sa RoboidControl::Thing::Thing()
class ParticipantUDP : public Participant {
#pragma region Init
public:
/// @brief Create a participant without connecting to a site
/// @param port The port on which the participant communicates
@ -55,8 +51,11 @@ class ParticipantUDP : public Participant {
/// @brief Create a participant which will try to connect to a site.
/// @param ipAddress The IP address of the site
/// @param port The port used by the site
/// @param localPort The port used by the local participant
ParticipantUDP(const char* ipAddress, int port = 7681, int localPort = 7681);
ParticipantUDP(const char* ipAddress,
int port = 7681,
int localPort = 7681);
// Note to self: one cannot specify the port used by the local participant
// now!!
/// @brief Isolated participant is used when the application is run without
/// networking
@ -65,23 +64,28 @@ class ParticipantUDP : public Participant {
/// @brief True if the participant is running isolated.
/// Isolated participants do not communicate with other participants
#pragma endregion Init
/// @brief True if the participant is running isolated.
/// Isolated participants do not communicate with other participants
bool isIsolated = false;
/// @brief The remote site when this participant is connected to a site
Participant* remoteSite = nullptr;
/// The interval in milliseconds for publishing (broadcasting) data on the
/// local network
long publishInterval = 3000; // 3 seconds
protected:
char buffer[1024];
/// @brief The name of the participant
const char* name = "ParticipantUDP";
// int localPort = 0;
/// @brief The remote site when this participant is connected to a site
Participant* remoteSite = nullptr;
#if defined(ARDUINO)
// const char* remoteIpAddress = nullptr;
// unsigned short remotePort = 0;
// char* broadcastIpAddress = nullptr;
// WiFiUDP udp;
#else
#if !defined(ARDUINO)
#if defined(__unix__) || defined(__APPLE__)
int sock;
#elif defined(_WIN32) || defined(_WIN64)
@ -89,50 +93,46 @@ class ParticipantUDP : public Participant {
sockaddr_in server_addr;
sockaddr_in broadcast_addr;
#endif
#endif
public:
void begin();
bool connected = false;
#pragma region Update
virtual void Update(unsigned long currentTimeMs = 0) override;
public:
virtual void Update() override;
protected:
unsigned long nextPublishMe = 0;
/// @brief Prepare the local things for the next update
virtual void PrepMyThings();
virtual void UpdateMyThings();
virtual void UpdateOtherThings();
#pragma endregion Update
#pragma region Send
void SendThingInfo(Participant* remoteParticipant, Thing* thing);
void SendThingInfo(Participant* remoteParticipant, Thing* thing, bool recurse = false);
void PublishThingInfo(Thing* thing);
bool Send(Participant* remoteParticipant, IMessage* msg);
bool Publish(IMessage* msg);
#pragma endregion Send
#pragma region Receive
protected:
void ReceiveData(unsigned char bufferSize,
char* senderIpAddress,
unsigned int senderPort);
void ReceiveData(unsigned char bufferSize, Participant* remoteParticipant);
#if defined(NO_STD)
unsigned char senderCount = 0;
Participant* senders[MAX_SENDER_COUNT];
#else
std::list<Participant*> senders;
#endif
protected:
unsigned long nextPublishMe = 0;
char buffer[1024];
void SetupUDP(int localPort, const char* remoteIpAddress, int remotePort);
Participant* GetParticipant(const char* ipAddress, int port);
Participant* AddParticipant(const char* ipAddress, int port);
void ReceiveUDP();
virtual void Process(Participant* sender, ParticipantMsg* msg);
virtual void Process(Participant* sender, NetworkIdMsg* msg);
virtual void Process(Participant* sender, SiteMsg* msg);
virtual void Process(Participant* sender, InvestigateMsg* msg);
virtual void Process(Participant* sender, ThingMsg* msg);
virtual void Process(Participant* sender, NameMsg* msg);
@ -140,8 +140,34 @@ protected:
virtual void Process(Participant* sender, PoseMsg* msg);
virtual void Process(Participant* sender, BinaryMsg* msg);
#pragma endregion Receive
#if !defined(NO_STD)
// public:
// using ThingConstructor = std::function<Thing*(Participant* participant,
// unsigned char networkId,
// unsigned char thingId)>;
// template <typename ThingClass>
// void Register(unsigned char thingType) {
// thingMsgProcessors[thingType] = [](Participant* participant,
// unsigned char networkId,
// unsigned char thingId) {
// return new ThingClass(participant, networkId, thingId);
// };
// };
// template <typename ThingClass>
// void Register2(unsigned char thingType, ThingConstructor f) {
// thingMsgProcessors[thingType] = [f](Participant* participant,
// unsigned char networkId,
// unsigned char thingId) {
// return f(participant, networkId, thingId);
// };
// };
// protected:
// std::unordered_map<unsigned char, ThingConstructor> thingMsgProcessors;
#endif
};
} // namespace RoboidControl

View File

@ -9,89 +9,58 @@
namespace RoboidControl {
#pragma region Init
SiteServer::SiteServer(int port) : ParticipantUDP(port) {
SiteServer::SiteServer(int port) {
this->name = "Site Server";
this->publishInterval = 0;
SetupUDP(port, ipAddress, 0);
}
this->ipAddress = "0.0.0.0";
this->port = port;
#pragma endregion Init
#pragma region Update
void SiteServer::UpdateMyThings() {
for (Thing* thing : this->things) {
if (thing == nullptr)
continue;
thing->Update(true);
if (this->isIsolated == false) {
// Send to all other participants
#if defined(NO_STD)
Participant** participants = Participant::registry.GetAll();
for (int ix = 0; ix < Participant::registry.count; ix++) {
Participant* participant = participants[ix];
this->senders[this->senderCount++] = this;
#else
for (Participant* participant : Participant::registry.GetAll()) {
this->senders.push_back(this);
#endif
if (participant == nullptr || participant == this)
continue;
PoseMsg* poseMsg = new PoseMsg(this->networkId, thing);
this->Send(participant, poseMsg);
delete poseMsg;
BinaryMsg* binaryMsg = new BinaryMsg(this->networkId, thing);
this->Send(participant, binaryMsg);
delete binaryMsg;
}
}
}
SetupUDP(port, ipAddress, 0);
#if !defined(NO_STD)
// Register<TemperatureSensor>((unsigned char)Thing::Type::TemperatureSensor);
#endif
}
#pragma endregion Update
#pragma region Receive
void SiteServer::Process(Participant* sender, ParticipantMsg* msg) {
if (msg->networkId != sender->networkId) {
if (msg->networkId == 0) {
// std::cout << this->name << " received New Client -> " <<
// sender->ipAddress
// << ":" << (int)sender->port << "\n";
NetworkIdMsg* msg = new NetworkIdMsg(sender->networkId);
SiteMsg* msg = new SiteMsg(sender->networkId);
this->Send(sender, msg);
delete msg;
}
}
void SiteServer::Process(Participant* sender, NetworkIdMsg* msg) {}
void SiteServer::Process(Participant* sender, SiteMsg* msg) {}
void SiteServer::Process(Participant* sender, ThingMsg* msg) {
Thing* thing = sender->Get(msg->thingId);
if (thing == nullptr)
// new Thing(sender, (Thing::Type)msg->thingType, msg->thingId);
// Thing::Reconstruct(sender, msg->thingType, msg->thingId);
//thing = new Thing(msg->thingType, sender->root);
;
thing->id = msg->thingId;
if (msg->parentId != 0) {
thing->SetParent(Get(msg->parentId));
if (thing->IsRoot())
// if (thing->GetParent() != nullptr)
#if defined(NO_STD)
;
#else
std::cout << "Could not find parent [" << (int)msg->networkId << "/"
<< (int)msg->parentId << "]\n";
#endif
} else
thing->SetParent(Thing::LocalRoot());
if (thing == nullptr) {
// #if defined(NO_STD)
new Thing(sender, (Thing::Type)msg->thingType,
msg->thingId);
// #else
// auto thingMsgProcessor = thingMsgProcessors.find(msg->thingType);
// //Thing* newThing;
// if (thingMsgProcessor != thingMsgProcessors.end()) // found item
// //newThing =
// thingMsgProcessor->second(sender, msg->networkId,
// msg->thingId);
// else
// //newThing =
// new Thing(sender, msg->networkId, msg->thingId,
// (Thing::Type)msg->thingType);
// #endif
}
}
#pragma endregion Receive
} // namespace RoboidControl

View File

@ -12,33 +12,35 @@ namespace RoboidControl {
/// @brief A participant is device which can communicate with other participants
class SiteServer : public ParticipantUDP {
#pragma region Init
public:
/// @brief Create a new site server
/// @param port The port of which to receive the messages
SiteServer(int port = 7681);
#pragma endregion Init
// virtual void Update(unsigned long currentTimeMs = 0) override;
#pragma region Update
virtual void UpdateMyThings() override;
#pragma endregion Update
#pragma region Receive
// #if !defined(NO_STD)
// template <typename ThingClass>
// void Register(unsigned char thingType) {
// thingMsgProcessors[thingType] = [](Participant* participant,
// unsigned char networkId,
// unsigned char thingId) {
// return new ThingClass(participant, networkId, thingId);
// };
// };
// #endif
protected:
unsigned long nextPublishMe = 0;
virtual void Process(Participant* sender, ParticipantMsg* msg) override;
virtual void Process(Participant* sender, NetworkIdMsg* msg) override;
virtual void Process(Participant* sender, SiteMsg* msg) override;
virtual void Process(Participant* sender, ThingMsg* msg) override;
#pragma endregion Receive
// #if !defined(NO_STD)
// using ThingConstructor = std::function<Thing*(Participant* participant,
// unsigned char networkId,
// unsigned char thingId)>;
// std::unordered_map<unsigned char, ThingConstructor> thingMsgProcessors;
// #endif
};
} // namespace RoboidControl

View File

@ -11,7 +11,7 @@
namespace RoboidControl {
namespace Posix {
void ParticipantUDP::Setup(int localPort, const char* remoteIpAddress, int remotePort) {
void Setup(int localPort, const char* remoteIpAddress, int remotePort) {
#if defined(__unix__) || defined(__APPLE__)
// Create a UDP socket
@ -63,7 +63,7 @@ void ParticipantUDP::Setup(int localPort, const char* remoteIpAddress, int remot
#endif
}
void ParticipantUDP::Receive() {
void Receive() {
#if defined(__unix__) || defined(__APPLE__)
sockaddr_in client_addr;
socklen_t len = sizeof(client_addr);
@ -74,9 +74,9 @@ void ParticipantUDP::Receive() {
unsigned int sender_port = ntohs(client_addr.sin_port);
ReceiveData(packetSize, sender_ipAddress, sender_port);
// RoboidControl::Participant* remoteParticipant = this->Get(sender_ipAddress, sender_port);
// RoboidControl::Participant* remoteParticipant = this->GetParticipant(sender_ipAddress, sender_port);
// if (remoteParticipant == nullptr) {
// remoteParticipant = this->Add(sender_ipAddress, sender_port);
// remoteParticipant = this->AddParticipant(sender_ipAddress, sender_port);
// // std::cout << "New sender " << sender_ipAddress << ":" << sender_port
// // << "\n";
// // std::cout << "New remote participant " << remoteParticipant->ipAddress
@ -90,7 +90,7 @@ void ParticipantUDP::Receive() {
#endif
}
bool ParticipantUDP::Send(Participant* remoteParticipant, int bufferSize) {
bool 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 ParticipantUDP::Send(Participant* remoteParticipant, int bufferSize) {
return true;
}
bool ParticipantUDP::Publish(IMessage* msg) {
bool Publish(IMessage* msg) {
#if defined(__unix__) || defined(__APPLE__)
int bufferSize = msg->Serialize(this->buffer);
if (bufferSize <= 0)

View File

@ -11,13 +11,6 @@ class ParticipantUDP : public RoboidControl::ParticipantUDP {
void Receive();
bool Send(Participant* remoteParticipant, int bufferSize);
bool Publish(IMessage* msg);
protected:
#if defined(__unix__) || defined(__APPLE__)
sockaddr_in remote_addr;
sockaddr_in server_addr;
sockaddr_in broadcast_addr;
#endif
};
} // namespace Posix

View File

@ -14,4 +14,5 @@ Supporting:
# Basic components
- RoboidControl::Thing
- RoboidControl::Participant
- RoboidControl::LocalParticipant
- RoboidControl::SiteServer

250
Thing.cpp
View File

@ -5,7 +5,6 @@
#include "Participants/IsolatedParticipant.h"
#include <string.h>
// #include <iostream>
#if defined(ARDUINO)
#include "Arduino.h"
@ -18,79 +17,54 @@
namespace RoboidControl {
#pragma region Init
Thing::Thing(int thingType)
: Thing(IsolatedParticipant::Isolated(), thingType) {}
Thing* Thing::LocalRoot() {
Participant* p = Participant::LocalParticipant;
Thing* localRoot = p->root;
return localRoot;
}
// Only use this for root things
Thing::Thing(Participant* owner) {
this->type = Type::Roboid; // should become root
this->position = Spherical::zero;
this->positionUpdated = true;
this->orientation = SwingTwist::identity;
this->orientationUpdated = true;
this->hierarchyChanged = true;
this->linearVelocity = Spherical::zero;
this->angularVelocity = Spherical::zero;
Thing::Thing(Participant* owner, Type thingType, unsigned char thingId)
: Thing(owner, (unsigned char)thingType, thingId) {}
Thing::Thing(Participant* owner, int thingType, unsigned char thingId) {
this->owner = owner;
//this->owner->Add(this, true);
std::cout << this->owner->name << ": New root thing " << std::endl;
}
Thing::Thing(unsigned char thingType, Thing* parent) {
this->id = thingId;
this->type = thingType;
this->networkId = 0;
this->position = Spherical::zero;
this->positionUpdated = true;
this->orientation = SwingTwist::identity;
this->orientationUpdated = true;
this->hierarchyChanged = true;
this->linearVelocity = Spherical::zero;
this->angularVelocity = Spherical::zero;
this->owner = parent->owner;
this->owner->Add(this, true);
this->SetParent(parent);
std::cout << this->owner->name << ": New thing for " << parent->name
<< std::endl;
std::cout << "add thing [" << (int)this->id << "] to owner "
<< this->owner->ipAddress << ":" << this->owner->port <<
std::endl;
}
Thing::~Thing() {
std::cout << "Destroy thing " << this->name << std::endl;
Thing::Thing(Thing* parent, int thingType, unsigned char thingId)
: Thing(parent->owner, thingType, thingId) {
this->parent = parent;
}
// Thing Thing::Reconstruct(Participant* owner, unsigned char thingType,
// unsigned char thingId) {
// Thing thing = Thing(owner, thingType);
// thing.id = thingId;
// return thing;
// }
#pragma endregion Init
void Thing::SetName(const char* name) {
this->name = name;
this->nameChanged = true;
void Thing::Terminate() {
// Thing::Remove(this);
}
const char* Thing::GetName() const {
return this->name;
}
Thing* Thing::FindThing(const char* name) {
for (unsigned char childIx = 0; childIx < this->childCount; childIx++) {
Thing* child = this->children[childIx];
if (child == nullptr || child->name == nullptr)
continue;
void Thing::SetModel(const char* url) {
this->modelUrl = url;
}
if (strcmp(child->name, name) == 0)
return child;
#pragma region Hierarchy
Thing* foundChild = child->FindThing(name);
if (foundChild != nullptr)
return foundChild;
}
return nullptr;
}
void Thing::SetParent(Thing* parent) {
if (parent == nullptr) {
@ -100,36 +74,18 @@ void Thing::SetParent(Thing* parent) {
this->parent = nullptr;
} else
parent->AddChild(this);
this->hierarchyChanged = true;
}
// void Thing::SetParent(Thing* parent) {
// parent->AddChild(this);
// this->hierarchyChanged = true;
// }
// const Thing& Thing::GetParent() {
// return *this->parent;
// }
bool Thing::IsRoot() const {
return this == LocalRoot() || this->parent == nullptr; //&Thing::Root;
void Thing::SetParent(Thing* root, const char* name) {
Thing* thing = root->FindThing(name);
if (thing != nullptr)
this->SetParent(thing);
}
// void Thing::SetParent(Thing* root, const char* name) {
// Thing* thing = root->FindChild(name);
// if (thing != nullptr)
// this->SetParent(thing);
// }
Thing* Thing::GetParent() {
return this->parent;
}
Thing* Thing::GetChildByIndex(unsigned char ix) {
return this->children[ix];
}
void Thing::AddChild(Thing* child) {
unsigned char newChildCount = this->childCount + 1;
Thing** newChildren = new Thing*[newChildCount];
@ -169,7 +125,7 @@ Thing* Thing::RemoveChild(Thing* child) {
}
}
child->parent = Thing::LocalRoot();
child->parent = nullptr;
delete[] this->children;
this->children = newChildren;
@ -178,7 +134,7 @@ Thing* Thing::RemoveChild(Thing* child) {
return child;
}
Thing* Thing::GetChild(unsigned char id, bool recurse) {
Thing* Thing::GetChild(unsigned char id, bool recursive) {
for (unsigned char childIx = 0; childIx < this->childCount; childIx++) {
Thing* child = this->children[childIx];
if (child == nullptr)
@ -186,8 +142,8 @@ Thing* Thing::GetChild(unsigned char id, bool recurse) {
if (child->id == id)
return child;
if (recurse) {
Thing* foundChild = child->GetChild(id, recurse);
if (recursive) {
Thing* foundChild = child->GetChild(id, recursive);
if (foundChild != nullptr)
return foundChild;
}
@ -195,25 +151,57 @@ Thing* Thing::GetChild(unsigned char id, bool recurse) {
return nullptr;
}
Thing* Thing::FindChild(const char* name, bool recurse) {
for (unsigned char childIx = 0; childIx < this->childCount; childIx++) {
Thing* child = this->children[childIx];
if (child == nullptr || child->name == nullptr)
continue;
if (strcmp(child->name, name) == 0)
return child;
Thing* foundChild = child->FindChild(name);
if (foundChild != nullptr)
return foundChild;
}
return nullptr;
Thing* Thing::GetChildByIndex(unsigned char ix) {
return this->children[ix];
}
#pragma endregion Hierarchy
void Thing::SetModel(const char* url) {
this->modelUrl = url;
}
#pragma region Pose
unsigned long Thing::GetTimeMs() {
#if defined(ARDUINO)
return millis();
#else
auto now = std::chrono::steady_clock::now();
auto ms = std::chrono::duration_cast<std::chrono::milliseconds>(
now.time_since_epoch());
return static_cast<unsigned long>(ms.count());
#endif
}
void Thing::Update(bool recursive) {
Update(GetTimeMs(), recursive);
}
void Thing::Update(unsigned long currentTimeMs, bool recursive) {
// if (this->positionUpdated || this->orientationUpdated)
// OnPoseChanged callback
this->positionUpdated = false;
this->orientationUpdated = false;
if (recursive) {
for (unsigned char childIx = 0; childIx < this->childCount; childIx++) {
Thing* child = this->children[childIx];
if (child == nullptr)
continue;
child->Update(currentTimeMs, recursive);
}
}
}
void Thing::UpdateThings(unsigned long currentTimeMs) {
IsolatedParticipant::Isolated()->Update(currentTimeMs);
}
int Thing::GenerateBinary(char* buffer, unsigned char* ix) {
(void)buffer;
(void)ix;
return 0;
}
void Thing::ProcessBinary(char* bytes) {
(void)bytes;
};
void Thing::SetPosition(Spherical position) {
this->position = position;
@ -233,10 +221,8 @@ SwingTwist Thing::GetOrientation() {
}
void Thing::SetLinearVelocity(Spherical linearVelocity) {
if (this->linearVelocity.distance != linearVelocity.distance) {
this->linearVelocity = linearVelocity;
this->linearVelocityUpdated = true;
}
this->linearVelocity = linearVelocity;
this->linearVelocityUpdated = true;
}
Spherical Thing::GetLinearVelocity() {
@ -244,72 +230,12 @@ Spherical Thing::GetLinearVelocity() {
}
void Thing::SetAngularVelocity(Spherical angularVelocity) {
if (this->angularVelocity.distance != angularVelocity.distance) {
this->angularVelocity = angularVelocity;
this->angularVelocityUpdated = true;
}
this->angularVelocity = angularVelocity;
this->angularVelocityUpdated = true;
}
Spherical Thing::GetAngularVelocity() {
return this->angularVelocity;
}
#pragma endregion Pose
#pragma region Update
unsigned long Thing::GetTimeMs() {
#if defined(ARDUINO)
unsigned long ms = millis();
return ms;
#else
auto now = std::chrono::steady_clock::now();
auto ms = std::chrono::duration_cast<std::chrono::milliseconds>(
now.time_since_epoch());
return static_cast<unsigned long>(ms.count());
#endif
}
// void Thing::Update(bool recursive) {
// Update(GetTimeMs(), recursive);
// }
void Thing::PrepareForUpdate() {}
void Thing::Update(bool recursive) {
// if (this->positionUpdated || this->orientationUpdated)
// OnPoseChanged callback
this->positionUpdated = false;
this->orientationUpdated = false;
// this->linearVelocityUpdated = false;
// this->angularVelocityUpdated = false;
this->hierarchyChanged = false;
this->nameChanged = false;
if (recursive) {
// std::cout << "# children: " << (int)this->childCount << std::endl;
for (unsigned char childIx = 0; childIx < this->childCount; childIx++) {
Thing* child = this->children[childIx];
if (child == nullptr)
continue;
child->Update(recursive);
}
}
}
void Thing::UpdateThings() {
IsolatedParticipant::Isolated()->Update();
}
#pragma endregion Update
int Thing::GenerateBinary(char* buffer, unsigned char* ix) {
(void)buffer;
(void)ix;
return 0;
}
void Thing::ProcessBinary(char* bytes) {
(void)bytes;
};
} // namespace RoboidControl

211
Thing.h
View File

@ -20,7 +20,7 @@ class ParticipantUDP;
class Thing {
public:
/// @brief Predefined thing types
enum Type : unsigned char {
enum Type {
Undetermined,
// Sensor,
Switch,
@ -32,107 +32,59 @@ class Thing {
ControlledMotor,
UncontrolledMotor,
Servo,
IncrementalEncoder,
// Other
Roboid,
Humanoid,
ExternalSensor,
DifferentialDrive
};
#pragma region Init
static Thing* LocalRoot();
/// @brief Create a new thing using an implicit local participant
/// @param thingType The type of thing
Thing(int thingType = Type::Undetermined);
/// @brief Create a new thing of the given type
/// @param thingType The predefined type of thing
Thing(Participant* participant,
Type thingType = Type::Undetermined,
unsigned char thingId = 0);
/// @brief Create a new thing of the give type
/// @param thingType The custom type of the thing
Thing(Participant* participant, int thingType, unsigned char thingId = 0);
/// <summary>
/// Create a new thing as a child of another thing
/// </summary>
/// <param name="parent">The parent thing</param>
/// <param name="thingType">The type of thing</param>
/// <param name="thingId">The thing id, level at 0 to automatically generate
/// an id</param>
Thing(Thing* parent, int thingType = 0, unsigned char thingId = 0);
private:
// Special constructor to create a root thing
Thing(Participant* parent);
// Which can only be used by the Participant
friend class Participant;
public:
/// @brief Create a new thing
/// @param thingType The type of thing (can use Thing::Type)
/// @param parent (optional) The parent thing
/// The owner will be the same as the owner of the parent thing, it will
/// be Participant::LocalParticipant if the parent is not specified. A thing
/// without a parent will be a root thing.
Thing(unsigned char thingType = Thing::Type::Undetermined,
Thing* parent = LocalRoot());
/// @brief Create a new child thing
/// @param parent The parent thing
/// @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
/// @note The owner will be the same as the owner of the parent thing
~Thing();
static Thing Reconstruct(Participant* owner,
unsigned char thingType,
unsigned char thingId);
#pragma endregion Init
public:
/// @brief Terminated things are no longer updated
bool terminate = false;
#pragma region Properties
/// @brief The participant managing this thing
Participant* owner = nullptr;
Participant* owner;
/// @brief The network ID of this thing
/// @note This field will likely disappear in future versions
unsigned char networkId = 0;
/// @brief The ID of the thing
unsigned char id = 0;
/// @brief The type of Thing
/// This can be either a Thing::Type of a byte value for custom types
unsigned char type = Type::Undetermined;
unsigned char type = 0;
/// @brief The name of the thing
const char* name = nullptr;
/// @brief Find a thing by name
/// @param name Rhe name of the thing
/// @return The found thing or nullptr when nothing is found
Thing* FindThing(const char* name);
public:
void SetName(const char* name);
const char* GetName() const;
bool nameChanged = false;
/// @brief Sets the location from where the 3D model of this Thing can be
/// loaded from
/// @param url The url of the model
/// @remark Although the roboid implementation is not dependent on the model,
/// the only official supported model format is .obj
void SetModel(const char* url);
/// @brief An URL pointing to the location where a model of the thing can be
/// found
const char* modelUrl = nullptr;
/// @brief The scale of the model (deprecated I think)
float modelScale = 1;
#pragma endregion Properties
#pragma region Hierarchy
/// @brief Sets the parent of this Thing
/// @param parent The Thing which should become the parent
// virtual void SetParent(Thing* parent);
void SetParent(Thing* parent);
/// @brief Gets the parent of this Thing
/// @brief Sets the parent Thing
/// @param parent The Thing which should become the parnet
/// @remark This is equivalent to calling parent->AddChild(this);
virtual void SetParent(Thing* parent);
void SetParent(Thing* root, const char* name);
/// @brief Gets the parent Thing
/// @return The parent Thing
// Thing* GetParent();
Thing* GetParent();
bool IsRoot() const;
/// @brief The number of children
unsigned char childCount = 0;
/// @brief Get a child by index
/// @param ix The child index
/// @return The found thing of nullptr when nothing is found
Thing* GetChildByIndex(unsigned char ix);
/// @brief Add a child Thing to this Thing
/// @param child The Thing which should become a child
/// @remark When the Thing is already a child, it will not be added again
@ -142,46 +94,49 @@ class Thing {
/// @return The removed child or nullptr if the child could not be found
Thing* RemoveChild(Thing* child);
/// @brief The number of children
unsigned char childCount = 0;
/// @brief Get a child by thing Id
/// @param id The thing ID to find
/// @param recurse Look recursively through all descendants
/// @param recursive Look recursively through all descendants
/// @return The found thing of nullptr when nothing is found
Thing* GetChild(unsigned char id, bool recurse = false);
Thing* GetChild(unsigned char id, bool recursive = false);
/// @brief Get a child by index
/// @param ix The child index
/// @return The found thing of nullptr when nothing is found
Thing* GetChildByIndex(unsigned char ix);
/// @brief Find a thing by name
/// @param name The name of the thing
/// @param recurse Look recursively through all descendants
/// @return The found thing or nullptr when nothing is found
Thing* FindChild(const char* name, bool recurse = true);
/// @brief Indicator that the hierarchy of the thing has changed
bool hierarchyChanged = true;
private:
protected:
Thing* parent = nullptr;
Thing** children = nullptr;
#pragma endregion Hierarchy
#pragma region Pose
public:
/// @brief The name of the thing
const char* name = nullptr;
/// @brief An URL pointing to the location where a model of the thing can be
/// found
const char* modelUrl = nullptr;
/// @brief The scale of the model (deprecated I think)
float modelScale = 1;
/// @brief Set the position of the thing
/// @param position The new position in local space, in meters
void SetPosition(Spherical position);
/// @brief Get the position of the thing
/// @return The position in local space, in meters
Spherical GetPosition();
/// @brief Boolean indicating that the thing has an updated position
bool positionUpdated = false;
/// @brief Set the orientation of the thing
/// @param orientation The new orientation in local space
void SetOrientation(SwingTwist orientation);
/// @brief Get the orientation of the thing
/// @return The orienation in local space
SwingTwist GetOrientation();
/// @brief Boolean indicating the thing has an updated orientation
/// @brief The scale of the thing (deprecated I think)
// float scale = 1; // assuming uniform scale
/// @brief boolean indicating if the position was updated
bool positionUpdated = false;
/// @brief boolean indicating if the orientation was updated
bool orientationUpdated = false;
/// @brief Set the linear velocity of the thing
@ -191,63 +146,57 @@ class Thing {
/// @brief Get the linear velocity of the thing
/// @return The linear velocity in local space, in meters per second
virtual Spherical GetLinearVelocity();
/// @brief Boolean indicating the thing has an updated linear velocity
bool linearVelocityUpdated = false;
/// @brief Set the angular velocity of the thing
/// @param angularVelocity the new angular velocity in local space
virtual void SetAngularVelocity(Spherical angularVelocity);
/// @brief Get the angular velocity of the thing
/// @return The angular velocity in local space
virtual Spherical GetAngularVelocity();
/// @brief Boolean indicating the thing has an updated angular velocity
bool linearVelocityUpdated = false;
bool angularVelocityUpdated = false;
private:
/// @brief The position of the thing in local space, in meters
/// @brief The position in local space
/// @remark When this Thing has a parent, the position is relative to the
/// parent's position and orientation
Spherical position;
/// @brief The orientation of the thing in local space
/// @brief The orientation in local space
/// @remark When this Thing has a parent, the orientation is relative to the
/// parent's orientation
SwingTwist orientation;
/// @brief The linear velocity of the thing in local space, in meters per
/// second
/// @brief The linear velocity in local space
Spherical linearVelocity;
/// @brief The angular velocity of the thing in local space, in degrees per
/// second
/// @brief The angular velocity in local spze
Spherical angularVelocity;
#pragma endregion Pose
#pragma region Update
public:
virtual void PrepareForUpdate();
/// @brief Terminated things are no longer updated
void Terminate();
/// @brief Updates the state of the thing
/// @param currentTimeMs The current clock time in milliseconds; if this is
/// zero, the current time is retrieved automatically
/// @param recurse When true, this will Update the descendants recursively
virtual void Update(bool recurse = false);
/// @brief Sets the location from where the 3D model of this Thing can be
/// loaded from
/// @param url The url of the model
/// @remark Although the roboid implementation is not dependent on the model,
/// the only official supported model format is .obj
void SetModel(const char* url);
static void UpdateThings();
/// @brief Get the current time in milliseconds
/// @return The current time in milliseconds
static unsigned long GetTimeMs();
#pragma endregion Update
void Update(bool recursive = false);
/// @brief Updates the state of the thing
/// @param currentTimeMs The current clock time in milliseconds
virtual void Update(unsigned long currentTimeMs, bool recursive = false);
static void UpdateThings(unsigned long currentTimeMs);
public:
/// @brief Function used to generate binary data for this thing
/// @param buffer The byte array for thw binary data
/// @param ix The starting position for writing the binary data
/// @return The size of the binary data
/// @returns The size of the binary data
virtual int GenerateBinary(char* buffer, unsigned char* ix);
/// @brief Function used to process binary data received for this thing
// /// @brief FUnction used to process binary data received for this thing
/// @param bytes The binary data
virtual void ProcessBinary(char* bytes);
};

View File

@ -0,0 +1,2 @@
#include "AbsoluteEncoder.h"

15
Things/AbsoluteEncoder.h Normal file
View File

@ -0,0 +1,15 @@
#pragma once
#include "ServoMotor.h"
namespace RoboidControl {
class AbsoluteEncoder {
public:
AbsoluteEncoder() {}
virtual Angle16 GetActualAngle() = 0;
virtual float GetActualVelocity() = 0;
};
} // namespace RoboidControl

View File

@ -1,68 +1,67 @@
#include "ControlledMotor.h"
#include "LinearAlgebra/FloatSingle.h"
namespace RoboidControl {
ControlledMotor::ControlledMotor(Motor* motor,
RelativeEncoder* encoder,
Thing* parent)
: Motor(parent), motor(motor), encoder(encoder) {
this->type = Type::ControlledMotor;
//encoder->SetParent(null);
// Thing parent = motor.GetParent();
// this->SetParent(parent);
this->integral = 0;
ControlledMotor::ControlledMotor() { this->type = Thing::ControlledMotor; }
ControlledMotor::ControlledMotor(Motor *motor, IncrementalEncoder *encoder)
: ControlledMotor() {
this->motor = motor;
this->encoder = encoder;
// this->rotationDirection = Direction::Forward;
}
void ControlledMotor::SetTargetVelocity(float velocity) {
this->targetVelocity = velocity;
this->rotationDirection =
(targetVelocity < 0) ? Direction::Reverse : Direction::Forward;
//#include <Arduino.h>
void ControlledMotor::SetTargetSpeed(float speed) {
this->currentTargetSpeed = speed;
// this->rotationDirection =
// (targetSpeed < 0) ? Direction::Reverse : Direction::Forward;
// this->direction = (targetSpeed < 0) ? Motor::Direction::CounterClockwise
// : Motor::Direction::Clockwise;
}
void ControlledMotor::Update(bool recurse) {
unsigned long currentTimeMs = GetTimeMs();
float timeStep = (currentTimeMs - this->lastUpdateTime) / 1000.0f;
void ControlledMotor::Update(unsigned long currentTimeMs) {
this->actualSpeed = encoder->GetRevolutionsPerSecond(currentTimeMs);
if (this->currentTargetSpeed < 0)
this->actualSpeed = -this->actualSpeed;
float deltaTime = currentTimeMs - this->lastUpdateTime;
float error = this->currentTargetSpeed - this->actualSpeed;
float errorChange = (error - lastError) * deltaTime;
float delta = error * pidP + errorChange * pidD;
// Serial.print(" actual Speed ");
// Serial.print(actualSpeed);
// Serial.print(" target Speed ");
// Serial.print(this->currentTargetSpeed);
// Serial.print(" motor target speed ");
// Serial.print(motor->currentTargetSpeed);
// Serial.print(" + ");
// Serial.print(error * pidP);
// Serial.print(" + ");
// Serial.print(errorChange * pidD);
// Serial.print(" = ");
// Serial.println(motor->currentTargetSpeed + delta);
motor->SetTargetSpeed(motor->currentTargetSpeed +
delta); // or something like that
this->lastUpdateTime = currentTimeMs;
if (timeStep <= 0)
return;
// encoder->Update(false);
this->actualVelocity = (int)rotationDirection * encoder->rotationSpeed;
float error = this->targetVelocity - this->actualVelocity;
float p_term = error * pidP;
this->integral += error * timeStep;
float i_term = pidI * this->integral;
float d_term = pidD * (error - this->lastError) / timeStep;
this->lastError = error;
float output = p_term + i_term + d_term;
std::cout << "target " << this->targetVelocity << " actual "
<< this->actualVelocity << " output = " << output << std::endl;
// float acceleration =
// error * timeStep * pidP; // Just P is used at this moment
// std::cout << "motor acc. " << acceleration << std::endl;
// float newTargetVelocity = motor->targetVelocity + acceleration;
output = LinearAlgebra::Float::Clamp(output, -1, 1);
motor->SetTargetVelocity(output); // or something like that
//motor->Update(false);
}
// float ControlledMotor::GetActualVelocity() {
// return (int)rotationDirection * encoder->rotationSpeed;
// }
float ControlledMotor::GetActualSpeed() { return actualSpeed; }
// bool ControlledMotor::Drive(float distance) {
// if (!driving) {
// targetDistance = distance;
// startDistance = encoder->GetDistance();
// driving = true;
// }
// float totalDistance = encoder->GetDistance() - startDistance;
// bool completed = totalDistance > targetDistance;
// return completed;
// }
} // namespace RoboidControl
bool ControlledMotor::Drive(float distance) {
if (!driving) {
targetDistance = distance;
startDistance = encoder->GetDistance();
driving = true;
}
float totalDistance = encoder->GetDistance() - startDistance;
bool completed = totalDistance > targetDistance;
return completed;
}
}

View File

@ -1,7 +1,7 @@
#pragma once
#include "IncrementalEncoder.h"
#include "Motor.h"
#include "RelativeEncoder.h"
namespace RoboidControl {
@ -10,31 +10,48 @@ namespace RoboidControl {
/// The speed is measured in revolutions per second.
class ControlledMotor : public Motor {
public:
ControlledMotor(Motor* motor, RelativeEncoder* encoder, Thing* parent = Thing::LocalRoot());
ControlledMotor();
ControlledMotor(Motor* motor, IncrementalEncoder* encoder);
float pidP = 0.5;
float pidD = 0;
float pidI = 0.2;
inline static bool CheckType(Thing* thing) {
return (thing->type & (int)Thing::Type::ControlledMotor) != 0;
}
float velocity;
/// @brief The actual velocity in revolutions per second
float actualVelocity;
float pidP = 0.1F;
float pidD = 0.0F;
float pidI = 0.0F;
enum Direction { Forward = 1, Reverse = -1 };
Direction rotationDirection;
void Update(unsigned long currentTimeMs) override;
virtual void Update(bool recurse = false) override;
/// @brief Set the target speed for the motor controller
/// @param speed the target in revolutions per second.
virtual void SetTargetSpeed(float speed) override;
/// @brief Set the target verlocity for the motor controller
/// @param speed the target velocity in revolutions per second
virtual void SetTargetVelocity(float velocity) override;
/// @brief Get the actual speed from the encoder
/// @return The speed in revolutions per second
virtual float GetActualSpeed() override;
bool Drive(float distance);
Motor* motor;
RelativeEncoder* encoder;
IncrementalEncoder* encoder;
protected:
float integral = 0;
float lastUpdateTime = 0;
float lastError = 0;
float lastUpdateTime;
// float targetSpeed;
float actualSpeed;
float netDistance = 0;
float startDistance = 0;
// enum Direction { Forward = 1, Reverse = -1 };
// Direction rotationDirection;
bool driving = false;
float targetDistance = 0;
float lastEncoderPosition = 0;
};
} // namespace RoboidControl

View File

@ -1,28 +1,10 @@
#include "DifferentialDrive.h"
#include "Messages/LowLevelMessages.h"
namespace RoboidControl {
DifferentialDrive::DifferentialDrive() : Thing() {}
DifferentialDrive::DifferentialDrive(Thing* parent)
: Thing(Type::DifferentialDrive, parent) {
this->name = "Differential drive";
this->leftWheel = new Motor(this);
this->leftWheel->name = "Left motor";
this->rightWheel = new Motor(this);
this->rightWheel->name = "Right motor";
}
DifferentialDrive::DifferentialDrive(Motor* leftMotor,
Motor* rightMotor,
Thing* parent)
: Thing(Type::DifferentialDrive, parent) {
this->name = "Differential drive";
this->leftWheel = leftMotor;
this->rightWheel = rightMotor;
}
RoboidControl::DifferentialDrive::DifferentialDrive(Participant* participant)
: Thing(participant) {}
void DifferentialDrive::SetDriveDimensions(float wheelDiameter,
float wheelSeparation) {
@ -39,66 +21,51 @@ void DifferentialDrive::SetDriveDimensions(float wheelDiameter,
this->rightWheel->SetPosition(Spherical(distance, Direction::right));
}
// Motor& DifferentialDrive::GetMotorLeft() {
// return *this->leftWheel;
// }
// Motor& DifferentialDrive::GetMotorRight() {
// return *this->rightWheel;
// }
void DifferentialDrive::SetMotors(Motor& leftMotor, Motor& rightMotor) {
void DifferentialDrive::SetMotors(Thing* leftWheel, Thing* rightWheel) {
float distance = this->wheelSeparation / 2;
this->leftWheel = &leftMotor;
this->leftWheel->SetPosition(Spherical(distance, Direction::left));
this->leftWheel = leftWheel;
;
if (leftWheel != nullptr)
this->leftWheel->SetPosition(Spherical(distance, Direction::left));
this->rightWheel = &rightMotor;
this->rightWheel->SetPosition(Spherical(distance, Direction::right));
this->rightWheel = rightWheel;
if (rightWheel != nullptr)
this->rightWheel->SetPosition(Spherical(distance, Direction::right));
}
void DifferentialDrive::SetWheelVelocity(float velocityLeft,
float velocityRight) {
// if (this->leftWheel != nullptr)
// this->leftWheel->SetAngularVelocity(Spherical(velocityLeft,
// Direction::left));
// if (this->rightWheel != nullptr)
// this->rightWheel->SetAngularVelocity(
// Spherical(velocityRight, Direction::right));
void DifferentialDrive::SetWheelVelocity(float speedLeft, float speedRight) {
if (this->leftWheel != nullptr)
this->leftWheel->SetTargetVelocity(velocityLeft);
this->leftWheel->SetAngularVelocity(Spherical(speedLeft, Direction::left));
if (this->rightWheel != nullptr)
this->rightWheel->SetTargetVelocity(velocityRight);
this->rightWheel->SetAngularVelocity(
Spherical(speedRight, Direction::right));
}
void DifferentialDrive::Update(bool recursive) {
if (this->linearVelocityUpdated) {
// this assumes forward velocity only....
float linearVelocity = this->GetLinearVelocity().distance;
void DifferentialDrive::Update(unsigned long currentMs, bool recursive) {
if (this->linearVelocityUpdated == false)
return;
// this assumes forward velocity only....
float linearVelocity = this->GetLinearVelocity().distance;
Spherical angularVelocity = this->GetAngularVelocity();
float angularSpeed = angularVelocity.distance * Deg2Rad; // in degrees/sec
// Determine the rotation direction
if (angularVelocity.direction.horizontal.InDegrees() < 0)
angularSpeed = -angularSpeed;
Spherical angularVelocity = this->GetAngularVelocity();
float angularSpeed = angularVelocity.distance * Deg2Rad; // in degrees/sec
// Determine the rotation direction
if (angularVelocity.direction.horizontal.InDegrees() < 0)
angularSpeed = -angularSpeed;
// wheel separation can be replaced by this->leftwheel->position->distance
float speedLeft =
(linearVelocity + angularSpeed * this->wheelSeparation / 2) /
this->wheelRadius * Rad2Deg;
float speedRight =
(linearVelocity - angularSpeed * this->wheelSeparation / 2) /
this->wheelRadius * Rad2Deg;
// wheel separation can be replaced by this->leftwheel->position->distance
float speedLeft =
(linearVelocity + angularSpeed * this->wheelSeparation / 2) /
this->wheelRadius * Rad2Deg;
float speedRight =
(linearVelocity - angularSpeed * this->wheelSeparation / 2) /
this->wheelRadius * Rad2Deg;
this->SetWheelVelocity(speedLeft, speedRight);
}
Thing::Update(recursive);
}
int DifferentialDrive::GenerateBinary(char* data, unsigned char* ix) {
data[(*ix)++] = this->leftWheel->id;
data[(*ix)++] = this->rightWheel->id;
LowLevelMessages::SendFloat16(data, ix, this->wheelRadius);
return 4;
this->SetWheelVelocity(speedLeft, speedRight);
Thing::Update(currentMs, recursive);
// std::cout << "lin. speed " << linearVelocity << " ang. speed " <<
// angularVelocity.distance << " left wheel "
// << speedLeft << " right wheel " << speedRight << "\n";
}
} // namespace RoboidControl

View File

@ -1,7 +1,6 @@
#pragma once
#include "Thing.h"
#include "Motor.h"
namespace RoboidControl {
@ -10,13 +9,11 @@ namespace RoboidControl {
/// @sa @link https://en.wikipedia.org/wiki/Differential_wheeled_robot @endlink
class DifferentialDrive : public Thing {
public:
/// @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 = Thing::LocalRoot());
DifferentialDrive(Motor* leftMotor, Motor* rightMotor, Thing* parent = Thing::LocalRoot());
/// @brief Create a differential drive without networking support
DifferentialDrive();
/// @brief Create a differential drive with networking support
/// @param participant The local participant
DifferentialDrive(Participant* participant);
/// @brief Configures the dimensions of the drive
/// @param wheelDiameter The diameter of the wheels in meters
@ -26,41 +23,35 @@ class DifferentialDrive : public Thing {
/// linear and angular velocity.
/// @sa SetLinearVelocity SetAngularVelocity
void SetDriveDimensions(float wheelDiameter, float wheelSeparation);
// Motor& GetMotorLeft();
// Motor& GetMotorRight();
/// @brief Congures the motors for the wheels
/// @param leftWheel The motor for the left wheel
/// @param rightWheel The motor for the right wheel
void SetMotors(Motor& leftMotor, Motor& rightMotor);
void SetMotors(Thing* leftWheel, Thing* rightWheel);
/// @brief Directly specify the speeds of the motors
/// @param speedLeft The speed of the left wheel in degrees per second.
/// Positive moves the robot in the forward direction.
/// @param speedRight The speed of the right wheel in degrees per second.
/// Positive moves the robot in the forward direction.
void SetWheelVelocity(float speedLeft, float speedRight);
/// @copydoc RoboidControl::Thing::Update(unsigned long)
virtual void Update(bool recursive = true) override;
int GenerateBinary(char* bytes, unsigned char* ix) override;
// virtual void ProcessBinary(char* bytes) override;
/// @brief The left wheel
Motor* leftWheel = nullptr;
/// @brief The right wheel
Motor* rightWheel = nullptr;
virtual void Update(unsigned long currentMs, bool recursive = true) override;
protected:
/// @brief The radius of a wheel in meters
float wheelRadius = 0.0f;
float wheelRadius = 1.0f;
/// @brief The distance between the wheels in meters
float wheelSeparation = 0.0f;
float wheelSeparation = 1.0f;
/// @brief Convert revolutions per second to meters per second
float rpsToMs = 1.0f;
/// @brief The left wheel
Thing* leftWheel = nullptr;
/// @brief The right wheel
Thing* rightWheel = nullptr;
};
} // namespace RoboidControl

View File

@ -2,26 +2,8 @@
namespace RoboidControl {
//DigitalSensor::DigitalSensor() : Thing(Type::Switch) {}
//DigitalSensor::DigitalSensor() {}
// DigitalSensor::DigitalSensor(Participant* owner, unsigned char thingId)
// : Thing(owner, Type::Switch, thingId) {}
// DigitalSensor::DigitalSensor(Thing* parent, unsigned char thingId)
// : Thing(parent, Type::Switch) {}
// DigitalSensor::DigitalSensor(Participant* owner) : Thing(owner, 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;
return 1;
}
void DigitalSensor::ProcessBinary(char* bytes) {
this->state |= (bytes[0] == 1);
}
DigitalSensor::DigitalSensor(Participant* participant, unsigned char networkId, unsigned char thingId) : Thing(participant) {}
} // namespace RoboidControl

View File

@ -7,31 +7,15 @@ namespace RoboidControl {
/// @brief A digital (on/off, 1/0, true/false) sensor
class DigitalSensor : public Thing {
public:
/// @brief Create a digital sensor without communication abilities
//DigitalSensor();
/// @brief Create a digital sensor for a participant
/// @param owner The owning participant
/// @param thingId The ID of the thing, leave out or set to zero to generate
/// an ID
DigitalSensor(Participant* owner = nullptr); //, unsigned char thingId = 0);
/// @brief Create a new child digital sensor
/// @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 = Thing::LocalRoot());
/// @brief The sigital state
bool state = 0;
/// @brief Function used to generate binary data for this digital sensor
/// @param buffer The byte array for thw binary data
/// @param ix The starting position for writing the binary data
int GenerateBinary(char* bytes, unsigned char* ix) override;
/// @brief Function used to process binary data received for this digital
/// sensor
/// @param bytes The binary data to process
virtual void ProcessBinary(char* bytes) override;
/// @brief The default constructor
//DigitalSensor();
/// @brief Create a temperature sensor with the given ID
/// @param networkId The network ID of the sensor
/// @param thingId The ID of the thing
DigitalSensor(Participant* participant, unsigned char networkId, unsigned char thingId);
};
} // namespace RoboidControl

View File

@ -0,0 +1,23 @@
#include "IncrementalEncoder.h"
namespace RoboidControl {
IncrementalEncoder::IncrementalEncoder(unsigned char pulsesPerRevolution,
unsigned char distancePerRotation) {
this->pulsesPerRevolution = pulsesPerRevolution;
this->distancePerRevolution = distancePerRotation;
}
int IncrementalEncoder::GetPulseCount() { return 0; }
float IncrementalEncoder::GetDistance() { return 0; }
float IncrementalEncoder::GetPulsesPerSecond(float currentTimeMs) { return 0; }
float IncrementalEncoder::GetRevolutionsPerSecond(float currentTimeMs) {
return 0;
}
float IncrementalEncoder::GetSpeed(float currentTimeMs) { return 0; }
}

View File

@ -0,0 +1,48 @@
#pragma once
namespace RoboidControl {
/// @brief An Encoder measures the rotations of an axle using a rotary
/// sensor Some encoders are able to detect direction, while others can not.
class IncrementalEncoder {
public:
/// @brief Creates a sensor which measures distance from pulses
/// @param pulsesPerRevolution The number of pulse edges which make a
/// full rotation
/// @param distancePerRevolution The distance a wheel travels per full
/// rotation
IncrementalEncoder(unsigned char pulsesPerRevolution = 1,
unsigned char distancePerRevolution = 1);
/// @brief Get the total number of pulses since the previous call
/// @return The number of pulses, is zero or greater
virtual int GetPulseCount();
/// @brief Get the pulse speed since the previous call
/// @param currentTimeMs The clock time in milliseconds
/// @return The average pulses per second in the last period.
virtual float GetPulsesPerSecond(float currentTimeMs);
/// @brief Get the distance traveled since the previous call
/// @return The distance in meters.
virtual float GetDistance();
/// @brief Get the rotation speed since the previous call
/// @param currentTimeMs The clock time in milliseconds
/// @return The speed in rotations per second
virtual float GetRevolutionsPerSecond(float currentTimeMs);
/// @brief Get the speed since the previous call
/// @param currentTimeMs The clock time in milliseconds
/// @return The speed in meters per second.
/// @note this value is dependent on the accurate setting of the
/// pulsesPerRevolution and distancePerRevolution parameters;
virtual float GetSpeed(float currentTimeMs);
/// @brief The numer of pulses corresponding to a full rotation of the axle
unsigned char pulsesPerRevolution = 1;
/// @brief The number of revolutions which makes the wheel move forward 1
/// meter
unsigned char distancePerRevolution = 1;
};
} // namespace RoboidControl

View File

@ -1,16 +1,21 @@
#include "Motor.h"
#include <time.h>
namespace RoboidControl {
Motor::Motor(Thing* parent) : Thing(Type::UncontrolledMotor, parent) {}
void Motor::SetTargetVelocity(float targetSpeed) {
this->targetVelocity = targetSpeed;
Motor::Motor() : Thing(0) { // for now, id should be set properly later
this->type = (int)Thing::UncontrolledMotor;
}
int Motor::GenerateBinary(char* data, unsigned char* ix) {
data[(*ix)++] = this->targetVelocity * 127.0f;
return 1;
float Motor::GetActualSpeed() { return this->currentTargetSpeed; }
void Motor::SetTargetSpeed(float targetSpeed) {
this->currentTargetSpeed = targetSpeed;
}
} // namespace RoboidControl
float Motor::GetTargetSpeed() { return (this->currentTargetSpeed); }
void Motor::Update(unsigned long currentTimeMs) {}
}

View File

@ -2,24 +2,41 @@
#include "Thing.h"
//#include <time.h>
namespace RoboidControl {
/// @brief A Motor is a Thing which can move parts of the Roboid
/// @note Currently only rotational motors are supported
class Motor : public Thing {
public:
Motor(Thing* parent = Thing::LocalRoot());
public:
/// @brief Default constructor for the Motor
Motor();
/// @brief Motor turning direction
enum class Direction { Clockwise = 1, CounterClockwise = -1 };
/// @brief The forward turning direction of the motor
Direction direction;
Direction direction = Direction::Clockwise;
virtual void SetTargetVelocity(float velocity); // -1..0..1
/// @brief Set the target motor speed
/// @param speed The speed between -1 (full backward), 0 (stop) and 1 (full
/// forward)
virtual void SetTargetSpeed(float speed);
/// @brief Get the current target speed of the motor
/// @return The speed between -1 (full backward), 0 (stop) and 1 (full
/// forward)
virtual float GetTargetSpeed();
int GenerateBinary(char* bytes, unsigned char* ix) override;
// virtual void ProcessBinary(char* bytes) override;
/// @brief Get the current actual speed of the motor
/// @return The speed between -1 (full backward), 0 (stop) and 1 (full
/// forward)
virtual float GetActualSpeed();
//protected:
float targetVelocity = 0;
virtual void Update(unsigned long currentTimeMs);
float currentTargetSpeed = 0;
protected:
};
} // namespace RoboidControl
} // namespace RoboidControl

View File

@ -1,21 +0,0 @@
#include "RelativeEncoder.h"
namespace RoboidControl {
RelativeEncoder::RelativeEncoder(Thing* parent)
: Thing(Type::IncrementalEncoder, parent) {}
float RelativeEncoder::GetRotationSpeed() {
return rotationSpeed;
}
int RelativeEncoder::GenerateBinary(char* data, unsigned char* ix) {
data[(*ix)++] = (unsigned char)(this->rotationSpeed * 127);
return 1;
}
void RelativeEncoder::ProcessBinary(char* data) {
this->rotationSpeed = (float)data[0] / 127;
}
} // namespace RoboidControl

View File

@ -1,39 +0,0 @@
#pragma once
#include "Thing.h"
namespace RoboidControl {
/// @brief An Incremental Encoder measures the rotations of an axle using a
/// rotary sensor. Some encoders are able to detect direction, while others can
/// not.
class RelativeEncoder : public Thing {
public:
/// @brief Creates a sensor which measures distance from pulses
/// @param pulsesPerRevolution The number of pulse edges which make a
/// full rotation
/// @param distancePerRevolution The distance a wheel travels per full
/// rotation
//RelativeEncoder(Participant* owner);
// RelativeEncoder(Thing* parent);
RelativeEncoder(Thing* parent = Thing::LocalRoot());
/// @brief Get the rotation speed
/// @return The speed in revolutions per second
virtual float GetRotationSpeed();
float rotationSpeed = 0;
/// @brief Function used to generate binary data for this touch sensor
/// @param buffer The byte array for thw binary data
/// @param ix The starting position for writing the binary data
int GenerateBinary(char* bytes, unsigned char* ix) override;
/// @brief Function used to process binary data received for this touch sensor
/// @param bytes The binary data to process
virtual void ProcessBinary(char* bytes) override;
protected:
/// @brief rotation speed in revolutions per second
//float _rotationSpeed;
};
} // namespace RoboidControl

113
Things/ServoMotor.cpp Normal file
View File

@ -0,0 +1,113 @@
#include "ServoMotor.h"
#include "LinearAlgebra/FloatSingle.h"
#include "Participant.h"
namespace RoboidControl {
ServoMotor::ServoMotor(Participant* participant) : Thing(participant, Thing::Servo, 0) {
this->controlMode = ControlMode::Position;
this->targetAngle = Angle16();
this->hasTargetAngle = false;
}
ServoMotor::ServoMotor(Thing* parent) : ServoMotor(parent->owner) {
std::cout << "new parent " << parent->name << " owner " << parent->owner << std::endl;
this->parent = parent;
}
void ServoMotor::SetTargetAngle(Angle16 angle) {
angle = Angle16::Clamp(angle, minAngle, maxAngle);
if (maxSpeed == 0.0F) {
SetAngle(angle);
this->limitedTargetAngle = angle;
}
this->controlMode = ControlMode::Position;
this->targetAngle = angle;
this->hasTargetAngle = true;
}
Angle16 ServoMotor::GetTargetAngle() {
return this->targetAngle;
}
void ServoMotor::SetMaximumVelocity(float maxVelocity) {
this->maxSpeed = maxVelocity;
}
void ServoMotor::SetTargetVelocity(float targetVelocity) {
targetVelocity = Float::Clamp(targetVelocity, -this->maxSpeed, maxSpeed);
this->controlMode = ControlMode::Velocity;
this->targetVelocity = targetVelocity;
this->hasTargetAngle = false; // can't we use the controlMode for this?
}
float ServoMotor::GetTargetVelocity() {
return this->targetVelocity;
}
void ServoMotor::Update(unsigned long currentTimeMs, bool recurse) {
for (unsigned char childIx = 0; childIx < this->childCount; childIx++) {
Thing* child = this->GetChild(childIx);
if (child != nullptr && child->type == Thing::Servo) {
ServoMotor* servo = (ServoMotor*)child;
servo->Update(currentTimeMs, recurse);
}
}
if (this->lastUpdateTimeMs == 0 || currentTimeMs < this->lastUpdateTimeMs) {
this->lastUpdateTimeMs = currentTimeMs;
return;
}
float deltaTime = (currentTimeMs - this->lastUpdateTimeMs) / 1000.0F;
// Position control
if (controlMode == ControlMode::Position) {
if (maxSpeed == 0.0F || hasTargetAngle == false) {
this->lastUpdateTimeMs = currentTimeMs;
return;
} else {
float angleStep = maxSpeed * deltaTime;
float deltaAngle =
this->targetAngle.InDegrees() - this->limitedTargetAngle.InDegrees();
float absDeltaAngle = (deltaAngle < 0) ? -deltaAngle : deltaAngle;
if (absDeltaAngle < angleStep) {
this->limitedTargetAngle = this->targetAngle;
SetAngle(targetAngle);
} else {
if (deltaAngle < 0)
limitedTargetAngle = limitedTargetAngle - Angle16::Degrees(angleStep);
else
limitedTargetAngle = limitedTargetAngle + Angle16::Degrees(angleStep);
}
SetAngle(limitedTargetAngle);
this->lastUpdateTimeMs = currentTimeMs;
return;
}
// Velocity control
} else {
float newAngle = this->targetAngle.InDegrees() + targetVelocity * deltaTime;
newAngle =
Float::Clamp(newAngle, minAngle.InDegrees(), maxAngle.InDegrees());
Angle16 targetAngle = Angle16::Degrees(newAngle);
ServoMotor::SetTargetAngle(targetAngle);
SetAngle(targetAngle);
this->lastUpdateTimeMs = currentTimeMs;
}
}
void ServoMotor::SetAngle(Angle16 angle) {
this->actualAngle = angle;
};
} // namespace RoboidControl

51
Things/ServoMotor.h Normal file
View File

@ -0,0 +1,51 @@
#pragma once
#include "ControlledMotor.h"
#include "LinearAlgebra/Angle.h"
namespace RoboidControl {
class ServoMotor : public Thing {
public:
// Inherit constructors from Thing
using Thing::Thing;
ServoMotor(Participant* participant);
ServoMotor(Thing* parent);
Direction16 rotationAxis = Direction16::up;
Angle16 minAngle = Angle16::Degrees(-90);
Angle16 maxAngle = Angle16::Degrees(90);
enum ControlMode { Position, Velocity };
ControlMode controlMode = ControlMode::Position;
Thing* target = nullptr;
virtual void SetTargetAngle(Angle16 angle);
virtual Angle16 GetTargetAngle();
virtual void SetMaximumVelocity(float maxVelocity);
virtual void SetTargetVelocity(float velocity);
virtual float GetTargetVelocity();
virtual void Update(unsigned long currentTimeMs, bool recurse) override;
Angle16 limitedTargetAngle = Angle16();
protected:
bool hasTargetAngle = false;
Angle16 targetAngle = Angle16();
Angle16 actualAngle = Angle16();
float maxSpeed = 0.0F;
float targetVelocity = 0.0F;
float lastUpdateTimeMs = 0.0F;
virtual void SetAngle(Angle16 angle);
};
} // namespace RoboidControl

View File

@ -4,15 +4,9 @@
namespace RoboidControl {
// TemperatureSensor::TemperatureSensor(Participant* participant,
// unsigned char thingId)
// : Thing(participant, Type::TemperatureSensor, thingId) {}
// TemperatureSensor::TemperatureSensor(Participant* owner) : Thing(owner, Type::TemperatureSensor) {}
TemperatureSensor::TemperatureSensor(Thing* parent) : Thing(Type::TemperatureSensor, parent) {}
// TemperatureSensor::TemperatureSensor(Thing* parent) : Thing(parent, Type::TemperatureSensor) {}
TemperatureSensor::TemperatureSensor(Participant* participant,
unsigned char thingId)
: Thing(participant, Type::TemperatureSensor, thingId) {}
void TemperatureSensor::SetTemperature(float temp) {
this->temperature = temp;

View File

@ -7,17 +7,15 @@ namespace RoboidControl {
/// @brief A temperature sensor
class TemperatureSensor : public Thing {
public:
/// @brief The measured temperature
float temperature = 0;
/// @brief The default constructor
//TemperatureSensor();
/// @brief Create a temperature sensor with the given ID
/// @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 = Thing::LocalRoot());
/// @brief The measured temperature
float temperature = 0;
TemperatureSensor(Participant* participant, unsigned char thingId);
/// @brief Manually override the measured temperature
/// @param temperature The new temperature

View File

@ -1,30 +1,23 @@
#include "TouchSensor.h"
namespace RoboidControl {
TouchSensor::TouchSensor() : Thing(Thing::Type::TouchSensor) {}
TouchSensor::TouchSensor(Thing* parent) : Thing(Type::TouchSensor, parent) {
this->name = "Touch sensor";
}
TouchSensor::TouchSensor(Participant* participant)
: Thing(participant, Thing::Type::TouchSensor) {}
void TouchSensor::PrepareForUpdate() {
this->touchedSomething = this->externalTouch;
}
void TouchSensor::Update(bool recursive) {
Thing::Update(recursive);
TouchSensor::TouchSensor(Thing* parent) : Thing(parent->owner) {
this->SetParent(parent);
}
int TouchSensor::GenerateBinary(char* bytes, unsigned char* ix) {
bytes[(*ix)++] = this->touchedSomething ? 1 : 0;
return 1;
return 0;
}
void TouchSensor::ProcessBinary(char* bytes) {
this->externalTouch = (bytes[0] == 1);
if (this->externalTouch)
std::cout << "touching!\n";
else
std::cout << "not touching\n";
// if (bytes[0] == 1)
// std::cout << this->name << " is Touching something!\n";
this->touchedSomething |= (bytes[0] == 1);
}
} // namespace RoboidControl

View File

@ -6,30 +6,29 @@ namespace RoboidControl {
/// @brief A sensor which can detect touches
class TouchSensor : public Thing {
// Why finishing this release (0.3), I notice that this is equivalent to a digital sensor
public:
/// @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 = Thing::LocalRoot());
/// @brief Create a touch sensor with isolated participant
TouchSensor();
/// @brief Create a touch sensor
TouchSensor(Participant* participant);
/// @brief Create a temperature sensor with the given ID
/// @param networkId The network ID of the sensor
/// @param thingId The ID of the thing
TouchSensor(Thing* parent);
// TouchSensor(RemoteParticipant* participant, unsigned char networkId,
// unsigned char thingId);
/// @brief Value which is true when the sensor is touching something, false
/// otherwise
bool touchedSomething = false;
virtual void PrepareForUpdate() override;
virtual void Update(bool recursive) override;
/// @brief Function used to generate binary data for this touch sensor
/// @brief Function to create a binary message with the temperature
/// @param buffer The byte array for thw binary data
/// @param ix The starting position for writing the binary data
int GenerateBinary(char* bytes, unsigned char* ix) override;
/// @brief Function used to process binary data received for this touch sensor
/// @param bytes The binary data to process
/// @brief Function to extract the temperature received in the binary message
/// @param bytes The binary data
virtual void ProcessBinary(char* bytes) override;
protected:
bool externalTouch = false;
};
} // namespace RoboidControl

View File

@ -85,9 +85,9 @@ void ParticipantUDP::Receive() {
unsigned int sender_port = ntohs(client_addr.sin_port);
ReceiveData(packetSize, sender_ipAddress, sender_port);
// RoboidControl::ParticipantUDP* remoteParticipant = this->Get(sender_ipAddress, sender_port);
// RoboidControl::ParticipantUDP* remoteParticipant = this->GetParticipant(sender_ipAddress, sender_port);
// if (remoteParticipant == nullptr) {
// remoteParticipant = this->Add(sender_ipAddress, sender_port);
// remoteParticipant = this->AddParticipant(sender_ipAddress, sender_port);
// // std::cout << "New sender " << sender_ipAddress << ":"
// // << sender_port << "\n";
// // std::cout << "New remote participant " <<

View File

@ -1 +0,0 @@
Important: this folder has to be names 'examples' exactly to maintain compatibility with Arduino

View File

@ -4,75 +4,111 @@
// not supported using Visual Studio 2022 compiler...
#include <gtest/gtest.h>
#include <chrono>
#include <thread>
// #include <ws2tcpip.h>
#include "Participant.h"
#include "Participants/SiteServer.h"
#include "Thing.h"
#include <chrono>
#include <thread>
using namespace RoboidControl;
TEST(Participant, Participant) {
ParticipantUDP* participant = new ParticipantUDP("127.0.0.1", 7682);
unsigned long milliseconds = Thing::GetTimeMs();
unsigned long startTime = milliseconds;
while (milliseconds < startTime + 7000) {
participant->Update();
std::this_thread::sleep_for(std::chrono::milliseconds(100));
milliseconds = Thing::GetTimeMs();
}
SUCCEED();
// Function to get the current time in milliseconds as unsigned long
unsigned long get_time_ms() {
auto now = std::chrono::steady_clock::now();
auto ms = std::chrono::duration_cast<std::chrono::milliseconds>(
now.time_since_epoch());
return static_cast<unsigned long>(ms.count());
}
TEST(Participant, SiteServer) {
SiteServer* siteServer = new SiteServer();
unsigned long milliseconds = Thing::GetTimeMs();
unsigned long startTime = milliseconds;
while (milliseconds < startTime + 7000) {
siteServer->Update();
std::this_thread::sleep_for(std::chrono::milliseconds(100));
milliseconds = Thing::GetTimeMs();
}
SUCCEED();
}
TEST(Participant, SiteParticipant) {
SiteServer* siteServer = new SiteServer(7681);
ParticipantUDP* participant = new ParticipantUDP("127.0.0.1", 7681, 7682);
unsigned long milliseconds = Thing::GetTimeMs();
unsigned long startTime = milliseconds;
while (milliseconds < startTime + 7000) {
siteServer->Update();
participant->Update();
std::this_thread::sleep_for(std::chrono::milliseconds(100));
milliseconds = Thing::GetTimeMs();
}
SUCCEED();
}
TEST(Participant, ThingMsg) {
SiteServer* siteServer = new SiteServer(7681);
ParticipantUDP* participant = new ParticipantUDP("127.0.0.1", 7681, 7682);
Thing* thing = new Thing();
thing->SetName("First Thing");
thing->SetModel("https://passer.life/extras/ant.jpg");
// class RoboidControlSuite : public ::testing::test {
// TEST_F(RoboidControlSuite, HiddenParticipant) {
// Thing thing = Thing();
unsigned long milliseconds = Thing::GetTimeMs();
unsigned long startTime = milliseconds;
while (milliseconds < startTime + 7000) {
siteServer->Update();
participant->Update();
// unsigned long milliseconds = get_time_ms();
// unsigned long startTime = milliseconds;
// while (milliseconds < startTime + 1000) {
// Thing.Update(milliseconds);
// milliseconds = get_time_ms();
// }
// ASSERT_EQ(1, 1);
// }
// }
std::this_thread::sleep_for(std::chrono::milliseconds(100));
milliseconds = Thing::GetTimeMs();
class ParticipantSuite : public ::testing::Test {
protected:
// SetUp and TearDown can be used to set up and clean up before/after each
// test
void SetUp() override {
// Initialize test data here
}
SUCCEED();
}
void TearDown() override {
// Clean up test data here
}
};
// TEST_F(ParticipantSuite, ParticipantUDP) {
// ParticipantUDP* participant = new ParticipantUDP("127.0.0.1", 7681);
// unsigned long milliseconds = get_time_ms();
// unsigned long startTime = milliseconds;
// while (milliseconds < startTime + 1000) {
// participant->Update(milliseconds);
// milliseconds = get_time_ms();
// }
// ASSERT_EQ(1, 1);
// }
// TEST_F(ParticipantSuite, SiteServer) {
// SiteServer site = SiteServer(7681);
// unsigned long milliseconds = get_time_ms();
// unsigned long startTime = milliseconds;
// while (milliseconds < startTime + 1000) {
// site.Update(milliseconds);
// milliseconds = get_time_ms();
// }
// ASSERT_EQ(1, 1);
// }
// TEST_F(ParticipantSuite, SiteParticipant) {
// SiteServer site = SiteServer(7681);
// ParticipantUDP participant = ParticipantUDP("127.0.0.1", 7681);
// unsigned long milliseconds = get_time_ms();
// unsigned long startTime = milliseconds;
// while (milliseconds < startTime + 1000) {
// site.Update(milliseconds);
// participant.Update(milliseconds);
// std::this_thread::sleep_for(std::chrono::milliseconds(100));
// milliseconds = get_time_ms();
// }
// ASSERT_EQ(1, 1);
// }
// TEST_F(ParticipantSuite, Thing) {
// SiteServer site = SiteServer(7681);
// ParticipantUDP participant = ParticipantUDP("127.0.0.1", 7681);
// Thing thing = Thing(&participant);
// unsigned long milliseconds = get_time_ms();
// unsigned long startTime = milliseconds;
// while (milliseconds < startTime + 1000) {
// site.Update(milliseconds);
// participant.Update(milliseconds);
// std::this_thread::sleep_for(std::chrono::milliseconds(100));
// milliseconds = get_time_ms();
// }
// ASSERT_EQ(1, 1);
// }
#endif

View File

@ -15,7 +15,7 @@ TEST(RoboidControlSuite, HiddenParticipant) {
unsigned long milliseconds = Thing::GetTimeMs();
unsigned long startTime = milliseconds;
while (milliseconds < startTime + 1000) {
Thing::UpdateThings();
Thing::UpdateThings(milliseconds);
milliseconds = Thing::GetTimeMs();
}
@ -24,12 +24,12 @@ TEST(RoboidControlSuite, HiddenParticipant) {
TEST(RoboidControlSuite, IsolatedParticipant) {
ParticipantUDP* participant = ParticipantUDP::Isolated();
Thing* thing = new Thing();
Thing* thing = new Thing(participant);
unsigned long milliseconds = Thing::GetTimeMs();
unsigned long startTime = milliseconds;
while (milliseconds < startTime + 1000) {
participant->Update();
participant->Update(milliseconds);
milliseconds = Thing::GetTimeMs();
}