Compare commits
9 Commits
Author | SHA1 | Date | |
---|---|---|---|
399eb5476e | |||
467ffd8d07 | |||
fdd23604f5 | |||
fe021e3b8a | |||
5bce1b7d2a | |||
4ce7f5fb0c | |||
e472c3626c | |||
142ba8377f | |||
dbe9c9237f |
@ -1,30 +1,28 @@
|
|||||||
#include "ArduinoParticipant.h"
|
#include "ArduinoParticipant.h"
|
||||||
|
|
||||||
#if !defined(NO_STD)
|
|
||||||
#include <iostream>
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if defined(ARDUINO)
|
|
||||||
#if defined(ARDUINO_ARCH_ESP8266)
|
#if defined(ARDUINO_ARCH_ESP8266)
|
||||||
|
#define HAS_WIFI 1
|
||||||
#include <ESP8266WiFi.h>
|
#include <ESP8266WiFi.h>
|
||||||
|
|
||||||
#elif defined(ESP32)
|
#elif defined(ESP32)
|
||||||
|
#define HAS_WIFI 1
|
||||||
#include <WiFi.h>
|
#include <WiFi.h>
|
||||||
|
|
||||||
#elif defined(UNO_R4)
|
#elif defined(UNO_R4)
|
||||||
|
#define HAS_WIFI 1
|
||||||
#include <WiFi.h>
|
#include <WiFi.h>
|
||||||
|
|
||||||
#elif defined(ARDUINO_ARCH_RP2040) // not functional, for future use
|
#elif defined(ARDUINO_ARCH_RP2040) // not functional, for future use
|
||||||
|
#define HAS_WIFI 1
|
||||||
#include <WifiNINA.h>
|
#include <WifiNINA.h>
|
||||||
|
|
||||||
#endif
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
namespace Arduino {
|
namespace Arduino {
|
||||||
|
|
||||||
#if defined(ARDUINO) && defined(HAS_WIFI)
|
#if HAS_WIFI
|
||||||
WiFiUDP* udp;
|
WiFiUDP udp;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
void ParticipantUDP::Setup() {
|
void ParticipantUDP::Setup() {
|
||||||
@ -33,9 +31,7 @@ void ParticipantUDP::Setup() {
|
|||||||
|
|
||||||
#if defined(UNO_R4)
|
#if defined(UNO_R4)
|
||||||
if (WiFi.status() == WL_NO_MODULE) {
|
if (WiFi.status() == WL_NO_MODULE) {
|
||||||
#if !defined(NO_STD)
|
|
||||||
std::cout << "No network available!\n";
|
std::cout << "No network available!\n";
|
||||||
#endif
|
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
@ -44,16 +40,13 @@ void ParticipantUDP::Setup() {
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
#endif
|
#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 << ", remote "
|
||||||
std::cout << "Wifi sync started local " << this->port;
|
<< this->remoteSite->ipAddress << ":" << this->remoteSite->port
|
||||||
if (this->remoteSite != nullptr)
|
<< "\n";
|
||||||
std::cout << ", remote " << this->remoteSite->ipAddress << ":"
|
|
||||||
<< this->remoteSite->port << "\n";
|
|
||||||
#endif
|
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -65,27 +58,28 @@ void ParticipantUDP::GetBroadcastAddress() {
|
|||||||
this->broadcastIpAddress = new char[broadcastIpString.length() + 1];
|
this->broadcastIpAddress = new char[broadcastIpString.length() + 1];
|
||||||
broadcastIpString.toCharArray(this->broadcastIpAddress,
|
broadcastIpString.toCharArray(this->broadcastIpAddress,
|
||||||
broadcastIpString.length() + 1);
|
broadcastIpString.length() + 1);
|
||||||
#if !defined(NO_STD)
|
|
||||||
std::cout << "Broadcast address: " << broadcastIpAddress << "\n";
|
std::cout << "Broadcast address: " << broadcastIpAddress << "\n";
|
||||||
#endif
|
#endif
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void ParticipantUDP::Receive() {
|
void ParticipantUDP::Receive() {
|
||||||
#if defined(ARDUINO) && defined(HAS_WIFI)
|
#if defined(ARDUINO) && defined(HAS_WIFI)
|
||||||
int packetSize = udp->parsePacket();
|
int packetSize = udp.parsePacket();
|
||||||
while (packetSize > 0) {
|
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];
|
char sender_ipAddress[16];
|
||||||
senderAddress.toCharArray(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);
|
ReceiveData(packetSize, sender_ipAddress, sender_port);
|
||||||
packetSize = udp->parsePacket();
|
|
||||||
|
packetSize = udp.parsePacket();
|
||||||
}
|
}
|
||||||
#endif
|
#endif // ARDUINO && HAS_WIFI
|
||||||
}
|
}
|
||||||
|
|
||||||
bool ParticipantUDP::Send(Participant* remoteParticipant, int bufferSize) {
|
bool ParticipantUDP::Send(Participant* remoteParticipant, int bufferSize) {
|
||||||
@ -94,39 +88,33 @@ bool ParticipantUDP::Send(Participant* remoteParticipant, int bufferSize) {
|
|||||||
// << remoteParticipant->port << "\n";
|
// << remoteParticipant->port << "\n";
|
||||||
|
|
||||||
int n = 0;
|
int n = 0;
|
||||||
int r = 0;
|
|
||||||
do {
|
do {
|
||||||
if (n > 0) {
|
if (n > 0) {
|
||||||
#if !defined(NO_STD)
|
|
||||||
std::cout << "Retry sending\n";
|
std::cout << "Retry sending\n";
|
||||||
#endif
|
|
||||||
delay(10);
|
delay(10);
|
||||||
}
|
}
|
||||||
n++;
|
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);
|
#endif // ARDUINO && HAS_WIFI
|
||||||
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
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool ParticipantUDP::Publish(IMessage* msg) {
|
bool ParticipantUDP::Publish(IMessage* msg) {
|
||||||
#if defined(ARDUINO) && defined(HAS_WIFI)
|
#if defined(ARDUINO) && defined(HAS_WIFI)
|
||||||
|
// std::cout << "Publish to " << this->broadcastIpAddress << ":"
|
||||||
|
// << this->remoteSite->port << "\n";
|
||||||
|
|
||||||
int bufferSize = msg->Serialize((char*)this->buffer);
|
int bufferSize = msg->Serialize((char*)this->buffer);
|
||||||
if (bufferSize <= 0)
|
if (bufferSize <= 0)
|
||||||
return true;
|
return true;
|
||||||
|
|
||||||
udp->beginPacket(this->broadcastIpAddress, this->port);
|
udp.beginPacket(this->broadcastIpAddress, this->remoteSite->port);
|
||||||
udp->write((unsigned char*)buffer, bufferSize);
|
udp.write((unsigned char*)buffer, bufferSize);
|
||||||
udp->endPacket();
|
udp.endPacket();
|
||||||
|
|
||||||
// std::cout << "Publish to " << this->broadcastIpAddress << ":"
|
|
||||||
// << this->remotePort << "\n";
|
|
||||||
#endif
|
#endif
|
||||||
return true;
|
return true;
|
||||||
};
|
};
|
||||||
|
@ -2,19 +2,31 @@
|
|||||||
|
|
||||||
#include "Participants/ParticipantUDP.h"
|
#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 RoboidControl {
|
||||||
namespace Arduino {
|
namespace Arduino {
|
||||||
|
|
||||||
class ParticipantUDP : public RoboidControl::ParticipantUDP {
|
class ParticipantUDP : public RoboidControl::ParticipantUDP {
|
||||||
public:
|
public:
|
||||||
void Setup();
|
void Setup(); // const char* remoteIpAddress, int remotePort);
|
||||||
void Receive();
|
void Receive();
|
||||||
bool Send(Participant* remoteParticipant, int bufferSize);
|
bool Send(Participant* remoteParticipant, int bufferSize);
|
||||||
bool Publish(IMessage* msg);
|
bool Publish(IMessage* msg);
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
//#if defined(HAS_WIFI)
|
||||||
char* broadcastIpAddress = nullptr;
|
char* broadcastIpAddress = nullptr;
|
||||||
|
|
||||||
|
//#endif
|
||||||
|
|
||||||
void GetBroadcastAddress();
|
void GetBroadcastAddress();
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -45,9 +45,6 @@ struct NssServer {
|
|||||||
bool StartWifi(const char* wifiSsid,
|
bool StartWifi(const char* wifiSsid,
|
||||||
const char* wifiPassword,
|
const char* wifiPassword,
|
||||||
bool hotspotFallback) {
|
bool hotspotFallback) {
|
||||||
#if !defined(HAS_WIFI)
|
|
||||||
return false;
|
|
||||||
#else
|
|
||||||
#if defined(UNO_R4) || defined(ARDUINO_ARCH_RP2040)
|
#if defined(UNO_R4) || defined(ARDUINO_ARCH_RP2040)
|
||||||
if (WiFi.status() == WL_NO_MODULE) {
|
if (WiFi.status() == WL_NO_MODULE) {
|
||||||
Serial.println("WiFi not present, WiFiSync is disabled");
|
Serial.println("WiFi not present, WiFiSync is disabled");
|
||||||
@ -150,13 +147,9 @@ bool StartWifi(const char* wifiSsid,
|
|||||||
}
|
}
|
||||||
|
|
||||||
return (!hotSpotEnabled);
|
return (!hotSpotEnabled);
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void CheckFirmware(String url, String FIRMWARE_NAME, int FIRMWARE_VERSION) {
|
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
|
#if defined(UNO_R4) // Uno R4 Wifi does not support this kind of firmware
|
||||||
// update (as far as I know)
|
// update (as far as I know)
|
||||||
return;
|
return;
|
||||||
@ -213,6 +206,5 @@ void CheckFirmware(String url, String FIRMWARE_NAME, int FIRMWARE_VERSION) {
|
|||||||
Serial.println(httpCode);
|
Serial.println(httpCode);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
@ -5,81 +5,49 @@
|
|||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
namespace Arduino {
|
namespace Arduino {
|
||||||
|
|
||||||
#pragma region DRV8833
|
DRV8833Motor::DRV8833Motor(Participant* participant, unsigned char pinIn1, unsigned char pinIn2, bool reverse)
|
||||||
|
: Thing(participant) {
|
||||||
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);
|
|
||||||
|
|
||||||
this->pinIn1 = pinIn1;
|
this->pinIn1 = pinIn1;
|
||||||
this->pinIn2 = pinIn2;
|
this->pinIn2 = pinIn2;
|
||||||
|
|
||||||
#if (ESP32)
|
#if (ESP32)
|
||||||
in1Ch = DRV8833Motor::nextAvailablePwmChannel++;
|
in1Ch = nextAvailablePwmChannel++;
|
||||||
ledcSetup(in1Ch, 500, 8);
|
ledcSetup(in1Ch, 500, 8);
|
||||||
ledcAttachPin(pinIn1, in1Ch);
|
ledcAttachPin(pinIn1, in1Ch);
|
||||||
|
in2Ch = nextAvailablePwmChannel++;
|
||||||
in2Ch = DRV8833Motor::nextAvailablePwmChannel++;
|
|
||||||
ledcSetup(in2Ch, 500, 8);
|
ledcSetup(in2Ch, 500, 8);
|
||||||
ledcAttachPin(pinIn2, in2Ch);
|
ledcAttachPin(pinIn2, in2Ch);
|
||||||
|
|
||||||
#else
|
#else
|
||||||
pinMode(pinIn1, OUTPUT); // configure the in1 pin to output mode
|
pinMode(pinIn1, OUTPUT); // configure the in1 pin to output mode
|
||||||
pinMode(pinIn2, OUTPUT); // configure the in1 pin to output mode
|
pinMode(pinIn2, OUTPUT); // configure the in1 pin to output mode
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// this->reverse = reverse;
|
this->reverse = reverse;
|
||||||
}
|
}
|
||||||
|
|
||||||
// void DRV8833Motor::SetMaxRPM(unsigned int rpm) {
|
void DRV8833Motor::SetMaxRPM(unsigned int rpm) {
|
||||||
// this->maxRpm = rpm;
|
this->maxRpm = rpm;
|
||||||
// }
|
}
|
||||||
|
|
||||||
void DRV8833Motor::SetTargetVelocity(float motorSpeed) {
|
void DRV8833Motor::SetAngularVelocity(Spherical velocity) {
|
||||||
Motor::SetTargetVelocity(motorSpeed);
|
Thing::SetAngularVelocity(velocity);
|
||||||
|
// ignoring rotation axis for now.
|
||||||
|
// Spherical angularVelocity = this->GetAngularVelocity();
|
||||||
|
float angularSpeed = velocity.distance; // in degrees/sec
|
||||||
|
|
||||||
uint8_t motorSignal =
|
float rpm = angularSpeed / 360 * 60;
|
||||||
(uint8_t)(motorSpeed > 0 ? motorSpeed * 255 : -motorSpeed * 255);
|
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";
|
// << ", motor signal = " << (int)motorSignal << "\n";
|
||||||
|
|
||||||
#if (ESP32)
|
#if (ESP32)
|
||||||
@ -129,7 +97,24 @@ void DRV8833Motor::SetTargetVelocity(float motorSpeed) {
|
|||||||
#endif
|
#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 Arduino
|
||||||
} // namespace RoboidControl
|
} // namespace RoboidControl
|
@ -1,76 +1,35 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <Arduino.h>
|
|
||||||
#include "Participants/IsolatedParticipant.h"
|
|
||||||
#include "Thing.h"
|
#include "Thing.h"
|
||||||
#include "Things/DifferentialDrive.h"
|
#include "Things/DifferentialDrive.h"
|
||||||
#include "Things/Motor.h"
|
|
||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
namespace Arduino {
|
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
|
/// @brief Support for a DRV8833 motor controller
|
||||||
class DRV8833Motor : public Motor {
|
class DRV8833Motor : public Thing {
|
||||||
public:
|
public:
|
||||||
|
/// @brief Motor turning direction
|
||||||
|
enum class RotationDirection { Clockwise = 1, CounterClockwise = -1 };
|
||||||
|
|
||||||
/// @brief Setup the DC motor
|
/// @brief Setup the DC motor
|
||||||
/// @param pinIn1 the pin number for the in1 signal
|
/// @param pinIn1 the pin number for the in1 signal
|
||||||
/// @param pinIn2 the pin number for the in2 signal
|
/// @param pinIn2 the pin number for the in2 signal
|
||||||
/// @param direction the forward turning direction of the motor
|
/// @param direction the forward turning direction of the motor
|
||||||
DRV8833Motor(DRV8833* driver,
|
DRV8833Motor(Participant* participant,
|
||||||
unsigned char pinIn1,
|
unsigned char pinIn1,
|
||||||
unsigned char pinIn2,
|
unsigned char pinIn2,
|
||||||
bool reverse = false);
|
bool reverse = false);
|
||||||
// void SetMaxRPM(unsigned int rpm);
|
void SetMaxRPM(unsigned int rpm);
|
||||||
|
|
||||||
// virtual void SetAngularVelocity(Spherical velocity) override;
|
virtual void SetAngularVelocity(Spherical velocity) override;
|
||||||
virtual void SetTargetVelocity(float targetSpeed) override;
|
|
||||||
// bool reverse = false;
|
bool reverse = false;
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
unsigned char pinIn1 = 255;
|
unsigned char pinIn1 = 255;
|
||||||
unsigned char pinIn2 = 255;
|
unsigned char pinIn2 = 255;
|
||||||
// unsigned int maxRpm = 200;
|
unsigned int maxRpm = 200;
|
||||||
|
|
||||||
#if (ESP32)
|
#if (ESP32)
|
||||||
uint8_t in1Ch;
|
uint8_t in1Ch;
|
||||||
@ -79,7 +38,32 @@ class DRV8833Motor : public Motor {
|
|||||||
#endif
|
#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 Arduino
|
||||||
} // namespace RoboidControl
|
} // namespace RoboidControl
|
@ -5,125 +5,19 @@
|
|||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
namespace Arduino {
|
namespace Arduino {
|
||||||
|
|
||||||
#pragma region Digital input
|
DigitalInput::DigitalInput(Participant* participant, unsigned char pin)
|
||||||
|
: TouchSensor(participant) {
|
||||||
DigitalInput::DigitalInput(unsigned char pin, Thing* parent)
|
|
||||||
: Thing(Type::Undetermined, parent) {
|
|
||||||
this->pin = pin;
|
this->pin = pin;
|
||||||
pinMode(this->pin, INPUT);
|
|
||||||
std::cout << "digital input start\n";
|
pinMode(pin, INPUT);
|
||||||
}
|
}
|
||||||
|
|
||||||
void DigitalInput::Update(bool recursive) {
|
void DigitalInput::Update(unsigned long currentTimeMs, bool recursive) {
|
||||||
this->isHigh = digitalRead(this->pin);
|
this->touchedSomething = digitalRead(pin) == LOW;
|
||||||
this->isLow = !this->isHigh;
|
// std::cout << "DigitalINput pin " << (int)this->pin << ": " <<
|
||||||
Thing::Update(recursive);
|
// 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 Arduino
|
||||||
} // namespace RoboidControl
|
} // namespace RoboidControl
|
@ -1,92 +1,26 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "Things/RelativeEncoder.h"
|
|
||||||
#include "Things/TouchSensor.h"
|
#include "Things/TouchSensor.h"
|
||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
namespace Arduino {
|
namespace Arduino {
|
||||||
|
|
||||||
/// @brief A digital input represents the stat of a digital GPIO pin
|
/// @brief A digital input represents the stat of a digital GPIO pin
|
||||||
class DigitalInput : public Thing {
|
class DigitalInput : public TouchSensor {
|
||||||
public:
|
public:
|
||||||
/// @brief Create a new digital input
|
/// @brief Create a new digital input
|
||||||
/// @param participant The participant to use
|
/// @param participant The participant to use
|
||||||
/// @param pin The digital pin
|
/// @param pin The digital pin
|
||||||
//DigitalInput(Participant* participant, unsigned char 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;
|
|
||||||
|
|
||||||
/// @copydoc RoboidControl::Thing::Update(unsigned long currentTimeMs)
|
/// @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:
|
protected:
|
||||||
/// @brief The pin used for digital input
|
/// @brief The pin used for digital input
|
||||||
unsigned char pin = 0;
|
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 Arduino
|
||||||
} // namespace RoboidControl
|
} // namespace RoboidControl
|
@ -1,16 +1,16 @@
|
|||||||
#include "UltrasonicSensor.h"
|
#include "UltrasonicSensor.h"
|
||||||
|
|
||||||
#include <Arduino.h>
|
#include <Arduino.h>
|
||||||
#include <iostream>
|
|
||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
namespace Arduino {
|
namespace Arduino {
|
||||||
|
|
||||||
UltrasonicSensor::UltrasonicSensor(Configuration config, Thing* parent)
|
UltrasonicSensor::UltrasonicSensor(Participant* participant,
|
||||||
: Thing(Type::Undetermined, parent) {
|
unsigned char pinTrigger,
|
||||||
this->name = "Ultrasonic sensor";
|
unsigned char pinEcho)
|
||||||
this->pinTrigger = config.trigger;
|
: TouchSensor(participant) {
|
||||||
this->pinEcho = config.echo;
|
this->pinTrigger = pinTrigger;
|
||||||
|
this->pinEcho = pinEcho;
|
||||||
|
|
||||||
pinMode(pinTrigger, OUTPUT); // configure the trigger pin to output mode
|
pinMode(pinTrigger, OUTPUT); // configure the trigger pin to output mode
|
||||||
pinMode(pinEcho, INPUT); // configure the echo pin to input mode
|
pinMode(pinEcho, INPUT); // configure the echo pin to input mode
|
||||||
@ -19,14 +19,14 @@ UltrasonicSensor::UltrasonicSensor(Configuration config, Thing* parent)
|
|||||||
float UltrasonicSensor::GetDistance() {
|
float UltrasonicSensor::GetDistance() {
|
||||||
// Start the ultrasonic 'ping'
|
// Start the ultrasonic 'ping'
|
||||||
digitalWrite(pinTrigger, LOW);
|
digitalWrite(pinTrigger, LOW);
|
||||||
delayMicroseconds(2);
|
delayMicroseconds(5);
|
||||||
digitalWrite(pinTrigger, HIGH);
|
digitalWrite(pinTrigger, HIGH);
|
||||||
delayMicroseconds(10);
|
delayMicroseconds(10);
|
||||||
digitalWrite(pinTrigger, LOW);
|
digitalWrite(pinTrigger, LOW);
|
||||||
|
|
||||||
// Measure the duration of the pulse on the echo pin
|
// Measure the duration of the pulse on the echo pin
|
||||||
unsigned long duration_us =
|
float duration_us =
|
||||||
pulseIn(pinEcho, HIGH, 10000); // the result is in microseconds
|
pulseIn(pinEcho, HIGH, 100000); // the result is in microseconds
|
||||||
|
|
||||||
// Calculate the distance:
|
// Calculate the distance:
|
||||||
// * Duration should be divided by 2, because the ping goes to the object
|
// * 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):
|
// * Now we calculate the distance based on the speed of sound (340 m/s):
|
||||||
// distance = duration_sec * 340;
|
// distance = duration_sec * 340;
|
||||||
// * The result calculation is therefore:
|
// * The result calculation is therefore:
|
||||||
this->distance = (float)duration_us / 2 / 1000000 * 340;
|
this->distance = duration_us / 2 / 1000000 * 340;
|
||||||
|
|
||||||
// Serial.println(this->distance);
|
|
||||||
|
|
||||||
// std::cout << "US distance " << this->distance << std::endl;
|
|
||||||
|
|
||||||
// Filter faulty measurements. The sensor can often give values > 30 m which
|
// Filter faulty measurements. The sensor can often give values > 30 m which
|
||||||
// are not correct
|
// are not correct
|
||||||
// if (distance > 30)
|
// if (distance > 30)
|
||||||
// distance = 0;
|
// 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();
|
GetDistance();
|
||||||
Thing::Update(recursive);
|
Thing::Update(currentTimeMs, recursive);
|
||||||
}
|
}
|
||||||
|
|
||||||
#pragma region Touch sensor
|
// void UltrasonicSensor::ProcessBinary(char* bytes) {
|
||||||
|
// this->touchedSomething = (bytes[0] == 1);
|
||||||
UltrasonicSensor::TouchSensor::TouchSensor(Configuration config, Thing* parent)
|
// if (this->touchedSomething)
|
||||||
: RoboidControl::TouchSensor(parent), ultrasonic(config, this) {}
|
// std::cout << "Touching something!\n";
|
||||||
|
// }
|
||||||
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
|
|
||||||
|
|
||||||
} // namespace Arduino
|
} // namespace Arduino
|
||||||
} // namespace RoboidControl
|
} // namespace RoboidControl
|
@ -6,19 +6,20 @@ namespace RoboidControl {
|
|||||||
namespace Arduino {
|
namespace Arduino {
|
||||||
|
|
||||||
/// @brief An HC-SR04 ultrasonic distance sensor
|
/// @brief An HC-SR04 ultrasonic distance sensor
|
||||||
class UltrasonicSensor : Thing {
|
class UltrasonicSensor : public TouchSensor {
|
||||||
public:
|
public:
|
||||||
struct Configuration {
|
/// @brief Setup an ultrasonic sensor
|
||||||
int trigger;
|
/// @param participant The participant to use
|
||||||
int echo;
|
/// @param pinTrigger The pin number of the trigger signal
|
||||||
};
|
/// @param pinEcho The pin number of the echo signal
|
||||||
|
UltrasonicSensor(Participant* participant,
|
||||||
UltrasonicSensor(Configuration config, Thing* parent = Thing::LocalRoot());
|
unsigned char pinTrigger,
|
||||||
|
unsigned char pinEcho);
|
||||||
|
|
||||||
// parameters
|
// parameters
|
||||||
|
|
||||||
/// @brief The distance at which the object is considered to be touched
|
/// @brief The distance at which the object is considered to be touched
|
||||||
// float touchDistance = 0.2f;
|
float touchDistance = 0.2f;
|
||||||
|
|
||||||
// state
|
// state
|
||||||
|
|
||||||
@ -30,35 +31,15 @@ class UltrasonicSensor : Thing {
|
|||||||
float GetDistance();
|
float GetDistance();
|
||||||
|
|
||||||
/// @copydoc RoboidControl::Thing::Update(unsigned long currentTimeMs)
|
/// @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:
|
protected:
|
||||||
/// @brief The pin number of the trigger signal
|
/// @brief The pin number of the trigger signal
|
||||||
unsigned char pinTrigger = 0;
|
unsigned char pinTrigger = 0;
|
||||||
/// @brief The pin number of the echo signal
|
/// @brief The pin number of the echo signal
|
||||||
unsigned char pinEcho = 0;
|
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 Arduino
|
||||||
} // namespace RoboidControl
|
} // namespace RoboidControl
|
@ -19,13 +19,13 @@ if(ESP_PLATFORM)
|
|||||||
REQUIRES esp_netif esp_wifi
|
REQUIRES esp_netif esp_wifi
|
||||||
)
|
)
|
||||||
else()
|
else()
|
||||||
set(CMAKE_CXX_STANDARD 17) # Enable c++11 standard
|
|
||||||
set(CMAKE_POSITION_INDEPENDENT_CODE ON)
|
|
||||||
|
|
||||||
project(RoboidControl)
|
project(RoboidControl)
|
||||||
add_subdirectory(LinearAlgebra)
|
add_subdirectory(LinearAlgebra)
|
||||||
add_subdirectory(Examples)
|
add_subdirectory(Examples)
|
||||||
|
|
||||||
|
set(CMAKE_CXX_STANDARD 17) # Enable c++11 standard
|
||||||
|
set(CMAKE_POSITION_INDEPENDENT_CODE ON)
|
||||||
|
|
||||||
add_compile_definitions(GTEST)
|
add_compile_definitions(GTEST)
|
||||||
include(FetchContent)
|
include(FetchContent)
|
||||||
FetchContent_Declare(
|
FetchContent_Declare(
|
||||||
|
@ -7,9 +7,9 @@
|
|||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
namespace EspIdf {
|
namespace EspIdf {
|
||||||
|
|
||||||
void ParticipantUDP::Setup(int localPort,
|
void ParticipantUDP::Setup() {//int localPort,
|
||||||
const char* remoteIpAddress,
|
// const char* remoteIpAddress,
|
||||||
int remotePort) {
|
// int remotePort) {
|
||||||
#if defined(IDF_VER)
|
#if defined(IDF_VER)
|
||||||
std::cout << "Set up UDP\n";
|
std::cout << "Set up UDP\n";
|
||||||
GetBroadcastAddress();
|
GetBroadcastAddress();
|
||||||
|
@ -11,7 +11,7 @@ namespace EspIdf {
|
|||||||
|
|
||||||
class ParticipantUDP : public RoboidControl::ParticipantUDP {
|
class ParticipantUDP : public RoboidControl::ParticipantUDP {
|
||||||
public:
|
public:
|
||||||
void Setup(int localPort, const char* remoteIpAddress, int remotePort);
|
void Setup(); //const char* remoteIpAddress, int remotePort);
|
||||||
void Receive();
|
void Receive();
|
||||||
bool Send(Participant* remoteParticipant, int bufferSize);
|
bool Send(Participant* remoteParticipant, int bufferSize);
|
||||||
bool Publish(IMessage* msg);
|
bool Publish(IMessage* msg);
|
||||||
|
@ -17,26 +17,26 @@ using namespace RoboidControl;
|
|||||||
|
|
||||||
int main() {
|
int main() {
|
||||||
// The robot's propulsion is a differential drive
|
// 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
|
// 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
|
// and other one on the right
|
||||||
TouchSensor touchRight = TouchSensor(&bb2b);
|
TouchSensor* touchRight = new TouchSensor(bb2b);
|
||||||
|
|
||||||
// Do forever:
|
// Do forever:
|
||||||
while (true) {
|
while (true) {
|
||||||
// The left wheel turns forward when nothing is touched on the right side
|
// The left wheel turns forward when nothing is touched on the right side
|
||||||
// and turn backward when the roboid hits something on the right
|
// 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
|
// The right wheel does the same, but instead is controlled by
|
||||||
// touches on the left side
|
// 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
|
// When both sides are touching something, both wheels will turn backward
|
||||||
// and the roboid will move backwards
|
// and the roboid will move backwards
|
||||||
bb2b.SetWheelVelocity(leftWheelSpeed, rightWheelSpeed);
|
bb2b->SetWheelVelocity(leftWheelSpeed, rightWheelSpeed);
|
||||||
|
|
||||||
// Update the roboid state
|
// Update the roboid state
|
||||||
bb2b.Update(true);
|
bb2b->Update(true);
|
||||||
|
|
||||||
// and sleep for 100ms
|
// and sleep for 100ms
|
||||||
#if defined(ARDUINO)
|
#if defined(ARDUINO)
|
@ -9,7 +9,6 @@
|
|||||||
|
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
|
|
||||||
namespace LinearAlgebra {
|
|
||||||
template <typename T>
|
template <typename T>
|
||||||
DirectionOf<T>::DirectionOf() {
|
DirectionOf<T>::DirectionOf() {
|
||||||
this->horizontal = AngleOf<T>();
|
this->horizontal = AngleOf<T>();
|
||||||
@ -99,6 +98,5 @@ void DirectionOf<T>::Normalize() {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
template class LinearAlgebra::DirectionOf<float>;
|
template class DirectionOf<float>;
|
||||||
template class LinearAlgebra::DirectionOf<signed short>;
|
template class DirectionOf<signed short>;
|
||||||
}
|
|
||||||
|
@ -99,4 +99,6 @@ using Direction = DirectionSingle;
|
|||||||
|
|
||||||
} // namespace LinearAlgebra
|
} // namespace LinearAlgebra
|
||||||
|
|
||||||
|
using namespace LinearAlgebra;
|
||||||
|
|
||||||
#endif
|
#endif
|
@ -1,7 +1,5 @@
|
|||||||
#include "Matrix.h"
|
#include "Matrix.h"
|
||||||
#if !defined(NO_STD)
|
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
#endif
|
|
||||||
|
|
||||||
namespace LinearAlgebra {
|
namespace LinearAlgebra {
|
||||||
|
|
||||||
@ -63,9 +61,7 @@ Matrix2::Matrix2(const Matrix2& m)
|
|||||||
this->data = nullptr;
|
this->data = nullptr;
|
||||||
else {
|
else {
|
||||||
this->data = new float[this->nValues];
|
this->data = new float[this->nValues];
|
||||||
|
std::copy(m.data, m.data + nValues, this->data);
|
||||||
for (int ix = 0; ix < this->nValues; ++ix)
|
|
||||||
this->data[ix] = m.data[ix];
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -80,8 +76,7 @@ Matrix2& Matrix2::operator=(const Matrix2& m) {
|
|||||||
this->data = nullptr;
|
this->data = nullptr;
|
||||||
else {
|
else {
|
||||||
this->data = new float[this->nValues];
|
this->data = new float[this->nValues];
|
||||||
for (int ix = 0; ix < this->nValues; ++ix)
|
std::copy(m.data, m.data + this->nValues, this->data);
|
||||||
this->data[ix] = m.data[ix];
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
return *this;
|
return *this;
|
||||||
@ -94,8 +89,7 @@ Matrix2::~Matrix2() {
|
|||||||
|
|
||||||
Matrix2 Matrix2::Clone() const {
|
Matrix2 Matrix2::Clone() const {
|
||||||
Matrix2 r = Matrix2(this->nRows, this->nCols);
|
Matrix2 r = Matrix2(this->nRows, this->nCols);
|
||||||
for (int ix = 0; ix < this->nValues; ++ix)
|
std::copy(this->data, this->data + this->nValues, r.data);
|
||||||
r.data[ix] = this->data[ix];
|
|
||||||
return r;
|
return r;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -139,7 +133,7 @@ Matrix2 Matrix2::Identity(int size) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
Matrix2 Matrix2::Diagonal(float f, int size) {
|
Matrix2 Matrix2::Diagonal(float f, int size) {
|
||||||
Matrix2 r = Matrix2::Zero(size, size);
|
Matrix2 r = Matrix2(size, size);
|
||||||
float* data = r.data;
|
float* data = r.data;
|
||||||
int valueIx = 0;
|
int valueIx = 0;
|
||||||
for (int ix = 0; ix < size; ix++) {
|
for (int ix = 0; ix < size; ix++) {
|
||||||
@ -164,8 +158,8 @@ Matrix2 Matrix2::SkewMatrix(const Vector3& v) {
|
|||||||
Matrix2 Matrix2::Transpose() const {
|
Matrix2 Matrix2::Transpose() const {
|
||||||
Matrix2 r = Matrix2(this->nCols, this->nRows);
|
Matrix2 r = Matrix2(this->nCols, this->nRows);
|
||||||
|
|
||||||
for (int rowIx = 0; rowIx < this->nRows; rowIx++) {
|
for (uint rowIx = 0; rowIx < this->nRows; rowIx++) {
|
||||||
for (int colIx = 0; colIx < this->nCols; colIx++)
|
for (uint colIx = 0; colIx < this->nCols; colIx++)
|
||||||
r.data[colIx * this->nCols + rowIx] =
|
r.data[colIx * this->nCols + rowIx] =
|
||||||
this->data[rowIx * this->nCols + colIx];
|
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
|
int BColOffset = i * BCols; // BColOffset is constant for each row of B
|
||||||
for (int j = 0; j < BCols; ++j) {
|
for (int j = 0; j < BCols; ++j) {
|
||||||
float sum = 0;
|
float sum = 0;
|
||||||
std::cout << " 0";
|
// std::cout << " 0";
|
||||||
int BIndex = j;
|
int BIndex = j;
|
||||||
for (int k = 0; k < ACols; ++k) {
|
for (int k = 0; k < ACols; ++k) {
|
||||||
std::cout << " + " << this->data[ARowOffset + k] << " * "
|
// std::cout << " + " << this->data[ARowOffset + k] << " * "
|
||||||
<< B.data[BIndex];
|
// << B.data[BIndex];
|
||||||
sum += this->data[ARowOffset + k] * B.data[BIndex];
|
sum += this->data[ARowOffset + k] * B.data[BIndex];
|
||||||
BIndex += BCols;
|
BIndex += BCols;
|
||||||
}
|
}
|
||||||
r.data[BColOffset + j] = sum;
|
r.data[BColOffset + j] = sum;
|
||||||
std::cout << " = " << sum << " ix: " << BColOffset + j << "\n";
|
// std::cout << " = " << sum << " ix: " << BColOffset + j << "\n";
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
return r;
|
return r;
|
||||||
|
@ -175,5 +175,5 @@ PolarOf<T> PolarOf<T>::Rotate(const PolarOf& v, AngleOf<T> angle) {
|
|||||||
return r;
|
return r;
|
||||||
}
|
}
|
||||||
|
|
||||||
template class LinearAlgebra::PolarOf<float>;
|
template class PolarOf<float>;
|
||||||
template class LinearAlgebra::PolarOf<signed short>;
|
template class PolarOf<signed short>;
|
@ -5,8 +5,6 @@
|
|||||||
|
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
|
|
||||||
namespace LinearAlgebra {
|
|
||||||
|
|
||||||
template <typename T>
|
template <typename T>
|
||||||
SphericalOf<T>::SphericalOf() {
|
SphericalOf<T>::SphericalOf() {
|
||||||
this->distance = 0.0f;
|
this->distance = 0.0f;
|
||||||
@ -303,5 +301,3 @@ SphericalOf<T> SphericalOf<T>::RotateVertical(const SphericalOf<T>& v,
|
|||||||
|
|
||||||
template class SphericalOf<float>;
|
template class SphericalOf<float>;
|
||||||
template class SphericalOf<signed short>;
|
template class SphericalOf<signed short>;
|
||||||
|
|
||||||
} // namespace LinearAlgebra
|
|
@ -186,6 +186,7 @@ using Spherical = SphericalSingle;
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
} // namespace LinearAlgebra
|
} // namespace LinearAlgebra
|
||||||
|
using namespace LinearAlgebra;
|
||||||
|
|
||||||
#include "Polar.h"
|
#include "Polar.h"
|
||||||
#include "Vector3.h"
|
#include "Vector3.h"
|
||||||
|
@ -4,8 +4,6 @@
|
|||||||
|
|
||||||
#include "SwingTwist.h"
|
#include "SwingTwist.h"
|
||||||
|
|
||||||
namespace LinearAlgebra {
|
|
||||||
|
|
||||||
template <typename T>
|
template <typename T>
|
||||||
SwingTwistOf<T>::SwingTwistOf() {
|
SwingTwistOf<T>::SwingTwistOf() {
|
||||||
this->swing = DirectionOf<T>(AngleOf<T>(), AngleOf<T>());
|
this->swing = DirectionOf<T>(AngleOf<T>(), AngleOf<T>());
|
||||||
@ -168,5 +166,3 @@ void SwingTwistOf<T>::Normalize() {
|
|||||||
|
|
||||||
template class SwingTwistOf<float>;
|
template class SwingTwistOf<float>;
|
||||||
template class SwingTwistOf<signed short>;
|
template class SwingTwistOf<signed short>;
|
||||||
|
|
||||||
}
|
|
@ -6,8 +6,6 @@
|
|||||||
|
|
||||||
#include "Direction.h"
|
#include "Direction.h"
|
||||||
|
|
||||||
using namespace LinearAlgebra;
|
|
||||||
|
|
||||||
#define FLOAT_INFINITY std::numeric_limits<float>::infinity()
|
#define FLOAT_INFINITY std::numeric_limits<float>::infinity()
|
||||||
|
|
||||||
TEST(Direction16, Compare) {
|
TEST(Direction16, Compare) {
|
||||||
|
@ -2,7 +2,6 @@
|
|||||||
#include <gtest/gtest.h>
|
#include <gtest/gtest.h>
|
||||||
#include <limits>
|
#include <limits>
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
#include <chrono>
|
|
||||||
|
|
||||||
#include "Polar.h"
|
#include "Polar.h"
|
||||||
#include "Spherical.h"
|
#include "Spherical.h"
|
||||||
|
@ -2,7 +2,6 @@
|
|||||||
#include <gtest/gtest.h>
|
#include <gtest/gtest.h>
|
||||||
#include <limits>
|
#include <limits>
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
#include <chrono>
|
|
||||||
|
|
||||||
#include "Spherical.h"
|
#include "Spherical.h"
|
||||||
#include "Vector3.h"
|
#include "Vector3.h"
|
||||||
|
@ -2,7 +2,6 @@
|
|||||||
#include <gtest/gtest.h>
|
#include <gtest/gtest.h>
|
||||||
#include <limits>
|
#include <limits>
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
#include <chrono>
|
|
||||||
|
|
||||||
#include "Spherical.h"
|
#include "Spherical.h"
|
||||||
|
|
||||||
|
@ -6,8 +6,7 @@ BinaryMsg::BinaryMsg(unsigned char networkId, Thing* thing) {
|
|||||||
this->networkId = networkId;
|
this->networkId = networkId;
|
||||||
this->thingId = thing->id;
|
this->thingId = thing->id;
|
||||||
this->thing = thing;
|
this->thing = thing;
|
||||||
unsigned char ix = 0; //BinaryMsg::length;
|
unsigned char ix = BinaryMsg::length;
|
||||||
this->data = new char[255];
|
|
||||||
this->dataLength = this->thing->GenerateBinary(this->data, &ix);
|
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->networkId;
|
||||||
buffer[ix++] = this->thingId;
|
buffer[ix++] = this->thingId;
|
||||||
buffer[ix++] = this->dataLength;
|
buffer[ix++] = this->dataLength;
|
||||||
for (int dataIx = 0; dataIx < this->dataLength; dataIx++)
|
|
||||||
buffer[ix++] = this->data[dataIx];
|
|
||||||
return this->length + this->dataLength;
|
return this->length + this->dataLength;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1,17 +1,15 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "IMessage.h"
|
#include "Messages.h"
|
||||||
#include "Thing.h"
|
|
||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
|
||||||
/// @brief A message containing binary data for custom communication
|
/// @brief Message to send thing-specific data
|
||||||
class BinaryMsg : public IMessage {
|
class BinaryMsg : public IMessage {
|
||||||
public:
|
public:
|
||||||
/// @brief The message ID
|
/// @brief The message ID
|
||||||
static const unsigned char id = 0xB1;
|
static const unsigned char id = 0xB1;
|
||||||
/// @brief The length of the message in bytes, excluding the binary data
|
/// @brief The length of the message without the binary data itslef
|
||||||
/// For the total size of the message this.bytes.Length should be added to this value.
|
|
||||||
static const unsigned length = 4;
|
static const unsigned length = 4;
|
||||||
|
|
||||||
/// @brief The network ID of the thing
|
/// @brief The network ID of the thing
|
||||||
@ -25,7 +23,7 @@ class BinaryMsg : public IMessage {
|
|||||||
/// @brief The binary data which is communicated
|
/// @brief The binary data which is communicated
|
||||||
char* data = nullptr;
|
char* data = nullptr;
|
||||||
|
|
||||||
/// @brief Create a BinaryMsg
|
/// @brief Create a new message for sending
|
||||||
/// @param networkId The network ID of the thing
|
/// @param networkId The network ID of the thing
|
||||||
/// @param thing The thing for which binary data is sent
|
/// @param thing The thing for which binary data is sent
|
||||||
BinaryMsg(unsigned char networkId, Thing* thing);
|
BinaryMsg(unsigned char networkId, Thing* thing);
|
||||||
|
@ -7,17 +7,14 @@ DestroyMsg::DestroyMsg(unsigned char networkId, Thing* thing) {
|
|||||||
this->thingId = thing->id;
|
this->thingId = thing->id;
|
||||||
}
|
}
|
||||||
|
|
||||||
DestroyMsg::DestroyMsg(char* buffer) {
|
DestroyMsg::DestroyMsg(char* buffer) {}
|
||||||
this->networkId = buffer[1];
|
|
||||||
this->thingId = buffer[2];
|
|
||||||
}
|
|
||||||
|
|
||||||
DestroyMsg::~DestroyMsg() {}
|
DestroyMsg::~DestroyMsg() {}
|
||||||
|
|
||||||
unsigned char DestroyMsg::Serialize(char *buffer) {
|
unsigned char DestroyMsg::Serialize(char *buffer) {
|
||||||
#if defined(DEBUG)
|
#if defined(DEBUG)
|
||||||
std::cout << "Send DestroyMsg [" << (int)this->networkId << "/"
|
std::cout << "Send DestroyMsg [" << (int)this->networkId << "/" << (int)this->thingId
|
||||||
<< (int)this->thingId << "] " << std::endl;
|
<< "] " << std::endl;
|
||||||
#endif
|
#endif
|
||||||
unsigned char ix = 0;
|
unsigned char ix = 0;
|
||||||
buffer[ix++] = this->id;
|
buffer[ix++] = this->id;
|
||||||
|
@ -1,16 +1,13 @@
|
|||||||
#pragma once
|
#include "Messages.h"
|
||||||
|
|
||||||
#include "IMessage.h"
|
|
||||||
#include "Thing.h"
|
|
||||||
|
|
||||||
namespace RoboidControl {
|
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 {
|
class DestroyMsg : public IMessage {
|
||||||
public:
|
public:
|
||||||
/// @brief The message ID
|
/// @brief The message ID
|
||||||
static const unsigned char id = 0x20;
|
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;
|
static const unsigned length = 3;
|
||||||
/// @brief The network ID of the thing
|
/// @brief The network ID of the thing
|
||||||
unsigned char networkId;
|
unsigned char networkId;
|
||||||
|
@ -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
|
|
@ -7,9 +7,9 @@ InvestigateMsg::InvestigateMsg(char* buffer) {
|
|||||||
this->networkId = buffer[ix++];
|
this->networkId = buffer[ix++];
|
||||||
this->thingId = 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->networkId = networkId;
|
||||||
this->thingId = thing->id;
|
this->thingId = thingId;
|
||||||
}
|
}
|
||||||
|
|
||||||
InvestigateMsg::~InvestigateMsg() {}
|
InvestigateMsg::~InvestigateMsg() {}
|
||||||
|
@ -1,7 +1,4 @@
|
|||||||
#pragma once
|
#include "Messages.h"
|
||||||
|
|
||||||
#include "IMessage.h"
|
|
||||||
#include "Thing.h"
|
|
||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
|
||||||
@ -17,10 +14,10 @@ class InvestigateMsg : public IMessage {
|
|||||||
/// @brief the ID of the thing
|
/// @brief the ID of the thing
|
||||||
unsigned char thingId;
|
unsigned char thingId;
|
||||||
|
|
||||||
/// @brief Create an investigate message
|
/// @brief Create a new message for sending
|
||||||
/// @param networkId The network ID for the thing
|
/// @param networkId The network ID for the thing
|
||||||
/// @param thing The thing for which the details are requested
|
/// @param thingId The ID of the thing
|
||||||
InvestigateMsg(unsigned char networkId, Thing* thing);
|
InvestigateMsg(unsigned char networkId, unsigned char thingId);
|
||||||
/// @copydoc RoboidControl::IMessage::IMessage(char*)
|
/// @copydoc RoboidControl::IMessage::IMessage(char*)
|
||||||
InvestigateMsg(char* buffer);
|
InvestigateMsg(char* buffer);
|
||||||
/// @brief Destructor for the message
|
/// @brief Destructor for the message
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
#pragma once
|
|
||||||
|
|
||||||
#include "LinearAlgebra/Spherical.h"
|
#include "LinearAlgebra/Spherical.h"
|
||||||
#include "LinearAlgebra/SwingTwist.h"
|
#include "LinearAlgebra/SwingTwist.h"
|
||||||
|
|
||||||
@ -7,18 +5,18 @@ namespace RoboidControl {
|
|||||||
|
|
||||||
class LowLevelMessages {
|
class LowLevelMessages {
|
||||||
public:
|
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 void SendSpherical(char* buffer, unsigned char* ix, Spherical s);
|
||||||
static Spherical ReceiveSpherical(const char* buffer,
|
static Spherical ReceiveSpherical(const char* buffer,
|
||||||
unsigned char* startIndex);
|
unsigned char* startIndex);
|
||||||
|
|
||||||
static void SendQuat32(char* buffer, unsigned char* ix, SwingTwist q);
|
static void SendQuat32(char* buffer, unsigned char* ix, SwingTwist q);
|
||||||
static SwingTwist ReceiveQuat32(const char* buffer, unsigned char* ix);
|
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
|
} // namespace RoboidControl
|
||||||
|
@ -1,4 +1,7 @@
|
|||||||
#include "IMessage.h"
|
#include "Messages.h"
|
||||||
|
|
||||||
|
#include "LowLevelMessages.h"
|
||||||
|
#include "string.h"
|
||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
|
22
Messages/Messages.h
Normal file
22
Messages/Messages.h
Normal 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
|
@ -1,7 +1,4 @@
|
|||||||
#pragma once
|
#include "Messages.h"
|
||||||
|
|
||||||
#include "IMessage.h"
|
|
||||||
#include "Thing.h"
|
|
||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
|
||||||
@ -29,6 +26,8 @@ class ModelUrlMsg : public IMessage {
|
|||||||
ModelUrlMsg(unsigned char networkId, Thing* thing);
|
ModelUrlMsg(unsigned char networkId, Thing* thing);
|
||||||
/// @copydoc RoboidControl::IMessage::IMessage(char*)
|
/// @copydoc RoboidControl::IMessage::IMessage(char*)
|
||||||
ModelUrlMsg(const char* buffer);
|
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
|
/// @brief Destructor for the message
|
||||||
virtual ~ModelUrlMsg();
|
virtual ~ModelUrlMsg();
|
||||||
|
@ -7,16 +7,15 @@ namespace RoboidControl {
|
|||||||
NameMsg::NameMsg(unsigned char networkId, Thing* thing) {
|
NameMsg::NameMsg(unsigned char networkId, Thing* thing) {
|
||||||
this->networkId = networkId;
|
this->networkId = networkId;
|
||||||
this->thingId = thing->id;
|
this->thingId = thing->id;
|
||||||
const char* thingName = thing->GetName();
|
if (thing->name == nullptr)
|
||||||
if (thingName == nullptr)
|
|
||||||
this->nameLength = 0;
|
this->nameLength = 0;
|
||||||
else
|
else
|
||||||
this->nameLength = (unsigned char)strlen(thingName);
|
this->nameLength = (unsigned char)strlen(thing->name);
|
||||||
|
|
||||||
// the name string in the buffer is not \0 terminated!
|
// the name string in the buffer is not \0 terminated!
|
||||||
char* name = new char[this->nameLength + 1];
|
char* name = new char[this->nameLength + 1];
|
||||||
for (int i = 0; i < this->nameLength; i++)
|
for (int i = 0; i < this->nameLength; i++)
|
||||||
name[i] = thingName[i];
|
name[i] = thing->name[i];
|
||||||
name[this->nameLength] = '\0';
|
name[this->nameLength] = '\0';
|
||||||
this->name = name;
|
this->name = name;
|
||||||
}
|
}
|
||||||
|
@ -1,7 +1,4 @@
|
|||||||
#pragma once
|
#include "Messages.h"
|
||||||
|
|
||||||
#include "IMessage.h"
|
|
||||||
#include "Thing.h"
|
|
||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
|
||||||
@ -25,6 +22,9 @@ class NameMsg : public IMessage {
|
|||||||
/// @param networkId The network ID of the thing
|
/// @param networkId The network ID of the thing
|
||||||
/// @param thing The ID of the thing
|
/// @param thing The ID of the thing
|
||||||
NameMsg(unsigned char networkId, Thing* 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*)
|
/// @copydoc RoboidControl::IMessage::IMessage(char*)
|
||||||
NameMsg(const char* buffer);
|
NameMsg(const char* buffer);
|
||||||
/// @brief Destructor for the message
|
/// @brief Destructor for the message
|
||||||
|
@ -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
|
|
@ -1,9 +1,5 @@
|
|||||||
#include "ParticipantMsg.h"
|
#include "ParticipantMsg.h"
|
||||||
|
|
||||||
#if !defined(NO_STD)
|
|
||||||
#include <iostream>
|
|
||||||
#endif
|
|
||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
|
||||||
ParticipantMsg::ParticipantMsg(char networkId) {
|
ParticipantMsg::ParticipantMsg(char networkId) {
|
||||||
@ -17,7 +13,7 @@ ParticipantMsg::ParticipantMsg(const char* buffer) {
|
|||||||
ParticipantMsg::~ParticipantMsg() {}
|
ParticipantMsg::~ParticipantMsg() {}
|
||||||
|
|
||||||
unsigned char ParticipantMsg::Serialize(char* buffer) {
|
unsigned char ParticipantMsg::Serialize(char* buffer) {
|
||||||
#if defined(DEBUG) && !defined(NO_STD)
|
#if defined(DEBUG)
|
||||||
std::cout << "Send ParticipantMsg [" << (int)this->networkId << "] "
|
std::cout << "Send ParticipantMsg [" << (int)this->networkId << "] "
|
||||||
<< std::endl;
|
<< std::endl;
|
||||||
#endif
|
#endif
|
||||||
|
@ -1,6 +1,6 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "IMessage.h"
|
#include "Messages.h"
|
||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
|
||||||
|
@ -8,11 +8,11 @@ PoseMsg::PoseMsg(unsigned char networkId, Thing* thing, bool force) {
|
|||||||
this->thingId = thing->id;
|
this->thingId = thing->id;
|
||||||
|
|
||||||
this->poseType = 0;
|
this->poseType = 0;
|
||||||
if (thing->positionUpdated || (force && thing->IsRoot())) {
|
if (thing->positionUpdated || force) {
|
||||||
this->position = thing->GetPosition();
|
this->position = thing->GetPosition();
|
||||||
this->poseType |= Pose_Position;
|
this->poseType |= Pose_Position;
|
||||||
}
|
}
|
||||||
if (thing->orientationUpdated || (force && thing->IsRoot())) {
|
if (thing->orientationUpdated || force) {
|
||||||
this->orientation = thing->GetOrientation();
|
this->orientation = thing->GetOrientation();
|
||||||
this->poseType |= Pose_Orientation;
|
this->poseType |= Pose_Orientation;
|
||||||
}
|
}
|
||||||
@ -45,7 +45,7 @@ unsigned char PoseMsg::Serialize(char* buffer) {
|
|||||||
if (this->poseType == 0)
|
if (this->poseType == 0)
|
||||||
return 0;
|
return 0;
|
||||||
|
|
||||||
#if defined(DEBUG) && DEBUG > 1
|
#if defined(DEBUG)
|
||||||
std::cout << "Send PoseMsg [" << (int)this->networkId << "/"
|
std::cout << "Send PoseMsg [" << (int)this->networkId << "/"
|
||||||
<< (int)this->thingId << "] " << (int)this->poseType << std::endl;
|
<< (int)this->thingId << "] " << (int)this->poseType << std::endl;
|
||||||
#endif
|
#endif
|
||||||
|
@ -1,6 +1,4 @@
|
|||||||
#pragma once
|
#include "Messages.h"
|
||||||
#include "IMessage.h"
|
|
||||||
#include "Thing.h"
|
|
||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
|
||||||
@ -11,7 +9,7 @@ class PoseMsg : public IMessage {
|
|||||||
public:
|
public:
|
||||||
/// @brief The message ID
|
/// @brief The message ID
|
||||||
static const unsigned char id = 0x10;
|
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;
|
unsigned char length = 4 + 4 + 4;
|
||||||
|
|
||||||
/// @brief The network ID of the thing
|
/// @brief The network ID of the thing
|
||||||
@ -43,7 +41,6 @@ class PoseMsg : public IMessage {
|
|||||||
/// @brief Create a new message for sending
|
/// @brief Create a new message for sending
|
||||||
/// @param networkId he network ID of the thing
|
/// @param networkId he network ID of the thing
|
||||||
/// @param thing The thing for which the pose shouldbe sent
|
/// @param thing The thing for which the pose shouldbe sent
|
||||||
/// @param force If true, position and orientation are always included, even when they are not updated
|
|
||||||
PoseMsg(unsigned char networkId, Thing* thing, bool force = false);
|
PoseMsg(unsigned char networkId, Thing* thing, bool force = false);
|
||||||
|
|
||||||
/// @copydoc RoboidControl::IMessage::IMessage(char*)
|
/// @copydoc RoboidControl::IMessage::IMessage(char*)
|
||||||
|
25
Messages/SiteMsg.cpp
Normal file
25
Messages/SiteMsg.cpp
Normal 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
|
@ -1,11 +1,9 @@
|
|||||||
#pragma once
|
#include "Messages.h"
|
||||||
|
|
||||||
#include "IMessage.h"
|
|
||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
|
||||||
/// @brief A message communicating the network ID for that participant
|
/// @brief A message communicating the network ID for that participant
|
||||||
class NetworkIdMsg : public IMessage {
|
class SiteMsg : public IMessage {
|
||||||
public:
|
public:
|
||||||
/// @brief The message ID
|
/// @brief The message ID
|
||||||
static const unsigned char id = 0xA1;
|
static const unsigned char id = 0xA1;
|
||||||
@ -16,11 +14,11 @@ public:
|
|||||||
|
|
||||||
/// @brief Create a new message for sending
|
/// @brief Create a new message for sending
|
||||||
/// @param networkId The network ID for the participant
|
/// @param networkId The network ID for the participant
|
||||||
NetworkIdMsg(unsigned char networkId);
|
SiteMsg(unsigned char networkId);
|
||||||
/// @copydoc RoboidControl::IMessage::IMessage(char*)
|
/// @copydoc RoboidControl::IMessage::IMessage(char*)
|
||||||
NetworkIdMsg(const char *buffer);
|
SiteMsg(const char *buffer);
|
||||||
/// @brief Destructor for the message
|
/// @brief Destructor for the message
|
||||||
virtual ~NetworkIdMsg();
|
virtual ~SiteMsg();
|
||||||
|
|
||||||
/// @copydoc RoboidControl::IMessage::Serialize
|
/// @copydoc RoboidControl::IMessage::Serialize
|
||||||
virtual unsigned char Serialize(char *buffer) override;
|
virtual unsigned char Serialize(char *buffer) override;
|
@ -1,9 +1,5 @@
|
|||||||
#include "TextMsg.h"
|
#include "TextMsg.h"
|
||||||
|
|
||||||
#if !defined(NO_STD)
|
|
||||||
#include <iostream>
|
|
||||||
#endif
|
|
||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
|
||||||
TextMsg::TextMsg(const char* text, unsigned char textLength) {
|
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)
|
if (this->textLength == 0 || this->text == nullptr)
|
||||||
return 0;
|
return 0;
|
||||||
|
|
||||||
#if defined(DEBUG) && !defined(NO_STD)
|
#if defined(DEBUG)
|
||||||
std::cout << "Send TextMsg " << (int)this->textLength << " " << this->text << std::endl;
|
std::cout << "Send TextMsg " << (int)this->textLength << " " << this->text << std::endl;
|
||||||
#endif
|
#endif
|
||||||
unsigned char ix = 0;
|
unsigned char ix = 0;
|
||||||
|
@ -1,4 +1,4 @@
|
|||||||
#include "IMessage.h"
|
#include "Messages.h"
|
||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
|
||||||
@ -9,6 +9,10 @@ class TextMsg : public IMessage {
|
|||||||
static const unsigned char id = 0xB0;
|
static const unsigned char id = 0xB0;
|
||||||
/// @brief The length of the message without the text itself
|
/// @brief The length of the message without the text itself
|
||||||
static const unsigned char length = 2;
|
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
|
/// @brief The text without the null terminator
|
||||||
const char* text;
|
const char* text;
|
||||||
/// @brief The length of the text
|
/// @brief The length of the text
|
||||||
|
@ -14,21 +14,27 @@ ThingMsg::ThingMsg(unsigned char networkId, Thing* thing) {
|
|||||||
this->networkId = networkId;
|
this->networkId = networkId;
|
||||||
this->thingId = thing->id;
|
this->thingId = thing->id;
|
||||||
this->thingType = thing->type;
|
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;
|
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() {}
|
ThingMsg::~ThingMsg() {}
|
||||||
|
|
||||||
unsigned char ThingMsg::Serialize(char* buffer) {
|
unsigned char ThingMsg::Serialize(char* buffer) {
|
||||||
#if defined(DEBUG)
|
#if defined(DEBUG)
|
||||||
std::cout << "Send ThingMsg [" << (int)this->networkId << "/"
|
std::cout << "Send ThingMsg [" << (int)this->networkId << "/" << (int)this->thingId
|
||||||
<< (int)this->thingId << "] " << (int)this->thingType << " "
|
<< "] " << (int)this->thingType << " " << (int)this->parentId << std::endl;
|
||||||
<< (int)this->parentId << std::endl;
|
|
||||||
#endif
|
#endif
|
||||||
unsigned char ix = 0;
|
unsigned char ix = 0;
|
||||||
buffer[ix++] = this->id;
|
buffer[ix++] = this->id;
|
||||||
|
@ -1,9 +1,8 @@
|
|||||||
#include "IMessage.h"
|
#include "Messages.h"
|
||||||
#include "Thing.h"
|
|
||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
|
||||||
/// @brief Message providing generic details about a Thing
|
/// @brief Message providing generic information about a Thing
|
||||||
class ThingMsg : public IMessage {
|
class ThingMsg : public IMessage {
|
||||||
public:
|
public:
|
||||||
/// @brief The message ID
|
/// @brief The message ID
|
||||||
@ -14,15 +13,17 @@ class ThingMsg : public IMessage {
|
|||||||
unsigned char networkId;
|
unsigned char networkId;
|
||||||
/// @brief The ID of the thing
|
/// @brief The ID of the thing
|
||||||
unsigned char thingId;
|
unsigned char thingId;
|
||||||
/// @brief The type of thing
|
/// @brief The Thing.Type of the thing
|
||||||
unsigned char thingType;
|
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;
|
unsigned char parentId;
|
||||||
|
|
||||||
/// @brief Create a message for sending
|
/// @brief Create a message for sending
|
||||||
/// @param networkId The network ID of the thing</param>
|
/// @param networkId The network ID of the thing</param>
|
||||||
/// @param thing The thing
|
/// @param thing The thing
|
||||||
ThingMsg(unsigned char networkId, Thing* 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*)
|
/// @copydoc RoboidControl::IMessage::IMessage(char*)
|
||||||
ThingMsg(const char* buffer);
|
ThingMsg(const char* buffer);
|
||||||
|
141
Participant.cpp
141
Participant.cpp
@ -4,30 +4,9 @@
|
|||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
|
||||||
#pragma region Participant
|
Participant::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(const char* ipAddress, int port) {
|
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
|
// make a copy of the ip address string
|
||||||
int addressLength = (int)strlen(ipAddress);
|
int addressLength = (int)strlen(ipAddress);
|
||||||
int stringLength = addressLength + 1;
|
int stringLength = addressLength + 1;
|
||||||
@ -45,14 +24,13 @@ Participant::Participant(const char* ipAddress, int port) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
Participant::~Participant() {
|
Participant::~Participant() {
|
||||||
// registry.Remove(this);
|
|
||||||
delete[] this->ipAddress;
|
delete[] this->ipAddress;
|
||||||
}
|
}
|
||||||
|
|
||||||
void Participant::Update() {
|
void Participant::Update(unsigned long currentTimeMs) {
|
||||||
for (Thing* thing : this->things) {
|
for (Thing* thing : this->things) {
|
||||||
if (thing != nullptr)
|
if (thing != nullptr)
|
||||||
thing->Update(true);
|
thing->Update(currentTimeMs, true);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -61,8 +39,7 @@ Thing* Participant::Get(unsigned char thingId) {
|
|||||||
if (thing->id == thingId)
|
if (thing->id == thingId)
|
||||||
return thing;
|
return thing;
|
||||||
}
|
}
|
||||||
// std::cout << "Could not find thing " << this->ipAddress << ":" <<
|
// std::cout << "Could not find thing " << this->ipAddress << ":" << this->port
|
||||||
// this->port
|
|
||||||
// << "[" << (int)thingId << "]\n";
|
// << "[" << (int)thingId << "]\n";
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
@ -74,15 +51,7 @@ void Participant::Add(Thing* thing, bool checkId) {
|
|||||||
thing->id = this->thingCount + 1;
|
thing->id = this->thingCount + 1;
|
||||||
this->things[this->thingCount++] = thing;
|
this->things[this->thingCount++] = thing;
|
||||||
#else
|
#else
|
||||||
// find highest id
|
thing->id = (unsigned char)this->things.size() + 1;
|
||||||
int highestIx = 0;
|
|
||||||
for (Thing* thing : this->things) {
|
|
||||||
if (thing == nullptr)
|
|
||||||
continue;
|
|
||||||
if (thing->id > highestIx)
|
|
||||||
highestIx = thing->id;
|
|
||||||
}
|
|
||||||
thing->id = highestIx + 1;
|
|
||||||
this->things.push_back(thing);
|
this->things.push_back(thing);
|
||||||
#endif
|
#endif
|
||||||
// std::cout << "Add thing with generated ID " << this->ipAddress << ":"
|
// std::cout << "Add thing with generated ID " << this->ipAddress << ":"
|
||||||
@ -95,8 +64,7 @@ void Participant::Add(Thing* thing, bool checkId) {
|
|||||||
#else
|
#else
|
||||||
this->things.push_back(thing);
|
this->things.push_back(thing);
|
||||||
#endif
|
#endif
|
||||||
// std::cout << "Add thing " << this->ipAddress << ":" << this->port <<
|
// std::cout << "Add thing " << this->ipAddress << ":" << this->port << "["
|
||||||
// "["
|
|
||||||
// << (int)thing->id << "]\n";
|
// << (int)thing->id << "]\n";
|
||||||
} else {
|
} else {
|
||||||
// std::cout << "Did not add, existing thing " << this->ipAddress << ":"
|
// std::cout << "Did not add, existing thing " << this->ipAddress << ":"
|
||||||
@ -121,93 +89,22 @@ void Participant::Remove(Thing* thing) {
|
|||||||
this->thingCount = lastThingIx;
|
this->thingCount = lastThingIx;
|
||||||
#else
|
#else
|
||||||
this->things.remove_if([thing](Thing* obj) { return obj == thing; });
|
this->things.remove_if([thing](Thing* obj) { return obj == thing; });
|
||||||
// std::cout << "Removing [" << (int)thing->networkId << "/" << (int)thing->id
|
std::cout << "Removing " << thing->networkId << "/" << thing->id
|
||||||
// << "] list size = " << this->things.size() << "\n";
|
<< " list size = " << this->things.size() << "\n";
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
#pragma endregion
|
// void Participant::UpdateAll(unsigned long currentTimeMs) {
|
||||||
|
// // Not very efficient, but it works for now.
|
||||||
|
|
||||||
#pragma region ParticipantRegistry
|
// for (Thing* thing : this->things) {
|
||||||
|
// if (thing != nullptr && thing->GetParent() == nullptr) { // update all
|
||||||
Participant* ParticipantRegistry::Get(const char* ipAddress,
|
// root things
|
||||||
unsigned int port) {
|
// // std::cout << " update " << (int)ix << " thingid " << (int)thing->id
|
||||||
#if !defined(NO_STD)
|
// // << "\n";
|
||||||
for (Participant* participant : ParticipantRegistry::participants) {
|
// thing->Update(currentTimeMs);
|
||||||
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
|
|
||||||
|
|
||||||
} // namespace RoboidControl
|
} // namespace RoboidControl
|
||||||
|
@ -1,57 +1,10 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "Thing.h"
|
#include "Thing.h"
|
||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
|
||||||
constexpr int MAX_THING_COUNT = 256;
|
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.
|
/// @brief A participant is a device which manages things.
|
||||||
/// It can communicate with other participant to synchronise the state of
|
/// It can communicate with other participant to synchronise the state of
|
||||||
/// things. This class is used to register the things the participant is
|
/// things. This class is used to register the things the participant is
|
||||||
@ -60,56 +13,52 @@ class ParticipantRegistry {
|
|||||||
/// reference to remote participants.
|
/// reference to remote participants.
|
||||||
class Participant {
|
class Participant {
|
||||||
public:
|
public:
|
||||||
/// @brief The name of the participant
|
/// @brief The Ip Address of a participant. When the participant is local,
|
||||||
const char* name = "Participant";
|
/// this contains 0.0.0.0
|
||||||
|
|
||||||
/// @brief The Ip Address of a participant.
|
|
||||||
const char* ipAddress = "0.0.0.0";
|
const char* ipAddress = "0.0.0.0";
|
||||||
/// @brief The port number for UDP communication with the participant.
|
/// @brief The port number for UDP communication with the participant. This is
|
||||||
unsigned int port = 0;
|
/// 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;
|
unsigned char networkId = 0;
|
||||||
|
|
||||||
|
/// @brief Default constructor
|
||||||
Participant();
|
Participant();
|
||||||
/// @brief Create a new participant with the given communcation info
|
/// @brief Create a new participant with the given communcation info
|
||||||
/// @param ipAddress The IP address of the participant
|
/// @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);
|
Participant(const char* ipAddress, int port);
|
||||||
/// @brief Destructor for the participant
|
/// @brief Destructor for the participant
|
||||||
~Participant();
|
~Participant();
|
||||||
|
|
||||||
static Participant* LocalParticipant;
|
virtual void Update(unsigned long currentTimeMs = 0);
|
||||||
static void ReplaceLocalParticipant(Participant& newParticipant);
|
|
||||||
|
|
||||||
Thing* root = new Thing(this);
|
protected:
|
||||||
|
|
||||||
public:
|
|
||||||
#if defined(NO_STD)
|
#if defined(NO_STD)
|
||||||
unsigned char thingCount = 0;
|
unsigned char thingCount = 0;
|
||||||
Thing* things[MAX_THING_COUNT];
|
Thing* things[MAX_THING_COUNT];
|
||||||
#else
|
#else
|
||||||
/// @brief The things managed by this participant
|
/// @brief The list of things managed by this participant
|
||||||
std::list<Thing*> things;
|
std::list<Thing*> things;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
public:
|
||||||
/// @brief Find a thing managed by this participant
|
/// @brief Find a thing managed by this participant
|
||||||
|
/// @param networkId The network ID for the thing
|
||||||
/// @param thingId The ID of 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);
|
Thing* Get(unsigned char thingId);
|
||||||
/// @brief Add a new thing for this participant.
|
/// @brief Add a new thing for this participant.
|
||||||
/// @param thing The thing to add
|
/// @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);
|
void Add(Thing* thing, bool checkId = true);
|
||||||
/// @brief Remove a thing for this participant
|
/// @brief Remove a thing for this participant
|
||||||
/// @param thing The thing to remove
|
/// @param thing The thing to remove
|
||||||
void Remove(Thing* thing);
|
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
|
} // namespace RoboidControl
|
||||||
|
@ -1,49 +1,44 @@
|
|||||||
#include "ParticipantUDP.h"
|
#include "ParticipantUDP.h"
|
||||||
|
|
||||||
#include "Participant.h"
|
|
||||||
#include "Thing.h"
|
#include "Thing.h"
|
||||||
|
|
||||||
#include "Arduino/ArduinoParticipant.h"
|
#include "Arduino/ArduinoParticipant.h"
|
||||||
#include "EspIdf/EspIdfParticipant.h"
|
#include "EspIdf/EspIdfParticipant.h"
|
||||||
#include "Posix/PosixParticipant.h"
|
|
||||||
|
#if defined(_WIN32) || defined(_WIN64)
|
||||||
|
#include <winsock2.h>
|
||||||
|
#include <ws2tcpip.h>
|
||||||
#include "Windows/WindowsParticipant.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>
|
#include <string.h>
|
||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
|
||||||
#pragma region Init
|
ParticipantUDP::ParticipantUDP(int port) {
|
||||||
|
this->ipAddress = "0.0.0.0";
|
||||||
ParticipantUDP::ParticipantUDP(int port) : Participant("127.0.0.1", port) {
|
this->port = port;
|
||||||
this->name = "ParticipantUDP";
|
|
||||||
this->remoteSite = nullptr;
|
this->remoteSite = nullptr;
|
||||||
if (this->port == 0)
|
if (this->port == 0)
|
||||||
this->isIsolated = true;
|
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)
|
ParticipantUDP::ParticipantUDP(const char* ipAddress, int port, int localPort)
|
||||||
: Participant("127.0.0.1", localPort) {
|
: Participant("127.0.0.1", localPort) {
|
||||||
this->name = "ParticipantUDP";
|
|
||||||
if (this->port == 0)
|
if (this->port == 0)
|
||||||
this->isIsolated = true;
|
this->isIsolated = true;
|
||||||
else
|
else
|
||||||
this->remoteSite = new Participant(ipAddress, port);
|
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;
|
static ParticipantUDP* isolatedParticipant = nullptr;
|
||||||
@ -55,7 +50,7 @@ ParticipantUDP* ParticipantUDP::Isolated() {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void ParticipantUDP::begin() {
|
void ParticipantUDP::begin() {
|
||||||
if (this->isIsolated || this->remoteSite == nullptr)
|
if (this->isIsolated)
|
||||||
return;
|
return;
|
||||||
|
|
||||||
SetupUDP(this->port, this->remoteSite->ipAddress, this->remoteSite->port);
|
SetupUDP(this->port, this->remoteSite->ipAddress, this->remoteSite->port);
|
||||||
@ -74,27 +69,18 @@ void ParticipantUDP::SetupUDP(int localPort,
|
|||||||
#elif defined(ARDUINO)
|
#elif defined(ARDUINO)
|
||||||
Arduino::ParticipantUDP* thisArduino =
|
Arduino::ParticipantUDP* thisArduino =
|
||||||
static_cast<Arduino::ParticipantUDP*>(this);
|
static_cast<Arduino::ParticipantUDP*>(this);
|
||||||
thisArduino->Setup();
|
thisArduino->Setup(); // localPort, remoteIpAddress, remotePort);
|
||||||
#elif defined(IDF_VER)
|
#elif defined(IDF_VER)
|
||||||
EspIdf::ParticipantUDP* thisEspIdf =
|
EspIdf::ParticipantUDP* thisEspIdf =
|
||||||
static_cast<EspIdf::ParticipantUDP*>(this);
|
static_cast<EspIdf::ParticipantUDP*>(this);
|
||||||
thisEspIdf->Setup(localPort, remoteIpAddress, remotePort);
|
thisEspIdf->Setup(); // localPort, remoteIpAddress, remotePort);
|
||||||
#endif
|
#endif
|
||||||
this->connected = true;
|
this->connected = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
#pragma endregion Init
|
void ParticipantUDP::Update(unsigned long currentTimeMs) {
|
||||||
|
if (currentTimeMs == 0)
|
||||||
#pragma region Update
|
currentTimeMs = Thing::GetTimeMs();
|
||||||
|
|
||||||
// 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();
|
|
||||||
|
|
||||||
if (this->isIsolated == false) {
|
if (this->isIsolated == false) {
|
||||||
if (this->connected == false)
|
if (this->connected == false)
|
||||||
@ -114,111 +100,66 @@ void ParticipantUDP::Update() {
|
|||||||
this->ReceiveUDP();
|
this->ReceiveUDP();
|
||||||
}
|
}
|
||||||
|
|
||||||
UpdateMyThings();
|
|
||||||
UpdateOtherThings();
|
|
||||||
}
|
|
||||||
|
|
||||||
void ParticipantUDP::PrepMyThings() {
|
|
||||||
for (Thing* thing : this->things) {
|
for (Thing* thing : this->things) {
|
||||||
if (thing == nullptr)
|
if (thing == nullptr)
|
||||||
continue;
|
continue;
|
||||||
|
|
||||||
thing->PrepareForUpdate();
|
if (this->isIsolated == false) {
|
||||||
}
|
//std::cout << "thingg " << thing->name << " pos upd. " << thing->positionUpdated << std::endl;
|
||||||
}
|
|
||||||
|
|
||||||
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);
|
PoseMsg* poseMsg = new PoseMsg(this->networkId, thing);
|
||||||
this->Send(this->remoteSite, poseMsg);
|
this->Send(thing->owner, poseMsg);
|
||||||
delete poseMsg;
|
|
||||||
BinaryMsg* binaryMsg = new BinaryMsg(this->networkId, thing);
|
BinaryMsg* binaryMsg = new BinaryMsg(this->networkId, thing);
|
||||||
this->Send(this->remoteSite, binaryMsg);
|
this->Send(thing->owner, 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);
|
|
||||||
delete poseMsg;
|
delete poseMsg;
|
||||||
BinaryMsg* binaryMsg = new BinaryMsg(participant->networkId, thing);
|
|
||||||
this->Send(participant, binaryMsg);
|
|
||||||
delete binaryMsg;
|
|
||||||
}
|
}
|
||||||
|
thing->Update(currentTimeMs, true);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Update
|
void ParticipantUDP::ReceiveUDP() {
|
||||||
#pragma endregion
|
#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
|
#pragma region Send
|
||||||
|
|
||||||
void ParticipantUDP::SendThingInfo(Participant* remoteParticipant,
|
void ParticipantUDP::SendThingInfo(Participant* remoteParticipant,
|
||||||
Thing* thing) {
|
Thing* thing, bool recurse) {
|
||||||
// std::cout << "Send thing info [" << (int)thing->id << "] \n";
|
// std::cout << "Send thing info [" << (int)thing->id << "] \n";
|
||||||
ThingMsg* thingMsg = new ThingMsg(this->networkId, thing);
|
ThingMsg* thingMsg = new ThingMsg(this->networkId, thing);
|
||||||
this->Send(remoteParticipant, thingMsg);
|
this->Send(remoteParticipant, thingMsg);
|
||||||
@ -235,6 +176,11 @@ void ParticipantUDP::SendThingInfo(Participant* remoteParticipant,
|
|||||||
BinaryMsg* customMsg = new BinaryMsg(this->networkId, thing);
|
BinaryMsg* customMsg = new BinaryMsg(this->networkId, thing);
|
||||||
this->Send(remoteParticipant, customMsg);
|
this->Send(remoteParticipant, customMsg);
|
||||||
delete 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) {
|
bool ParticipantUDP::Send(Participant* remoteParticipant, IMessage* msg) {
|
||||||
@ -242,9 +188,6 @@ bool ParticipantUDP::Send(Participant* remoteParticipant, IMessage* msg) {
|
|||||||
if (bufferSize <= 0)
|
if (bufferSize <= 0)
|
||||||
return true;
|
return true;
|
||||||
|
|
||||||
// std::cout << "send msg " << (static_cast<int>(this->buffer[0]) & 0xff)
|
|
||||||
// << " to " << remoteParticipant->ipAddress << std::endl;
|
|
||||||
|
|
||||||
#if defined(_WIN32) || defined(_WIN64)
|
#if defined(_WIN32) || defined(_WIN64)
|
||||||
Windows::ParticipantUDP* thisWindows =
|
Windows::ParticipantUDP* thisWindows =
|
||||||
static_cast<Windows::ParticipantUDP*>(this);
|
static_cast<Windows::ParticipantUDP*>(this);
|
||||||
@ -287,7 +230,6 @@ void ParticipantUDP::PublishThingInfo(Thing* thing) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
bool ParticipantUDP::Publish(IMessage* msg) {
|
bool ParticipantUDP::Publish(IMessage* msg) {
|
||||||
// std::cout << "publish msg\n";
|
|
||||||
#if defined(_WIN32) || defined(_WIN64)
|
#if defined(_WIN32) || defined(_WIN64)
|
||||||
Windows::ParticipantUDP* thisWindows =
|
Windows::ParticipantUDP* thisWindows =
|
||||||
static_cast<Windows::ParticipantUDP*>(this);
|
static_cast<Windows::ParticipantUDP*>(this);
|
||||||
@ -313,37 +255,14 @@ bool ParticipantUDP::Publish(IMessage* msg) {
|
|||||||
|
|
||||||
#pragma region Receive
|
#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,
|
void ParticipantUDP::ReceiveData(unsigned char packetSize,
|
||||||
char* senderIpAddress,
|
char* senderIpAddress,
|
||||||
unsigned int senderPort) {
|
unsigned int senderPort) {
|
||||||
// std::cout << "Receive data from " << senderIpAddress << ":" << senderPort
|
Participant* sender = this->GetParticipant(senderIpAddress, senderPort);
|
||||||
// << std::endl;
|
|
||||||
Participant* sender = this->registry.Get(senderIpAddress, senderPort);
|
|
||||||
if (sender == nullptr) {
|
if (sender == nullptr) {
|
||||||
sender = this->registry.Add(senderIpAddress, senderPort);
|
sender = this->AddParticipant(senderIpAddress, senderPort);
|
||||||
#if !defined(NO_STD)
|
|
||||||
std::cout << "New remote participant " << sender->ipAddress << ":"
|
std::cout << "New remote participant " << sender->ipAddress << ":"
|
||||||
<< sender->port << std::endl;
|
<< sender->port << std::endl;
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
ReceiveData(packetSize, sender);
|
ReceiveData(packetSize, sender);
|
||||||
@ -361,8 +280,8 @@ void ParticipantUDP::ReceiveData(unsigned char bufferSize,
|
|||||||
Process(sender, msg);
|
Process(sender, msg);
|
||||||
delete msg;
|
delete msg;
|
||||||
} break;
|
} break;
|
||||||
case NetworkIdMsg::id: {
|
case SiteMsg::id: {
|
||||||
NetworkIdMsg* msg = new NetworkIdMsg(this->buffer);
|
SiteMsg* msg = new SiteMsg(this->buffer);
|
||||||
bufferSize -= msg->length;
|
bufferSize -= msg->length;
|
||||||
Process(sender, msg);
|
Process(sender, msg);
|
||||||
delete msg;
|
delete msg;
|
||||||
@ -405,10 +324,8 @@ void ParticipantUDP::ReceiveData(unsigned char bufferSize,
|
|||||||
};
|
};
|
||||||
|
|
||||||
// Check if the buffer has been read completely
|
// Check if the buffer has been read completely
|
||||||
#if !defined(NO_STD)
|
|
||||||
if (bufferSize > 0)
|
if (bufferSize > 0)
|
||||||
std::cout << "Buffer not fully read, remaining " << (int)bufferSize << "\n";
|
std::cout << "Buffer not fully read, remaining " << (int)bufferSize << "\n";
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void ParticipantUDP::Process(Participant* sender, ParticipantMsg* msg) {
|
void ParticipantUDP::Process(Participant* sender, ParticipantMsg* msg) {
|
||||||
@ -418,18 +335,17 @@ void ParticipantUDP::Process(Participant* sender, ParticipantMsg* msg) {
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void ParticipantUDP::Process(Participant* sender, NetworkIdMsg* msg) {
|
void ParticipantUDP::Process(Participant* sender, SiteMsg* msg) {
|
||||||
#if defined(DEBUG)
|
#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";
|
<< " -> " << (int)msg->networkId << "\n";
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
if (this->networkId != msg->networkId) {
|
if (this->networkId != msg->networkId) {
|
||||||
this->networkId = msg->networkId;
|
this->networkId = msg->networkId;
|
||||||
|
|
||||||
std::cout << this->things.size() << " things\n";
|
std::cout << this->things.size() << " things\n";
|
||||||
for (Thing* thing : this->things)
|
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
|
nameLength); // Leave space for null terminator
|
||||||
#endif
|
#endif
|
||||||
thingName[nameLength] = '\0';
|
thingName[nameLength] = '\0';
|
||||||
thing->SetName(thingName);
|
thing->name = thingName;
|
||||||
|
|
||||||
#if !defined(NO_STD)
|
std::cout << thing->name;
|
||||||
std::cout << thing->GetName();
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
#if !defined(NO_STD)
|
|
||||||
std::cout << std::endl;
|
std::cout << std::endl;
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void ParticipantUDP::Process(Participant* sender, ModelUrlMsg* msg) {
|
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) {
|
void ParticipantUDP::Process(Participant* sender, PoseMsg* msg) {
|
||||||
#if !defined(DEBUG) && !defined(NO_STD)
|
#if defined(DEBUG)
|
||||||
std::cout << this->name << ": process PoseMsg [" << (int)this->networkId
|
std::cout << this->name << ": process PoseMsg [" << (int)msg->networkId
|
||||||
<< "/" << (int)msg->networkId << "] " << (int)msg->poseType << "\n";
|
<< "/" << (int)msg->thingId << "]\n";
|
||||||
#endif
|
#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) {
|
void ParticipantUDP::Process(Participant* sender, BinaryMsg* msg) {
|
||||||
#if defined(DEBUG)
|
#if defined(DEBUG)
|
||||||
std::cout << this->name << ": process BinaryMsg [" << (int)msg->networkId
|
std::cout << this->name << ": process BinaryMsg [" << (int)msg->networkId
|
||||||
<< "/" << (int)msg->thingId << "]\n";
|
<< "/" << (int)msg->thingId << "] ";
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
Participant* owner = Participant::registry.Get(msg->networkId);
|
Thing* thing = sender->Get(msg->thingId);
|
||||||
if (owner != nullptr) {
|
|
||||||
Thing* thing = owner->Get(msg->thingId);
|
|
||||||
if (thing != nullptr)
|
if (thing != nullptr)
|
||||||
thing->ProcessBinary(msg->data);
|
thing->ProcessBinary(msg->data);
|
||||||
#if !defined(NO_STD)
|
|
||||||
else {
|
else {
|
||||||
#if defined(DEBUG)
|
|
||||||
std::cout << " unknown thing [" << (int)msg->networkId << "/"
|
std::cout << " unknown thing [" << (int)msg->networkId << "/"
|
||||||
<< (int)msg->thingId << "]";
|
<< (int)msg->thingId << "]";
|
||||||
#endif
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
std::cout << std::endl;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Receive
|
// Receive
|
||||||
|
@ -1,13 +1,12 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "Messages/BinaryMsg.h"
|
#include "Messages/BinaryMsg.h"
|
||||||
#include "Messages/DestroyMsg.h"
|
|
||||||
#include "Messages/InvestigateMsg.h"
|
#include "Messages/InvestigateMsg.h"
|
||||||
#include "Messages/ModelUrlMsg.h"
|
#include "Messages/ModelUrlMsg.h"
|
||||||
#include "Messages/NameMsg.h"
|
#include "Messages/NameMsg.h"
|
||||||
#include "Messages/ParticipantMsg.h"
|
#include "Messages/ParticipantMsg.h"
|
||||||
#include "Messages/PoseMsg.h"
|
#include "Messages/PoseMsg.h"
|
||||||
#include "Messages/NetworkIdMsg.h"
|
#include "Messages/SiteMsg.h"
|
||||||
#include "Messages/ThingMsg.h"
|
#include "Messages/ThingMsg.h"
|
||||||
#include "Participant.h"
|
#include "Participant.h"
|
||||||
|
|
||||||
@ -30,8 +29,7 @@ namespace RoboidControl {
|
|||||||
|
|
||||||
constexpr int MAX_SENDER_COUNT = 256;
|
constexpr int MAX_SENDER_COUNT = 256;
|
||||||
|
|
||||||
/// @brief A participant using UDP communication
|
/// @brief A local participant is the local device which can communicate with
|
||||||
/// A local participant is the local device which can communicate with
|
|
||||||
/// other participants It manages all local things and communcation with other
|
/// other participants It manages all local things and communcation with other
|
||||||
/// participants. Each application has a local participant which is usually
|
/// participants. Each application has a local participant which is usually
|
||||||
/// explicit in the code. An participant can be isolated. In that case it is
|
/// 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().
|
/// RoboidControl::IsolatedParticipant::Isolated().
|
||||||
/// @sa RoboidControl::Thing::Thing()
|
/// @sa RoboidControl::Thing::Thing()
|
||||||
class ParticipantUDP : public Participant {
|
class ParticipantUDP : public Participant {
|
||||||
#pragma region Init
|
|
||||||
|
|
||||||
public:
|
public:
|
||||||
/// @brief Create a participant without connecting to a site
|
/// @brief Create a participant without connecting to a site
|
||||||
/// @param port The port on which the participant communicates
|
/// @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.
|
/// @brief Create a participant which will try to connect to a site.
|
||||||
/// @param ipAddress The IP address of the site
|
/// @param ipAddress The IP address of the site
|
||||||
/// @param port The port used by the site
|
/// @param port The port used by the site
|
||||||
/// @param localPort The port used by the local participant
|
ParticipantUDP(const char* ipAddress,
|
||||||
ParticipantUDP(const char* ipAddress, int port = 7681, int localPort = 7681);
|
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
|
/// @brief Isolated participant is used when the application is run without
|
||||||
/// networking
|
/// networking
|
||||||
@ -65,23 +64,28 @@ class ParticipantUDP : public Participant {
|
|||||||
|
|
||||||
/// @brief True if the participant is running isolated.
|
/// @brief True if the participant is running isolated.
|
||||||
/// Isolated participants do not communicate with other participants
|
/// 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;
|
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
|
/// The interval in milliseconds for publishing (broadcasting) data on the
|
||||||
/// local network
|
/// local network
|
||||||
long publishInterval = 3000; // 3 seconds
|
long publishInterval = 3000; // 3 seconds
|
||||||
|
|
||||||
protected:
|
/// @brief The name of the participant
|
||||||
char buffer[1024];
|
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__)
|
#if defined(__unix__) || defined(__APPLE__)
|
||||||
int sock;
|
int sock;
|
||||||
#elif defined(_WIN32) || defined(_WIN64)
|
#elif defined(_WIN32) || defined(_WIN64)
|
||||||
@ -89,50 +93,46 @@ class ParticipantUDP : public Participant {
|
|||||||
sockaddr_in server_addr;
|
sockaddr_in server_addr;
|
||||||
sockaddr_in broadcast_addr;
|
sockaddr_in broadcast_addr;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
public:
|
|
||||||
void begin();
|
void begin();
|
||||||
bool connected = false;
|
bool connected = false;
|
||||||
|
|
||||||
#pragma region Update
|
virtual void Update(unsigned long currentTimeMs = 0) override;
|
||||||
|
|
||||||
public:
|
void SendThingInfo(Participant* remoteParticipant, Thing* thing, bool recurse = false);
|
||||||
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 PublishThingInfo(Thing* thing);
|
void PublishThingInfo(Thing* thing);
|
||||||
|
|
||||||
bool Send(Participant* remoteParticipant, IMessage* msg);
|
bool Send(Participant* remoteParticipant, IMessage* msg);
|
||||||
bool Publish(IMessage* msg);
|
bool Publish(IMessage* msg);
|
||||||
|
|
||||||
#pragma endregion Send
|
|
||||||
|
|
||||||
#pragma region Receive
|
|
||||||
|
|
||||||
protected:
|
|
||||||
void ReceiveData(unsigned char bufferSize,
|
void ReceiveData(unsigned char bufferSize,
|
||||||
char* senderIpAddress,
|
char* senderIpAddress,
|
||||||
unsigned int senderPort);
|
unsigned int senderPort);
|
||||||
void ReceiveData(unsigned char bufferSize, Participant* remoteParticipant);
|
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);
|
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();
|
void ReceiveUDP();
|
||||||
|
|
||||||
virtual void Process(Participant* sender, ParticipantMsg* msg);
|
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, InvestigateMsg* msg);
|
||||||
virtual void Process(Participant* sender, ThingMsg* msg);
|
virtual void Process(Participant* sender, ThingMsg* msg);
|
||||||
virtual void Process(Participant* sender, NameMsg* 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, PoseMsg* msg);
|
||||||
virtual void Process(Participant* sender, BinaryMsg* 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
|
} // namespace RoboidControl
|
||||||
|
@ -9,89 +9,58 @@
|
|||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
|
||||||
#pragma region Init
|
SiteServer::SiteServer(int port) {
|
||||||
|
|
||||||
SiteServer::SiteServer(int port) : ParticipantUDP(port) {
|
|
||||||
this->name = "Site Server";
|
this->name = "Site Server";
|
||||||
this->publishInterval = 0;
|
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)
|
#if defined(NO_STD)
|
||||||
Participant** participants = Participant::registry.GetAll();
|
this->senders[this->senderCount++] = this;
|
||||||
for (int ix = 0; ix < Participant::registry.count; ix++) {
|
|
||||||
Participant* participant = participants[ix];
|
|
||||||
#else
|
#else
|
||||||
for (Participant* participant : Participant::registry.GetAll()) {
|
this->senders.push_back(this);
|
||||||
#endif
|
#endif
|
||||||
if (participant == nullptr || participant == this)
|
|
||||||
continue;
|
|
||||||
|
|
||||||
PoseMsg* poseMsg = new PoseMsg(this->networkId, thing);
|
SetupUDP(port, ipAddress, 0);
|
||||||
this->Send(participant, poseMsg);
|
|
||||||
delete poseMsg;
|
|
||||||
BinaryMsg* binaryMsg = new BinaryMsg(this->networkId, thing);
|
|
||||||
this->Send(participant, binaryMsg);
|
|
||||||
delete binaryMsg;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
#pragma endregion Update
|
#if !defined(NO_STD)
|
||||||
|
// Register<TemperatureSensor>((unsigned char)Thing::Type::TemperatureSensor);
|
||||||
#pragma region Receive
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
void SiteServer::Process(Participant* sender, ParticipantMsg* msg) {
|
void SiteServer::Process(Participant* sender, ParticipantMsg* msg) {
|
||||||
if (msg->networkId != sender->networkId) {
|
if (msg->networkId == 0) {
|
||||||
// std::cout << this->name << " received New Client -> " <<
|
// std::cout << this->name << " received New Client -> " <<
|
||||||
// sender->ipAddress
|
// sender->ipAddress
|
||||||
// << ":" << (int)sender->port << "\n";
|
// << ":" << (int)sender->port << "\n";
|
||||||
NetworkIdMsg* msg = new NetworkIdMsg(sender->networkId);
|
SiteMsg* msg = new SiteMsg(sender->networkId);
|
||||||
this->Send(sender, msg);
|
this->Send(sender, msg);
|
||||||
delete msg;
|
delete msg;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void SiteServer::Process(Participant* sender, NetworkIdMsg* msg) {}
|
void SiteServer::Process(Participant* sender, SiteMsg* msg) {}
|
||||||
|
|
||||||
void SiteServer::Process(Participant* sender, ThingMsg* msg) {
|
void SiteServer::Process(Participant* sender, ThingMsg* msg) {
|
||||||
Thing* thing = sender->Get(msg->thingId);
|
Thing* thing = sender->Get(msg->thingId);
|
||||||
if (thing == nullptr)
|
if (thing == nullptr) {
|
||||||
// new Thing(sender, (Thing::Type)msg->thingType, msg->thingId);
|
// #if defined(NO_STD)
|
||||||
// Thing::Reconstruct(sender, msg->thingType, msg->thingId);
|
new Thing(sender, (Thing::Type)msg->thingType,
|
||||||
//thing = new Thing(msg->thingType, sender->root);
|
msg->thingId);
|
||||||
;
|
// #else
|
||||||
thing->id = msg->thingId;
|
// auto thingMsgProcessor = thingMsgProcessors.find(msg->thingType);
|
||||||
|
// //Thing* newThing;
|
||||||
if (msg->parentId != 0) {
|
// if (thingMsgProcessor != thingMsgProcessors.end()) // found item
|
||||||
thing->SetParent(Get(msg->parentId));
|
// //newThing =
|
||||||
if (thing->IsRoot())
|
// thingMsgProcessor->second(sender, msg->networkId,
|
||||||
// if (thing->GetParent() != nullptr)
|
// msg->thingId);
|
||||||
#if defined(NO_STD)
|
// else
|
||||||
;
|
// //newThing =
|
||||||
#else
|
// new Thing(sender, msg->networkId, msg->thingId,
|
||||||
std::cout << "Could not find parent [" << (int)msg->networkId << "/"
|
// (Thing::Type)msg->thingType);
|
||||||
<< (int)msg->parentId << "]\n";
|
// #endif
|
||||||
#endif
|
}
|
||||||
} else
|
|
||||||
thing->SetParent(Thing::LocalRoot());
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#pragma endregion Receive
|
|
||||||
|
|
||||||
} // namespace RoboidControl
|
} // namespace RoboidControl
|
||||||
|
@ -12,33 +12,35 @@ namespace RoboidControl {
|
|||||||
|
|
||||||
/// @brief A participant is device which can communicate with other participants
|
/// @brief A participant is device which can communicate with other participants
|
||||||
class SiteServer : public ParticipantUDP {
|
class SiteServer : public ParticipantUDP {
|
||||||
|
|
||||||
#pragma region Init
|
|
||||||
|
|
||||||
public:
|
public:
|
||||||
/// @brief Create a new site server
|
|
||||||
/// @param port The port of which to receive the messages
|
|
||||||
SiteServer(int port = 7681);
|
SiteServer(int port = 7681);
|
||||||
|
|
||||||
#pragma endregion Init
|
// virtual void Update(unsigned long currentTimeMs = 0) override;
|
||||||
|
|
||||||
#pragma region Update
|
// #if !defined(NO_STD)
|
||||||
|
// template <typename ThingClass>
|
||||||
virtual void UpdateMyThings() override;
|
// void Register(unsigned char thingType) {
|
||||||
|
// thingMsgProcessors[thingType] = [](Participant* participant,
|
||||||
#pragma endregion Update
|
// unsigned char networkId,
|
||||||
|
// unsigned char thingId) {
|
||||||
#pragma region Receive
|
// return new ThingClass(participant, networkId, thingId);
|
||||||
|
// };
|
||||||
|
// };
|
||||||
|
// #endif
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
unsigned long nextPublishMe = 0;
|
unsigned long nextPublishMe = 0;
|
||||||
|
|
||||||
virtual void Process(Participant* sender, ParticipantMsg* msg) override;
|
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;
|
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
|
} // namespace RoboidControl
|
||||||
|
@ -11,7 +11,7 @@
|
|||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
namespace Posix {
|
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__)
|
#if defined(__unix__) || defined(__APPLE__)
|
||||||
|
|
||||||
// Create a UDP socket
|
// Create a UDP socket
|
||||||
@ -63,7 +63,7 @@ void ParticipantUDP::Setup(int localPort, const char* remoteIpAddress, int remot
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void ParticipantUDP::Receive() {
|
void Receive() {
|
||||||
#if defined(__unix__) || defined(__APPLE__)
|
#if defined(__unix__) || defined(__APPLE__)
|
||||||
sockaddr_in client_addr;
|
sockaddr_in client_addr;
|
||||||
socklen_t len = sizeof(client_addr);
|
socklen_t len = sizeof(client_addr);
|
||||||
@ -74,9 +74,9 @@ void ParticipantUDP::Receive() {
|
|||||||
unsigned int sender_port = ntohs(client_addr.sin_port);
|
unsigned int sender_port = ntohs(client_addr.sin_port);
|
||||||
|
|
||||||
ReceiveData(packetSize, sender_ipAddress, sender_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) {
|
// 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
|
// // std::cout << "New sender " << sender_ipAddress << ":" << sender_port
|
||||||
// // << "\n";
|
// // << "\n";
|
||||||
// // std::cout << "New remote participant " << remoteParticipant->ipAddress
|
// // std::cout << "New remote participant " << remoteParticipant->ipAddress
|
||||||
@ -90,7 +90,7 @@ void ParticipantUDP::Receive() {
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
bool ParticipantUDP::Send(Participant* remoteParticipant, int bufferSize) {
|
bool Send(Participant* remoteParticipant, int bufferSize) {
|
||||||
#if defined(__unix__) || defined(__APPLE__)
|
#if defined(__unix__) || defined(__APPLE__)
|
||||||
// std::cout << "Send to " << remoteParticipant->ipAddress << ":" << ntohs(remoteParticipant->port)
|
// std::cout << "Send to " << remoteParticipant->ipAddress << ":" << ntohs(remoteParticipant->port)
|
||||||
// << "\n";
|
// << "\n";
|
||||||
@ -113,7 +113,7 @@ bool ParticipantUDP::Send(Participant* remoteParticipant, int bufferSize) {
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool ParticipantUDP::Publish(IMessage* msg) {
|
bool Publish(IMessage* msg) {
|
||||||
#if defined(__unix__) || defined(__APPLE__)
|
#if defined(__unix__) || defined(__APPLE__)
|
||||||
int bufferSize = msg->Serialize(this->buffer);
|
int bufferSize = msg->Serialize(this->buffer);
|
||||||
if (bufferSize <= 0)
|
if (bufferSize <= 0)
|
||||||
|
@ -11,13 +11,6 @@ class ParticipantUDP : public RoboidControl::ParticipantUDP {
|
|||||||
void Receive();
|
void Receive();
|
||||||
bool Send(Participant* remoteParticipant, int bufferSize);
|
bool Send(Participant* remoteParticipant, int bufferSize);
|
||||||
bool Publish(IMessage* msg);
|
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
|
} // namespace Posix
|
||||||
|
@ -14,4 +14,5 @@ Supporting:
|
|||||||
# Basic components
|
# Basic components
|
||||||
|
|
||||||
- RoboidControl::Thing
|
- RoboidControl::Thing
|
||||||
- RoboidControl::Participant
|
- RoboidControl::LocalParticipant
|
||||||
|
- RoboidControl::SiteServer
|
234
Thing.cpp
234
Thing.cpp
@ -5,7 +5,6 @@
|
|||||||
#include "Participants/IsolatedParticipant.h"
|
#include "Participants/IsolatedParticipant.h"
|
||||||
|
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
// #include <iostream>
|
|
||||||
|
|
||||||
#if defined(ARDUINO)
|
#if defined(ARDUINO)
|
||||||
#include "Arduino.h"
|
#include "Arduino.h"
|
||||||
@ -18,79 +17,54 @@
|
|||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
|
||||||
#pragma region Init
|
Thing::Thing(int thingType)
|
||||||
|
: Thing(IsolatedParticipant::Isolated(), thingType) {}
|
||||||
|
|
||||||
Thing* Thing::LocalRoot() {
|
Thing::Thing(Participant* owner, Type thingType, unsigned char thingId)
|
||||||
Participant* p = Participant::LocalParticipant;
|
: Thing(owner, (unsigned char)thingType, thingId) {}
|
||||||
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, int thingType, unsigned char thingId) {
|
||||||
this->owner = owner;
|
this->owner = owner;
|
||||||
//this->owner->Add(this, true);
|
this->id = thingId;
|
||||||
std::cout << this->owner->name << ": New root thing " << std::endl;
|
|
||||||
}
|
|
||||||
|
|
||||||
Thing::Thing(unsigned char thingType, Thing* parent) {
|
|
||||||
this->type = thingType;
|
this->type = thingType;
|
||||||
|
this->networkId = 0;
|
||||||
|
|
||||||
this->position = Spherical::zero;
|
this->position = Spherical::zero;
|
||||||
this->positionUpdated = true;
|
|
||||||
this->orientation = SwingTwist::identity;
|
this->orientation = SwingTwist::identity;
|
||||||
this->orientationUpdated = true;
|
|
||||||
this->hierarchyChanged = true;
|
|
||||||
|
|
||||||
this->linearVelocity = Spherical::zero;
|
this->linearVelocity = Spherical::zero;
|
||||||
this->angularVelocity = Spherical::zero;
|
this->angularVelocity = Spherical::zero;
|
||||||
|
|
||||||
this->owner = parent->owner;
|
|
||||||
this->owner->Add(this, true);
|
this->owner->Add(this, true);
|
||||||
this->SetParent(parent);
|
std::cout << "add thing [" << (int)this->id << "] to owner "
|
||||||
|
<< this->owner->ipAddress << ":" << this->owner->port <<
|
||||||
std::cout << this->owner->name << ": New thing for " << parent->name
|
std::endl;
|
||||||
<< std::endl;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
Thing::~Thing() {
|
Thing::Thing(Thing* parent, int thingType, unsigned char thingId)
|
||||||
std::cout << "Destroy thing " << this->name << std::endl;
|
: Thing(parent->owner, thingType, thingId) {
|
||||||
|
this->parent = parent;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Thing Thing::Reconstruct(Participant* owner, unsigned char thingType,
|
void Thing::Terminate() {
|
||||||
// unsigned char thingId) {
|
// Thing::Remove(this);
|
||||||
// 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;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
const char* Thing::GetName() const {
|
Thing* Thing::FindThing(const char* name) {
|
||||||
return this->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) {
|
if (strcmp(child->name, name) == 0)
|
||||||
this->modelUrl = url;
|
return child;
|
||||||
}
|
|
||||||
|
|
||||||
#pragma region Hierarchy
|
Thing* foundChild = child->FindThing(name);
|
||||||
|
if (foundChild != nullptr)
|
||||||
|
return foundChild;
|
||||||
|
}
|
||||||
|
return nullptr;
|
||||||
|
}
|
||||||
|
|
||||||
void Thing::SetParent(Thing* parent) {
|
void Thing::SetParent(Thing* parent) {
|
||||||
if (parent == nullptr) {
|
if (parent == nullptr) {
|
||||||
@ -100,36 +74,18 @@ void Thing::SetParent(Thing* parent) {
|
|||||||
this->parent = nullptr;
|
this->parent = nullptr;
|
||||||
} else
|
} else
|
||||||
parent->AddChild(this);
|
parent->AddChild(this);
|
||||||
this->hierarchyChanged = true;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// void Thing::SetParent(Thing* parent) {
|
void Thing::SetParent(Thing* root, const char* name) {
|
||||||
// parent->AddChild(this);
|
Thing* thing = root->FindThing(name);
|
||||||
// this->hierarchyChanged = true;
|
if (thing != nullptr)
|
||||||
// }
|
this->SetParent(thing);
|
||||||
|
|
||||||
// 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->FindChild(name);
|
|
||||||
// if (thing != nullptr)
|
|
||||||
// this->SetParent(thing);
|
|
||||||
// }
|
|
||||||
|
|
||||||
Thing* Thing::GetParent() {
|
Thing* Thing::GetParent() {
|
||||||
return this->parent;
|
return this->parent;
|
||||||
}
|
}
|
||||||
|
|
||||||
Thing* Thing::GetChildByIndex(unsigned char ix) {
|
|
||||||
return this->children[ix];
|
|
||||||
}
|
|
||||||
|
|
||||||
void Thing::AddChild(Thing* child) {
|
void Thing::AddChild(Thing* child) {
|
||||||
unsigned char newChildCount = this->childCount + 1;
|
unsigned char newChildCount = this->childCount + 1;
|
||||||
Thing** newChildren = new Thing*[newChildCount];
|
Thing** newChildren = new Thing*[newChildCount];
|
||||||
@ -169,7 +125,7 @@ Thing* Thing::RemoveChild(Thing* child) {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
child->parent = Thing::LocalRoot();
|
child->parent = nullptr;
|
||||||
|
|
||||||
delete[] this->children;
|
delete[] this->children;
|
||||||
this->children = newChildren;
|
this->children = newChildren;
|
||||||
@ -178,7 +134,7 @@ Thing* Thing::RemoveChild(Thing* child) {
|
|||||||
return 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++) {
|
for (unsigned char childIx = 0; childIx < this->childCount; childIx++) {
|
||||||
Thing* child = this->children[childIx];
|
Thing* child = this->children[childIx];
|
||||||
if (child == nullptr)
|
if (child == nullptr)
|
||||||
@ -186,8 +142,8 @@ Thing* Thing::GetChild(unsigned char id, bool recurse) {
|
|||||||
if (child->id == id)
|
if (child->id == id)
|
||||||
return child;
|
return child;
|
||||||
|
|
||||||
if (recurse) {
|
if (recursive) {
|
||||||
Thing* foundChild = child->GetChild(id, recurse);
|
Thing* foundChild = child->GetChild(id, recursive);
|
||||||
if (foundChild != nullptr)
|
if (foundChild != nullptr)
|
||||||
return foundChild;
|
return foundChild;
|
||||||
}
|
}
|
||||||
@ -195,25 +151,57 @@ Thing* Thing::GetChild(unsigned char id, bool recurse) {
|
|||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
|
|
||||||
Thing* Thing::FindChild(const char* name, bool recurse) {
|
Thing* Thing::GetChildByIndex(unsigned char ix) {
|
||||||
|
return this->children[ix];
|
||||||
|
}
|
||||||
|
|
||||||
|
void Thing::SetModel(const char* url) {
|
||||||
|
this->modelUrl = url;
|
||||||
|
}
|
||||||
|
|
||||||
|
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++) {
|
for (unsigned char childIx = 0; childIx < this->childCount; childIx++) {
|
||||||
Thing* child = this->children[childIx];
|
Thing* child = this->children[childIx];
|
||||||
if (child == nullptr || child->name == nullptr)
|
if (child == nullptr)
|
||||||
continue;
|
continue;
|
||||||
|
child->Update(currentTimeMs, recursive);
|
||||||
if (strcmp(child->name, name) == 0)
|
}
|
||||||
return child;
|
|
||||||
|
|
||||||
Thing* foundChild = child->FindChild(name);
|
|
||||||
if (foundChild != nullptr)
|
|
||||||
return foundChild;
|
|
||||||
}
|
}
|
||||||
return nullptr;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#pragma endregion Hierarchy
|
void Thing::UpdateThings(unsigned long currentTimeMs) {
|
||||||
|
IsolatedParticipant::Isolated()->Update(currentTimeMs);
|
||||||
|
}
|
||||||
|
|
||||||
#pragma region Pose
|
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) {
|
void Thing::SetPosition(Spherical position) {
|
||||||
this->position = position;
|
this->position = position;
|
||||||
@ -233,83 +221,21 @@ SwingTwist Thing::GetOrientation() {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void Thing::SetLinearVelocity(Spherical linearVelocity) {
|
void Thing::SetLinearVelocity(Spherical linearVelocity) {
|
||||||
if (this->linearVelocity.distance != linearVelocity.distance) {
|
|
||||||
this->linearVelocity = linearVelocity;
|
this->linearVelocity = linearVelocity;
|
||||||
this->linearVelocityUpdated = true;
|
this->linearVelocityUpdated = true;
|
||||||
}
|
}
|
||||||
}
|
|
||||||
|
|
||||||
Spherical Thing::GetLinearVelocity() {
|
Spherical Thing::GetLinearVelocity() {
|
||||||
return this->linearVelocity;
|
return this->linearVelocity;
|
||||||
}
|
}
|
||||||
|
|
||||||
void Thing::SetAngularVelocity(Spherical angularVelocity) {
|
void Thing::SetAngularVelocity(Spherical angularVelocity) {
|
||||||
if (this->angularVelocity.distance != angularVelocity.distance) {
|
|
||||||
this->angularVelocity = angularVelocity;
|
this->angularVelocity = angularVelocity;
|
||||||
this->angularVelocityUpdated = true;
|
this->angularVelocityUpdated = true;
|
||||||
}
|
}
|
||||||
}
|
|
||||||
|
|
||||||
Spherical Thing::GetAngularVelocity() {
|
Spherical Thing::GetAngularVelocity() {
|
||||||
return this->angularVelocity;
|
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
|
} // namespace RoboidControl
|
211
Thing.h
211
Thing.h
@ -20,7 +20,7 @@ class ParticipantUDP;
|
|||||||
class Thing {
|
class Thing {
|
||||||
public:
|
public:
|
||||||
/// @brief Predefined thing types
|
/// @brief Predefined thing types
|
||||||
enum Type : unsigned char {
|
enum Type {
|
||||||
Undetermined,
|
Undetermined,
|
||||||
// Sensor,
|
// Sensor,
|
||||||
Switch,
|
Switch,
|
||||||
@ -32,107 +32,59 @@ class Thing {
|
|||||||
ControlledMotor,
|
ControlledMotor,
|
||||||
UncontrolledMotor,
|
UncontrolledMotor,
|
||||||
Servo,
|
Servo,
|
||||||
IncrementalEncoder,
|
|
||||||
// Other
|
// Other
|
||||||
Roboid,
|
Roboid,
|
||||||
Humanoid,
|
Humanoid,
|
||||||
ExternalSensor,
|
ExternalSensor,
|
||||||
DifferentialDrive
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#pragma region Init
|
/// @brief Create a new thing using an implicit local participant
|
||||||
static Thing* LocalRoot();
|
/// @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
|
/// @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
|
/// @brief The ID of the thing
|
||||||
unsigned char id = 0;
|
unsigned char id = 0;
|
||||||
|
|
||||||
/// @brief The type of Thing
|
/// @brief The type of Thing
|
||||||
/// This can be either a Thing::Type of a byte value for custom types
|
/// 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
|
/// @brief Find a thing by name
|
||||||
const char* name = nullptr;
|
/// @param name Rhe name of the thing
|
||||||
|
/// @return The found thing or nullptr when nothing is found
|
||||||
|
Thing* FindThing(const char* name);
|
||||||
|
|
||||||
public:
|
/// @brief Sets the parent Thing
|
||||||
void SetName(const char* name);
|
/// @param parent The Thing which should become the parnet
|
||||||
const char* GetName() const;
|
/// @remark This is equivalent to calling parent->AddChild(this);
|
||||||
bool nameChanged = false;
|
virtual void SetParent(Thing* parent);
|
||||||
|
void SetParent(Thing* root, const char* name);
|
||||||
/// @brief Sets the location from where the 3D model of this Thing can be
|
/// @brief Gets the parent Thing
|
||||||
/// 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
|
|
||||||
/// @return The parent Thing
|
/// @return The parent Thing
|
||||||
// Thing* GetParent();
|
|
||||||
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
|
/// @brief Add a child Thing to this Thing
|
||||||
/// @param child The Thing which should become a child
|
/// @param child The Thing which should become a child
|
||||||
/// @remark When the Thing is already a child, it will not be added again
|
/// @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
|
/// @return The removed child or nullptr if the child could not be found
|
||||||
Thing* RemoveChild(Thing* child);
|
Thing* RemoveChild(Thing* child);
|
||||||
|
|
||||||
|
/// @brief The number of children
|
||||||
|
unsigned char childCount = 0;
|
||||||
/// @brief Get a child by thing Id
|
/// @brief Get a child by thing Id
|
||||||
/// @param id The thing ID to find
|
/// @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
|
/// @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
|
protected:
|
||||||
/// @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:
|
|
||||||
Thing* parent = nullptr;
|
Thing* parent = nullptr;
|
||||||
Thing** children = nullptr;
|
Thing** children = nullptr;
|
||||||
|
|
||||||
#pragma endregion Hierarchy
|
|
||||||
|
|
||||||
#pragma region Pose
|
|
||||||
|
|
||||||
public:
|
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
|
/// @brief Set the position of the thing
|
||||||
/// @param position The new position in local space, in meters
|
/// @param position The new position in local space, in meters
|
||||||
void SetPosition(Spherical position);
|
void SetPosition(Spherical position);
|
||||||
/// @brief Get the position of the thing
|
/// @brief Get the position of the thing
|
||||||
/// @return The position in local space, in meters
|
/// @return The position in local space, in meters
|
||||||
Spherical GetPosition();
|
Spherical GetPosition();
|
||||||
/// @brief Boolean indicating that the thing has an updated position
|
|
||||||
bool positionUpdated = false;
|
|
||||||
|
|
||||||
/// @brief Set the orientation of the thing
|
/// @brief Set the orientation of the thing
|
||||||
/// @param orientation The new orientation in local space
|
/// @param orientation The new orientation in local space
|
||||||
void SetOrientation(SwingTwist orientation);
|
void SetOrientation(SwingTwist orientation);
|
||||||
/// @brief Get the orientation of the thing
|
/// @brief Get the orientation of the thing
|
||||||
/// @return The orienation in local space
|
/// @return The orienation in local space
|
||||||
SwingTwist GetOrientation();
|
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;
|
bool orientationUpdated = false;
|
||||||
|
|
||||||
/// @brief Set the linear velocity of the thing
|
/// @brief Set the linear velocity of the thing
|
||||||
@ -191,63 +146,57 @@ class Thing {
|
|||||||
/// @brief Get the linear velocity of the thing
|
/// @brief Get the linear velocity of the thing
|
||||||
/// @return The linear velocity in local space, in meters per second
|
/// @return The linear velocity in local space, in meters per second
|
||||||
virtual Spherical GetLinearVelocity();
|
virtual Spherical GetLinearVelocity();
|
||||||
/// @brief Boolean indicating the thing has an updated linear velocity
|
|
||||||
bool linearVelocityUpdated = false;
|
|
||||||
|
|
||||||
/// @brief Set the angular velocity of the thing
|
/// @brief Set the angular velocity of the thing
|
||||||
/// @param angularVelocity the new angular velocity in local space
|
/// @param angularVelocity the new angular velocity in local space
|
||||||
virtual void SetAngularVelocity(Spherical angularVelocity);
|
virtual void SetAngularVelocity(Spherical angularVelocity);
|
||||||
/// @brief Get the angular velocity of the thing
|
/// @brief Get the angular velocity of the thing
|
||||||
/// @return The angular velocity in local space
|
/// @return The angular velocity in local space
|
||||||
virtual Spherical GetAngularVelocity();
|
virtual Spherical GetAngularVelocity();
|
||||||
/// @brief Boolean indicating the thing has an updated angular velocity
|
bool linearVelocityUpdated = false;
|
||||||
bool angularVelocityUpdated = false;
|
bool angularVelocityUpdated = false;
|
||||||
|
|
||||||
private:
|
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
|
/// @remark When this Thing has a parent, the position is relative to the
|
||||||
/// parent's position and orientation
|
/// parent's position and orientation
|
||||||
Spherical position;
|
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
|
/// @remark When this Thing has a parent, the orientation is relative to the
|
||||||
/// parent's orientation
|
/// parent's orientation
|
||||||
SwingTwist orientation;
|
SwingTwist orientation;
|
||||||
|
|
||||||
/// @brief The linear velocity of the thing in local space, in meters per
|
/// @brief The linear velocity in local space
|
||||||
/// second
|
|
||||||
Spherical linearVelocity;
|
Spherical linearVelocity;
|
||||||
/// @brief The angular velocity of the thing in local space, in degrees per
|
/// @brief The angular velocity in local spze
|
||||||
/// second
|
|
||||||
Spherical angularVelocity;
|
Spherical angularVelocity;
|
||||||
|
|
||||||
#pragma endregion Pose
|
|
||||||
|
|
||||||
#pragma region Update
|
|
||||||
|
|
||||||
public:
|
public:
|
||||||
virtual void PrepareForUpdate();
|
/// @brief Terminated things are no longer updated
|
||||||
|
void Terminate();
|
||||||
|
|
||||||
/// @brief Updates the state of the thing
|
/// @brief Sets the location from where the 3D model of this Thing can be
|
||||||
/// @param currentTimeMs The current clock time in milliseconds; if this is
|
/// loaded from
|
||||||
/// zero, the current time is retrieved automatically
|
/// @param url The url of the model
|
||||||
/// @param recurse When true, this will Update the descendants recursively
|
/// @remark Although the roboid implementation is not dependent on the model,
|
||||||
virtual void Update(bool recurse = false);
|
/// 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();
|
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
|
/// @brief Function used to generate binary data for this thing
|
||||||
/// @param buffer The byte array for thw binary data
|
/// @param buffer The byte array for thw binary data
|
||||||
/// @param ix The starting position for writing the 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);
|
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
|
/// @param bytes The binary data
|
||||||
virtual void ProcessBinary(char* bytes);
|
virtual void ProcessBinary(char* bytes);
|
||||||
};
|
};
|
||||||
|
2
Things/AbsoluteEncoder.cpp
Normal file
2
Things/AbsoluteEncoder.cpp
Normal file
@ -0,0 +1,2 @@
|
|||||||
|
#include "AbsoluteEncoder.h"
|
||||||
|
|
15
Things/AbsoluteEncoder.h
Normal file
15
Things/AbsoluteEncoder.h
Normal 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
|
@ -1,68 +1,67 @@
|
|||||||
#include "ControlledMotor.h"
|
#include "ControlledMotor.h"
|
||||||
#include "LinearAlgebra/FloatSingle.h"
|
|
||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
|
||||||
ControlledMotor::ControlledMotor(Motor* motor,
|
ControlledMotor::ControlledMotor() { this->type = Thing::ControlledMotor; }
|
||||||
RelativeEncoder* encoder,
|
|
||||||
Thing* parent)
|
ControlledMotor::ControlledMotor(Motor *motor, IncrementalEncoder *encoder)
|
||||||
: Motor(parent), motor(motor), encoder(encoder) {
|
: ControlledMotor() {
|
||||||
this->type = Type::ControlledMotor;
|
this->motor = motor;
|
||||||
//encoder->SetParent(null);
|
this->encoder = encoder;
|
||||||
// Thing parent = motor.GetParent();
|
// this->rotationDirection = Direction::Forward;
|
||||||
// this->SetParent(parent);
|
|
||||||
this->integral = 0;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void ControlledMotor::SetTargetVelocity(float velocity) {
|
//#include <Arduino.h>
|
||||||
this->targetVelocity = velocity;
|
|
||||||
this->rotationDirection =
|
void ControlledMotor::SetTargetSpeed(float speed) {
|
||||||
(targetVelocity < 0) ? Direction::Reverse : Direction::Forward;
|
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) {
|
void ControlledMotor::Update(unsigned long currentTimeMs) {
|
||||||
unsigned long currentTimeMs = GetTimeMs();
|
this->actualSpeed = encoder->GetRevolutionsPerSecond(currentTimeMs);
|
||||||
float timeStep = (currentTimeMs - this->lastUpdateTime) / 1000.0f;
|
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;
|
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() {
|
float ControlledMotor::GetActualSpeed() { return actualSpeed; }
|
||||||
// return (int)rotationDirection * encoder->rotationSpeed;
|
|
||||||
// }
|
|
||||||
|
|
||||||
// bool ControlledMotor::Drive(float distance) {
|
bool ControlledMotor::Drive(float distance) {
|
||||||
// if (!driving) {
|
if (!driving) {
|
||||||
// targetDistance = distance;
|
targetDistance = distance;
|
||||||
// startDistance = encoder->GetDistance();
|
startDistance = encoder->GetDistance();
|
||||||
// driving = true;
|
driving = true;
|
||||||
// }
|
}
|
||||||
// float totalDistance = encoder->GetDistance() - startDistance;
|
float totalDistance = encoder->GetDistance() - startDistance;
|
||||||
// bool completed = totalDistance > targetDistance;
|
bool completed = totalDistance > targetDistance;
|
||||||
// return completed;
|
return completed;
|
||||||
// }
|
}
|
||||||
} // namespace RoboidControl
|
|
||||||
|
}
|
@ -1,7 +1,7 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include "IncrementalEncoder.h"
|
||||||
#include "Motor.h"
|
#include "Motor.h"
|
||||||
#include "RelativeEncoder.h"
|
|
||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
|
||||||
@ -10,31 +10,48 @@ namespace RoboidControl {
|
|||||||
/// The speed is measured in revolutions per second.
|
/// The speed is measured in revolutions per second.
|
||||||
class ControlledMotor : public Motor {
|
class ControlledMotor : public Motor {
|
||||||
public:
|
public:
|
||||||
ControlledMotor(Motor* motor, RelativeEncoder* encoder, Thing* parent = Thing::LocalRoot());
|
ControlledMotor();
|
||||||
|
ControlledMotor(Motor* motor, IncrementalEncoder* encoder);
|
||||||
|
|
||||||
float pidP = 0.5;
|
inline static bool CheckType(Thing* thing) {
|
||||||
float pidD = 0;
|
return (thing->type & (int)Thing::Type::ControlledMotor) != 0;
|
||||||
float pidI = 0.2;
|
}
|
||||||
|
float velocity;
|
||||||
|
|
||||||
/// @brief The actual velocity in revolutions per second
|
float pidP = 0.1F;
|
||||||
float actualVelocity;
|
float pidD = 0.0F;
|
||||||
|
float pidI = 0.0F;
|
||||||
|
|
||||||
enum Direction { Forward = 1, Reverse = -1 };
|
void Update(unsigned long currentTimeMs) override;
|
||||||
Direction rotationDirection;
|
|
||||||
|
|
||||||
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
|
/// @brief Get the actual speed from the encoder
|
||||||
/// @param speed the target velocity in revolutions per second
|
/// @return The speed in revolutions per second
|
||||||
virtual void SetTargetVelocity(float velocity) override;
|
virtual float GetActualSpeed() override;
|
||||||
|
|
||||||
|
bool Drive(float distance);
|
||||||
|
|
||||||
Motor* motor;
|
Motor* motor;
|
||||||
RelativeEncoder* encoder;
|
IncrementalEncoder* encoder;
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
float integral = 0;
|
float lastUpdateTime = 0;
|
||||||
float lastError = 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
|
} // namespace RoboidControl
|
||||||
|
@ -1,28 +1,10 @@
|
|||||||
#include "DifferentialDrive.h"
|
#include "DifferentialDrive.h"
|
||||||
|
|
||||||
#include "Messages/LowLevelMessages.h"
|
|
||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
DifferentialDrive::DifferentialDrive() : Thing() {}
|
||||||
|
|
||||||
DifferentialDrive::DifferentialDrive(Thing* parent)
|
RoboidControl::DifferentialDrive::DifferentialDrive(Participant* participant)
|
||||||
: Thing(Type::DifferentialDrive, parent) {
|
: Thing(participant) {}
|
||||||
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;
|
|
||||||
}
|
|
||||||
|
|
||||||
void DifferentialDrive::SetDriveDimensions(float wheelDiameter,
|
void DifferentialDrive::SetDriveDimensions(float wheelDiameter,
|
||||||
float wheelSeparation) {
|
float wheelSeparation) {
|
||||||
@ -39,39 +21,29 @@ void DifferentialDrive::SetDriveDimensions(float wheelDiameter,
|
|||||||
this->rightWheel->SetPosition(Spherical(distance, Direction::right));
|
this->rightWheel->SetPosition(Spherical(distance, Direction::right));
|
||||||
}
|
}
|
||||||
|
|
||||||
// Motor& DifferentialDrive::GetMotorLeft() {
|
void DifferentialDrive::SetMotors(Thing* leftWheel, Thing* rightWheel) {
|
||||||
// return *this->leftWheel;
|
|
||||||
// }
|
|
||||||
|
|
||||||
// Motor& DifferentialDrive::GetMotorRight() {
|
|
||||||
// return *this->rightWheel;
|
|
||||||
// }
|
|
||||||
|
|
||||||
void DifferentialDrive::SetMotors(Motor& leftMotor, Motor& rightMotor) {
|
|
||||||
float distance = this->wheelSeparation / 2;
|
float distance = this->wheelSeparation / 2;
|
||||||
this->leftWheel = &leftMotor;
|
this->leftWheel = leftWheel;
|
||||||
|
;
|
||||||
|
if (leftWheel != nullptr)
|
||||||
this->leftWheel->SetPosition(Spherical(distance, Direction::left));
|
this->leftWheel->SetPosition(Spherical(distance, Direction::left));
|
||||||
|
|
||||||
this->rightWheel = &rightMotor;
|
this->rightWheel = rightWheel;
|
||||||
|
if (rightWheel != nullptr)
|
||||||
this->rightWheel->SetPosition(Spherical(distance, Direction::right));
|
this->rightWheel->SetPosition(Spherical(distance, Direction::right));
|
||||||
}
|
}
|
||||||
|
|
||||||
void DifferentialDrive::SetWheelVelocity(float velocityLeft,
|
void DifferentialDrive::SetWheelVelocity(float speedLeft, float speedRight) {
|
||||||
float velocityRight) {
|
|
||||||
// if (this->leftWheel != nullptr)
|
|
||||||
// this->leftWheel->SetAngularVelocity(Spherical(velocityLeft,
|
|
||||||
// Direction::left));
|
|
||||||
// if (this->rightWheel != nullptr)
|
|
||||||
// this->rightWheel->SetAngularVelocity(
|
|
||||||
// Spherical(velocityRight, Direction::right));
|
|
||||||
if (this->leftWheel != nullptr)
|
if (this->leftWheel != nullptr)
|
||||||
this->leftWheel->SetTargetVelocity(velocityLeft);
|
this->leftWheel->SetAngularVelocity(Spherical(speedLeft, Direction::left));
|
||||||
if (this->rightWheel != nullptr)
|
if (this->rightWheel != nullptr)
|
||||||
this->rightWheel->SetTargetVelocity(velocityRight);
|
this->rightWheel->SetAngularVelocity(
|
||||||
|
Spherical(speedRight, Direction::right));
|
||||||
}
|
}
|
||||||
|
|
||||||
void DifferentialDrive::Update(bool recursive) {
|
void DifferentialDrive::Update(unsigned long currentMs, bool recursive) {
|
||||||
if (this->linearVelocityUpdated) {
|
if (this->linearVelocityUpdated == false)
|
||||||
|
return;
|
||||||
// this assumes forward velocity only....
|
// this assumes forward velocity only....
|
||||||
float linearVelocity = this->GetLinearVelocity().distance;
|
float linearVelocity = this->GetLinearVelocity().distance;
|
||||||
|
|
||||||
@ -90,15 +62,10 @@ void DifferentialDrive::Update(bool recursive) {
|
|||||||
this->wheelRadius * Rad2Deg;
|
this->wheelRadius * Rad2Deg;
|
||||||
|
|
||||||
this->SetWheelVelocity(speedLeft, speedRight);
|
this->SetWheelVelocity(speedLeft, speedRight);
|
||||||
}
|
Thing::Update(currentMs, recursive);
|
||||||
Thing::Update(recursive);
|
// std::cout << "lin. speed " << linearVelocity << " ang. speed " <<
|
||||||
}
|
// angularVelocity.distance << " left wheel "
|
||||||
|
// << speedLeft << " right wheel " << speedRight << "\n";
|
||||||
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;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace RoboidControl
|
} // namespace RoboidControl
|
@ -1,7 +1,6 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "Thing.h"
|
#include "Thing.h"
|
||||||
#include "Motor.h"
|
|
||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
|
||||||
@ -10,13 +9,11 @@ namespace RoboidControl {
|
|||||||
/// @sa @link https://en.wikipedia.org/wiki/Differential_wheeled_robot @endlink
|
/// @sa @link https://en.wikipedia.org/wiki/Differential_wheeled_robot @endlink
|
||||||
class DifferentialDrive : public Thing {
|
class DifferentialDrive : public Thing {
|
||||||
public:
|
public:
|
||||||
/// @brief Create a new child differential drive
|
/// @brief Create a differential drive without networking support
|
||||||
/// @param parent The parent thing
|
DifferentialDrive();
|
||||||
/// @param thingId The ID of the thing, leave out or set to zero to generate
|
/// @brief Create a differential drive with networking support
|
||||||
/// an ID
|
/// @param participant The local participant
|
||||||
DifferentialDrive(Thing* parent = Thing::LocalRoot());
|
DifferentialDrive(Participant* participant);
|
||||||
|
|
||||||
DifferentialDrive(Motor* leftMotor, Motor* rightMotor, Thing* parent = Thing::LocalRoot());
|
|
||||||
|
|
||||||
/// @brief Configures the dimensions of the drive
|
/// @brief Configures the dimensions of the drive
|
||||||
/// @param wheelDiameter The diameter of the wheels in meters
|
/// @param wheelDiameter The diameter of the wheels in meters
|
||||||
@ -26,41 +23,35 @@ class DifferentialDrive : public Thing {
|
|||||||
/// linear and angular velocity.
|
/// linear and angular velocity.
|
||||||
/// @sa SetLinearVelocity SetAngularVelocity
|
/// @sa SetLinearVelocity SetAngularVelocity
|
||||||
void SetDriveDimensions(float wheelDiameter, float wheelSeparation);
|
void SetDriveDimensions(float wheelDiameter, float wheelSeparation);
|
||||||
|
|
||||||
// Motor& GetMotorLeft();
|
|
||||||
// Motor& GetMotorRight();
|
|
||||||
/// @brief Congures the motors for the wheels
|
/// @brief Congures the motors for the wheels
|
||||||
/// @param leftWheel The motor for the left wheel
|
/// @param leftWheel The motor for the left wheel
|
||||||
/// @param rightWheel The motor for the right 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
|
/// @brief Directly specify the speeds of the motors
|
||||||
/// @param speedLeft The speed of the left wheel in degrees per second.
|
/// @param speedLeft The speed of the left wheel in degrees per second.
|
||||||
/// Positive moves the robot in the forward direction.
|
/// Positive moves the robot in the forward direction.
|
||||||
/// @param speedRight The speed of the right wheel in degrees per second.
|
/// @param speedRight The speed of the right wheel in degrees per second.
|
||||||
/// Positive moves the robot in the forward direction.
|
/// Positive moves the robot in the forward direction.
|
||||||
|
|
||||||
void SetWheelVelocity(float speedLeft, float speedRight);
|
void SetWheelVelocity(float speedLeft, float speedRight);
|
||||||
|
|
||||||
/// @copydoc RoboidControl::Thing::Update(unsigned long)
|
/// @copydoc RoboidControl::Thing::Update(unsigned long)
|
||||||
virtual void Update(bool recursive = true) override;
|
virtual void Update(unsigned long currentMs, 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;
|
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
/// @brief The radius of a wheel in meters
|
/// @brief The radius of a wheel in meters
|
||||||
float wheelRadius = 0.0f;
|
float wheelRadius = 1.0f;
|
||||||
/// @brief The distance between the wheels in meters
|
/// @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
|
/// @brief Convert revolutions per second to meters per second
|
||||||
float rpsToMs = 1.0f;
|
float rpsToMs = 1.0f;
|
||||||
|
|
||||||
|
/// @brief The left wheel
|
||||||
|
Thing* leftWheel = nullptr;
|
||||||
|
/// @brief The right wheel
|
||||||
|
Thing* rightWheel = nullptr;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace RoboidControl
|
} // namespace RoboidControl
|
@ -2,26 +2,8 @@
|
|||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
|
||||||
//DigitalSensor::DigitalSensor() : Thing(Type::Switch) {}
|
//DigitalSensor::DigitalSensor() {}
|
||||||
|
|
||||||
// DigitalSensor::DigitalSensor(Participant* owner, unsigned char thingId)
|
DigitalSensor::DigitalSensor(Participant* participant, unsigned char networkId, unsigned char thingId) : Thing(participant) {}
|
||||||
// : 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);
|
|
||||||
}
|
|
||||||
|
|
||||||
} // namespace RoboidControl
|
} // namespace RoboidControl
|
||||||
|
@ -7,31 +7,15 @@ namespace RoboidControl {
|
|||||||
/// @brief A digital (on/off, 1/0, true/false) sensor
|
/// @brief A digital (on/off, 1/0, true/false) sensor
|
||||||
class DigitalSensor : public Thing {
|
class DigitalSensor : public Thing {
|
||||||
public:
|
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
|
/// @brief The sigital state
|
||||||
bool state = 0;
|
bool state = 0;
|
||||||
|
|
||||||
/// @brief Function used to generate binary data for this digital sensor
|
/// @brief The default constructor
|
||||||
/// @param buffer The byte array for thw binary data
|
//DigitalSensor();
|
||||||
/// @param ix The starting position for writing the binary data
|
/// @brief Create a temperature sensor with the given ID
|
||||||
int GenerateBinary(char* bytes, unsigned char* ix) override;
|
/// @param networkId The network ID of the sensor
|
||||||
/// @brief Function used to process binary data received for this digital
|
/// @param thingId The ID of the thing
|
||||||
/// sensor
|
DigitalSensor(Participant* participant, unsigned char networkId, unsigned char thingId);
|
||||||
/// @param bytes The binary data to process
|
|
||||||
virtual void ProcessBinary(char* bytes) override;
|
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace RoboidControl
|
} // namespace RoboidControl
|
||||||
|
23
Things/IncrementalEncoder.cpp
Normal file
23
Things/IncrementalEncoder.cpp
Normal 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; }
|
||||||
|
|
||||||
|
}
|
48
Things/IncrementalEncoder.h
Normal file
48
Things/IncrementalEncoder.h
Normal 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
|
@ -1,16 +1,21 @@
|
|||||||
#include "Motor.h"
|
#include "Motor.h"
|
||||||
|
|
||||||
|
#include <time.h>
|
||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
|
||||||
Motor::Motor(Thing* parent) : Thing(Type::UncontrolledMotor, parent) {}
|
Motor::Motor() : Thing(0) { // for now, id should be set properly later
|
||||||
|
this->type = (int)Thing::UncontrolledMotor;
|
||||||
void Motor::SetTargetVelocity(float targetSpeed) {
|
|
||||||
this->targetVelocity = targetSpeed;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
int Motor::GenerateBinary(char* data, unsigned char* ix) {
|
float Motor::GetActualSpeed() { return this->currentTargetSpeed; }
|
||||||
data[(*ix)++] = this->targetVelocity * 127.0f;
|
|
||||||
return 1;
|
void Motor::SetTargetSpeed(float targetSpeed) {
|
||||||
|
this->currentTargetSpeed = targetSpeed;
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace RoboidControl
|
float Motor::GetTargetSpeed() { return (this->currentTargetSpeed); }
|
||||||
|
|
||||||
|
void Motor::Update(unsigned long currentTimeMs) {}
|
||||||
|
|
||||||
|
}
|
@ -2,24 +2,41 @@
|
|||||||
|
|
||||||
#include "Thing.h"
|
#include "Thing.h"
|
||||||
|
|
||||||
|
//#include <time.h>
|
||||||
|
|
||||||
namespace RoboidControl {
|
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 {
|
class Motor : public Thing {
|
||||||
public:
|
public:
|
||||||
Motor(Thing* parent = Thing::LocalRoot());
|
/// @brief Default constructor for the Motor
|
||||||
|
Motor();
|
||||||
|
|
||||||
/// @brief Motor turning direction
|
/// @brief Motor turning direction
|
||||||
enum class Direction { Clockwise = 1, CounterClockwise = -1 };
|
enum class Direction { Clockwise = 1, CounterClockwise = -1 };
|
||||||
/// @brief The forward turning direction of the motor
|
/// @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;
|
/// @brief Get the current actual speed of the motor
|
||||||
// virtual void ProcessBinary(char* bytes) override;
|
/// @return The speed between -1 (full backward), 0 (stop) and 1 (full
|
||||||
|
/// forward)
|
||||||
|
virtual float GetActualSpeed();
|
||||||
|
|
||||||
//protected:
|
virtual void Update(unsigned long currentTimeMs);
|
||||||
float targetVelocity = 0;
|
|
||||||
|
float currentTargetSpeed = 0;
|
||||||
|
|
||||||
|
protected:
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace RoboidControl
|
} // namespace RoboidControl
|
@ -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
|
|
@ -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
113
Things/ServoMotor.cpp
Normal 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
51
Things/ServoMotor.h
Normal 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
|
@ -4,15 +4,9 @@
|
|||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
|
||||||
// TemperatureSensor::TemperatureSensor(Participant* participant,
|
TemperatureSensor::TemperatureSensor(Participant* participant,
|
||||||
// unsigned char thingId)
|
unsigned char thingId)
|
||||||
// : Thing(participant, Type::TemperatureSensor, 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) {}
|
|
||||||
|
|
||||||
void TemperatureSensor::SetTemperature(float temp) {
|
void TemperatureSensor::SetTemperature(float temp) {
|
||||||
this->temperature = temp;
|
this->temperature = temp;
|
||||||
|
@ -7,17 +7,15 @@ namespace RoboidControl {
|
|||||||
/// @brief A temperature sensor
|
/// @brief A temperature sensor
|
||||||
class TemperatureSensor : public Thing {
|
class TemperatureSensor : public Thing {
|
||||||
public:
|
public:
|
||||||
|
/// @brief The measured temperature
|
||||||
|
float temperature = 0;
|
||||||
|
|
||||||
/// @brief The default constructor
|
/// @brief The default constructor
|
||||||
//TemperatureSensor();
|
//TemperatureSensor();
|
||||||
/// @brief Create a temperature sensor with the given ID
|
/// @brief Create a temperature sensor with the given ID
|
||||||
/// @param networkId The network ID of the sensor
|
/// @param networkId The network ID of the sensor
|
||||||
/// @param thingId The ID of the thing
|
/// @param thingId The ID of the thing
|
||||||
TemperatureSensor(Participant* participant); //, unsigned char thingId);
|
TemperatureSensor(Participant* participant, unsigned char thingId);
|
||||||
// TemperatureSensor(Thing* parent);
|
|
||||||
TemperatureSensor(Thing* parent = Thing::LocalRoot());
|
|
||||||
|
|
||||||
/// @brief The measured temperature
|
|
||||||
float temperature = 0;
|
|
||||||
|
|
||||||
/// @brief Manually override the measured temperature
|
/// @brief Manually override the measured temperature
|
||||||
/// @param temperature The new temperature
|
/// @param temperature The new temperature
|
||||||
|
@ -1,30 +1,23 @@
|
|||||||
#include "TouchSensor.h"
|
#include "TouchSensor.h"
|
||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
TouchSensor::TouchSensor() : Thing(Thing::Type::TouchSensor) {}
|
||||||
|
|
||||||
TouchSensor::TouchSensor(Thing* parent) : Thing(Type::TouchSensor, parent) {
|
TouchSensor::TouchSensor(Participant* participant)
|
||||||
this->name = "Touch sensor";
|
: Thing(participant, Thing::Type::TouchSensor) {}
|
||||||
}
|
|
||||||
|
|
||||||
void TouchSensor::PrepareForUpdate() {
|
TouchSensor::TouchSensor(Thing* parent) : Thing(parent->owner) {
|
||||||
this->touchedSomething = this->externalTouch;
|
this->SetParent(parent);
|
||||||
}
|
|
||||||
|
|
||||||
void TouchSensor::Update(bool recursive) {
|
|
||||||
Thing::Update(recursive);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
int TouchSensor::GenerateBinary(char* bytes, unsigned char* ix) {
|
int TouchSensor::GenerateBinary(char* bytes, unsigned char* ix) {
|
||||||
bytes[(*ix)++] = this->touchedSomething ? 1 : 0;
|
return 0;
|
||||||
return 1;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void TouchSensor::ProcessBinary(char* bytes) {
|
void TouchSensor::ProcessBinary(char* bytes) {
|
||||||
this->externalTouch = (bytes[0] == 1);
|
// if (bytes[0] == 1)
|
||||||
if (this->externalTouch)
|
// std::cout << this->name << " is Touching something!\n";
|
||||||
std::cout << "touching!\n";
|
this->touchedSomething |= (bytes[0] == 1);
|
||||||
else
|
|
||||||
std::cout << "not touching\n";
|
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace RoboidControl
|
} // namespace RoboidControl
|
@ -6,30 +6,29 @@ namespace RoboidControl {
|
|||||||
|
|
||||||
/// @brief A sensor which can detect touches
|
/// @brief A sensor which can detect touches
|
||||||
class TouchSensor : public Thing {
|
class TouchSensor : public Thing {
|
||||||
// Why finishing this release (0.3), I notice that this is equivalent to a digital sensor
|
|
||||||
public:
|
public:
|
||||||
/// @brief Create a new child touch sensor
|
/// @brief Create a touch sensor with isolated participant
|
||||||
/// @param parent The parent thing
|
TouchSensor();
|
||||||
/// @param thingId The ID of the thing, leave out or set to zero to generate
|
/// @brief Create a touch sensor
|
||||||
/// an ID
|
TouchSensor(Participant* participant);
|
||||||
TouchSensor(Thing* parent = Thing::LocalRoot());
|
/// @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
|
/// @brief Value which is true when the sensor is touching something, false
|
||||||
/// otherwise
|
/// otherwise
|
||||||
bool touchedSomething = false;
|
bool touchedSomething = false;
|
||||||
|
|
||||||
virtual void PrepareForUpdate() override;
|
/// @brief Function to create a binary message with the temperature
|
||||||
virtual void Update(bool recursive) override;
|
|
||||||
|
|
||||||
/// @brief Function used to generate binary data for this touch sensor
|
|
||||||
/// @param buffer The byte array for thw binary data
|
/// @param buffer The byte array for thw binary data
|
||||||
/// @param ix The starting position for writing the binary data
|
/// @param ix The starting position for writing the binary data
|
||||||
int GenerateBinary(char* bytes, unsigned char* ix) override;
|
int GenerateBinary(char* bytes, unsigned char* ix) override;
|
||||||
/// @brief Function used to process binary data received for this touch sensor
|
/// @brief Function to extract the temperature received in the binary message
|
||||||
/// @param bytes The binary data to process
|
/// @param bytes The binary data
|
||||||
virtual void ProcessBinary(char* bytes) override;
|
virtual void ProcessBinary(char* bytes) override;
|
||||||
protected:
|
|
||||||
bool externalTouch = false;
|
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace RoboidControl
|
} // namespace RoboidControl
|
||||||
|
@ -85,9 +85,9 @@ void ParticipantUDP::Receive() {
|
|||||||
unsigned int sender_port = ntohs(client_addr.sin_port);
|
unsigned int sender_port = ntohs(client_addr.sin_port);
|
||||||
|
|
||||||
ReceiveData(packetSize, sender_ipAddress, sender_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) {
|
// if (remoteParticipant == nullptr) {
|
||||||
// remoteParticipant = this->Add(sender_ipAddress, sender_port);
|
// remoteParticipant = this->AddParticipant(sender_ipAddress, sender_port);
|
||||||
// // std::cout << "New sender " << sender_ipAddress << ":"
|
// // std::cout << "New sender " << sender_ipAddress << ":"
|
||||||
// // << sender_port << "\n";
|
// // << sender_port << "\n";
|
||||||
// // std::cout << "New remote participant " <<
|
// // std::cout << "New remote participant " <<
|
||||||
|
@ -1 +0,0 @@
|
|||||||
Important: this folder has to be names 'examples' exactly to maintain compatibility with Arduino
|
|
@ -4,75 +4,111 @@
|
|||||||
// not supported using Visual Studio 2022 compiler...
|
// not supported using Visual Studio 2022 compiler...
|
||||||
#include <gtest/gtest.h>
|
#include <gtest/gtest.h>
|
||||||
|
|
||||||
|
#include <chrono>
|
||||||
|
#include <thread>
|
||||||
|
// #include <ws2tcpip.h>
|
||||||
|
|
||||||
|
#include "Participant.h"
|
||||||
#include "Participants/SiteServer.h"
|
#include "Participants/SiteServer.h"
|
||||||
#include "Thing.h"
|
#include "Thing.h"
|
||||||
|
|
||||||
#include <chrono>
|
|
||||||
#include <thread>
|
|
||||||
|
|
||||||
using namespace RoboidControl;
|
using namespace RoboidControl;
|
||||||
|
|
||||||
TEST(Participant, Participant) {
|
// Function to get the current time in milliseconds as unsigned long
|
||||||
ParticipantUDP* participant = new ParticipantUDP("127.0.0.1", 7682);
|
unsigned long get_time_ms() {
|
||||||
|
auto now = std::chrono::steady_clock::now();
|
||||||
unsigned long milliseconds = Thing::GetTimeMs();
|
auto ms = std::chrono::duration_cast<std::chrono::milliseconds>(
|
||||||
unsigned long startTime = milliseconds;
|
now.time_since_epoch());
|
||||||
while (milliseconds < startTime + 7000) {
|
return static_cast<unsigned long>(ms.count());
|
||||||
participant->Update();
|
|
||||||
|
|
||||||
std::this_thread::sleep_for(std::chrono::milliseconds(100));
|
|
||||||
milliseconds = Thing::GetTimeMs();
|
|
||||||
}
|
|
||||||
SUCCEED();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
TEST(Participant, SiteServer) {
|
// class RoboidControlSuite : public ::testing::test {
|
||||||
SiteServer* siteServer = new SiteServer();
|
// TEST_F(RoboidControlSuite, HiddenParticipant) {
|
||||||
|
// Thing thing = Thing();
|
||||||
|
|
||||||
unsigned long milliseconds = Thing::GetTimeMs();
|
// unsigned long milliseconds = get_time_ms();
|
||||||
unsigned long startTime = milliseconds;
|
// unsigned long startTime = milliseconds;
|
||||||
while (milliseconds < startTime + 7000) {
|
// while (milliseconds < startTime + 1000) {
|
||||||
siteServer->Update();
|
// Thing.Update(milliseconds);
|
||||||
|
|
||||||
std::this_thread::sleep_for(std::chrono::milliseconds(100));
|
// milliseconds = get_time_ms();
|
||||||
milliseconds = Thing::GetTimeMs();
|
// }
|
||||||
}
|
// ASSERT_EQ(1, 1);
|
||||||
SUCCEED();
|
// }
|
||||||
|
// }
|
||||||
|
|
||||||
|
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
|
||||||
}
|
}
|
||||||
|
|
||||||
TEST(Participant, SiteParticipant) {
|
void TearDown() override {
|
||||||
SiteServer* siteServer = new SiteServer(7681);
|
// Clean up test data here
|
||||||
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");
|
|
||||||
|
|
||||||
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));
|
// TEST_F(ParticipantSuite, ParticipantUDP) {
|
||||||
milliseconds = Thing::GetTimeMs();
|
// ParticipantUDP* participant = new ParticipantUDP("127.0.0.1", 7681);
|
||||||
}
|
|
||||||
SUCCEED();
|
// 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
|
#endif
|
||||||
|
@ -15,7 +15,7 @@ TEST(RoboidControlSuite, HiddenParticipant) {
|
|||||||
unsigned long milliseconds = Thing::GetTimeMs();
|
unsigned long milliseconds = Thing::GetTimeMs();
|
||||||
unsigned long startTime = milliseconds;
|
unsigned long startTime = milliseconds;
|
||||||
while (milliseconds < startTime + 1000) {
|
while (milliseconds < startTime + 1000) {
|
||||||
Thing::UpdateThings();
|
Thing::UpdateThings(milliseconds);
|
||||||
|
|
||||||
milliseconds = Thing::GetTimeMs();
|
milliseconds = Thing::GetTimeMs();
|
||||||
}
|
}
|
||||||
@ -24,12 +24,12 @@ TEST(RoboidControlSuite, HiddenParticipant) {
|
|||||||
|
|
||||||
TEST(RoboidControlSuite, IsolatedParticipant) {
|
TEST(RoboidControlSuite, IsolatedParticipant) {
|
||||||
ParticipantUDP* participant = ParticipantUDP::Isolated();
|
ParticipantUDP* participant = ParticipantUDP::Isolated();
|
||||||
Thing* thing = new Thing();
|
Thing* thing = new Thing(participant);
|
||||||
|
|
||||||
unsigned long milliseconds = Thing::GetTimeMs();
|
unsigned long milliseconds = Thing::GetTimeMs();
|
||||||
unsigned long startTime = milliseconds;
|
unsigned long startTime = milliseconds;
|
||||||
while (milliseconds < startTime + 1000) {
|
while (milliseconds < startTime + 1000) {
|
||||||
participant->Update();
|
participant->Update(milliseconds);
|
||||||
|
|
||||||
milliseconds = Thing::GetTimeMs();
|
milliseconds = Thing::GetTimeMs();
|
||||||
}
|
}
|
||||||
|
Loading…
x
Reference in New Issue
Block a user