Compare commits
13 Commits
Author | SHA1 | Date | |
---|---|---|---|
140138977a | |||
1b5fef15e6 | |||
da8831a968 | |||
![]() |
5b5513971c | ||
![]() |
3f8eadf8cc | ||
17de9db0be | |||
![]() |
26be4557c5 | ||
31c725b0ca | |||
169d842143 | |||
ada8973964 | |||
38fd8f51c8 | |||
23ea03fbaf | |||
40aab4dc7a |
@ -1,5 +1,9 @@
|
|||||||
#include "ArduinoParticipant.h"
|
#include "ArduinoParticipant.h"
|
||||||
|
|
||||||
|
#if !defined(NO_STD)
|
||||||
|
#include <iostream>
|
||||||
|
#endif
|
||||||
|
|
||||||
#if defined(ARDUINO)
|
#if defined(ARDUINO)
|
||||||
#if defined(ARDUINO_ARCH_ESP8266)
|
#if defined(ARDUINO_ARCH_ESP8266)
|
||||||
#include <ESP8266WiFi.h>
|
#include <ESP8266WiFi.h>
|
||||||
@ -29,7 +33,9 @@ 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
|
||||||
@ -42,11 +48,13 @@ void ParticipantUDP::Setup() {
|
|||||||
udp = new WiFiUDP();
|
udp = new WiFiUDP();
|
||||||
udp->begin(this->port);
|
udp->begin(this->port);
|
||||||
|
|
||||||
|
#if !defined(NO_STD)
|
||||||
std::cout << "Wifi sync started local " << this->port;
|
std::cout << "Wifi sync started local " << this->port;
|
||||||
if (this->remoteSite != nullptr)
|
if (this->remoteSite != nullptr)
|
||||||
std::cout << ", remote " << this->remoteSite->ipAddress << ":"
|
std::cout << ", remote " << this->remoteSite->ipAddress << ":"
|
||||||
<< this->remoteSite->port << "\n";
|
<< this->remoteSite->port << "\n";
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void ParticipantUDP::GetBroadcastAddress() {
|
void ParticipantUDP::GetBroadcastAddress() {
|
||||||
@ -57,8 +65,10 @@ 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() {
|
||||||
@ -72,19 +82,6 @@ void ParticipantUDP::Receive() {
|
|||||||
senderAddress.toCharArray(sender_ipAddress, 16);
|
senderAddress.toCharArray(sender_ipAddress, 16);
|
||||||
unsigned int sender_port = udp->remotePort();
|
unsigned int sender_port = udp->remotePort();
|
||||||
|
|
||||||
// Participant* remoteParticipant = this->Get(sender_ipAddress,
|
|
||||||
// sender_port); if (remoteParticipant == nullptr) {
|
|
||||||
// remoteParticipant = this->Add(sender_ipAddress,
|
|
||||||
// sender_port);
|
|
||||||
// // std::cout << "New sender " << sender_ipAddress << ":" << sender_port
|
|
||||||
// // << "\n";
|
|
||||||
// // std::cout << "New remote participant " <<
|
|
||||||
// remoteParticipant->ipAddress
|
|
||||||
// // << ":" << remoteParticipant->port << " "
|
|
||||||
// // << (int)remoteParticipant->networkId << "\n";
|
|
||||||
// }
|
|
||||||
|
|
||||||
// ReceiveData(packetSize, remoteParticipant);
|
|
||||||
ReceiveData(packetSize, sender_ipAddress, sender_port);
|
ReceiveData(packetSize, sender_ipAddress, sender_port);
|
||||||
packetSize = udp->parsePacket();
|
packetSize = udp->parsePacket();
|
||||||
}
|
}
|
||||||
@ -97,15 +94,22 @@ 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->beginPacket(remoteParticipant->ipAddress, remoteParticipant->port);
|
||||||
udp->write((unsigned char*)buffer, bufferSize);
|
udp->write((unsigned char*)buffer, bufferSize);
|
||||||
} while (udp->endPacket() == 0 && n < 10);
|
r = udp->endPacket();
|
||||||
|
// On an Uno R4 WiFi, endPacket blocks for 10 seconds the first time
|
||||||
|
// It is not cleary yet why
|
||||||
|
} while (r == 0 && n < 10);
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
return true;
|
return true;
|
||||||
|
@ -5,6 +5,39 @@
|
|||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
namespace Arduino {
|
namespace Arduino {
|
||||||
|
|
||||||
|
#pragma region DRV8833
|
||||||
|
|
||||||
|
DRV8833::DRV8833(Configuration config, Thing* parent) : Thing(Type::Undetermined, parent) {
|
||||||
|
this->pinStandby = config.standby;
|
||||||
|
if (pinStandby != 255)
|
||||||
|
pinMode(pinStandby, OUTPUT);
|
||||||
|
|
||||||
|
this->motorA = new DRV8833Motor(this, config.AIn1, config.AIn2);
|
||||||
|
this->motorA->SetName("Motor A");
|
||||||
|
this->motorB = new DRV8833Motor(this, config.BIn1, config.BIn2);
|
||||||
|
this->motorB->SetName("Motor B");
|
||||||
|
}
|
||||||
|
|
||||||
|
#pragma endregion DRV8833
|
||||||
|
|
||||||
|
#pragma region Differential drive
|
||||||
|
|
||||||
|
DRV8833::DifferentialDrive::DifferentialDrive(DRV8833::Configuration config,
|
||||||
|
Thing* parent)
|
||||||
|
: RoboidControl::DifferentialDrive(this->drv8833.motorA,
|
||||||
|
this->drv8833.motorB,
|
||||||
|
parent),
|
||||||
|
drv8833(config, this) {}
|
||||||
|
|
||||||
|
void DRV8833::DifferentialDrive::Update(bool recurse) {
|
||||||
|
RoboidControl::DifferentialDrive::Update(recurse);
|
||||||
|
this->drv8833.Update(false);
|
||||||
|
}
|
||||||
|
|
||||||
|
#pragma endregion Differential drive
|
||||||
|
|
||||||
|
#pragma region Motor
|
||||||
|
|
||||||
#if (ESP32)
|
#if (ESP32)
|
||||||
uint8_t DRV8833Motor::nextAvailablePwmChannel = 0;
|
uint8_t DRV8833Motor::nextAvailablePwmChannel = 0;
|
||||||
#endif
|
#endif
|
||||||
@ -13,7 +46,7 @@ DRV8833Motor::DRV8833Motor(DRV8833* driver,
|
|||||||
unsigned char pinIn1,
|
unsigned char pinIn1,
|
||||||
unsigned char pinIn2,
|
unsigned char pinIn2,
|
||||||
bool reverse)
|
bool reverse)
|
||||||
: Thing(driver->owner) {
|
: Motor() {
|
||||||
this->SetParent(driver);
|
this->SetParent(driver);
|
||||||
|
|
||||||
this->pinIn1 = pinIn1;
|
this->pinIn1 = pinIn1;
|
||||||
@ -33,33 +66,20 @@ DRV8833Motor::DRV8833Motor(DRV8833* driver,
|
|||||||
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::SetAngularVelocity(Spherical velocity) {
|
void DRV8833Motor::SetTargetVelocity(float motorSpeed) {
|
||||||
Thing::SetAngularVelocity(velocity);
|
Motor::SetTargetVelocity(motorSpeed);
|
||||||
// ignoring rotation axis for now.
|
|
||||||
// Spherical angularVelocity = this->GetAngularVelocity();
|
|
||||||
float angularSpeed = velocity.distance; // in degrees/sec
|
|
||||||
|
|
||||||
float rpm = angularSpeed / 360 * 60;
|
uint8_t motorSignal =
|
||||||
float motorSpeed = rpm / this->maxRpm;
|
(uint8_t)(motorSpeed > 0 ? motorSpeed * 255 : -motorSpeed * 255);
|
||||||
|
|
||||||
uint8_t motorSignal = (uint8_t)(motorSpeed * 255);
|
// std::cout << "moto speed " << this->name << " = " << motorSpeed
|
||||||
// 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)
|
||||||
@ -109,43 +129,7 @@ void DRV8833Motor::SetAngularVelocity(Spherical velocity) {
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
DRV8833::DRV8833(Participant* participant,
|
#pragma endregion Motor
|
||||||
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(this, pinAIn1, pinAIn2, reverseA);
|
|
||||||
this->motorA->SetName("Motor A");
|
|
||||||
this->motorB = new DRV8833Motor(this, pinBIn1, pinBIn2, reverseB);
|
|
||||||
this->motorB->SetName("Motor B");
|
|
||||||
}
|
|
||||||
|
|
||||||
DRV8833::DRV8833(Thing* parent,
|
|
||||||
unsigned char pinAIn1,
|
|
||||||
unsigned char pinAIn2,
|
|
||||||
unsigned char pinBIn1,
|
|
||||||
unsigned char pinBIn2,
|
|
||||||
unsigned char pinStandby,
|
|
||||||
bool reverseA,
|
|
||||||
bool reverseB)
|
|
||||||
: DRV8833(parent->owner,
|
|
||||||
pinAIn1,
|
|
||||||
pinAIn2,
|
|
||||||
pinBIn1,
|
|
||||||
pinBIn2,
|
|
||||||
pinStandby,
|
|
||||||
reverseA,
|
|
||||||
reverseB) {
|
|
||||||
this->SetParent(parent);
|
|
||||||
}
|
|
||||||
|
|
||||||
} // namespace Arduino
|
} // namespace Arduino
|
||||||
} // namespace RoboidControl
|
} // namespace RoboidControl
|
@ -1,8 +1,10 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <Arduino.h>
|
#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 {
|
||||||
@ -11,44 +13,46 @@ class DRV8833Motor;
|
|||||||
|
|
||||||
class DRV8833 : public Thing {
|
class DRV8833 : public Thing {
|
||||||
public:
|
public:
|
||||||
|
struct Configuration {
|
||||||
|
int AIn1;
|
||||||
|
int AIn2;
|
||||||
|
int BIn1;
|
||||||
|
int BIn2;
|
||||||
|
int standby;
|
||||||
|
};
|
||||||
|
|
||||||
/// @brief Setup a DRV8833 motor controller
|
/// @brief Setup a DRV8833 motor controller
|
||||||
/// @param pinAIn1 The pin number connected to the AIn1 port
|
DRV8833(Configuration config, Thing* parent = Thing::LocalRoot());
|
||||||
/// @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);
|
|
||||||
DRV8833(Thing* parent,
|
|
||||||
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* motorA = nullptr;
|
||||||
DRV8833Motor* motorB = nullptr;
|
DRV8833Motor* motorB = nullptr;
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
unsigned char pinStandby = 255;
|
unsigned char pinStandby = 255;
|
||||||
|
|
||||||
|
public:
|
||||||
|
class DifferentialDrive;
|
||||||
};
|
};
|
||||||
|
|
||||||
/// @brief Support for a DRV8833 motor controller
|
#pragma region Differential drive
|
||||||
class DRV8833Motor : public Thing {
|
|
||||||
public:
|
|
||||||
/// @brief Motor turning direction
|
|
||||||
enum class RotationDirection { Clockwise = 1, CounterClockwise = -1 };
|
|
||||||
|
|
||||||
|
class DRV8833::DifferentialDrive : public RoboidControl::DifferentialDrive {
|
||||||
|
public:
|
||||||
|
DifferentialDrive(DRV8833::Configuration config, Thing* parent = Thing::LocalRoot());
|
||||||
|
|
||||||
|
virtual void Update(bool recurse = false) override;
|
||||||
|
|
||||||
|
protected:
|
||||||
|
DRV8833 drv8833;
|
||||||
|
};
|
||||||
|
|
||||||
|
#pragma endregion Differential drive
|
||||||
|
|
||||||
|
#pragma region Motor
|
||||||
|
|
||||||
|
/// @brief Support for a DRV8833 motor controller
|
||||||
|
class DRV8833Motor : public Motor {
|
||||||
|
public:
|
||||||
/// @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
|
||||||
@ -57,16 +61,16 @@ class DRV8833Motor : public Thing {
|
|||||||
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;
|
||||||
@ -75,5 +79,7 @@ class DRV8833Motor : public Thing {
|
|||||||
#endif
|
#endif
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#pragma endregion Motor
|
||||||
|
|
||||||
} // namespace Arduino
|
} // namespace Arduino
|
||||||
} // namespace RoboidControl
|
} // namespace RoboidControl
|
@ -5,19 +5,119 @@
|
|||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
namespace Arduino {
|
namespace Arduino {
|
||||||
|
|
||||||
DigitalInput::DigitalInput(Participant* participant, unsigned char pin)
|
#pragma region Digital input
|
||||||
: TouchSensor(participant) {
|
|
||||||
|
DigitalInput::DigitalInput(unsigned char pin, Thing* parent) : Thing(Type::Undetermined, parent) {
|
||||||
this->pin = pin;
|
this->pin = pin;
|
||||||
|
pinMode(this->pin, INPUT);
|
||||||
pinMode(pin, INPUT);
|
std::cout << "digital input start\n";
|
||||||
}
|
}
|
||||||
|
|
||||||
void DigitalInput::Update(unsigned long currentTimeMs, bool recursive) {
|
void DigitalInput::Update(bool recursive) {
|
||||||
this->touchedSomething = digitalRead(pin) == LOW;
|
this->isHigh = digitalRead(this->pin);
|
||||||
// std::cout << "DigitalINput pin " << (int)this->pin << ": " <<
|
this->isLow = !this->isHigh;
|
||||||
// this->touchedSomething << "\n";
|
Thing::Update(recursive);
|
||||||
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)
|
||||||
|
attachInterrupt(digitalPinToInterrupt(digitalInput.pin), PulseInterrupt0,
|
||||||
|
RISING);
|
||||||
|
else if (interruptCount == 1)
|
||||||
|
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;
|
||||||
|
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,26 +1,92 @@
|
|||||||
#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 TouchSensor {
|
class DigitalInput : public Thing {
|
||||||
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(unsigned long currentTimeMs,
|
virtual void Update(bool recursive = false) override;
|
||||||
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,39 +1,32 @@
|
|||||||
#include "UltrasonicSensor.h"
|
#include "UltrasonicSensor.h"
|
||||||
|
|
||||||
#include <Arduino.h>
|
#include <Arduino.h>
|
||||||
|
#include <iostream>
|
||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
namespace Arduino {
|
namespace Arduino {
|
||||||
|
|
||||||
UltrasonicSensor::UltrasonicSensor(Participant* participant,
|
UltrasonicSensor::UltrasonicSensor(Configuration config, Thing* parent)
|
||||||
unsigned char pinTrigger,
|
: Thing(Type::Undetermined, parent) {
|
||||||
unsigned char pinEcho)
|
this->name = "Ultrasonic sensor";
|
||||||
: TouchSensor(participant) {
|
this->pinTrigger = config.triggerPin;
|
||||||
this->pinTrigger = pinTrigger;
|
this->pinEcho = config.echoPin;
|
||||||
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
|
||||||
}
|
}
|
||||||
|
|
||||||
UltrasonicSensor::UltrasonicSensor(Thing* parent,
|
|
||||||
unsigned char pinTrigger,
|
|
||||||
unsigned char pinEcho)
|
|
||||||
: UltrasonicSensor(parent->owner, pinTrigger, pinEcho) {
|
|
||||||
this->SetParent(parent);
|
|
||||||
}
|
|
||||||
|
|
||||||
float UltrasonicSensor::GetDistance() {
|
float UltrasonicSensor::GetDistance() {
|
||||||
// Start the ultrasonic 'ping'
|
// Start the ultrasonic 'ping'
|
||||||
digitalWrite(pinTrigger, LOW);
|
digitalWrite(pinTrigger, LOW);
|
||||||
delayMicroseconds(5);
|
delayMicroseconds(2);
|
||||||
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
|
||||||
float duration_us =
|
unsigned long duration_us =
|
||||||
pulseIn(pinEcho, HIGH, 100000); // the result is in microseconds
|
pulseIn(pinEcho, HIGH, 10000); // 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
|
||||||
@ -44,32 +37,38 @@ 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 = duration_us / 2 / 1000000 * 340;
|
this->distance = (float)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;
|
||||||
|
|
||||||
this->touchedSomething |= (this->distance > 0 && this->distance <= this->touchDistance);
|
return this->distance;
|
||||||
|
|
||||||
// std::cout << "Ultrasonic " << this->touchedSomething << " | " << (this->distance > 0) << " " <<
|
|
||||||
// (this->distance <= this->touchDistance) << "\n";
|
|
||||||
|
|
||||||
return distance;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void UltrasonicSensor::Update(unsigned long currentTimeMs, bool recursive) {
|
void UltrasonicSensor::Update(bool recursive) {
|
||||||
this->touchedSomething = false;
|
|
||||||
GetDistance();
|
GetDistance();
|
||||||
Thing::Update(currentTimeMs, recursive);
|
Thing::Update(recursive);
|
||||||
}
|
}
|
||||||
|
|
||||||
// void UltrasonicSensor::ProcessBinary(char* bytes) {
|
#pragma region Touch sensor
|
||||||
// this->touchedSomething = (bytes[0] == 1);
|
|
||||||
// if (this->touchedSomething)
|
UltrasonicSensor::TouchSensor::TouchSensor(Configuration config, Thing* parent)
|
||||||
// std::cout << "Touching something!\n";
|
: RoboidControl::TouchSensor(parent), ultrasonic(config, this) {}
|
||||||
// }
|
|
||||||
|
void UltrasonicSensor::TouchSensor::Update(bool recursive) {
|
||||||
|
RoboidControl::TouchSensor::Update(recursive);
|
||||||
|
this->ultrasonic.Update(false);
|
||||||
|
this->touchedSomething |= (this->ultrasonic.distance > 0 &&
|
||||||
|
this->ultrasonic.distance <= this->touchDistance);
|
||||||
|
}
|
||||||
|
|
||||||
|
#pragma region Touch sensor
|
||||||
|
|
||||||
} // namespace Arduino
|
} // namespace Arduino
|
||||||
} // namespace RoboidControl
|
} // namespace RoboidControl
|
@ -6,26 +6,19 @@ namespace RoboidControl {
|
|||||||
namespace Arduino {
|
namespace Arduino {
|
||||||
|
|
||||||
/// @brief An HC-SR04 ultrasonic distance sensor
|
/// @brief An HC-SR04 ultrasonic distance sensor
|
||||||
class UltrasonicSensor : public TouchSensor {
|
class UltrasonicSensor : Thing {
|
||||||
public:
|
public:
|
||||||
// Inherit all constructors
|
struct Configuration {
|
||||||
//using TouchSensor::TouchSensor;
|
int triggerPin;
|
||||||
|
int echoPin;
|
||||||
|
};
|
||||||
|
|
||||||
/// @brief Setup an ultrasonic sensor
|
UltrasonicSensor(Configuration config, Thing* parent = Thing::LocalRoot());
|
||||||
/// @param participant The participant to use
|
|
||||||
/// @param pinTrigger The pin number of the trigger signal
|
|
||||||
/// @param pinEcho The pin number of the echo signal
|
|
||||||
UltrasonicSensor(Participant* participant,
|
|
||||||
unsigned char pinTrigger,
|
|
||||||
unsigned char pinEcho);
|
|
||||||
UltrasonicSensor(Thing* parent,
|
|
||||||
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
|
||||||
|
|
||||||
@ -37,15 +30,35 @@ class UltrasonicSensor : public TouchSensor {
|
|||||||
float GetDistance();
|
float GetDistance();
|
||||||
|
|
||||||
/// @copydoc RoboidControl::Thing::Update(unsigned long currentTimeMs)
|
/// @copydoc RoboidControl::Thing::Update(unsigned long currentTimeMs)
|
||||||
virtual void Update(unsigned long currentTimeMs,
|
virtual void Update(bool recursive = false) override;
|
||||||
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(
|
||||||
|
@ -9,6 +9,7 @@
|
|||||||
|
|
||||||
#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>();
|
||||||
@ -98,5 +99,6 @@ void DirectionOf<T>::Normalize() {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
template class DirectionOf<float>;
|
template class LinearAlgebra::DirectionOf<float>;
|
||||||
template class DirectionOf<signed short>;
|
template class LinearAlgebra::DirectionOf<signed short>;
|
||||||
|
}
|
@ -99,6 +99,4 @@ using Direction = DirectionSingle;
|
|||||||
|
|
||||||
} // namespace LinearAlgebra
|
} // namespace LinearAlgebra
|
||||||
|
|
||||||
using namespace LinearAlgebra;
|
|
||||||
|
|
||||||
#endif
|
#endif
|
@ -175,5 +175,5 @@ PolarOf<T> PolarOf<T>::Rotate(const PolarOf& v, AngleOf<T> angle) {
|
|||||||
return r;
|
return r;
|
||||||
}
|
}
|
||||||
|
|
||||||
template class PolarOf<float>;
|
template class LinearAlgebra::PolarOf<float>;
|
||||||
template class PolarOf<signed short>;
|
template class LinearAlgebra::PolarOf<signed short>;
|
@ -5,6 +5,8 @@
|
|||||||
|
|
||||||
#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;
|
||||||
@ -301,3 +303,5 @@ 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,7 +186,6 @@ 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,6 +4,8 @@
|
|||||||
|
|
||||||
#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>());
|
||||||
@ -166,3 +168,5 @@ void SwingTwistOf<T>::Normalize() {
|
|||||||
|
|
||||||
template class SwingTwistOf<float>;
|
template class SwingTwistOf<float>;
|
||||||
template class SwingTwistOf<signed short>;
|
template class SwingTwistOf<signed short>;
|
||||||
|
|
||||||
|
}
|
@ -6,6 +6,8 @@
|
|||||||
|
|
||||||
#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) {
|
||||||
|
@ -1,5 +1,7 @@
|
|||||||
#include "NetworkIdMsg.h"
|
#include "NetworkIdMsg.h"
|
||||||
|
|
||||||
|
#include <iostream>
|
||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
|
||||||
NetworkIdMsg::NetworkIdMsg(const char* buffer) {
|
NetworkIdMsg::NetworkIdMsg(const char* buffer) {
|
||||||
|
@ -1,5 +1,9 @@
|
|||||||
#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) {
|
||||||
@ -13,7 +17,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)
|
#if defined(DEBUG) && !defined(NO_STD)
|
||||||
std::cout << "Send ParticipantMsg [" << (int)this->networkId << "] "
|
std::cout << "Send ParticipantMsg [" << (int)this->networkId << "] "
|
||||||
<< std::endl;
|
<< std::endl;
|
||||||
#endif
|
#endif
|
||||||
|
@ -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->GetParent() != nullptr)) {
|
if (thing->positionUpdated || (force && thing->IsRoot())) {
|
||||||
this->position = thing->GetPosition();
|
this->position = thing->GetPosition();
|
||||||
this->poseType |= Pose_Position;
|
this->poseType |= Pose_Position;
|
||||||
}
|
}
|
||||||
if (thing->orientationUpdated || (force && thing->GetParent() != nullptr)) {
|
if (thing->orientationUpdated || (force && thing->IsRoot())) {
|
||||||
this->orientation = thing->GetOrientation();
|
this->orientation = thing->GetOrientation();
|
||||||
this->poseType |= Pose_Orientation;
|
this->poseType |= Pose_Orientation;
|
||||||
}
|
}
|
||||||
|
@ -1,5 +1,9 @@
|
|||||||
#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) {
|
||||||
@ -24,7 +28,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)
|
#if defined(DEBUG) && !defined(NO_STD)
|
||||||
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;
|
||||||
|
@ -14,27 +14,21 @@ 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;
|
||||||
Thing* parent = thing->GetParent();
|
if (thing->IsRoot())
|
||||||
if (parent != nullptr)
|
|
||||||
this->parentId = parent->id;
|
|
||||||
else
|
|
||||||
this->parentId = 0;
|
this->parentId = 0;
|
||||||
|
else {
|
||||||
|
Thing* parent = thing->GetParent();
|
||||||
|
this->parentId = parent->id;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// 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 << "/" << (int)this->thingId
|
std::cout << "Send ThingMsg [" << (int)this->networkId << "/"
|
||||||
<< "] " << (int)this->thingType << " " << (int)this->parentId << std::endl;
|
<< (int)this->thingId << "] " << (int)this->thingType << " "
|
||||||
|
<< (int)this->parentId << std::endl;
|
||||||
#endif
|
#endif
|
||||||
unsigned char ix = 0;
|
unsigned char ix = 0;
|
||||||
buffer[ix++] = this->id;
|
buffer[ix++] = this->id;
|
||||||
|
@ -8,7 +8,26 @@ namespace RoboidControl {
|
|||||||
|
|
||||||
ParticipantRegistry Participant::registry;
|
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;
|
||||||
@ -26,14 +45,14 @@ Participant::Participant(const char* ipAddress, int port) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
Participant::~Participant() {
|
Participant::~Participant() {
|
||||||
registry.Remove(this);
|
// registry.Remove(this);
|
||||||
delete[] this->ipAddress;
|
delete[] this->ipAddress;
|
||||||
}
|
}
|
||||||
|
|
||||||
void Participant::Update(unsigned long currentTimeMs) {
|
void Participant::Update() {
|
||||||
for (Thing* thing : this->things) {
|
for (Thing* thing : this->things) {
|
||||||
if (thing != nullptr)
|
if (thing != nullptr)
|
||||||
thing->Update(currentTimeMs, true);
|
thing->Update(true);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -113,22 +132,25 @@ void Participant::Remove(Thing* thing) {
|
|||||||
|
|
||||||
Participant* ParticipantRegistry::Get(const char* ipAddress,
|
Participant* ParticipantRegistry::Get(const char* ipAddress,
|
||||||
unsigned int port) {
|
unsigned int port) {
|
||||||
|
#if !defined(NO_STD)
|
||||||
for (Participant* participant : ParticipantRegistry::participants) {
|
for (Participant* participant : ParticipantRegistry::participants) {
|
||||||
if (participant == nullptr)
|
if (participant == nullptr)
|
||||||
continue;
|
continue;
|
||||||
if (strcmp(participant->ipAddress, ipAddress) == 0 &&
|
if (strcmp(participant->ipAddress, ipAddress) == 0 &&
|
||||||
participant->port == port) {
|
participant->port == port) {
|
||||||
std::cout << "found participant " << participant->ipAddress << ":"
|
// std::cout << "found participant " << participant->ipAddress << ":"
|
||||||
<< (int)participant->port << std::endl;
|
// << (int)participant->port << std::endl;
|
||||||
return participant;
|
return participant;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
std::cout << "Could not find participant " << ipAddress << ":" << (int)port
|
std::cout << "Could not find participant " << ipAddress << ":" << (int)port
|
||||||
<< std::endl;
|
<< std::endl;
|
||||||
|
#endif
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
|
|
||||||
Participant* ParticipantRegistry::Get(unsigned char participantId) {
|
Participant* ParticipantRegistry::Get(unsigned char participantId) {
|
||||||
|
#if !defined(NO_STD)
|
||||||
for (Participant* participant : ParticipantRegistry::participants) {
|
for (Participant* participant : ParticipantRegistry::participants) {
|
||||||
if (participant == nullptr)
|
if (participant == nullptr)
|
||||||
continue;
|
continue;
|
||||||
@ -136,6 +158,7 @@ Participant* ParticipantRegistry::Get(unsigned char participantId) {
|
|||||||
return participant;
|
return participant;
|
||||||
}
|
}
|
||||||
std::cout << "Could not find participant " << (int)participantId << std::endl;
|
std::cout << "Could not find participant " << (int)participantId << std::endl;
|
||||||
|
#endif
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -152,19 +175,22 @@ void ParticipantRegistry::Add(Participant* participant) {
|
|||||||
|
|
||||||
if (foundParticipant == nullptr) {
|
if (foundParticipant == nullptr) {
|
||||||
#if defined(NO_STD)
|
#if defined(NO_STD)
|
||||||
this->things[this->thingCount++] = thing;
|
// this->things[this->thingCount++] = thing;
|
||||||
#else
|
#else
|
||||||
ParticipantRegistry::participants.push_back(participant);
|
ParticipantRegistry::participants.push_back(participant);
|
||||||
#endif
|
#endif
|
||||||
std::cout << "Add participant " << participant->ipAddress << ":"
|
// std::cout << "Add participant " << participant->ipAddress << ":"
|
||||||
<< participant->port << "[" << (int)participant->networkId
|
// << participant->port << "[" << (int)participant->networkId
|
||||||
<< "]\n";
|
// << "]\n";
|
||||||
std::cout << "participants " << ParticipantRegistry::participants.size()
|
// std::cout << "participants " <<
|
||||||
<< "\n";
|
// ParticipantRegistry::participants.size()
|
||||||
} else {
|
// << "\n";
|
||||||
std::cout << "Did not add, existing participant " << participant->ipAddress
|
// } else {
|
||||||
<< ":" << participant->port << "[" << (int)participant->networkId
|
// std::cout << "Did not add, existing participant " <<
|
||||||
<< "]\n";
|
// participant->ipAddress
|
||||||
|
// << ":" << participant->port << "[" <<
|
||||||
|
// (int)participant->networkId
|
||||||
|
// << "]\n";
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -172,9 +198,15 @@ void ParticipantRegistry::Remove(Participant* participant) {
|
|||||||
// participants.remove(participant);
|
// participants.remove(participant);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if defined(NO_STD)
|
||||||
|
Participant** ParticipantRegistry::GetAll() const {
|
||||||
|
return ParticipantRegistry::participants;
|
||||||
|
}
|
||||||
|
#else
|
||||||
const std::list<Participant*>& ParticipantRegistry::GetAll() const {
|
const std::list<Participant*>& ParticipantRegistry::GetAll() const {
|
||||||
return ParticipantRegistry::participants;
|
return ParticipantRegistry::participants;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
#pragma endregion ParticipantRegistry
|
#pragma endregion ParticipantRegistry
|
||||||
|
|
||||||
|
@ -1,4 +1,5 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "Thing.h"
|
#include "Thing.h"
|
||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
@ -31,13 +32,21 @@ class ParticipantRegistry {
|
|||||||
/// @param participant The participant to remove
|
/// @param participant The participant to remove
|
||||||
void Remove(Participant* participant);
|
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
|
/// @brief Get all participants
|
||||||
/// @return All participants
|
/// @return All participants
|
||||||
const std::list<Participant*>& GetAll() const;
|
const std::list<Participant*>& GetAll() const;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
#if defined(NO_STD)
|
|
||||||
#else
|
|
||||||
/// @brief The list of known participants
|
/// @brief The list of known participants
|
||||||
std::list<Participant*> participants;
|
std::list<Participant*> participants;
|
||||||
#endif
|
#endif
|
||||||
@ -51,6 +60,9 @@ class ParticipantRegistry {
|
|||||||
/// reference to remote participants.
|
/// reference to remote participants.
|
||||||
class Participant {
|
class Participant {
|
||||||
public:
|
public:
|
||||||
|
/// @brief The name of the participant
|
||||||
|
const char* name = "Participant";
|
||||||
|
|
||||||
/// @brief The Ip Address of a participant.
|
/// @brief The Ip Address of a participant.
|
||||||
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.
|
||||||
@ -59,6 +71,7 @@ class Participant {
|
|||||||
/// @brief The network Id to identify the participant
|
/// @brief The network Id to identify the participant
|
||||||
unsigned char networkId = 0;
|
unsigned char networkId = 0;
|
||||||
|
|
||||||
|
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 UDP port of the participant
|
||||||
@ -66,6 +79,11 @@ class Participant {
|
|||||||
/// @brief Destructor for the participant
|
/// @brief Destructor for the participant
|
||||||
~Participant();
|
~Participant();
|
||||||
|
|
||||||
|
static Participant* LocalParticipant;
|
||||||
|
static void ReplaceLocalParticipant(Participant& newParticipant);
|
||||||
|
|
||||||
|
Thing* root = new Thing(this);
|
||||||
|
|
||||||
public:
|
public:
|
||||||
#if defined(NO_STD)
|
#if defined(NO_STD)
|
||||||
unsigned char thingCount = 0;
|
unsigned char thingCount = 0;
|
||||||
@ -88,7 +106,7 @@ class Participant {
|
|||||||
|
|
||||||
/// @brief Update all things for this participant
|
/// @brief Update all things for this participant
|
||||||
/// @param currentTimeMs The current time in milliseconds (optional)
|
/// @param currentTimeMs The current time in milliseconds (optional)
|
||||||
virtual void Update(unsigned long currentTimeMs = 0);
|
virtual void Update();
|
||||||
|
|
||||||
public:
|
public:
|
||||||
static ParticipantRegistry registry;
|
static ParticipantRegistry registry;
|
||||||
|
@ -1,30 +1,49 @@
|
|||||||
#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 "Windows/WindowsParticipant.h"
|
|
||||||
#include "Posix/PosixParticipant.h"
|
#include "Posix/PosixParticipant.h"
|
||||||
|
#include "Windows/WindowsParticipant.h"
|
||||||
|
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
|
||||||
|
#pragma region Init
|
||||||
|
|
||||||
ParticipantUDP::ParticipantUDP(int port) : Participant("127.0.0.1", port) {
|
ParticipantUDP::ParticipantUDP(int port) : Participant("127.0.0.1", 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);
|
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);
|
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;
|
||||||
@ -64,11 +83,18 @@ void ParticipantUDP::SetupUDP(int localPort,
|
|||||||
this->connected = true;
|
this->connected = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#pragma endregion Init
|
||||||
|
|
||||||
#pragma region Update
|
#pragma region Update
|
||||||
|
|
||||||
void ParticipantUDP::Update(unsigned long currentTimeMs) {
|
// The update order
|
||||||
if (currentTimeMs == 0)
|
// 1. receive external messages
|
||||||
currentTimeMs = Thing::GetTimeMs();
|
// 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)
|
||||||
@ -88,15 +114,26 @@ void ParticipantUDP::Update(unsigned long currentTimeMs) {
|
|||||||
this->ReceiveUDP();
|
this->ReceiveUDP();
|
||||||
}
|
}
|
||||||
|
|
||||||
UpdateMyThings(currentTimeMs);
|
UpdateMyThings();
|
||||||
UpdateOtherThings(currentTimeMs);
|
UpdateOtherThings();
|
||||||
}
|
}
|
||||||
|
|
||||||
void ParticipantUDP::UpdateMyThings(unsigned long currentTimeMs = 0) {
|
void ParticipantUDP::PrepMyThings() {
|
||||||
|
for (Thing* thing : this->things) {
|
||||||
|
if (thing == nullptr)
|
||||||
|
continue;
|
||||||
|
|
||||||
|
thing->PrepareForUpdate();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void ParticipantUDP::UpdateMyThings() {
|
||||||
|
// std::cout << this->things.size() << std::endl;
|
||||||
for (Thing* thing : this->things) {
|
for (Thing* thing : this->things) {
|
||||||
if (thing == nullptr) // || thing->GetParent() != nullptr)
|
if (thing == nullptr) // || thing->GetParent() != nullptr)
|
||||||
continue;
|
continue;
|
||||||
|
|
||||||
|
// std::cout << thing->name << "\n";
|
||||||
if (thing->hierarchyChanged) {
|
if (thing->hierarchyChanged) {
|
||||||
if (!(this->isIsolated || this->networkId == 0)) {
|
if (!(this->isIsolated || this->networkId == 0)) {
|
||||||
ThingMsg* thingMsg = new ThingMsg(this->networkId, thing);
|
ThingMsg* thingMsg = new ThingMsg(this->networkId, thing);
|
||||||
@ -111,12 +148,14 @@ void ParticipantUDP::UpdateMyThings(unsigned long currentTimeMs = 0) {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// std::cout << "B\n";
|
||||||
// Why don't we do recursive?
|
// Why don't we do recursive?
|
||||||
// Because when a thing creates a thing in the update,
|
// Because when a thing creates a thing in the update,
|
||||||
// that new thing is not sent out (because of hierarchyChanged)
|
// that new thing is not sent out (because of hierarchyChanged)
|
||||||
// before it is updated itself: it is immediatedly updated!
|
// before it is updated itself: it is immediatedly updated!
|
||||||
thing->Update(currentTimeMs, false);
|
thing->Update(false);
|
||||||
|
|
||||||
|
// std::cout << "C\n";
|
||||||
if (!(this->isIsolated || this->networkId == 0)) {
|
if (!(this->isIsolated || this->networkId == 0)) {
|
||||||
if (thing->terminate) {
|
if (thing->terminate) {
|
||||||
DestroyMsg* destroyMsg = new DestroyMsg(this->networkId, thing);
|
DestroyMsg* destroyMsg = new DestroyMsg(this->networkId, thing);
|
||||||
@ -137,20 +176,28 @@ void ParticipantUDP::UpdateMyThings(unsigned long currentTimeMs = 0) {
|
|||||||
delete binaryMsg;
|
delete binaryMsg;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
// std::cout << "D\n";
|
||||||
if (thing->terminate)
|
if (thing->terminate)
|
||||||
this->Remove(thing);
|
this->Remove(thing);
|
||||||
|
// std::cout << "E\n";
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void ParticipantUDP::UpdateOtherThings(unsigned long currentTimeMs = 0) {
|
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()) {
|
for (Participant* participant : Participant::registry.GetAll()) {
|
||||||
|
#endif
|
||||||
if (participant == nullptr || participant == this)
|
if (participant == nullptr || participant == this)
|
||||||
continue;
|
continue;
|
||||||
|
|
||||||
// Call only the Participant version of the Update.
|
// Call only the Participant version of the Update.
|
||||||
// This is to deal with the function where one of the (remote)
|
// This is to deal with the function where one of the (remote)
|
||||||
// participants is actually a local participant
|
// participants is actually a local participant
|
||||||
participant->Participant::Update(currentTimeMs);
|
participant->Participant::Update();
|
||||||
if (this->isIsolated)
|
if (this->isIsolated)
|
||||||
continue;
|
continue;
|
||||||
|
|
||||||
@ -195,8 +242,8 @@ bool ParticipantUDP::Send(Participant* remoteParticipant, IMessage* msg) {
|
|||||||
if (bufferSize <= 0)
|
if (bufferSize <= 0)
|
||||||
return true;
|
return true;
|
||||||
|
|
||||||
// std::cout << "send msg " << (int)this->buffer[0] << " to "
|
// std::cout << "send msg " << (static_cast<int>(this->buffer[0]) & 0xff)
|
||||||
// << remoteParticipant->ipAddress << std::endl;
|
// << " to " << remoteParticipant->ipAddress << std::endl;
|
||||||
|
|
||||||
#if defined(_WIN32) || defined(_WIN64)
|
#if defined(_WIN32) || defined(_WIN64)
|
||||||
Windows::ParticipantUDP* thisWindows =
|
Windows::ParticipantUDP* thisWindows =
|
||||||
@ -373,14 +420,14 @@ void ParticipantUDP::Process(Participant* sender, ParticipantMsg* msg) {
|
|||||||
|
|
||||||
void ParticipantUDP::Process(Participant* sender, NetworkIdMsg* msg) {
|
void ParticipantUDP::Process(Participant* sender, NetworkIdMsg* msg) {
|
||||||
#if defined(DEBUG)
|
#if defined(DEBUG)
|
||||||
std::cout << this->name << ": process SiteMsg " << (int)this->networkId
|
std::cout << this->name << ": process NetworkIdMsg " << (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);
|
||||||
}
|
}
|
||||||
@ -441,7 +488,7 @@ void ParticipantUDP::Process(Participant* sender, ModelUrlMsg* msg) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void ParticipantUDP::Process(Participant* sender, PoseMsg* msg) {
|
void ParticipantUDP::Process(Participant* sender, PoseMsg* msg) {
|
||||||
#if !defined(DEBUG)
|
#if !defined(DEBUG) && !defined(NO_STD)
|
||||||
std::cout << this->name << ": process PoseMsg [" << (int)this->networkId
|
std::cout << this->name << ": process PoseMsg [" << (int)this->networkId
|
||||||
<< "/" << (int)msg->networkId << "] " << (int)msg->poseType << "\n";
|
<< "/" << (int)msg->networkId << "] " << (int)msg->poseType << "\n";
|
||||||
#endif
|
#endif
|
||||||
|
@ -78,9 +78,6 @@ class ParticipantUDP : public Participant {
|
|||||||
/// local network
|
/// local network
|
||||||
long publishInterval = 3000; // 3 seconds
|
long publishInterval = 3000; // 3 seconds
|
||||||
|
|
||||||
/// @brief The name of the participant
|
|
||||||
const char* name = "ParticipantUDP";
|
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
char buffer[1024];
|
char buffer[1024];
|
||||||
|
|
||||||
@ -100,13 +97,15 @@ class ParticipantUDP : public Participant {
|
|||||||
#pragma region Update
|
#pragma region Update
|
||||||
|
|
||||||
public:
|
public:
|
||||||
virtual void Update(unsigned long currentTimeMs = 0) override;
|
virtual void Update() override;
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
unsigned long nextPublishMe = 0;
|
unsigned long nextPublishMe = 0;
|
||||||
|
|
||||||
virtual void UpdateMyThings(unsigned long currentTimeMs);
|
/// @brief Prepare the local things for the next update
|
||||||
virtual void UpdateOtherThings(unsigned long currentTimeMs);
|
virtual void PrepMyThings();
|
||||||
|
virtual void UpdateMyThings();
|
||||||
|
virtual void UpdateOtherThings();
|
||||||
|
|
||||||
#pragma endregion Update
|
#pragma endregion Update
|
||||||
|
|
||||||
|
@ -22,16 +22,22 @@ SiteServer::SiteServer(int port) : ParticipantUDP(port) {
|
|||||||
|
|
||||||
#pragma region Update
|
#pragma region Update
|
||||||
|
|
||||||
void SiteServer::UpdateMyThings(unsigned long currentTimeMs) {
|
void SiteServer::UpdateMyThings() {
|
||||||
for (Thing* thing : this->things) {
|
for (Thing* thing : this->things) {
|
||||||
if (thing == nullptr)
|
if (thing == nullptr)
|
||||||
continue;
|
continue;
|
||||||
|
|
||||||
thing->Update(currentTimeMs, true);
|
thing->Update(true);
|
||||||
|
|
||||||
if (this->isIsolated == false) {
|
if (this->isIsolated == false) {
|
||||||
// Send to all other participants
|
// Send to all other participants
|
||||||
|
#if defined(NO_STD)
|
||||||
|
Participant** participants = Participant::registry.GetAll();
|
||||||
|
for (int ix = 0; ix < Participant::registry.count; ix++) {
|
||||||
|
Participant* participant = participants[ix];
|
||||||
|
#else
|
||||||
for (Participant* participant : Participant::registry.GetAll()) {
|
for (Participant* participant : Participant::registry.GetAll()) {
|
||||||
|
#endif
|
||||||
if (participant == nullptr || participant == this)
|
if (participant == nullptr || participant == this)
|
||||||
continue;
|
continue;
|
||||||
|
|
||||||
@ -66,15 +72,24 @@ void SiteServer::Process(Participant* sender, NetworkIdMsg* 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);
|
// new Thing(sender, (Thing::Type)msg->thingType, msg->thingId);
|
||||||
|
// Thing::Reconstruct(sender, msg->thingType, msg->thingId);
|
||||||
|
//thing = new Thing(msg->thingType, sender->root);
|
||||||
|
;
|
||||||
|
thing->id = msg->thingId;
|
||||||
|
|
||||||
if (msg->parentId != 0) {
|
if (msg->parentId != 0) {
|
||||||
thing->SetParent(Get(msg->parentId));
|
thing->SetParent(Get(msg->parentId));
|
||||||
if (thing->GetParent() != nullptr)
|
if (thing->IsRoot())
|
||||||
|
// if (thing->GetParent() != nullptr)
|
||||||
|
#if defined(NO_STD)
|
||||||
|
;
|
||||||
|
#else
|
||||||
std::cout << "Could not find parent [" << (int)msg->networkId << "/"
|
std::cout << "Could not find parent [" << (int)msg->networkId << "/"
|
||||||
<< (int)msg->parentId << "]\n";
|
<< (int)msg->parentId << "]\n";
|
||||||
|
#endif
|
||||||
} else
|
} else
|
||||||
thing->SetParent(nullptr);
|
thing->SetParent(Thing::LocalRoot());
|
||||||
}
|
}
|
||||||
|
|
||||||
#pragma endregion Receive
|
#pragma endregion Receive
|
||||||
|
@ -24,7 +24,7 @@ class SiteServer : public ParticipantUDP {
|
|||||||
|
|
||||||
#pragma region Update
|
#pragma region Update
|
||||||
|
|
||||||
virtual void UpdateMyThings(unsigned long currentTimeMs) override;
|
virtual void UpdateMyThings() override;
|
||||||
|
|
||||||
#pragma endregion Update
|
#pragma endregion Update
|
||||||
|
|
||||||
|
@ -11,7 +11,7 @@
|
|||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
namespace Posix {
|
namespace Posix {
|
||||||
|
|
||||||
void Setup(int localPort, const char* remoteIpAddress, int remotePort) {
|
void ParticipantUDP::Setup(int localPort, const char* remoteIpAddress, int remotePort) {
|
||||||
#if defined(__unix__) || defined(__APPLE__)
|
#if defined(__unix__) || defined(__APPLE__)
|
||||||
|
|
||||||
// Create a UDP socket
|
// Create a UDP socket
|
||||||
@ -63,7 +63,7 @@ void Setup(int localPort, const char* remoteIpAddress, int remotePort) {
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void Receive() {
|
void ParticipantUDP::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);
|
||||||
@ -90,7 +90,7 @@ void Receive() {
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
bool Send(Participant* remoteParticipant, int bufferSize) {
|
bool ParticipantUDP::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 Send(Participant* remoteParticipant, int bufferSize) {
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool Publish(IMessage* msg) {
|
bool ParticipantUDP::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,6 +11,13 @@ 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
|
||||||
|
85
Thing.cpp
85
Thing.cpp
@ -5,6 +5,7 @@
|
|||||||
#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"
|
||||||
@ -19,14 +20,31 @@ namespace RoboidControl {
|
|||||||
|
|
||||||
#pragma region Init
|
#pragma region Init
|
||||||
|
|
||||||
Thing::Thing(unsigned char thingType)
|
Thing* Thing::LocalRoot() {
|
||||||
: Thing(IsolatedParticipant::Isolated(), thingType) {}
|
Participant* p = Participant::LocalParticipant;
|
||||||
|
Thing* localRoot = p->root;
|
||||||
|
return localRoot;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Only use this for root things
|
||||||
|
Thing::Thing(Participant* owner) {
|
||||||
|
this->type = Type::Roboid; // should become root
|
||||||
|
|
||||||
|
this->position = Spherical::zero;
|
||||||
|
this->positionUpdated = true;
|
||||||
|
this->orientation = SwingTwist::identity;
|
||||||
|
this->orientationUpdated = true;
|
||||||
|
this->hierarchyChanged = true;
|
||||||
|
|
||||||
|
this->linearVelocity = Spherical::zero;
|
||||||
|
this->angularVelocity = Spherical::zero;
|
||||||
|
|
||||||
Thing::Thing(Participant* owner,
|
|
||||||
unsigned char thingType,
|
|
||||||
unsigned char thingId) {
|
|
||||||
this->owner = owner;
|
this->owner = owner;
|
||||||
this->id = thingId;
|
//this->owner->Add(this, true);
|
||||||
|
std::cout << this->owner->name << ": New root thing " << std::endl;
|
||||||
|
}
|
||||||
|
|
||||||
|
Thing::Thing(unsigned char thingType, Thing* parent) {
|
||||||
this->type = thingType;
|
this->type = thingType;
|
||||||
|
|
||||||
this->position = Spherical::zero;
|
this->position = Spherical::zero;
|
||||||
@ -38,17 +56,25 @@ Thing::Thing(Participant* owner,
|
|||||||
this->linearVelocity = Spherical::zero;
|
this->linearVelocity = Spherical::zero;
|
||||||
this->angularVelocity = Spherical::zero;
|
this->angularVelocity = Spherical::zero;
|
||||||
|
|
||||||
// std::cout << "add thing [" << (int)this->id << "] to owner "
|
this->owner = parent->owner;
|
||||||
// << this->owner->ipAddress << ":" << this->owner->port <<
|
|
||||||
// std::endl;
|
|
||||||
this->owner->Add(this, true);
|
this->owner->Add(this, true);
|
||||||
|
this->SetParent(parent);
|
||||||
|
|
||||||
|
std::cout << this->owner->name << ": New thing for " << parent->name
|
||||||
|
<< std::endl;
|
||||||
}
|
}
|
||||||
|
|
||||||
Thing::Thing(Thing* parent, unsigned char thingType, unsigned char thingId)
|
Thing::~Thing() {
|
||||||
: Thing(parent->owner, thingType, thingId) {
|
std::cout << "Destroy thing " << this->name << std::endl;
|
||||||
this->SetParent(parent);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Thing Thing::Reconstruct(Participant* owner, unsigned char thingType,
|
||||||
|
// unsigned char thingId) {
|
||||||
|
// Thing thing = Thing(owner, thingType);
|
||||||
|
// thing.id = thingId;
|
||||||
|
// return thing;
|
||||||
|
// }
|
||||||
|
|
||||||
#pragma endregion Init
|
#pragma endregion Init
|
||||||
|
|
||||||
void Thing::SetName(const char* name) {
|
void Thing::SetName(const char* name) {
|
||||||
@ -77,6 +103,19 @@ void Thing::SetParent(Thing* parent) {
|
|||||||
this->hierarchyChanged = true;
|
this->hierarchyChanged = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// void Thing::SetParent(Thing* parent) {
|
||||||
|
// parent->AddChild(this);
|
||||||
|
// this->hierarchyChanged = true;
|
||||||
|
// }
|
||||||
|
|
||||||
|
// const Thing& Thing::GetParent() {
|
||||||
|
// return *this->parent;
|
||||||
|
// }
|
||||||
|
|
||||||
|
bool Thing::IsRoot() const {
|
||||||
|
return this == LocalRoot() || this->parent == nullptr; //&Thing::Root;
|
||||||
|
}
|
||||||
|
|
||||||
// void Thing::SetParent(Thing* root, const char* name) {
|
// void Thing::SetParent(Thing* root, const char* name) {
|
||||||
// Thing* thing = root->FindChild(name);
|
// Thing* thing = root->FindChild(name);
|
||||||
// if (thing != nullptr)
|
// if (thing != nullptr)
|
||||||
@ -130,7 +169,7 @@ Thing* Thing::RemoveChild(Thing* child) {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
child->parent = nullptr;
|
child->parent = Thing::LocalRoot();
|
||||||
|
|
||||||
delete[] this->children;
|
delete[] this->children;
|
||||||
this->children = newChildren;
|
this->children = newChildren;
|
||||||
@ -221,7 +260,8 @@ Spherical Thing::GetAngularVelocity() {
|
|||||||
|
|
||||||
unsigned long Thing::GetTimeMs() {
|
unsigned long Thing::GetTimeMs() {
|
||||||
#if defined(ARDUINO)
|
#if defined(ARDUINO)
|
||||||
return millis();
|
unsigned long ms = millis();
|
||||||
|
return ms;
|
||||||
#else
|
#else
|
||||||
auto now = std::chrono::steady_clock::now();
|
auto now = std::chrono::steady_clock::now();
|
||||||
auto ms = std::chrono::duration_cast<std::chrono::milliseconds>(
|
auto ms = std::chrono::duration_cast<std::chrono::milliseconds>(
|
||||||
@ -230,11 +270,13 @@ unsigned long Thing::GetTimeMs() {
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void Thing::Update(bool recursive) {
|
// void Thing::Update(bool recursive) {
|
||||||
Update(GetTimeMs(), recursive);
|
// Update(GetTimeMs(), recursive);
|
||||||
}
|
// }
|
||||||
|
|
||||||
void Thing::Update(unsigned long currentTimeMs, bool recursive) {
|
void Thing::PrepareForUpdate() {}
|
||||||
|
|
||||||
|
void Thing::Update(bool recursive) {
|
||||||
// if (this->positionUpdated || this->orientationUpdated)
|
// if (this->positionUpdated || this->orientationUpdated)
|
||||||
// OnPoseChanged callback
|
// OnPoseChanged callback
|
||||||
this->positionUpdated = false;
|
this->positionUpdated = false;
|
||||||
@ -245,17 +287,18 @@ void Thing::Update(unsigned long currentTimeMs, bool recursive) {
|
|||||||
this->nameChanged = false;
|
this->nameChanged = false;
|
||||||
|
|
||||||
if (recursive) {
|
if (recursive) {
|
||||||
|
// std::cout << "# children: " << (int)this->childCount << std::endl;
|
||||||
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)
|
||||||
continue;
|
continue;
|
||||||
child->Update(currentTimeMs, recursive);
|
child->Update(recursive);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void Thing::UpdateThings(unsigned long currentTimeMs) {
|
void Thing::UpdateThings() {
|
||||||
IsolatedParticipant::Isolated()->Update(currentTimeMs);
|
IsolatedParticipant::Isolated()->Update();
|
||||||
}
|
}
|
||||||
|
|
||||||
#pragma endregion Update
|
#pragma endregion Update
|
||||||
|
60
Thing.h
60
Thing.h
@ -32,6 +32,7 @@ class Thing {
|
|||||||
ControlledMotor,
|
ControlledMotor,
|
||||||
UncontrolledMotor,
|
UncontrolledMotor,
|
||||||
Servo,
|
Servo,
|
||||||
|
IncrementalEncoder,
|
||||||
// Other
|
// Other
|
||||||
Roboid,
|
Roboid,
|
||||||
Humanoid,
|
Humanoid,
|
||||||
@ -40,19 +41,23 @@ class Thing {
|
|||||||
};
|
};
|
||||||
|
|
||||||
#pragma region Init
|
#pragma region Init
|
||||||
|
static Thing* LocalRoot();
|
||||||
|
|
||||||
/// @brief Create a new thing without communication abilities
|
private:
|
||||||
/// @param thingType The type of thing (can use Thing::Type)
|
// Special constructor to create a root thing
|
||||||
Thing(unsigned char thingType = Type::Undetermined);
|
Thing(Participant* parent);
|
||||||
|
// Which can only be used by the Participant
|
||||||
|
friend class Participant;
|
||||||
|
|
||||||
/// @brief Create a new thing for a participant
|
public:
|
||||||
/// @param owner The owning participant
|
/// @brief Create a new thing
|
||||||
/// @param thingType The type of thing (can use Thing::Type)
|
/// @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
|
/// @param parent (optional) The parent thing
|
||||||
/// an ID
|
/// The owner will be the same as the owner of the parent thing, it will
|
||||||
Thing(Participant* owner,
|
/// be Participant::LocalParticipant if the parent is not specified. A thing
|
||||||
unsigned char thingType = Type::Undetermined,
|
/// without a parent will be a root thing.
|
||||||
unsigned char thingId = 0);
|
Thing(unsigned char thingType = Thing::Type::Undetermined,
|
||||||
|
Thing* parent = LocalRoot());
|
||||||
|
|
||||||
/// @brief Create a new child thing
|
/// @brief Create a new child thing
|
||||||
/// @param parent The parent thing
|
/// @param parent The parent thing
|
||||||
@ -60,7 +65,12 @@ class Thing {
|
|||||||
/// @param thingId The ID of the thing, leave out or set to zero to generate
|
/// @param thingId The ID of the thing, leave out or set to zero to generate
|
||||||
/// an ID
|
/// an ID
|
||||||
/// @note The owner will be the same as the owner of the parent thing
|
/// @note The owner will be the same as the owner of the parent thing
|
||||||
Thing(Thing* parent, unsigned char thingType = 0, unsigned char thingId = 0);
|
|
||||||
|
~Thing();
|
||||||
|
|
||||||
|
static Thing Reconstruct(Participant* owner,
|
||||||
|
unsigned char thingType,
|
||||||
|
unsigned char thingId);
|
||||||
|
|
||||||
#pragma endregion Init
|
#pragma endregion Init
|
||||||
|
|
||||||
@ -72,6 +82,7 @@ class Thing {
|
|||||||
|
|
||||||
/// @brief The participant managing this thing
|
/// @brief The participant managing this thing
|
||||||
Participant* owner = nullptr;
|
Participant* owner = nullptr;
|
||||||
|
|
||||||
/// @brief The ID of the thing
|
/// @brief The ID of the thing
|
||||||
unsigned char id = 0;
|
unsigned char id = 0;
|
||||||
|
|
||||||
@ -106,11 +117,15 @@ class Thing {
|
|||||||
|
|
||||||
/// @brief Sets the parent of this Thing
|
/// @brief Sets the parent of this Thing
|
||||||
/// @param parent The Thing which should become the parent
|
/// @param parent The Thing which should become the parent
|
||||||
virtual void SetParent(Thing* parent);
|
// virtual void SetParent(Thing* parent);
|
||||||
|
void SetParent(Thing* parent);
|
||||||
/// @brief Gets the parent of this Thing
|
/// @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
|
/// @brief The number of children
|
||||||
unsigned char childCount = 0;
|
unsigned char childCount = 0;
|
||||||
/// @brief Get a child by index
|
/// @brief Get a child by index
|
||||||
@ -198,9 +213,11 @@ class Thing {
|
|||||||
/// parent's orientation
|
/// parent's orientation
|
||||||
SwingTwist orientation;
|
SwingTwist orientation;
|
||||||
|
|
||||||
/// @brief The linear velocity of the thing in local space, in meters per second
|
/// @brief The linear velocity of the thing in local space, in meters per
|
||||||
|
/// second
|
||||||
Spherical linearVelocity;
|
Spherical linearVelocity;
|
||||||
/// @brief The angular velocity of the thing in local space, in degrees per second
|
/// @brief The angular velocity of the thing in local space, in degrees per
|
||||||
|
/// second
|
||||||
Spherical angularVelocity;
|
Spherical angularVelocity;
|
||||||
|
|
||||||
#pragma endregion Pose
|
#pragma endregion Pose
|
||||||
@ -208,20 +225,19 @@ class Thing {
|
|||||||
#pragma region Update
|
#pragma region Update
|
||||||
|
|
||||||
public:
|
public:
|
||||||
/// @brief Get the current time in milliseconds
|
virtual void PrepareForUpdate();
|
||||||
/// @return The current time in milliseconds
|
|
||||||
static unsigned long GetTimeMs();
|
|
||||||
|
|
||||||
/// @brief Updates the state of the thing
|
|
||||||
void Update(bool recursive = false);
|
|
||||||
|
|
||||||
/// @brief Updates the state of the thing
|
/// @brief Updates the state of the thing
|
||||||
/// @param currentTimeMs The current clock time in milliseconds; if this is
|
/// @param currentTimeMs The current clock time in milliseconds; if this is
|
||||||
/// zero, the current time is retrieved automatically
|
/// zero, the current time is retrieved automatically
|
||||||
/// @param recurse When true, this will Update the descendants recursively
|
/// @param recurse When true, this will Update the descendants recursively
|
||||||
virtual void Update(unsigned long currentTimeMs, bool recurse = false);
|
virtual void Update(bool recurse = false);
|
||||||
|
|
||||||
static void UpdateThings(unsigned long currentTimeMs);
|
static void UpdateThings();
|
||||||
|
|
||||||
|
/// @brief Get the current time in milliseconds
|
||||||
|
/// @return The current time in milliseconds
|
||||||
|
static unsigned long GetTimeMs();
|
||||||
|
|
||||||
#pragma endregion Update
|
#pragma endregion Update
|
||||||
|
|
||||||
|
54
Things/ControlledMotor.cpp
Normal file
54
Things/ControlledMotor.cpp
Normal file
@ -0,0 +1,54 @@
|
|||||||
|
#include "ControlledMotor.h"
|
||||||
|
|
||||||
|
namespace RoboidControl {
|
||||||
|
|
||||||
|
ControlledMotor::ControlledMotor(Motor* motor,
|
||||||
|
RelativeEncoder* encoder,
|
||||||
|
Thing* parent)
|
||||||
|
: Motor(parent), motor(motor), encoder(encoder) {
|
||||||
|
this->type = Type::ControlledMotor;
|
||||||
|
// encoder.SetParent(*this);
|
||||||
|
// Thing parent = motor.GetParent();
|
||||||
|
// this->SetParent(parent);
|
||||||
|
}
|
||||||
|
|
||||||
|
void ControlledMotor::SetTargetVelocity(float velocity) {
|
||||||
|
this->targetVelocity = velocity;
|
||||||
|
this->rotationDirection =
|
||||||
|
(targetVelocity < 0) ? Direction::Reverse : Direction::Forward;
|
||||||
|
}
|
||||||
|
|
||||||
|
void ControlledMotor::Update(bool recurse) {
|
||||||
|
encoder->Update(false);
|
||||||
|
|
||||||
|
this->actualVelocity = (int)rotationDirection * encoder->rotationSpeed;
|
||||||
|
|
||||||
|
unsigned long currentTimeMs = GetTimeMs();
|
||||||
|
float timeStep = (currentTimeMs - this->lastUpdateTime) / 1000.0f;
|
||||||
|
this->lastUpdateTime = currentTimeMs;
|
||||||
|
|
||||||
|
float error = this->targetVelocity - this->actualVelocity;
|
||||||
|
float acceleration =
|
||||||
|
error * timeStep * pidP; // Just P is used at this moment
|
||||||
|
std::cout << "motor acc. " << acceleration << std::endl;
|
||||||
|
motor->SetTargetVelocity(targetVelocity +
|
||||||
|
acceleration); // or something like that
|
||||||
|
|
||||||
|
motor->Update(false);
|
||||||
|
}
|
||||||
|
|
||||||
|
// float ControlledMotor::GetActualVelocity() {
|
||||||
|
// return (int)rotationDirection * encoder->rotationSpeed;
|
||||||
|
// }
|
||||||
|
|
||||||
|
// bool ControlledMotor::Drive(float distance) {
|
||||||
|
// if (!driving) {
|
||||||
|
// targetDistance = distance;
|
||||||
|
// startDistance = encoder->GetDistance();
|
||||||
|
// driving = true;
|
||||||
|
// }
|
||||||
|
// float totalDistance = encoder->GetDistance() - startDistance;
|
||||||
|
// bool completed = totalDistance > targetDistance;
|
||||||
|
// return completed;
|
||||||
|
// }
|
||||||
|
} // namespace RoboidControl
|
38
Things/ControlledMotor.h
Normal file
38
Things/ControlledMotor.h
Normal file
@ -0,0 +1,38 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include "Motor.h"
|
||||||
|
#include "RelativeEncoder.h"
|
||||||
|
|
||||||
|
namespace RoboidControl {
|
||||||
|
|
||||||
|
/// @brief A motor with speed control
|
||||||
|
/// It uses a feedback loop from an encoder to regulate the speed
|
||||||
|
/// The speed is measured in revolutions per second.
|
||||||
|
class ControlledMotor : public Motor {
|
||||||
|
public:
|
||||||
|
ControlledMotor(Motor* motor, RelativeEncoder* encoder, Thing* parent = Thing::LocalRoot());
|
||||||
|
|
||||||
|
float pidP = 1;
|
||||||
|
float pidD = 0;
|
||||||
|
float pidI = 0;
|
||||||
|
|
||||||
|
/// @brief The actual velocity in revolutions per second
|
||||||
|
float actualVelocity;
|
||||||
|
|
||||||
|
enum Direction { Forward = 1, Reverse = -1 };
|
||||||
|
Direction rotationDirection;
|
||||||
|
|
||||||
|
virtual void Update(bool recurse = false) override;
|
||||||
|
|
||||||
|
/// @brief Set the target verlocity for the motor controller
|
||||||
|
/// @param speed the target velocity in revolutions per second
|
||||||
|
virtual void SetTargetVelocity(float velocity) override;
|
||||||
|
|
||||||
|
Motor* motor;
|
||||||
|
RelativeEncoder* encoder;
|
||||||
|
|
||||||
|
protected:
|
||||||
|
float lastUpdateTime;
|
||||||
|
};
|
||||||
|
|
||||||
|
} // namespace RoboidControl
|
@ -1,13 +1,28 @@
|
|||||||
#include "DifferentialDrive.h"
|
#include "DifferentialDrive.h"
|
||||||
|
|
||||||
|
#include "Messages/LowLevelMessages.h"
|
||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
|
||||||
DifferentialDrive::DifferentialDrive() : Thing(Thing::Type::DifferentialDrive) {}
|
DifferentialDrive::DifferentialDrive(Thing* parent)
|
||||||
|
: Thing(Type::DifferentialDrive, parent) {
|
||||||
|
this->name = "Differential drive";
|
||||||
|
|
||||||
DifferentialDrive::DifferentialDrive(Participant* participant, unsigned char thingId)
|
this->leftWheel = new Motor(this);
|
||||||
: Thing(participant, Thing::Type::DifferentialDrive, thingId) {}
|
this->leftWheel->name = "Left motor";
|
||||||
|
|
||||||
DifferentialDrive::DifferentialDrive(Thing* parent, unsigned char thingId) : Thing(parent, Thing::Type::DifferentialDrive, thingId) {}
|
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) {
|
||||||
@ -24,27 +39,38 @@ void DifferentialDrive::SetDriveDimensions(float wheelDiameter,
|
|||||||
this->rightWheel->SetPosition(Spherical(distance, Direction::right));
|
this->rightWheel->SetPosition(Spherical(distance, Direction::right));
|
||||||
}
|
}
|
||||||
|
|
||||||
void DifferentialDrive::SetMotors(Thing* leftWheel, Thing* rightWheel) {
|
// Motor& DifferentialDrive::GetMotorLeft() {
|
||||||
|
// 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 = leftWheel;
|
this->leftWheel = &leftMotor;
|
||||||
;
|
|
||||||
if (leftWheel != nullptr)
|
|
||||||
this->leftWheel->SetPosition(Spherical(distance, Direction::left));
|
this->leftWheel->SetPosition(Spherical(distance, Direction::left));
|
||||||
|
|
||||||
this->rightWheel = rightWheel;
|
this->rightWheel = &rightMotor;
|
||||||
if (rightWheel != nullptr)
|
|
||||||
this->rightWheel->SetPosition(Spherical(distance, Direction::right));
|
this->rightWheel->SetPosition(Spherical(distance, Direction::right));
|
||||||
}
|
}
|
||||||
|
|
||||||
void DifferentialDrive::SetWheelVelocity(float speedLeft, float speedRight) {
|
void DifferentialDrive::SetWheelVelocity(float velocityLeft,
|
||||||
|
float velocityRight) {
|
||||||
|
// if (this->leftWheel != nullptr)
|
||||||
|
// this->leftWheel->SetAngularVelocity(Spherical(velocityLeft,
|
||||||
|
// Direction::left));
|
||||||
|
// if (this->rightWheel != nullptr)
|
||||||
|
// this->rightWheel->SetAngularVelocity(
|
||||||
|
// Spherical(velocityRight, Direction::right));
|
||||||
if (this->leftWheel != nullptr)
|
if (this->leftWheel != nullptr)
|
||||||
this->leftWheel->SetAngularVelocity(Spherical(speedLeft, Direction::left));
|
this->leftWheel->SetTargetVelocity(velocityLeft);
|
||||||
if (this->rightWheel != nullptr)
|
if (this->rightWheel != nullptr)
|
||||||
this->rightWheel->SetAngularVelocity(
|
this->rightWheel->SetTargetVelocity(velocityRight);
|
||||||
Spherical(speedRight, Direction::right));
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void DifferentialDrive::Update(unsigned long currentMs, bool recursive) {
|
void DifferentialDrive::Update(bool recursive) {
|
||||||
if (this->linearVelocityUpdated) {
|
if (this->linearVelocityUpdated) {
|
||||||
// this assumes forward velocity only....
|
// this assumes forward velocity only....
|
||||||
float linearVelocity = this->GetLinearVelocity().distance;
|
float linearVelocity = this->GetLinearVelocity().distance;
|
||||||
@ -65,7 +91,14 @@ void DifferentialDrive::Update(unsigned long currentMs, bool recursive) {
|
|||||||
|
|
||||||
this->SetWheelVelocity(speedLeft, speedRight);
|
this->SetWheelVelocity(speedLeft, speedRight);
|
||||||
}
|
}
|
||||||
Thing::Update(currentMs, recursive);
|
Thing::Update(recursive);
|
||||||
|
}
|
||||||
|
|
||||||
|
int DifferentialDrive::GenerateBinary(char* data, unsigned char* ix) {
|
||||||
|
data[(*ix)++] = this->leftWheel->id;
|
||||||
|
data[(*ix)++] = this->rightWheel->id;
|
||||||
|
LowLevelMessages::SendFloat16(data, ix, this->wheelRadius);
|
||||||
|
return 4;
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace RoboidControl
|
} // namespace RoboidControl
|
@ -1,6 +1,7 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "Thing.h"
|
#include "Thing.h"
|
||||||
|
#include "Motor.h"
|
||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
|
||||||
@ -9,18 +10,13 @@ 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 differential drive without networking support
|
|
||||||
DifferentialDrive();
|
|
||||||
/// @brief Create a differential drive with networking support
|
|
||||||
/// @param participant The local participant
|
|
||||||
/// @param thingId The ID of the thing, leave out or set to zero to generate
|
|
||||||
/// an ID
|
|
||||||
DifferentialDrive(Participant* participant, unsigned char thingId = 0);
|
|
||||||
/// @brief Create a new child differential drive
|
/// @brief Create a new child differential drive
|
||||||
/// @param parent The parent thing
|
/// @param parent The parent thing
|
||||||
/// @param thingId The ID of the thing, leave out or set to zero to generate
|
/// @param thingId The ID of the thing, leave out or set to zero to generate
|
||||||
/// an ID
|
/// an ID
|
||||||
DifferentialDrive(Thing* parent, unsigned char thingId = 0);
|
DifferentialDrive(Thing* parent = Thing::LocalRoot());
|
||||||
|
|
||||||
|
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
|
||||||
@ -30,10 +26,13 @@ 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(Thing* leftWheel, Thing* rightWheel);
|
void SetMotors(Motor& leftMotor, Motor& rightMotor);
|
||||||
|
|
||||||
/// @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.
|
||||||
@ -43,21 +42,25 @@ class DifferentialDrive : public Thing {
|
|||||||
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(unsigned long currentMs, bool recursive = true) override;
|
virtual void Update(bool recursive = true) override;
|
||||||
|
|
||||||
|
int GenerateBinary(char* bytes, unsigned char* ix) override;
|
||||||
|
// virtual void ProcessBinary(char* bytes) override;
|
||||||
|
|
||||||
|
/// @brief The left wheel
|
||||||
|
Motor* leftWheel = nullptr;
|
||||||
|
/// @brief The right wheel
|
||||||
|
Motor* rightWheel = nullptr;
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
/// @brief The radius of a wheel in meters
|
/// @brief The radius of a wheel in meters
|
||||||
float wheelRadius = 1.0f;
|
float wheelRadius = 0.0f;
|
||||||
/// @brief The distance between the wheels in meters
|
/// @brief The distance between the wheels in meters
|
||||||
float wheelSeparation = 1.0f;
|
float wheelSeparation = 0.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,13 +2,18 @@
|
|||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
|
||||||
DigitalSensor::DigitalSensor() : Thing(Type::Switch) {}
|
//DigitalSensor::DigitalSensor() : Thing(Type::Switch) {}
|
||||||
|
|
||||||
DigitalSensor::DigitalSensor(Participant* owner, unsigned char thingId)
|
// DigitalSensor::DigitalSensor(Participant* owner, unsigned char thingId)
|
||||||
: Thing(owner, Type::Switch, thingId) {}
|
// : Thing(owner, Type::Switch, thingId) {}
|
||||||
|
|
||||||
DigitalSensor::DigitalSensor(Thing* parent, unsigned char thingId)
|
// DigitalSensor::DigitalSensor(Thing* parent, unsigned char thingId)
|
||||||
: Thing(parent, Type::Switch) {}
|
// : 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) {
|
int DigitalSensor::GenerateBinary(char* bytes, unsigned char* ix) {
|
||||||
bytes[(*ix)++] = state ? 1 : 0;
|
bytes[(*ix)++] = state ? 1 : 0;
|
||||||
|
@ -8,17 +8,18 @@ namespace RoboidControl {
|
|||||||
class DigitalSensor : public Thing {
|
class DigitalSensor : public Thing {
|
||||||
public:
|
public:
|
||||||
/// @brief Create a digital sensor without communication abilities
|
/// @brief Create a digital sensor without communication abilities
|
||||||
DigitalSensor();
|
//DigitalSensor();
|
||||||
/// @brief Create a digital sensor for a participant
|
/// @brief Create a digital sensor for a participant
|
||||||
/// @param owner The owning participant
|
/// @param owner The owning participant
|
||||||
/// @param thingId The ID of the thing, leave out or set to zero to generate
|
/// @param thingId The ID of the thing, leave out or set to zero to generate
|
||||||
/// an ID
|
/// an ID
|
||||||
DigitalSensor(Participant* owner, unsigned char thingId = 0);
|
DigitalSensor(Participant* owner = nullptr); //, unsigned char thingId = 0);
|
||||||
/// @brief Create a new child digital sensor
|
/// @brief Create a new child digital sensor
|
||||||
/// @param parent The parent thing
|
/// @param parent The parent thing
|
||||||
/// @param thingId The ID of the thing, leave out or set to zero to generate
|
/// @param thingId The ID of the thing, leave out or set to zero to generate
|
||||||
/// an ID
|
/// an ID
|
||||||
DigitalSensor(Thing* parent, unsigned char thingId = 0);
|
// 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;
|
||||||
|
16
Things/Motor.cpp
Normal file
16
Things/Motor.cpp
Normal file
@ -0,0 +1,16 @@
|
|||||||
|
#include "Motor.h"
|
||||||
|
|
||||||
|
namespace RoboidControl {
|
||||||
|
|
||||||
|
Motor::Motor(Thing* parent) : Thing(Type::UncontrolledMotor, parent) {}
|
||||||
|
|
||||||
|
void Motor::SetTargetVelocity(float targetSpeed) {
|
||||||
|
this->targetVelocity = targetSpeed;
|
||||||
|
}
|
||||||
|
|
||||||
|
int Motor::GenerateBinary(char* data, unsigned char* ix) {
|
||||||
|
data[(*ix)++] = this->targetVelocity * 127.0f;
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
} // namespace RoboidControl
|
25
Things/Motor.h
Normal file
25
Things/Motor.h
Normal file
@ -0,0 +1,25 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include "Thing.h"
|
||||||
|
|
||||||
|
namespace RoboidControl {
|
||||||
|
|
||||||
|
class Motor : public Thing {
|
||||||
|
public:
|
||||||
|
Motor(Thing* parent = Thing::LocalRoot());
|
||||||
|
|
||||||
|
/// @brief Motor turning direction
|
||||||
|
enum class Direction { Clockwise = 1, CounterClockwise = -1 };
|
||||||
|
/// @brief The forward turning direction of the motor
|
||||||
|
Direction direction;
|
||||||
|
|
||||||
|
virtual void SetTargetVelocity(float velocity); // -1..0..1
|
||||||
|
|
||||||
|
int GenerateBinary(char* bytes, unsigned char* ix) override;
|
||||||
|
// virtual void ProcessBinary(char* bytes) override;
|
||||||
|
|
||||||
|
//protected:
|
||||||
|
float targetVelocity = 0;
|
||||||
|
};
|
||||||
|
|
||||||
|
} // namespace RoboidControl
|
21
Things/RelativeEncoder.cpp
Normal file
21
Things/RelativeEncoder.cpp
Normal file
@ -0,0 +1,21 @@
|
|||||||
|
#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
|
39
Things/RelativeEncoder.h
Normal file
39
Things/RelativeEncoder.h
Normal file
@ -0,0 +1,39 @@
|
|||||||
|
#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;
|
||||||
|
|
||||||
|
/// @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
|
@ -4,9 +4,15 @@
|
|||||||
|
|
||||||
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;
|
||||||
|
@ -12,7 +12,9 @@ class TemperatureSensor : public Thing {
|
|||||||
/// @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
|
/// @brief The measured temperature
|
||||||
float temperature = 0;
|
float temperature = 0;
|
||||||
|
@ -2,22 +2,29 @@
|
|||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
|
||||||
TouchSensor::TouchSensor() : Thing(Thing::Type::TouchSensor) {}
|
TouchSensor::TouchSensor(Thing* parent) : Thing(Type::TouchSensor, parent) {
|
||||||
|
this->name = "Touch sensor";
|
||||||
|
}
|
||||||
|
|
||||||
TouchSensor::TouchSensor(Participant* owner, unsigned char thingId)
|
void TouchSensor::PrepareForUpdate() {
|
||||||
: Thing(owner, Thing::Type::TouchSensor, thingId) {}
|
this->touchedSomething = this->externalTouch;
|
||||||
|
}
|
||||||
|
|
||||||
TouchSensor::TouchSensor(Thing* parent, unsigned char thingId) : Thing(parent->owner, Thing::Type::TouchSensor, thingId) {
|
void TouchSensor::Update(bool recursive) {
|
||||||
this->SetParent(parent);
|
Thing::Update(recursive);
|
||||||
}
|
}
|
||||||
|
|
||||||
int TouchSensor::GenerateBinary(char* bytes, unsigned char* ix) {
|
int TouchSensor::GenerateBinary(char* bytes, unsigned char* ix) {
|
||||||
bytes[(*ix)++] = touchedSomething ? 1 : 0;
|
bytes[(*ix)++] = this->touchedSomething ? 1 : 0;
|
||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
void TouchSensor::ProcessBinary(char* bytes) {
|
void TouchSensor::ProcessBinary(char* bytes) {
|
||||||
this->touchedSomething |= (bytes[0] == 1);
|
this->externalTouch = (bytes[0] == 1);
|
||||||
|
if (this->externalTouch)
|
||||||
|
std::cout << "touching!\n";
|
||||||
|
else
|
||||||
|
std::cout << "not touching\n";
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace RoboidControl
|
} // namespace RoboidControl
|
@ -8,23 +8,19 @@ namespace RoboidControl {
|
|||||||
class TouchSensor : public Thing {
|
class TouchSensor : public Thing {
|
||||||
// Why finishing this release (0.3), I notice that this is equivalent to a digital sensor
|
// Why finishing this release (0.3), I notice that this is equivalent to a digital sensor
|
||||||
public:
|
public:
|
||||||
/// @brief Create a touch sensor without communication abilities
|
|
||||||
TouchSensor();
|
|
||||||
/// @brief Create a touch 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
|
|
||||||
TouchSensor(Participant* owner, unsigned char thingId = 0);
|
|
||||||
/// @brief Create a new child touch sensor
|
/// @brief Create a new child touch sensor
|
||||||
/// @param parent The parent thing
|
/// @param parent The parent thing
|
||||||
/// @param thingId The ID of the thing, leave out or set to zero to generate
|
/// @param thingId The ID of the thing, leave out or set to zero to generate
|
||||||
/// an ID
|
/// an ID
|
||||||
TouchSensor(Thing* parent, unsigned char thingId = 0);
|
TouchSensor(Thing* parent = Thing::LocalRoot());
|
||||||
|
|
||||||
/// @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;
|
||||||
|
virtual void Update(bool recursive) override;
|
||||||
|
|
||||||
/// @brief Function used to generate binary data for this touch sensor
|
/// @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
|
||||||
@ -32,6 +28,8 @@ class TouchSensor : public Thing {
|
|||||||
/// @brief Function used to process binary data received for this touch sensor
|
/// @brief Function used to process binary data received for this touch sensor
|
||||||
/// @param bytes The binary data to process
|
/// @param bytes The binary data to process
|
||||||
virtual void ProcessBinary(char* bytes) override;
|
virtual void ProcessBinary(char* bytes) override;
|
||||||
|
protected:
|
||||||
|
bool externalTouch = false;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace RoboidControl
|
} // namespace RoboidControl
|
||||||
|
@ -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 = new DifferentialDrive();
|
DifferentialDrive bb2b = 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 = new TouchSensor(bb2b);
|
TouchSensor touchLeft = TouchSensor(bb2b);
|
||||||
// and other one on the right
|
// and other one on the right
|
||||||
TouchSensor* touchRight = new TouchSensor(bb2b);
|
TouchSensor touchRight = 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)
|
1
examples/README.md
Normal file
1
examples/README.md
Normal file
@ -0,0 +1 @@
|
|||||||
|
Important: this folder has to be names 'examples' exactly to maintain compatibility with Arduino
|
@ -7,6 +7,9 @@
|
|||||||
#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) {
|
TEST(Participant, Participant) {
|
||||||
@ -15,7 +18,7 @@ TEST(Participant, Participant) {
|
|||||||
unsigned long milliseconds = Thing::GetTimeMs();
|
unsigned long milliseconds = Thing::GetTimeMs();
|
||||||
unsigned long startTime = milliseconds;
|
unsigned long startTime = milliseconds;
|
||||||
while (milliseconds < startTime + 7000) {
|
while (milliseconds < startTime + 7000) {
|
||||||
participant->Update(milliseconds);
|
participant->Update();
|
||||||
|
|
||||||
std::this_thread::sleep_for(std::chrono::milliseconds(100));
|
std::this_thread::sleep_for(std::chrono::milliseconds(100));
|
||||||
milliseconds = Thing::GetTimeMs();
|
milliseconds = Thing::GetTimeMs();
|
||||||
@ -29,7 +32,7 @@ TEST(Participant, SiteServer) {
|
|||||||
unsigned long milliseconds = Thing::GetTimeMs();
|
unsigned long milliseconds = Thing::GetTimeMs();
|
||||||
unsigned long startTime = milliseconds;
|
unsigned long startTime = milliseconds;
|
||||||
while (milliseconds < startTime + 7000) {
|
while (milliseconds < startTime + 7000) {
|
||||||
siteServer->Update(milliseconds);
|
siteServer->Update();
|
||||||
|
|
||||||
std::this_thread::sleep_for(std::chrono::milliseconds(100));
|
std::this_thread::sleep_for(std::chrono::milliseconds(100));
|
||||||
milliseconds = Thing::GetTimeMs();
|
milliseconds = Thing::GetTimeMs();
|
||||||
@ -44,8 +47,8 @@ TEST(Participant, SiteParticipant) {
|
|||||||
unsigned long milliseconds = Thing::GetTimeMs();
|
unsigned long milliseconds = Thing::GetTimeMs();
|
||||||
unsigned long startTime = milliseconds;
|
unsigned long startTime = milliseconds;
|
||||||
while (milliseconds < startTime + 7000) {
|
while (milliseconds < startTime + 7000) {
|
||||||
siteServer->Update(milliseconds);
|
siteServer->Update();
|
||||||
participant->Update(milliseconds);
|
participant->Update();
|
||||||
|
|
||||||
std::this_thread::sleep_for(std::chrono::milliseconds(100));
|
std::this_thread::sleep_for(std::chrono::milliseconds(100));
|
||||||
milliseconds = Thing::GetTimeMs();
|
milliseconds = Thing::GetTimeMs();
|
||||||
@ -63,8 +66,8 @@ TEST(Participant, ThingMsg) {
|
|||||||
unsigned long milliseconds = Thing::GetTimeMs();
|
unsigned long milliseconds = Thing::GetTimeMs();
|
||||||
unsigned long startTime = milliseconds;
|
unsigned long startTime = milliseconds;
|
||||||
while (milliseconds < startTime + 7000) {
|
while (milliseconds < startTime + 7000) {
|
||||||
siteServer->Update(milliseconds);
|
siteServer->Update();
|
||||||
participant->Update(milliseconds);
|
participant->Update();
|
||||||
|
|
||||||
std::this_thread::sleep_for(std::chrono::milliseconds(100));
|
std::this_thread::sleep_for(std::chrono::milliseconds(100));
|
||||||
milliseconds = Thing::GetTimeMs();
|
milliseconds = Thing::GetTimeMs();
|
||||||
|
@ -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(milliseconds);
|
Thing::UpdateThings();
|
||||||
|
|
||||||
milliseconds = Thing::GetTimeMs();
|
milliseconds = Thing::GetTimeMs();
|
||||||
}
|
}
|
||||||
@ -29,7 +29,7 @@ TEST(RoboidControlSuite, IsolatedParticipant) {
|
|||||||
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(milliseconds);
|
participant->Update();
|
||||||
|
|
||||||
milliseconds = Thing::GetTimeMs();
|
milliseconds = Thing::GetTimeMs();
|
||||||
}
|
}
|
||||||
|
Loading…
x
Reference in New Issue
Block a user