Compare commits

..

1 Commits

Author SHA1 Message Date
cf40f311a8 Remove Unity DigitlaSensor 2025-05-01 15:16:19 +02:00
47 changed files with 754 additions and 4137 deletions

View File

@ -1,47 +1,31 @@
using LinearAlgebra; using System.Threading;
using RoboidControl;
namespace RoboidControl { class BB2B {
static void Main() {
// The robot is based on a differential drive // The robot's propulsion is a differential drive
public class BB2B : DifferentialDrive { DifferentialDrive bb2b = new();
readonly DifferentialDrive drive; // Is has a touch sensor at the front left of the roboid
readonly TouchSensor touchLeft; TouchSensor touchLeft = new(bb2b);
readonly TouchSensor touchRight; // and other one on the right
const float speed = 0.5f; TouchSensor touchRight = new(bb2b);
public BB2B(Thing parent = default) : base(parent) {
this.name = "BB2B";
this.SetMotors(new Motor(this), new Motor(this));
this.SetDriveDimensions(0.064f, 0.128f);
// Is has a touch sensor at the front left of the roboid
touchLeft = new(this) {
position = Spherical.Degrees(0.12f, -30, 0),
orientation = new SwingTwist(-30, 0, 0)
};
touchRight = new(this) {
position = Spherical.Degrees(0.12f, 30, 0),
orientation = new SwingTwist(30, 0, 0)
};
}
public override void Update(bool recurse = true) {
// Do forever:
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 ? -speed : speed; 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 ? -speed : speed; 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);
this.SetWheelVelocity(leftWheelSpeed, rightWheelSpeed); // Update the roboid state
bb2b.Update(true);
base.Update(recurse); // and sleep for 100ms
Thread.Sleep(100);
} }
} }
} }

View File

@ -1,55 +0,0 @@
using LinearAlgebra;
namespace RoboidControl {
// The robot is based on a differential drive
public class BB2B_Encoder : DifferentialDrive {
readonly DifferentialDrive drive;
readonly TouchSensor touchLeft;
readonly TouchSensor touchRight;
const float speed = 180.0f; // wheel rotation speed in degrees
public BB2B_Encoder(Thing parent) : base(parent) {
this.name = "BB2B";
this.SetDriveDimensions(0.064f, 0.128f);
// Update the basic motors to motors with encoder
ControlledMotor leftMotor = new(this, new RelativeEncoder()) {
position = new Spherical(0.064f, Direction.left)
};
ControlledMotor rightMotor = new(this, new RelativeEncoder()) {
position = new Spherical(0.064f, Direction.right)
};
this.SetMotors(leftMotor, rightMotor);
// Is has a touch sensor at the front left of the roboid
touchLeft = new(this) {
position = Spherical.Degrees(0.12f, -30, 0),
orientation = new SwingTwist(-30, 0, 0)
};
touchRight = new(this) {
position = Spherical.Degrees(0.12f, 30, 0),
orientation = new SwingTwist(30, 0, 0)
};
}
public override void Update(bool recurse = true) {
// The left wheel turns forward when nothing is touched on the right side
// and turn backward when the roboid hits something on the right
float leftWheelVelocity = touchRight.touchedSomething ? -speed : speed;
// The right wheel does the same, but instead is controlled by
// touches on the left side
float rightWheelVelocity = touchLeft.touchedSomething ? -speed : speed;
// When both sides are touching something, both wheels will turn backward
// and the roboid will move backwards
this.SetWheelAngularVelocity(leftWheelVelocity, rightWheelVelocity);
base.Update(recurse);
}
}
}

View File

@ -1,13 +0,0 @@
using System.Threading;
using RoboidControl;
class Program {
static void Main() {
BB2B bb2b = new();
while (true) {
bb2b.Update();
Thread.Sleep(100);
}
}
}

View File

@ -1,128 +1,17 @@
using System; using System;
using System.Reflection.Emit;
namespace LinearAlgebra { namespace LinearAlgebra {
public class Angle { /// <summary>
/// %Angle utilities
/// </summary>
public static class Angle {
public const float pi = 3.1415927410125732421875F;
// public static float Rad2Deg = 360.0f / ((float)Math.PI * 2);
// public static float Deg2Rad = ((float)Math.PI * 2) / 360.0f;
public const float Rad2Deg = 360.0f / ((float)Math.PI * 2); //0.0174532924F; public const float Rad2Deg = 360.0f / ((float)Math.PI * 2); //0.0174532924F;
public const float Deg2Rad = (float)Math.PI * 2 / 360.0f; //57.29578F; public const float Deg2Rad = ((float)Math.PI * 2) / 360.0f; //57.29578F;
private Angle(float degrees) {
this.value = degrees;
}
private readonly float value = 0;
public static readonly Angle zero = new(0);
public static Angle Degrees(float degrees) {
// Reduce it to (-180..180]
if (float.IsFinite(degrees)) {
while (degrees < -180)
degrees += 360;
while (degrees >= 180)
degrees -= 360;
}
return new Angle(degrees);
}
public static Angle Radians(float radians) {
// Reduce it to (-pi..pi]
if (float.IsFinite(radians)) {
while (radians <= -Math.PI)
radians += 2 * (float)Math.PI;
while (radians > Math.PI)
radians -= 2 * (float)Math.PI;
}
return new Angle(radians * Rad2Deg);
}
public static Angle Revolutions(float revolutions) {
// reduce it to (-0.5 .. 0.5]
if (float.IsFinite(revolutions)) {
// Get the integer part
int integerPart = (int)revolutions;
// Get the decimal part
revolutions -= integerPart;
if (revolutions < -0.5)
revolutions += 1;
if (revolutions >= 0.5)
revolutions -= 1;
}
return new Angle(revolutions * 360);
}
public float inDegrees {
get { return this.value; }
}
public float inRadians {
get { return this.value * Deg2Rad; }
}
public float inRevolutions {
get { return this.value / 360.0f; }
}
/// <summary>
/// Get the sign of the angle
/// </summary>
/// <param name="a">The angle</param>
/// <returns>-1 when the angle is negative, 1 when it is positive and 0 in all other cases</returns>
public static int Sign(Angle a) {
if (a.value < 0)
return -1;
if (a.value > 0)
return 1;
return 0;
}
/// <summary>
/// Returns the magnitude of the angle
/// </summary>
/// <param name="a">The angle</param>
/// <returns>The positive magnitude of the angle</returns>
/// Negative values are negated to get a positive result
public static Angle Abs(Angle a) {
if (Sign(a) < 0)
return -a;
else
return a;
}
/// <summary>
/// Negate the angle
/// </summary>
/// <param name="a">The angle</param>
/// <returns>The negated angle</returns>
/// The negation of -180 is still -180 because the range is (-180..180]
public static Angle operator -(Angle a) {
Angle r = new(-a.value);
return r;
}
/// <summary>
/// Subtract two angles
/// </summary>
/// <param name="a1">Angle 1</param>
/// <param name="a2">Angle 2</param>
/// <returns>The result of the subtraction</returns>
public static Angle operator -(Angle a1, Angle a2) {
Angle r = new(a1.value - a2.value);
return r;
}
/// <summary>
/// Add two angles
/// </summary>
/// <param name="a1">Angle 1</param>
/// <param name="a2">Angle 2</param>
/// <returns>The result of the addition</returns>
public static Angle operator +(Angle a1, Angle a2) {
Angle r = new(a1.value + a2.value);
return r;
}
/// <summary> /// <summary>
/// Clamp the angle between the given min and max values /// Clamp the angle between the given min and max values
@ -132,38 +21,11 @@ namespace LinearAlgebra {
/// <param name="max">The maximum angle</param> /// <param name="max">The maximum angle</param>
/// <returns>The clamped angle</returns> /// <returns>The clamped angle</returns>
/// Angles are normalized /// Angles are normalized
public static float Clamp(Angle angle, Angle min, Angle max) { public static float Clamp(float angle, float min, float max) {
return Float.Clamp(angle.inDegrees, min.inDegrees, max.inDegrees); float normalizedAngle = Normalize(angle);
return Float.Clamp(normalizedAngle, min, max);
} }
/// <summary>
/// Rotate from one angle to the other with a maximum degrees
/// </summary>
/// <param name="fromAngle">Starting angle</param>
/// <param name="toAngle">Target angle</param>
/// <param name="maxAngle">Maximum angle to rotate</param>
/// <returns>The resulting angle</returns>
/// This function is compatible with radian and degrees angles
public static Angle MoveTowards(Angle fromAngle, Angle toAngle, float maxDegrees) {
maxDegrees = Math.Max(0, maxDegrees); // filter out negative distances
Angle d = toAngle - fromAngle;
float dDegrees = Abs(d).inDegrees;
d = Degrees(Float.Clamp(dDegrees, 0, maxDegrees));
if (Sign(d) < 0)
d = -d;
return fromAngle + d;
}
}
/// <summary>
/// %Angle utilities
/// </summary>
public static class Angles {
public const float pi = 3.1415927410125732421875F;
// public static float Rad2Deg = 360.0f / ((float)Math.PI * 2);
// public static float Deg2Rad = ((float)Math.PI * 2) / 360.0f;
/// <summary> /// <summary>
/// Determine the angle difference, result is a normalized angle /// Determine the angle difference, result is a normalized angle
/// </summary> /// </summary>
@ -191,6 +53,21 @@ namespace LinearAlgebra {
return angle; return angle;
} }
/// <summary>
/// Rotate from one angle to the other with a maximum degrees
/// </summary>
/// <param name="fromAngle">Starting angle</param>
/// <param name="toAngle">Target angle</param>
/// <param name="maxAngle">Maximum angle to rotate</param>
/// <returns>The resulting angle</returns>
/// This function is compatible with radian and degrees angles
public static float MoveTowards(float fromAngle, float toAngle, float maxAngle) {
float d = toAngle - fromAngle;
d = Normalize(d);
d = Math.Sign(d) * Float.Clamp(Math.Abs(d), 0, maxAngle);
return fromAngle + d;
}
/// <summary> /// <summary>
/// Map interval of angles between vectors [0..Pi] to interval [0..1] /// Map interval of angles between vectors [0..Pi] to interval [0..1]
/// </summary> /// </summary>

View File

@ -3,7 +3,8 @@ using System;
using Vector3Float = UnityEngine.Vector3; using Vector3Float = UnityEngine.Vector3;
#endif #endif
namespace LinearAlgebra { namespace LinearAlgebra
{
/// <summary> /// <summary>
/// A direction in 3D space /// A direction in 3D space
@ -24,18 +25,18 @@ namespace LinearAlgebra {
horizontal = 0; horizontal = 0;
vertical = 0; vertical = 0;
} }
public Direction(Angle horizontal, Angle vertical) { // public Direction(float horizontal, float vertical) {
this.horizontal = horizontal.inDegrees; // this.horizontal = horizontal;
this.vertical = vertical.inDegrees; // this.vertical = vertical;
this.Normalize(); // //Normalize();
} // }
public static Direction Degrees(float horizontal, float vertical) { public static Direction Degrees(float horizontal, float vertical) {
Direction d = new() { Direction d = new() {
horizontal = horizontal, horizontal = horizontal,
vertical = vertical vertical = vertical
}; };
d.Normalize(); //Normalize();
return d; return d;
} }
public static Direction Radians(float horizontal, float vertical) { public static Direction Radians(float horizontal, float vertical) {
@ -43,7 +44,7 @@ namespace LinearAlgebra {
horizontal = horizontal * Angle.Rad2Deg, horizontal = horizontal * Angle.Rad2Deg,
vertical = vertical * Angle.Rad2Deg vertical = vertical * Angle.Rad2Deg
}; };
d.Normalize(); //Normalize();
return d; return d;
} }
@ -55,16 +56,15 @@ namespace LinearAlgebra {
public readonly static Direction right = Degrees(90, 0); public readonly static Direction right = Degrees(90, 0);
public void Normalize() { public void Normalize() {
this.vertical = Angles.Normalize(this.vertical);
if (this.vertical > 90 || this.vertical < -90) { if (this.vertical > 90 || this.vertical < -90) {
this.horizontal += 180; this.horizontal += 180;
this.vertical = 180 - this.vertical; this.vertical = 180 - this.vertical;
} }
this.horizontal = Angles.Normalize(this.horizontal);
} }
public Vector3Float ToVector3() { public Vector3Float ToVector3()
float verticalRad = ((float)Math.PI / 2) - this.vertical * Angle.Deg2Rad; {
float verticalRad = (Angle.pi / 2) - this.vertical * Angle.Deg2Rad;
float horizontalRad = this.horizontal * Angle.Deg2Rad; float horizontalRad = this.horizontal * Angle.Deg2Rad;
float cosVertical = (float)Math.Cos(verticalRad); float cosVertical = (float)Math.Cos(verticalRad);
float sinVertical = (float)Math.Sin(verticalRad); float sinVertical = (float)Math.Sin(verticalRad);
@ -78,33 +78,6 @@ namespace LinearAlgebra {
Vector3Float v = new(x, y, z); Vector3Float v = new(x, y, z);
return v; return v;
} }
public static bool operator ==(Direction d1, Direction d2) {
bool horizontalEq = d1.horizontal == d2.horizontal;
bool verticalEq = d1.vertical == d2.vertical;
return horizontalEq && verticalEq;
}
public static bool operator !=(Direction d1, Direction d2) {
bool horizontalNEq = d1.horizontal != d2.horizontal;
bool verticalNEq = d1.vertical != d2.vertical;
return horizontalNEq || verticalNEq;
}
public override bool Equals(object obj) {
if (obj is not Direction d)
return false;
bool horizontalEq = this.horizontal == d.horizontal;
bool verticalEq = this.vertical == d.vertical;
return horizontalEq && verticalEq;
}
public override int GetHashCode() {
return (this.horizontal, this.vertical).GetHashCode();
}
} }
} }

View File

@ -83,7 +83,7 @@ namespace LinearAlgebra {
if (distance == 0.0f) if (distance == 0.0f)
return Spherical.zero; return Spherical.zero;
else { else {
float verticalAngle = (float)(Math.PI / 2 - Math.Acos(v.y / distance)) * Angle.Rad2Deg; float verticalAngle = (float)((Angle.pi / 2 - Math.Acos(v.y / distance)) * Angle.Rad2Deg);
float horizontalAngle = (float)Math.Atan2(v.x, v.z) * Angle.Rad2Deg; float horizontalAngle = (float)Math.Atan2(v.x, v.z) * Angle.Rad2Deg;
return Spherical.Degrees(distance, horizontalAngle, verticalAngle); return Spherical.Degrees(distance, horizontalAngle, verticalAngle);
} }
@ -106,7 +106,7 @@ namespace LinearAlgebra {
// } // }
public Vector3 ToVector3() { public Vector3 ToVector3() {
float verticalRad = (float)(90 - this.direction.vertical) * Angle.Deg2Rad; float verticalRad = (Angle.pi / 2) - this.direction.vertical * Angle.Deg2Rad;
float horizontalRad = this.direction.horizontal * Angle.Deg2Rad; float horizontalRad = this.direction.horizontal * Angle.Deg2Rad;
float cosVertical = (float)Math.Cos(verticalRad); float cosVertical = (float)Math.Cos(verticalRad);
float sinVertical = (float)Math.Sin(verticalRad); float sinVertical = (float)Math.Sin(verticalRad);

View File

@ -28,24 +28,12 @@ namespace LinearAlgebra {
return r; return r;
} }
public static SwingTwist Degrees(float horizontalSwing, float verticalSwing, float twist) {
SwingTwist r = new(horizontalSwing, verticalSwing, twist);
return r;
}
#if UNITY_5_3_OR_NEWER #if UNITY_5_3_OR_NEWER
public static SwingTwist FromQuaternion(Quaternion q) {
// q.ToAngles(out float right, out float up, out float forward);
UnityEngine.Vector3 angles = q.eulerAngles;
SwingTwist r = Degrees(angles.y, -angles.x, -angles.z);
return r;
}
public Quaternion ToQuaternion() { public Quaternion ToQuaternion() {
Quaternion q = Quaternion.Euler(-this.swing.vertical, Quaternion q = Quaternion.Euler(-this.swing.vertical,
this.swing.horizontal, this.swing.horizontal,
-this.twist); this.twist);
return q; return q;
} }
#endif #endif
} }

View File

@ -1,207 +1,169 @@
#if !UNITY_5_6_OR_NEWER #if !UNITY_5_6_OR_NEWER
using System;
using System.Formats.Asn1;
using NUnit.Framework; using NUnit.Framework;
namespace LinearAlgebra.Test { namespace LinearAlgebra.Test
public class AngleTests { {
public class Tests
{
[SetUp] [SetUp]
public void Setup() { public void Setup()
{
} }
[Test] [Test]
public void Construct() { public void Normalize()
// Degrees {
float angle = 0.0f;
Angle a = Angle.Degrees(angle);
Assert.AreEqual(angle, a.inDegrees);
angle = -180.0f;
a = Angle.Degrees(angle);
Assert.AreEqual(angle, a.inDegrees);
angle = 270.0f;
a = Angle.Degrees(angle);
Assert.AreEqual(-90, a.inDegrees);
// Radians
angle = 0.0f;
a = Angle.Radians(angle);
Assert.AreEqual(angle, a.inRadians);
angle = (float)-Math.PI;
a = Angle.Radians(angle);
Assert.AreEqual(angle, a.inRadians);
angle = (float)Math.PI * 1.5f;
a = Angle.Radians(angle);
Assert.AreEqual(-Math.PI * 0.5f, a.inRadians, 1.0E-05F);
// Revolutions
angle = 0.0f;
a = Angle.Revolutions(angle);
Assert.AreEqual(angle, a.inRevolutions);
angle = -0.5f;
a = Angle.Revolutions(angle);
Assert.AreEqual(angle, a.inRevolutions);
angle = 0.75f;
a = Angle.Revolutions(angle);
Assert.AreEqual(-0.25f, a.inRevolutions);
}
// [Test]
// public void Normalize() {
// float r = 0;
// r = Angle.Normalize(90);
// Assert.AreEqual(r, 90, "Normalize 90");
// r = Angle.Normalize(-90);
// Assert.AreEqual(r, -90, "Normalize -90");
// r = Angle.Normalize(270);
// Assert.AreEqual(r, -90, "Normalize 270");
// r = Angle.Normalize(270 + 360);
// Assert.AreEqual(r, -90, "Normalize 270+360");
// r = Angle.Normalize(-270);
// Assert.AreEqual(r, 90, "Normalize -270");
// r = Angle.Normalize(-270 - 360);
// Assert.AreEqual(r, 90, "Normalize -270-360");
// r = Angle.Normalize(0);
// Assert.AreEqual(r, 0, "Normalize 0");
// r = Angle.Normalize(float.PositiveInfinity);
// Assert.AreEqual(r, float.PositiveInfinity, "Normalize INFINITY");
// r = Angle.Normalize(float.NegativeInfinity);
// Assert.AreEqual(r, float.NegativeInfinity, "Normalize INFINITY");
// }
[Test]
public void Clamp() {
float r = 0; float r = 0;
r = Angle.Clamp(Angle.Degrees(1), Angle.Degrees(0), Angle.Degrees(2)); r = Angle.Normalize(90);
Assert.AreEqual(r, 90, "Normalize 90");
r = Angle.Normalize(-90);
Assert.AreEqual(r, -90, "Normalize -90");
r = Angle.Normalize(270);
Assert.AreEqual(r, -90, "Normalize 270");
r = Angle.Normalize(270 + 360);
Assert.AreEqual(r, -90, "Normalize 270+360");
r = Angle.Normalize(-270);
Assert.AreEqual(r, 90, "Normalize -270");
r = Angle.Normalize(-270 - 360);
Assert.AreEqual(r, 90, "Normalize -270-360");
r = Angle.Normalize(0);
Assert.AreEqual(r, 0, "Normalize 0");
r = Angle.Normalize(float.PositiveInfinity);
Assert.AreEqual(r, float.PositiveInfinity, "Normalize INFINITY");
r = Angle.Normalize(float.NegativeInfinity);
Assert.AreEqual(r, float.NegativeInfinity, "Normalize INFINITY");
}
[Test]
public void Clamp()
{
float r = 0;
r = Angle.Clamp(1, 0, 2);
Assert.AreEqual(r, 1, "Clamp 1 0 2"); Assert.AreEqual(r, 1, "Clamp 1 0 2");
r = Angle.Clamp(Angle.Degrees(-1), Angle.Degrees(0), Angle.Degrees(2)); r = Angle.Clamp(-1, 0, 2);
Assert.AreEqual(r, 0, "Clamp -1 0 2"); Assert.AreEqual(r, 0, "Clamp -1 0 2");
r = Angle.Clamp(Angle.Degrees(3), Angle.Degrees(0), Angle.Degrees(2)); r = Angle.Clamp(3, 0, 2);
Assert.AreEqual(r, 2, "Clamp 3 0 2"); Assert.AreEqual(r, 2, "Clamp 3 0 2");
r = Angle.Clamp(Angle.Degrees(1), Angle.Degrees(0), Angle.Degrees(0)); r = Angle.Clamp(1, 0, 0);
Assert.AreEqual(r, 0, "Clamp 1 0 0"); Assert.AreEqual(r, 0, "Clamp 1 0 0");
r = Angle.Clamp(Angle.Degrees(0), Angle.Degrees(0), Angle.Degrees(0)); r = Angle.Clamp(0, 0, 0);
Assert.AreEqual(r, 0, "Clamp 0 0 0"); Assert.AreEqual(r, 0, "Clamp 0 0 0");
r = Angle.Clamp(Angle.Degrees(0), Angle.Degrees(1), Angle.Degrees(-1)); r = Angle.Clamp(0, 1, -1);
Assert.AreEqual(r, 1, "Clamp 0 1 -1"); Assert.AreEqual(r, 1, "Clamp 0 1 -1");
r = Angle.Clamp(Angle.Degrees(1), Angle.Degrees(0), Angle.Degrees(float.PositiveInfinity)); r = Angle.Clamp(1, 0, float.PositiveInfinity);
Assert.AreEqual(r, 1, "Clamp 1 0 INFINITY"); Assert.AreEqual(r, 1, "Clamp 1 0 INFINITY");
r = Angle.Clamp(Angle.Degrees(1), Angle.Degrees(float.NegativeInfinity), Angle.Degrees(1)); r = Angle.Clamp(1, float.NegativeInfinity, 1);
Assert.AreEqual(r, 1, "Clamp 1 -INFINITY 1"); Assert.AreEqual(r, 1, "Clamp 1 -INFINITY 1");
} }
// [Test] [Test]
// public void Difference() { public void Difference()
// float r = 0; {
float r = 0;
// r = Angle.Difference(0, 90); r = Angle.Difference(0, 90);
// Assert.AreEqual(r, 90, "Difference 0 90"); Assert.AreEqual(r, 90, "Difference 0 90");
// r = Angle.Difference(0, -90); r = Angle.Difference(0, -90);
// Assert.AreEqual(r, -90, "Difference 0 -90"); Assert.AreEqual(r, -90, "Difference 0 -90");
// r = Angle.Difference(0, 270); r = Angle.Difference(0, 270);
// Assert.AreEqual(r, -90, "Difference 0 270"); Assert.AreEqual(r, -90, "Difference 0 270");
// r = Angle.Difference(0, -270); r = Angle.Difference(0, -270);
// Assert.AreEqual(r, 90, "Difference 0 -270"); Assert.AreEqual(r, 90, "Difference 0 -270");
// r = Angle.Difference(90, 0); r = Angle.Difference(90, 0);
// Assert.AreEqual(r, -90, "Difference 90 0"); Assert.AreEqual(r, -90, "Difference 90 0");
// r = Angle.Difference(-90, 0); r = Angle.Difference(-90, 0);
// Assert.AreEqual(r, 90, "Difference -90 0"); Assert.AreEqual(r, 90, "Difference -90 0");
// r = Angle.Difference(0, 0); r = Angle.Difference(0, 0);
// Assert.AreEqual(r, 0, "Difference 0 0"); Assert.AreEqual(r, 0, "Difference 0 0");
// r = Angle.Difference(90, 90); r = Angle.Difference(90, 90);
// Assert.AreEqual(r, 0, "Difference 90 90"); Assert.AreEqual(r, 0, "Difference 90 90");
// r = Angle.Difference(0, float.PositiveInfinity); r = Angle.Difference(0, float.PositiveInfinity);
// Assert.AreEqual(r, float.PositiveInfinity, "Difference 0 INFINITY"); Assert.AreEqual(r, float.PositiveInfinity, "Difference 0 INFINITY");
// r = Angle.Difference(0, float.NegativeInfinity); r = Angle.Difference(0, float.NegativeInfinity);
// Assert.AreEqual(r, float.NegativeInfinity, "Difference 0 -INFINITY"); Assert.AreEqual(r, float.NegativeInfinity, "Difference 0 -INFINITY");
// r = Angle.Difference(float.NegativeInfinity, float.PositiveInfinity); r = Angle.Difference(float.NegativeInfinity, float.PositiveInfinity);
// Assert.AreEqual(r, float.PositiveInfinity, "Difference -INFINITY INFINITY"); Assert.AreEqual(r, float.PositiveInfinity, "Difference -INFINITY INFINITY");
// } }
[Test] [Test]
public void MoveTowards() { public void MoveTowards()
Angle r = Angle.zero; {
float r = 0;
r = Angle.MoveTowards(Angle.Degrees(0), Angle.Degrees(90), 30); r = Angle.MoveTowards(0, 90, 30);
Assert.AreEqual(r.inDegrees, 30, "MoveTowards 0 90 30"); Assert.AreEqual(r, 30, "MoveTowards 0 90 30");
r = Angle.MoveTowards(Angle.Degrees(0), Angle.Degrees(90), 90); r = Angle.MoveTowards(0, 90, 90);
Assert.AreEqual(r.inDegrees, 90, "MoveTowards 0 90 90"); Assert.AreEqual(r, 90, "MoveTowards 0 90 90");
r = Angle.MoveTowards(Angle.Degrees(0), Angle.Degrees(90), 180); r = Angle.MoveTowards(0, 90, 180);
Assert.AreEqual(r.inDegrees, 90, "MoveTowards 0 90 180"); Assert.AreEqual(r, 90, "MoveTowards 0 90 180");
r = Angle.MoveTowards(Angle.Degrees(0), Angle.Degrees(90), 270); r = Angle.MoveTowards(0, 90, 270);
Assert.AreEqual(r.inDegrees, 90, "MoveTowrads 0 90 270"); Assert.AreEqual(r, 90, "MoveTowrads 0 90 270");
r = Angle.MoveTowards(Angle.Degrees(0), Angle.Degrees(90), -30); r = Angle.MoveTowards(0, 90, -30);
Assert.AreEqual(r.inDegrees, 0, "MoveTowards 0 90 -30"); Assert.AreEqual(r, -30, "MoveTowards 0 90 -30");
r = Angle.MoveTowards(Angle.Degrees(0), Angle.Degrees(-90), -30); r = Angle.MoveTowards(0, -90, -30);
Assert.AreEqual(r.inDegrees, 0, "MoveTowards 0 -90 -30"); Assert.AreEqual(r, 30, "MoveTowards 0 -90 -30");
r = Angle.MoveTowards(Angle.Degrees(0), Angle.Degrees(-90), -90); r = Angle.MoveTowards(0, -90, -90);
Assert.AreEqual(r.inDegrees, 0, "MoveTowards 0 -90 -90"); Assert.AreEqual(r, 90, "MoveTowards 0 -90 -90");
r = Angle.MoveTowards(Angle.Degrees(0), Angle.Degrees(-90), -180); r = Angle.MoveTowards(0, -90, -180);
Assert.AreEqual(r.inDegrees, 0, "MoveTowards 0 -90 -180"); Assert.AreEqual(r, 180, "MoveTowards 0 -90 -180");
r = Angle.MoveTowards(Angle.Degrees(0), Angle.Degrees(-90), -270); r = Angle.MoveTowards(0, -90, -270);
Assert.AreEqual(r.inDegrees, 0, "MoveTowrads 0 -90 -270"); Assert.AreEqual(r, 270, "MoveTowrads 0 -90 -270");
r = Angle.MoveTowards(Angle.Degrees(0), Angle.Degrees(90), 0); r = Angle.MoveTowards(0, 90, 0);
Assert.AreEqual(r.inDegrees, 0, "MoveTowards 0 90 0"); Assert.AreEqual(r, 0, "MoveTowards 0 90 0");
r = Angle.MoveTowards(Angle.Degrees(0), Angle.Degrees(0), 0); r = Angle.MoveTowards(0, 0, 0);
Assert.AreEqual(r.inDegrees, 0, "MoveTowards 0 0 0"); Assert.AreEqual(r, 0, "MoveTowards 0 0 0");
r = Angle.MoveTowards(Angle.Degrees(0), Angle.Degrees(0), 30); r = Angle.MoveTowards(0, 0, 30);
Assert.AreEqual(r.inDegrees, 0, "MoveTowrads 0 0 30"); Assert.AreEqual(r, 0, "MoveTowrads 0 0 30");
r = Angle.MoveTowards(Angle.Degrees(0), Angle.Degrees(90), float.PositiveInfinity); r = Angle.MoveTowards(0, 90, float.PositiveInfinity);
Assert.AreEqual(r.inDegrees, 90, "MoveTowards 0 90 INFINITY"); Assert.AreEqual(r, 90, "MoveTowards 0 90 INFINITY");
r = Angle.MoveTowards(Angle.Degrees(0), Angle.Degrees(float.PositiveInfinity), 30); r = Angle.MoveTowards(0, float.PositiveInfinity, 30);
Assert.AreEqual(r.inDegrees, 30, "MoveTowrads 0 INFINITY 30"); Assert.AreEqual(r, 30, "MoveTowrads 0 INFINITY 30");
r = Angle.MoveTowards(Angle.Degrees(0), Angle.Degrees(-90), float.NegativeInfinity); r = Angle.MoveTowards(0, -90, float.NegativeInfinity);
Assert.AreEqual(r.inDegrees, 0, "MoveTowards 0 -90 -INFINITY"); Assert.AreEqual(r, float.PositiveInfinity, "MoveTowards 0 -90 -INFINITY");
r = Angle.MoveTowards(Angle.Degrees(0), Angle.Degrees(float.NegativeInfinity), -30); r = Angle.MoveTowards(0, float.NegativeInfinity, -30);
Assert.AreEqual(r.inDegrees, 0, "MoveTowrads 0 -INFINITY -30"); Assert.AreEqual(r, 30, "MoveTowrads 0 -INFINITY -30");
} }
} }

View File

@ -1,21 +0,0 @@
#if !UNITY_5_6_OR_NEWER
using NUnit.Framework;
namespace LinearAlgebra.Test {
public class DirectionTest {
[SetUp]
public void Setup() {
}
[Test]
public void Compare() {
Direction d1 = Direction.Degrees(45, 135);
Direction d2 = new(Angle.Degrees(45), Angle.Degrees(135));
bool r;
r = d1 == d2;
Assert.True(r);
Assert.AreEqual(d1, d2);
}
};
}
#endif

View File

@ -1,5 +1,4 @@
#if !UNITY_5_6_OR_NEWER #if !UNITY_5_6_OR_NEWER
using System;
using NUnit.Framework; using NUnit.Framework;
namespace LinearAlgebra.Test { namespace LinearAlgebra.Test {
@ -14,19 +13,7 @@ namespace LinearAlgebra.Test {
Spherical s = Spherical.FromVector3(v); Spherical s = Spherical.FromVector3(v);
Assert.AreEqual(1.0f, s.distance, "s.distance 0 0 1"); Assert.AreEqual(1.0f, s.distance, "s.distance 0 0 1");
Assert.AreEqual(0.0f, s.direction.horizontal, "s.hor 0 0 1"); Assert.AreEqual(0.0f, s.direction.horizontal, "s.hor 0 0 1");
Assert.AreEqual(0.0f, s.direction.vertical, 1.0E-05F, "s.vert 0 0 1"); Assert.AreEqual(0.0f, s.direction.vertical, "s.vert 0 0 1");
v = new(0, 1, 0);
s = Spherical.FromVector3(v);
Assert.AreEqual(1.0f, s.distance, "s.distance 0 1 0");
Assert.AreEqual(0.0f, s.direction.horizontal, "s.hor 0 1 0");
Assert.AreEqual(90.0f, s.direction.vertical, "s.vert 0 1 0");
v = new(1, 0, 0);
s = Spherical.FromVector3(v);
Assert.AreEqual(1.0f, s.distance, "s.distance 1 0 0");
Assert.AreEqual(90.0f, s.direction.horizontal, "s.hor 1 0 0");
Assert.AreEqual(0.0f, s.direction.vertical, 1.0E-05F, "s.vert 1 0 0");
} }
[Test] [Test]
@ -36,17 +23,7 @@ namespace LinearAlgebra.Test {
Spherical r = Spherical.zero; Spherical r = Spherical.zero;
r = v1 + v2; r = v1 + v2;
Assert.AreEqual(v1.distance, r.distance, 1.0E-05F, "Addition(0,0,0)"); Assert.AreEqual(v1.distance, r.distance, "Addition(0,0,0)");
r = v1;
r += v2;
Assert.AreEqual(v1.distance, r.distance, 1.0E-05F, "Addition(0,0,0)");
v2 = Spherical.Degrees(1, 0, 90);
r = v1 + v2;
Assert.AreEqual(Math.Sqrt(2), r.distance, 1.0E-05F, "Addition(1 0 90)");
Assert.AreEqual(45.0f, r.direction.horizontal, "Addition(1 0 90)");
Assert.AreEqual(45.0f, r.direction.vertical, 1.0E-05F, "Addition(1 0 90)");
} }
} }
} }

View File

@ -11,21 +11,3 @@ The documentation for Roboid Control for C# is found at https://docs.roboidcontr
- RoboidControl::Thing - RoboidControl::Thing
- RoboidControl::Participant - RoboidControl::Participant
# Get Started
## Unity
The Unity environment can use the same RoboidControl code as every other C# code, but needs a *starter* wrapper around it to make the things visibile. For example, to start the BB2B example in Unity one needs to write a BB2B_Starter.cs component as follows:
```
using RoboidControl.Unity;
public class BB2B_Starter : SiteServer {
void Start() {
new RoboidControl.BB2B();
}
}
```
This component then should be attached to a GameObject in the scene.
It is possible to create a Site Server in Unity by just adding the `SiteServer` Component to a GameObject in the scene. When this is run, other roboids will be able to connect to this site then.

View File

@ -1,4 +1,4 @@
#if UNITY_5_3_OR_NEWER && RC_DEBUG #if UNITY_5_3_OR_NEWER
using System.IO; using System.IO;
using System.Text; using System.Text;
using UnityEngine; using UnityEngine;

View File

@ -1,145 +0,0 @@
#if UNITY_5_3_OR_NEWER
using UnityEngine;
namespace RoboidControl.Unity {
/// <summary>
/// The Unity representation of a Roboid Control differential drive
/// </summary>
public class DifferentialDrive : Thing {
/// <summary>
/// The core differential drive
/// </summary>
public RoboidControl.DifferentialDrive coreDrive => core as RoboidControl.DifferentialDrive;
/// <summary>
/// Create the Unity representation
/// </summary>
/// <param name="coreDrive">The core touch sensor</param>
/// <returns>The Unity representation of the touch sensor</returns>
/// This uses a 'DifferentialDrive' resource when available for the Unity representation.
/// If this is not available, a default representation is created.
public static DifferentialDrive Create(RoboidControl.DifferentialDrive coreDrive) {
DifferentialDrive differentialDrive;
Rigidbody rb = null;
GameObject prefab = (GameObject)Resources.Load("DifferentialDrive");
if (prefab != null) {
// Use resource prefab when available
GameObject gameObj = Instantiate(prefab);
differentialDrive = gameObj.GetComponent<DifferentialDrive>();
differentialDrive.Init(coreDrive);
rb = gameObj.GetComponent<Rigidbody>();
}
else {
// Default implementation
GameObject gameObj = new(coreDrive.name);
differentialDrive = gameObj.AddComponent<DifferentialDrive>();
differentialDrive.Init(coreDrive);
rb = gameObj.AddComponent<Rigidbody>();
rb.isKinematic = false;
rb.mass = 0.1f;
}
if (coreDrive.isRemote) {
if (rb != null)
rb.isKinematic = true;
}
return differentialDrive;
}
public Motor leftMotor;
public Motor rightMotor;
/// <summary>
/// The left wheel of the differential drive
/// </summary>
public Wheel leftWheel;
/// <summary>
/// The right wheel of the differential drive
/// </summary>
public Wheel rightWheel;
/// <summary>
/// The caster wheel to keep the differential drive horizontal
/// </summary>
public SphereCollider casterWheel;
/// <summary>
/// The rigidbody of the differential drive
/// </summary>
private Rigidbody rb = null;
/// <summary>
/// Start the Unity representation
/// </summary>
protected virtual void Start() {
rb = GetComponent<Rigidbody>();
}
/// <summary>
/// Handle the binary event indicating a configuration change
/// </summary>
protected override void HandleBinary() {
HandleWheelBinary(coreDrive.leftWheel, ref leftMotor, ref leftWheel);
HandleWheelBinary(coreDrive.rightWheel, ref rightMotor, ref rightWheel);
if (casterWheel == null) {
GameObject gameObj = new("Caster wheel");
gameObj.transform.parent = this.transform;
casterWheel = gameObj.AddComponent<SphereCollider>();
casterWheel.material = Wheel.slidingWheel;
}
if (coreDrive.wheelRadius > 0 && coreDrive.leftWheel != null && coreDrive.rightWheel != null) {
casterWheel.radius = coreDrive.wheelRadius;
// Put it in the middle of the back
// This code assumes that the left wheel position has Direction.left and the right wheel Direction.right...
float wheelSeparation = coreDrive.leftWheel.position.distance + coreDrive.rightWheel.position.distance;
casterWheel.center = new Vector3(0, 0, -wheelSeparation);
}
}
private void HandleWheelBinary(RoboidControl.Motor coreMotor, ref Motor motor, ref Wheel wheel) {
if (coreMotor == null)
return;
if (motor == null) {
motor = coreMotor.component as Motor;
if (motor == null)
motor = Motor.Create(coreMotor);
wheel.transform.SetParent(motor.transform);
}
else if (motor.core.id != coreMotor.id) {
motor = coreMotor.component as Motor;
if (motor != null)
wheel.transform.SetParent(motor.transform);
}
}
/// <summary>
/// Update the Unity representation state
/// </summary>
protected override void FixedUpdate() {
base.FixedUpdate();
if (rb != null && leftMotor != null && rightMotor != null) {
float leftWheelVelocity = leftMotor.rotationSpeed * (2 * Mathf.PI) * leftWheel.wheelRadius;
float rightWheelVelocity = rightMotor.rotationSpeed * (2 * Mathf.PI) * rightWheel.wheelRadius;
if (leftWheel != null && rightWheel != null) {
float wheelSeparation = Vector3.Distance(leftWheel.transform.position, rightWheel.transform.position);
float forwardSpeed = (leftWheelVelocity + rightWheelVelocity) / 2f;
float turningSpeed = (leftWheelVelocity - rightWheelVelocity) / wheelSeparation;
// Use smoothing to emulate motor inertia
rb.velocity = 0.9f * rb.velocity + 0.1f * forwardSpeed * transform.forward;
rb.angularVelocity = 0.9f * rb.angularVelocity + 0.1f * turningSpeed * Vector3.up;
core.ReplacePosition(LinearAlgebra.Spherical.FromVector3(this.transform.localPosition));
core.ReplaceOrientation(LinearAlgebra.SwingTwist.FromQuaternion(this.transform.localRotation));
}
}
}
}
}
#endif

View File

@ -5,53 +5,42 @@ using UnityEngine;
namespace RoboidControl.Unity { namespace RoboidControl.Unity {
/// <summary> /// <summary>
/// The Unity representation of a Roboid Control distance sensor /// The Unity representation of a distance sensor
/// </summary> /// </summary>
public class DistanceSensor : Thing { public class DistanceSensor : Thing {
/// <summary> /// <summary>
/// The core distance sensor /// The core distance sensor
/// </summary> /// </summary>
public RoboidControl.DistanceSensor coreSensor => base.core as RoboidControl.DistanceSensor; public new RoboidControl.DistanceSensor core {
get => (RoboidControl.DistanceSensor)base.core;
public float distance { set => base.core = value;
get {
if (coreSensor == null)
return float.PositiveInfinity;
return coreSensor.distance;
}
} }
/// <summary> /// <summary>
/// Start the Unity representation /// Start the Unity representation
/// </summary> /// </summary>
protected virtual void Start() { protected virtual void Start() {
if (core == null) {
SiteServer siteServer = FindAnyObjectByType<SiteServer>();
SetCoreThing(new RoboidControl.DistanceSensor(siteServer.site));
}
StartCoroutine(MeasureDistance()); StartCoroutine(MeasureDistance());
} }
/// <summary> /// <summary>
/// Create the Unity representation of the distance sensor /// Create the Unity representation of the distance sensor
/// </summary> /// </summary>
/// <param name="core">The core distance sensor</param> /// <param name="parent">The parent of the core distance sensor</param>
/// <returns>The Unity representation of the distance sensor</returns> /// <returns>The Unity representation of the distance sensor</returns>
/// This uses a 'DistanceSensor' resource when available for the Unity representation. public static DistanceSensor Create(RoboidControl.DistanceSensor core) {
/// If this is not available, a default representation is created. GameObject distanceObj = new("Distance sensor");
public static DistanceSensor Create(RoboidControl.DistanceSensor coreSensor) { DistanceSensor component = distanceObj.AddComponent<DistanceSensor>();
DistanceSensor distanceSensor; if (core.parent != null && core.parent.component != null)
GameObject prefab = (GameObject)Resources.Load("DistanceSensor"); distanceObj.transform.SetParent(core.parent.component.transform, false);
if (prefab != null) {
// Use resource prefab when available return component;
GameObject gameObj = Instantiate(prefab);
distanceSensor = gameObj.GetComponent<DistanceSensor>();
distanceSensor.Init(coreSensor);
}
else {
// Default implementation
GameObject distanceObj = new(coreSensor.name);
distanceSensor = distanceObj.AddComponent<DistanceSensor>();
distanceSensor.Init(coreSensor);
}
return distanceSensor;
} }
/// <summary> /// <summary>
@ -64,10 +53,10 @@ namespace RoboidControl.Unity {
Thing thing = hitInfo.transform.GetComponentInParent<Thing>(); Thing thing = hitInfo.transform.GetComponentInParent<Thing>();
if (thing == null) { if (thing == null) {
// Debug.Log($"collision {hitInfo.transform.name} {hitInfo.distance}"); // Debug.Log($"collision {hitInfo.transform.name} {hitInfo.distance}");
coreSensor.internalDistance = hitInfo.distance; core.distance = hitInfo.distance;
} }
else else
coreSensor.internalDistance = float.PositiveInfinity; core.distance = 0;
} }
yield return new WaitForSeconds(0.1f); yield return new WaitForSeconds(0.1f);
} }

View File

@ -1,88 +0,0 @@
using System.Collections.Generic;
using UnityEngine;
using UnityEditor;
using UnityEditor.Callbacks;
using UnityEditor.PackageManager.Requests;
using UnityEditor.PackageManager;
namespace RoboidControl.Unity
{
[InitializeOnLoad]
public class ConfigurationCheck
{
static ConfigurationCheck()
{
RetrievePackageList();
}
protected static ListRequest request;
public static List<string> packageNameList;
public static void RetrievePackageList()
{
request = Client.List(); // List packages installed for the Project
EditorApplication.update += Progress;
}
public static void Progress()
{
if (request.IsCompleted)
{
if (request.Status == StatusCode.Success)
{
packageNameList = new List<string>();
foreach (UnityEditor.PackageManager.PackageInfo package in request.Result)
packageNameList.Add(package.name);
DidReloadScripts();
}
else if (request.Status >= StatusCode.Failure)
Debug.Log(request.Error.message);
EditorApplication.update -= Progress;
}
}
//[DidReloadScripts]
protected static void DidReloadScripts()
{
if (packageNameList == null)
return;
CheckExtension(
packageNameList.Contains("com.unity.cloud.gltfast"), "GLTF");
}
protected static void CheckExtension(bool enabled, string define)
{
if (enabled)
GlobalDefine(define);
else
GlobalUndefine(define);
}
public static void GlobalDefine(string name)
{
//Debug.Log("Define " + name);
string scriptDefines = PlayerSettings.GetScriptingDefineSymbolsForGroup(EditorUserBuildSettings.selectedBuildTargetGroup);
if (!scriptDefines.Contains(name))
{
string newScriptDefines = scriptDefines + " " + name;
if (EditorUserBuildSettings.selectedBuildTargetGroup != 0)
PlayerSettings.SetScriptingDefineSymbolsForGroup(EditorUserBuildSettings.selectedBuildTargetGroup, newScriptDefines);
}
}
public static void GlobalUndefine(string name)
{
//Debug.Log("Undefine " + name);
string scriptDefines = PlayerSettings.GetScriptingDefineSymbolsForGroup(EditorUserBuildSettings.selectedBuildTargetGroup);
if (scriptDefines.Contains(name))
{
int playMakerIndex = scriptDefines.IndexOf(name);
string newScriptDefines = scriptDefines.Remove(playMakerIndex, name.Length);
PlayerSettings.SetScriptingDefineSymbolsForGroup(EditorUserBuildSettings.selectedBuildTargetGroup, newScriptDefines);
}
}
}
}

View File

@ -1,15 +0,0 @@
using UnityEditor;
namespace RoboidControl.Unity {
[CustomEditor(typeof(DistanceSensor))]
public class DistanceSensor_Editor : Editor {
public override void OnInspectorGUI() {
DistanceSensor distanceSensor = (DistanceSensor)target;
DrawDefaultInspector();
EditorGUILayout.LabelField("Distance", distanceSensor.distance.ToString());
}
}
}

View File

@ -1,83 +0,0 @@
%YAML 1.1
%TAG !u! tag:unity3d.com,2011:
--- !u!21 &2100000
Material:
serializedVersion: 8
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_Name: Black
m_Shader: {fileID: 46, guid: 0000000000000000f000000000000000, type: 0}
m_Parent: {fileID: 0}
m_ModifiedSerializedProperties: 0
m_ValidKeywords: []
m_InvalidKeywords: []
m_LightmapFlags: 4
m_EnableInstancingVariants: 0
m_DoubleSidedGI: 0
m_CustomRenderQueue: -1
stringTagMap: {}
disabledShaderPasses: []
m_LockedProperties:
m_SavedProperties:
serializedVersion: 3
m_TexEnvs:
- _BumpMap:
m_Texture: {fileID: 0}
m_Scale: {x: 1, y: 1}
m_Offset: {x: 0, y: 0}
- _DetailAlbedoMap:
m_Texture: {fileID: 0}
m_Scale: {x: 1, y: 1}
m_Offset: {x: 0, y: 0}
- _DetailMask:
m_Texture: {fileID: 0}
m_Scale: {x: 1, y: 1}
m_Offset: {x: 0, y: 0}
- _DetailNormalMap:
m_Texture: {fileID: 0}
m_Scale: {x: 1, y: 1}
m_Offset: {x: 0, y: 0}
- _EmissionMap:
m_Texture: {fileID: 0}
m_Scale: {x: 1, y: 1}
m_Offset: {x: 0, y: 0}
- _MainTex:
m_Texture: {fileID: 0}
m_Scale: {x: 1, y: 1}
m_Offset: {x: 0, y: 0}
- _MetallicGlossMap:
m_Texture: {fileID: 0}
m_Scale: {x: 1, y: 1}
m_Offset: {x: 0, y: 0}
- _OcclusionMap:
m_Texture: {fileID: 0}
m_Scale: {x: 1, y: 1}
m_Offset: {x: 0, y: 0}
- _ParallaxMap:
m_Texture: {fileID: 0}
m_Scale: {x: 1, y: 1}
m_Offset: {x: 0, y: 0}
m_Ints: []
m_Floats:
- _BumpScale: 1
- _Cutoff: 0.5
- _DetailNormalMapScale: 1
- _DstBlend: 0
- _GlossMapScale: 1
- _Glossiness: 0.5
- _GlossyReflections: 1
- _Metallic: 0
- _Mode: 0
- _OcclusionStrength: 1
- _Parallax: 0.02
- _SmoothnessTextureChannel: 0
- _SpecularHighlights: 1
- _SrcBlend: 1
- _UVSec: 0
- _ZWrite: 1
m_Colors:
- _Color: {r: 0.18490559, g: 0.18490559, b: 0.18490559, a: 1}
- _EmissionColor: {r: 0, g: 0, b: 0, a: 1}
m_BuildTextureStacks: []

View File

@ -1,83 +0,0 @@
%YAML 1.1
%TAG !u! tag:unity3d.com,2011:
--- !u!21 &2100000
Material:
serializedVersion: 8
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_Name: Gray
m_Shader: {fileID: 46, guid: 0000000000000000f000000000000000, type: 0}
m_Parent: {fileID: 0}
m_ModifiedSerializedProperties: 0
m_ValidKeywords: []
m_InvalidKeywords: []
m_LightmapFlags: 4
m_EnableInstancingVariants: 0
m_DoubleSidedGI: 0
m_CustomRenderQueue: -1
stringTagMap: {}
disabledShaderPasses: []
m_LockedProperties:
m_SavedProperties:
serializedVersion: 3
m_TexEnvs:
- _BumpMap:
m_Texture: {fileID: 0}
m_Scale: {x: 1, y: 1}
m_Offset: {x: 0, y: 0}
- _DetailAlbedoMap:
m_Texture: {fileID: 0}
m_Scale: {x: 1, y: 1}
m_Offset: {x: 0, y: 0}
- _DetailMask:
m_Texture: {fileID: 0}
m_Scale: {x: 1, y: 1}
m_Offset: {x: 0, y: 0}
- _DetailNormalMap:
m_Texture: {fileID: 0}
m_Scale: {x: 1, y: 1}
m_Offset: {x: 0, y: 0}
- _EmissionMap:
m_Texture: {fileID: 0}
m_Scale: {x: 1, y: 1}
m_Offset: {x: 0, y: 0}
- _MainTex:
m_Texture: {fileID: 0}
m_Scale: {x: 1, y: 1}
m_Offset: {x: 0, y: 0}
- _MetallicGlossMap:
m_Texture: {fileID: 0}
m_Scale: {x: 1, y: 1}
m_Offset: {x: 0, y: 0}
- _OcclusionMap:
m_Texture: {fileID: 0}
m_Scale: {x: 1, y: 1}
m_Offset: {x: 0, y: 0}
- _ParallaxMap:
m_Texture: {fileID: 0}
m_Scale: {x: 1, y: 1}
m_Offset: {x: 0, y: 0}
m_Ints: []
m_Floats:
- _BumpScale: 1
- _Cutoff: 0.5
- _DetailNormalMapScale: 1
- _DstBlend: 0
- _GlossMapScale: 1
- _Glossiness: 0.5
- _GlossyReflections: 1
- _Metallic: 0
- _Mode: 0
- _OcclusionStrength: 1
- _Parallax: 0.02
- _SmoothnessTextureChannel: 0
- _SpecularHighlights: 1
- _SrcBlend: 1
- _UVSec: 0
- _ZWrite: 1
m_Colors:
- _Color: {r: 0.554717, g: 0.554717, b: 0.554717, a: 1}
- _EmissionColor: {r: 0, g: 0, b: 0, a: 1}
m_BuildTextureStacks: []

View File

@ -1,83 +0,0 @@
%YAML 1.1
%TAG !u! tag:unity3d.com,2011:
--- !u!21 &2100000
Material:
serializedVersion: 8
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_Name: Orange
m_Shader: {fileID: 46, guid: 0000000000000000f000000000000000, type: 0}
m_Parent: {fileID: 0}
m_ModifiedSerializedProperties: 0
m_ValidKeywords: []
m_InvalidKeywords: []
m_LightmapFlags: 4
m_EnableInstancingVariants: 0
m_DoubleSidedGI: 0
m_CustomRenderQueue: -1
stringTagMap: {}
disabledShaderPasses: []
m_LockedProperties:
m_SavedProperties:
serializedVersion: 3
m_TexEnvs:
- _BumpMap:
m_Texture: {fileID: 0}
m_Scale: {x: 1, y: 1}
m_Offset: {x: 0, y: 0}
- _DetailAlbedoMap:
m_Texture: {fileID: 0}
m_Scale: {x: 1, y: 1}
m_Offset: {x: 0, y: 0}
- _DetailMask:
m_Texture: {fileID: 0}
m_Scale: {x: 1, y: 1}
m_Offset: {x: 0, y: 0}
- _DetailNormalMap:
m_Texture: {fileID: 0}
m_Scale: {x: 1, y: 1}
m_Offset: {x: 0, y: 0}
- _EmissionMap:
m_Texture: {fileID: 0}
m_Scale: {x: 1, y: 1}
m_Offset: {x: 0, y: 0}
- _MainTex:
m_Texture: {fileID: 0}
m_Scale: {x: 1, y: 1}
m_Offset: {x: 0, y: 0}
- _MetallicGlossMap:
m_Texture: {fileID: 0}
m_Scale: {x: 1, y: 1}
m_Offset: {x: 0, y: 0}
- _OcclusionMap:
m_Texture: {fileID: 0}
m_Scale: {x: 1, y: 1}
m_Offset: {x: 0, y: 0}
- _ParallaxMap:
m_Texture: {fileID: 0}
m_Scale: {x: 1, y: 1}
m_Offset: {x: 0, y: 0}
m_Ints: []
m_Floats:
- _BumpScale: 1
- _Cutoff: 0.5
- _DetailNormalMapScale: 1
- _DstBlend: 0
- _GlossMapScale: 1
- _Glossiness: 0.5
- _GlossyReflections: 1
- _Metallic: 0
- _Mode: 0
- _OcclusionStrength: 1
- _Parallax: 0.02
- _SmoothnessTextureChannel: 0
- _SpecularHighlights: 1
- _SrcBlend: 1
- _UVSec: 0
- _ZWrite: 1
m_Colors:
- _Color: {r: 1, g: 0.5591924, b: 0, a: 1}
- _EmissionColor: {r: 0, g: 0, b: 0, a: 1}
m_BuildTextureStacks: []

View File

@ -1,74 +0,0 @@
#if UNITY_5_3_OR_NEWER
using UnityEngine;
namespace RoboidControl.Unity {
/// <summary>
/// The Unity representation of a Roboid Control motor
/// </summary>
public class Motor : Thing {
/// <summary>
/// The core motor
/// </summary>
public RoboidControl.Motor coreMotor => base.core as RoboidControl.Motor;
/// <summary>
/// Create the Unity representation of the motor
/// </summary>
/// <param name="coreMotor">The core motor</param>
/// <returns>The Unity representation of a motor</returns>
/// This uses a 'Motor' resource when available for the Unity representation.
/// If this is not available, a default representation is created.
public static Motor Create(RoboidControl.Motor coreMotor) {
Motor motor;
GameObject prefab = (GameObject)Resources.Load("Motor");
if (prefab != null) {
// Use resource prefab when available
GameObject gameObj = Instantiate(prefab);
motor = gameObj.GetComponent<Motor>();
motor.Init(coreMotor);
}
else {
// Default implementation
GameObject gameObj = new(coreMotor.name);
motor = gameObj.AddComponent<Motor>();
motor.Init(coreMotor);
// Rigidbody rb = gameObj.AddComponent<Rigidbody>();
// rb.isKinematic = true;
}
return motor;
}
/// <summary>
/// The maximum rotation speed of the motor in rotations per second
/// </summary>
public float maxSpeed = 5;
/// <summary>
/// The actual rotation speed in rotations per second
/// </summary>
public float rotationSpeed { get; protected set; }
/// <summary>
/// Update the Unity state
/// </summary>
protected override void FixedUpdate() {
base.FixedUpdate();
// We rotate the first child of the motor, which should be the axle.
float rotation = 360 * this.rotationSpeed * Time.fixedDeltaTime;
if (this.transform.childCount > 0)
this.transform.GetChild(0).Rotate(rotation, 0, 0);
}
/// <summary>
/// Handle the binary event containing the rotation speed
/// </summary>
protected override void HandleBinary() {
RoboidControl.Motor coreMotor = core as RoboidControl.Motor;
this.rotationSpeed = coreMotor.targetSpeed * maxSpeed;
}
}
}
#endif

View File

@ -1,84 +0,0 @@
using UnityEngine;
using System.Linq;
namespace RoboidControl.Unity {
public class Participant : MonoBehaviour {
public string ipAddress;
public int port;
public RoboidControl.Participant coreParticipant;
protected virtual void Update() {
if (coreParticipant == null)
return;
if (coreParticipant.updateQueue.TryDequeue(out RoboidControl.Participant.UpdateEvent e))
HandleUpdateEvent(e);
}
private void HandleUpdateEvent(RoboidControl.Participant.UpdateEvent e) {
switch (e.messageId) {
case ParticipantMsg.Id:
GameObject remoteParticipant = new GameObject("RemoteParticipant");
Participant participant = remoteParticipant.AddComponent<Participant>();
participant.coreParticipant = e.participant;
participant.coreParticipant.component = participant;
if (participant.coreParticipant is ParticipantUDP participantUDP) {
participant.ipAddress = participantUDP.ipAddress;
participant.port = participantUDP.port;
}
break;
case ThingMsg.id:
HandleThingEvent(e);
break;
default:
Debug.Log($"Unhandled event: {e.messageId}");
break;
}
}
protected virtual void HandleThingEvent(RoboidControl.Participant.UpdateEvent e) {
switch (e.thing) {
case RoboidControl.DistanceSensor coreDistanceSensor:
coreDistanceSensor.component = DistanceSensor.Create(coreDistanceSensor);
break;
case RoboidControl.TouchSensor coreTouchSensor:
coreTouchSensor.component = TouchSensor.Create(coreTouchSensor);
break;
case RoboidControl.DifferentialDrive coreDrive:
coreDrive.component = DifferentialDrive.Create(coreDrive);
break;
case RoboidControl.Motor coreMotor:
if (coreMotor.component == null) {
Motor wheel = Motor.Create(coreMotor);
coreMotor.component = wheel;
// We need to know the details (though a binary msg)
// before we can create the wheel reliably
}
else // Update the component from the core
coreMotor.component.Init(coreMotor);
break;
case RoboidControl.Thing coreThing:
if (coreThing.component == null) {
Thing[] things = FindObjectsByType<Thing>(FindObjectsSortMode.None);
// Debug.Log(things.Length);
Thing thing = things.FirstOrDefault(t =>
t != null &&
t.core != null &&
t.core.owner.networkId == coreThing.owner.networkId &&
t.core.id == coreThing.id
);
if (thing == null)
thing = Thing.Create(coreThing);
coreThing.component = thing;
}
else // Update the component from the core
coreThing.component.Init(coreThing);
break;
}
}
}
}

View File

@ -1,73 +0,0 @@
#if UNITY_5_3_OR_NEWER
using System.Collections;
using UnityEngine;
using LinearAlgebra;
namespace RoboidControl.Unity {
public class RelativeEncoder : Thing {
/// <summary>
/// Create the Unity representation
/// </summary>
/// <param name="core">The core motor</param>
/// <returns>The Unity representation of a motor</returns>
public static RelativeEncoder Create(RoboidControl.RelativeEncoder core) {
GameObject prefab = (GameObject)Resources.Load("IncrementalEncoder");
if (prefab != null) {
// Use resource prefab when available
GameObject gameObj = Instantiate(prefab);
RelativeEncoder component = gameObj.GetComponent<RelativeEncoder>();
if (component != null)
component.core = core;
return component;
}
else {
// Fallback implementation
GameObject gameObj = new(core.name);
RelativeEncoder component = gameObj.AddComponent<RelativeEncoder>();
component.Init(core);
Rigidbody rb = gameObj.AddComponent<Rigidbody>();
rb.isKinematic = true;
return component;
}
}
RoboidControl.RelativeEncoder coreEncoder => this.core as RoboidControl.RelativeEncoder;
/// <summary>
/// The rotation speed in degrees per second
/// </summary>
public float rotationSpeed = 0.0f;
protected override void HandleBinary() {
this.rotationSpeed = coreEncoder.angularSpeed;
}
private Quaternion lastRotation;
protected override void Update() {
base.Update();
if (this.transform.childCount == 0)
return;
Transform child = this.transform.GetChild(0);
// Get the delta rotation since last frame
Quaternion deltaRotation = Quaternion.Inverse(lastRotation) * child.localRotation;
// Normalize angles to range [-180..180)
// Note: it is not possible to track rotation speeds higher than 180 degrees per frame because of representation limitations of Quaternions
float deltaAngle = Angle.Degrees(deltaRotation.eulerAngles.x).inDegrees;
this.rotationSpeed = deltaAngle / Time.deltaTime;
}
IEnumerator UpdateCore() {
WaitForSeconds wait = new(0.1f);
while (true) {
this.coreEncoder.angularSpeed = this.rotationSpeed;
yield return wait;
}
}
}
}
#endif

View File

@ -1,546 +0,0 @@
%YAML 1.1
%TAG !u! tag:unity3d.com,2011:
--- !u!1 &135949056663158942
GameObject:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
serializedVersion: 6
m_Component:
- component: {fileID: 693610334404048217}
- component: {fileID: 874278397287993211}
- component: {fileID: 8149674613691108646}
- component: {fileID: 7453252590388621785}
m_Layer: 0
m_Name: Body
m_TagString: Untagged
m_Icon: {fileID: 0}
m_NavMeshLayer: 0
m_StaticEditorFlags: 0
m_IsActive: 1
--- !u!4 &693610334404048217
Transform:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 135949056663158942}
serializedVersion: 2
m_LocalRotation: {x: 0, y: 0, z: 0, w: 1}
m_LocalPosition: {x: 0, y: 0.01, z: -0.01}
m_LocalScale: {x: 0.12, y: 0.05, z: 0.2}
m_ConstrainProportionsScale: 0
m_Children: []
m_Father: {fileID: 6798369561388671537}
m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0}
--- !u!33 &874278397287993211
MeshFilter:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 135949056663158942}
m_Mesh: {fileID: 10202, guid: 0000000000000000e000000000000000, type: 0}
--- !u!23 &8149674613691108646
MeshRenderer:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 135949056663158942}
m_Enabled: 1
m_CastShadows: 1
m_ReceiveShadows: 1
m_DynamicOccludee: 1
m_StaticShadowCaster: 0
m_MotionVectors: 1
m_LightProbeUsage: 1
m_ReflectionProbeUsage: 1
m_RayTracingMode: 2
m_RayTraceProcedural: 0
m_RenderingLayerMask: 1
m_RendererPriority: 0
m_Materials:
- {fileID: 2100000, guid: f3dfb1ed318473a489167f10c75e6807, type: 2}
m_StaticBatchInfo:
firstSubMesh: 0
subMeshCount: 0
m_StaticBatchRoot: {fileID: 0}
m_ProbeAnchor: {fileID: 0}
m_LightProbeVolumeOverride: {fileID: 0}
m_ScaleInLightmap: 1
m_ReceiveGI: 1
m_PreserveUVs: 0
m_IgnoreNormalsForChartDetection: 0
m_ImportantGI: 0
m_StitchLightmapSeams: 1
m_SelectedEditorRenderState: 3
m_MinimumChartSize: 4
m_AutoUVMaxDistance: 0.5
m_AutoUVMaxAngle: 89
m_LightmapParameters: {fileID: 0}
m_SortingLayerID: 0
m_SortingLayer: 0
m_SortingOrder: 0
m_AdditionalVertexStreams: {fileID: 0}
--- !u!65 &7453252590388621785
BoxCollider:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 135949056663158942}
m_Material: {fileID: 0}
m_IncludeLayers:
serializedVersion: 2
m_Bits: 0
m_ExcludeLayers:
serializedVersion: 2
m_Bits: 0
m_LayerOverridePriority: 0
m_IsTrigger: 0
m_ProvidesContacts: 0
m_Enabled: 1
serializedVersion: 3
m_Size: {x: 1, y: 1, z: 1}
m_Center: {x: -3.4930155e-36, y: 0, z: 0}
--- !u!1 &3154420579555598162
GameObject:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
serializedVersion: 6
m_Component:
- component: {fileID: 213193100111257669}
- component: {fileID: 894333789048616995}
m_Layer: 0
m_Name: Caster wheel
m_TagString: Untagged
m_Icon: {fileID: 0}
m_NavMeshLayer: 0
m_StaticEditorFlags: 0
m_IsActive: 1
--- !u!4 &213193100111257669
Transform:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 3154420579555598162}
serializedVersion: 2
m_LocalRotation: {x: -0, y: -0, z: 7e-45, w: 1}
m_LocalPosition: {x: 0, y: 0, z: -0.1}
m_LocalScale: {x: 1, y: 1, z: 1}
m_ConstrainProportionsScale: 0
m_Children: []
m_Father: {fileID: 6798369561388671537}
m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0}
--- !u!135 &894333789048616995
SphereCollider:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 3154420579555598162}
m_Material: {fileID: 13400000, guid: 6311a2373d42743449d6eb1130ee618a, type: 2}
m_IncludeLayers:
serializedVersion: 2
m_Bits: 0
m_ExcludeLayers:
serializedVersion: 2
m_Bits: 0
m_LayerOverridePriority: 0
m_IsTrigger: 0
m_ProvidesContacts: 0
m_Enabled: 1
serializedVersion: 3
m_Radius: 0.025
m_Center: {x: 0, y: 0, z: 0}
--- !u!1 &3377575892836316963
GameObject:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
serializedVersion: 6
m_Component:
- component: {fileID: 7997617267105515189}
- component: {fileID: 6773972788910618332}
- component: {fileID: 3720747953092717687}
m_Layer: 0
m_Name: Left wheel
m_TagString: Untagged
m_Icon: {fileID: 0}
m_NavMeshLayer: 0
m_StaticEditorFlags: 0
m_IsActive: 1
--- !u!4 &7997617267105515189
Transform:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 3377575892836316963}
serializedVersion: 2
m_LocalRotation: {x: -0, y: -0, z: -0, w: 1}
m_LocalPosition: {x: -0.08, y: 0, z: 0}
m_LocalScale: {x: 1, y: 1, z: 1}
m_ConstrainProportionsScale: 0
m_Children:
- {fileID: 9144497505704104684}
m_Father: {fileID: 6798369561388671537}
m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0}
--- !u!114 &6773972788910618332
MonoBehaviour:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 3377575892836316963}
m_Enabled: 1
m_EditorHideFlags: 0
m_Script: {fileID: 11500000, guid: ddd5065d5e866894cbcb569c3a898ccb, type: 3}
m_Name:
m_EditorClassIdentifier:
owner: {fileID: 0}
wheelRadius: 0.025
--- !u!135 &3720747953092717687
SphereCollider:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 3377575892836316963}
m_Material: {fileID: 13400000, guid: 6311a2373d42743449d6eb1130ee618a, type: 2}
m_IncludeLayers:
serializedVersion: 2
m_Bits: 0
m_ExcludeLayers:
serializedVersion: 2
m_Bits: 0
m_LayerOverridePriority: 0
m_IsTrigger: 0
m_ProvidesContacts: 0
m_Enabled: 1
serializedVersion: 3
m_Radius: 0.025
m_Center: {x: 0, y: 0, z: 0}
--- !u!1 &4326386140118987503
GameObject:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
serializedVersion: 6
m_Component:
- component: {fileID: 6798369561388671537}
- component: {fileID: 1296007780791728683}
- component: {fileID: 4118868690347991998}
m_Layer: 0
m_Name: DifferentialDrive
m_TagString: Untagged
m_Icon: {fileID: 0}
m_NavMeshLayer: 0
m_StaticEditorFlags: 0
m_IsActive: 1
--- !u!4 &6798369561388671537
Transform:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 4326386140118987503}
serializedVersion: 2
m_LocalRotation: {x: 1.276433e-21, y: -1.082074e-19, z: -2.3980766e-36, w: 1}
m_LocalPosition: {x: 2.1932227e-37, y: -0.06941543, z: -1.3084181e-19}
m_LocalScale: {x: 1, y: 1, z: 1}
m_ConstrainProportionsScale: 0
m_Children:
- {fileID: 7997617267105515189}
- {fileID: 2660791421672615984}
- {fileID: 693610334404048217}
- {fileID: 213193100111257669}
m_Father: {fileID: 0}
m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0}
--- !u!114 &1296007780791728683
MonoBehaviour:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 4326386140118987503}
m_Enabled: 1
m_EditorHideFlags: 0
m_Script: {fileID: 11500000, guid: 5c80bc2fd1d8aa14facb1ad4b6ccf7b3, type: 3}
m_Name:
m_EditorClassIdentifier:
owner: {fileID: 0}
leftMotor: {fileID: 0}
rightMotor: {fileID: 0}
leftWheel: {fileID: 6773972788910618332}
rightWheel: {fileID: 7425139233737877139}
casterWheel: {fileID: 894333789048616995}
--- !u!54 &4118868690347991998
Rigidbody:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 4326386140118987503}
serializedVersion: 4
m_Mass: 0.1
m_Drag: 0
m_AngularDrag: 0.05
m_CenterOfMass: {x: 0, y: 0, z: 0}
m_InertiaTensor: {x: 1, y: 1, z: 1}
m_InertiaRotation: {x: 0, y: 0, z: 0, w: 1}
m_IncludeLayers:
serializedVersion: 2
m_Bits: 0
m_ExcludeLayers:
serializedVersion: 2
m_Bits: 0
m_ImplicitCom: 1
m_ImplicitTensor: 1
m_UseGravity: 1
m_IsKinematic: 0
m_Interpolate: 0
m_Constraints: 0
m_CollisionDetection: 0
--- !u!1 &4927629757198460283
GameObject:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
serializedVersion: 6
m_Component:
- component: {fileID: 9144497505704104684}
- component: {fileID: 8353236605004633556}
- component: {fileID: 1652944855748388758}
m_Layer: 0
m_Name: Cube
m_TagString: Untagged
m_Icon: {fileID: 0}
m_NavMeshLayer: 0
m_StaticEditorFlags: 0
m_IsActive: 1
--- !u!4 &9144497505704104684
Transform:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 4927629757198460283}
serializedVersion: 2
m_LocalRotation: {x: 0, y: 0, z: 0, w: 1}
m_LocalPosition: {x: 0, y: 0, z: 0}
m_LocalScale: {x: 0.01, y: 0.05, z: 0.05}
m_ConstrainProportionsScale: 0
m_Children: []
m_Father: {fileID: 7997617267105515189}
m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0}
--- !u!33 &8353236605004633556
MeshFilter:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 4927629757198460283}
m_Mesh: {fileID: 10202, guid: 0000000000000000e000000000000000, type: 0}
--- !u!23 &1652944855748388758
MeshRenderer:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 4927629757198460283}
m_Enabled: 1
m_CastShadows: 1
m_ReceiveShadows: 1
m_DynamicOccludee: 1
m_StaticShadowCaster: 0
m_MotionVectors: 1
m_LightProbeUsage: 1
m_ReflectionProbeUsage: 1
m_RayTracingMode: 2
m_RayTraceProcedural: 0
m_RenderingLayerMask: 1
m_RendererPriority: 0
m_Materials:
- {fileID: 2100000, guid: e3d2a8d9196e1ab4485b404933eeaa73, type: 2}
m_StaticBatchInfo:
firstSubMesh: 0
subMeshCount: 0
m_StaticBatchRoot: {fileID: 0}
m_ProbeAnchor: {fileID: 0}
m_LightProbeVolumeOverride: {fileID: 0}
m_ScaleInLightmap: 1
m_ReceiveGI: 1
m_PreserveUVs: 0
m_IgnoreNormalsForChartDetection: 0
m_ImportantGI: 0
m_StitchLightmapSeams: 1
m_SelectedEditorRenderState: 3
m_MinimumChartSize: 4
m_AutoUVMaxDistance: 0.5
m_AutoUVMaxAngle: 89
m_LightmapParameters: {fileID: 0}
m_SortingLayerID: 0
m_SortingLayer: 0
m_SortingOrder: 0
m_AdditionalVertexStreams: {fileID: 0}
--- !u!1 &5122915782100933114
GameObject:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
serializedVersion: 6
m_Component:
- component: {fileID: 2660791421672615984}
- component: {fileID: 7425139233737877139}
- component: {fileID: 8150853676422519226}
m_Layer: 0
m_Name: Right wheel
m_TagString: Untagged
m_Icon: {fileID: 0}
m_NavMeshLayer: 0
m_StaticEditorFlags: 0
m_IsActive: 1
--- !u!4 &2660791421672615984
Transform:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 5122915782100933114}
serializedVersion: 2
m_LocalRotation: {x: -0, y: -0, z: -0, w: 1}
m_LocalPosition: {x: 0.08, y: 0, z: 0}
m_LocalScale: {x: 1, y: 1, z: 1}
m_ConstrainProportionsScale: 0
m_Children:
- {fileID: 2324127387642107303}
m_Father: {fileID: 6798369561388671537}
m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0}
--- !u!114 &7425139233737877139
MonoBehaviour:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 5122915782100933114}
m_Enabled: 1
m_EditorHideFlags: 0
m_Script: {fileID: 11500000, guid: ddd5065d5e866894cbcb569c3a898ccb, type: 3}
m_Name:
m_EditorClassIdentifier:
owner: {fileID: 0}
wheelRadius: 0.025
--- !u!135 &8150853676422519226
SphereCollider:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 5122915782100933114}
m_Material: {fileID: 13400000, guid: 6311a2373d42743449d6eb1130ee618a, type: 2}
m_IncludeLayers:
serializedVersion: 2
m_Bits: 0
m_ExcludeLayers:
serializedVersion: 2
m_Bits: 0
m_LayerOverridePriority: 0
m_IsTrigger: 0
m_ProvidesContacts: 0
m_Enabled: 1
serializedVersion: 3
m_Radius: 0.025
m_Center: {x: 0, y: 0, z: 0}
--- !u!1 &5663058822615269368
GameObject:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
serializedVersion: 6
m_Component:
- component: {fileID: 2324127387642107303}
- component: {fileID: 7927909525546489266}
- component: {fileID: 1038362976985791207}
m_Layer: 0
m_Name: Cube
m_TagString: Untagged
m_Icon: {fileID: 0}
m_NavMeshLayer: 0
m_StaticEditorFlags: 0
m_IsActive: 1
--- !u!4 &2324127387642107303
Transform:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 5663058822615269368}
serializedVersion: 2
m_LocalRotation: {x: -0, y: -0, z: 7e-45, w: 1}
m_LocalPosition: {x: 0, y: 0, z: 0}
m_LocalScale: {x: 0.01, y: 0.049999997, z: 0.049999997}
m_ConstrainProportionsScale: 0
m_Children: []
m_Father: {fileID: 2660791421672615984}
m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0}
--- !u!33 &7927909525546489266
MeshFilter:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 5663058822615269368}
m_Mesh: {fileID: 10202, guid: 0000000000000000e000000000000000, type: 0}
--- !u!23 &1038362976985791207
MeshRenderer:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 5663058822615269368}
m_Enabled: 1
m_CastShadows: 1
m_ReceiveShadows: 1
m_DynamicOccludee: 1
m_StaticShadowCaster: 0
m_MotionVectors: 1
m_LightProbeUsage: 1
m_ReflectionProbeUsage: 1
m_RayTracingMode: 2
m_RayTraceProcedural: 0
m_RenderingLayerMask: 1
m_RendererPriority: 0
m_Materials:
- {fileID: 2100000, guid: e3d2a8d9196e1ab4485b404933eeaa73, type: 2}
m_StaticBatchInfo:
firstSubMesh: 0
subMeshCount: 0
m_StaticBatchRoot: {fileID: 0}
m_ProbeAnchor: {fileID: 0}
m_LightProbeVolumeOverride: {fileID: 0}
m_ScaleInLightmap: 1
m_ReceiveGI: 1
m_PreserveUVs: 0
m_IgnoreNormalsForChartDetection: 0
m_ImportantGI: 0
m_StitchLightmapSeams: 1
m_SelectedEditorRenderState: 3
m_MinimumChartSize: 4
m_AutoUVMaxDistance: 0.5
m_AutoUVMaxAngle: 89
m_LightmapParameters: {fileID: 0}
m_SortingLayerID: 0
m_SortingLayer: 0
m_SortingOrder: 0
m_AdditionalVertexStreams: {fileID: 0}

View File

@ -1,546 +0,0 @@
%YAML 1.1
%TAG !u! tag:unity3d.com,2011:
--- !u!1 &135949056663158942
GameObject:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
serializedVersion: 6
m_Component:
- component: {fileID: 693610334404048217}
- component: {fileID: 874278397287993211}
- component: {fileID: 8149674613691108646}
- component: {fileID: 7453252590388621785}
m_Layer: 0
m_Name: Body
m_TagString: Untagged
m_Icon: {fileID: 0}
m_NavMeshLayer: 0
m_StaticEditorFlags: 0
m_IsActive: 1
--- !u!4 &693610334404048217
Transform:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 135949056663158942}
serializedVersion: 2
m_LocalRotation: {x: 0, y: 0, z: 0, w: 1}
m_LocalPosition: {x: 0, y: 0.01, z: -0.01}
m_LocalScale: {x: 0.12, y: 0.05, z: 0.2}
m_ConstrainProportionsScale: 0
m_Children: []
m_Father: {fileID: 6798369561388671537}
m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0}
--- !u!33 &874278397287993211
MeshFilter:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 135949056663158942}
m_Mesh: {fileID: 10202, guid: 0000000000000000e000000000000000, type: 0}
--- !u!23 &8149674613691108646
MeshRenderer:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 135949056663158942}
m_Enabled: 1
m_CastShadows: 1
m_ReceiveShadows: 1
m_DynamicOccludee: 1
m_StaticShadowCaster: 0
m_MotionVectors: 1
m_LightProbeUsage: 1
m_ReflectionProbeUsage: 1
m_RayTracingMode: 2
m_RayTraceProcedural: 0
m_RenderingLayerMask: 1
m_RendererPriority: 0
m_Materials:
- {fileID: 10303, guid: 0000000000000000f000000000000000, type: 0}
m_StaticBatchInfo:
firstSubMesh: 0
subMeshCount: 0
m_StaticBatchRoot: {fileID: 0}
m_ProbeAnchor: {fileID: 0}
m_LightProbeVolumeOverride: {fileID: 0}
m_ScaleInLightmap: 1
m_ReceiveGI: 1
m_PreserveUVs: 0
m_IgnoreNormalsForChartDetection: 0
m_ImportantGI: 0
m_StitchLightmapSeams: 1
m_SelectedEditorRenderState: 3
m_MinimumChartSize: 4
m_AutoUVMaxDistance: 0.5
m_AutoUVMaxAngle: 89
m_LightmapParameters: {fileID: 0}
m_SortingLayerID: 0
m_SortingLayer: 0
m_SortingOrder: 0
m_AdditionalVertexStreams: {fileID: 0}
--- !u!65 &7453252590388621785
BoxCollider:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 135949056663158942}
m_Material: {fileID: 0}
m_IncludeLayers:
serializedVersion: 2
m_Bits: 0
m_ExcludeLayers:
serializedVersion: 2
m_Bits: 0
m_LayerOverridePriority: 0
m_IsTrigger: 0
m_ProvidesContacts: 0
m_Enabled: 0
serializedVersion: 3
m_Size: {x: 1, y: 1, z: 1}
m_Center: {x: -3.4930155e-36, y: 0, z: 0}
--- !u!1 &3154420579555598162
GameObject:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
serializedVersion: 6
m_Component:
- component: {fileID: 213193100111257669}
- component: {fileID: 894333789048616995}
m_Layer: 0
m_Name: Caster wheel
m_TagString: Untagged
m_Icon: {fileID: 0}
m_NavMeshLayer: 0
m_StaticEditorFlags: 0
m_IsActive: 1
--- !u!4 &213193100111257669
Transform:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 3154420579555598162}
serializedVersion: 2
m_LocalRotation: {x: -0, y: -0, z: 7e-45, w: 1}
m_LocalPosition: {x: 0, y: 0, z: -0.1}
m_LocalScale: {x: 1, y: 1, z: 1}
m_ConstrainProportionsScale: 0
m_Children: []
m_Father: {fileID: 6798369561388671537}
m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0}
--- !u!135 &894333789048616995
SphereCollider:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 3154420579555598162}
m_Material: {fileID: 13400000, guid: 6311a2373d42743449d6eb1130ee618a, type: 2}
m_IncludeLayers:
serializedVersion: 2
m_Bits: 0
m_ExcludeLayers:
serializedVersion: 2
m_Bits: 0
m_LayerOverridePriority: 0
m_IsTrigger: 0
m_ProvidesContacts: 0
m_Enabled: 1
serializedVersion: 3
m_Radius: 0.00001
m_Center: {x: 0, y: 0, z: 0}
--- !u!1 &3377575892836316963
GameObject:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
serializedVersion: 6
m_Component:
- component: {fileID: 7997617267105515189}
- component: {fileID: 6773972788910618332}
- component: {fileID: 3720747953092717687}
m_Layer: 0
m_Name: Left wheel
m_TagString: Untagged
m_Icon: {fileID: 0}
m_NavMeshLayer: 0
m_StaticEditorFlags: 0
m_IsActive: 1
--- !u!4 &7997617267105515189
Transform:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 3377575892836316963}
serializedVersion: 2
m_LocalRotation: {x: -0, y: -0, z: -0, w: 1}
m_LocalPosition: {x: -0.08, y: 0, z: 0}
m_LocalScale: {x: 1, y: 1, z: 1}
m_ConstrainProportionsScale: 0
m_Children:
- {fileID: 9144497505704104684}
m_Father: {fileID: 6798369561388671537}
m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0}
--- !u!114 &6773972788910618332
MonoBehaviour:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 3377575892836316963}
m_Enabled: 1
m_EditorHideFlags: 0
m_Script: {fileID: 11500000, guid: ddd5065d5e866894cbcb569c3a898ccb, type: 3}
m_Name:
m_EditorClassIdentifier:
participant: {fileID: 0}
maxSpeed: 5
rotationSpeed: 0
--- !u!135 &3720747953092717687
SphereCollider:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 3377575892836316963}
m_Material: {fileID: 13400000, guid: 6311a2373d42743449d6eb1130ee618a, type: 2}
m_IncludeLayers:
serializedVersion: 2
m_Bits: 0
m_ExcludeLayers:
serializedVersion: 2
m_Bits: 0
m_LayerOverridePriority: 0
m_IsTrigger: 0
m_ProvidesContacts: 0
m_Enabled: 1
serializedVersion: 3
m_Radius: 0.00001
m_Center: {x: 0, y: 0, z: 0}
--- !u!1 &4326386140118987503
GameObject:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
serializedVersion: 6
m_Component:
- component: {fileID: 6798369561388671537}
- component: {fileID: 2975045340952151157}
- component: {fileID: 4118868690347991998}
m_Layer: 0
m_Name: DifferentialDrive_disabled
m_TagString: Untagged
m_Icon: {fileID: 0}
m_NavMeshLayer: 0
m_StaticEditorFlags: 0
m_IsActive: 1
--- !u!4 &6798369561388671537
Transform:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 4326386140118987503}
serializedVersion: 2
m_LocalRotation: {x: 1.276433e-21, y: -1.082074e-19, z: -2.3980766e-36, w: 1}
m_LocalPosition: {x: 2.1932227e-37, y: -0.06941543, z: -1.3084181e-19}
m_LocalScale: {x: 1, y: 1, z: 1}
m_ConstrainProportionsScale: 0
m_Children:
- {fileID: 7997617267105515189}
- {fileID: 2660791421672615984}
- {fileID: 693610334404048217}
- {fileID: 213193100111257669}
m_Father: {fileID: 0}
m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0}
--- !u!114 &2975045340952151157
MonoBehaviour:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 4326386140118987503}
m_Enabled: 1
m_EditorHideFlags: 0
m_Script: {fileID: 11500000, guid: 5c80bc2fd1d8aa14facb1ad4b6ccf7b3, type: 3}
m_Name:
m_EditorClassIdentifier:
participant: {fileID: 0}
leftWheel: {fileID: 6773972788910618332}
rightWheel: {fileID: 7425139233737877139}
casterWheel: {fileID: 894333789048616995}
--- !u!54 &4118868690347991998
Rigidbody:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 4326386140118987503}
serializedVersion: 4
m_Mass: 0.1
m_Drag: 0
m_AngularDrag: 0.05
m_CenterOfMass: {x: 0, y: 0, z: 0}
m_InertiaTensor: {x: 1, y: 1, z: 1}
m_InertiaRotation: {x: 0, y: 0, z: 0, w: 1}
m_IncludeLayers:
serializedVersion: 2
m_Bits: 0
m_ExcludeLayers:
serializedVersion: 2
m_Bits: 0
m_ImplicitCom: 1
m_ImplicitTensor: 1
m_UseGravity: 1
m_IsKinematic: 0
m_Interpolate: 0
m_Constraints: 0
m_CollisionDetection: 0
--- !u!1 &4927629757198460283
GameObject:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
serializedVersion: 6
m_Component:
- component: {fileID: 9144497505704104684}
- component: {fileID: 8353236605004633556}
- component: {fileID: 1652944855748388758}
m_Layer: 0
m_Name: Cube
m_TagString: Untagged
m_Icon: {fileID: 0}
m_NavMeshLayer: 0
m_StaticEditorFlags: 0
m_IsActive: 1
--- !u!4 &9144497505704104684
Transform:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 4927629757198460283}
serializedVersion: 2
m_LocalRotation: {x: 0, y: 0, z: 0, w: 1}
m_LocalPosition: {x: 0, y: 0, z: 0}
m_LocalScale: {x: 0.01, y: 0.05, z: 0.05}
m_ConstrainProportionsScale: 0
m_Children: []
m_Father: {fileID: 7997617267105515189}
m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0}
--- !u!33 &8353236605004633556
MeshFilter:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 4927629757198460283}
m_Mesh: {fileID: 10202, guid: 0000000000000000e000000000000000, type: 0}
--- !u!23 &1652944855748388758
MeshRenderer:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 4927629757198460283}
m_Enabled: 1
m_CastShadows: 1
m_ReceiveShadows: 1
m_DynamicOccludee: 1
m_StaticShadowCaster: 0
m_MotionVectors: 1
m_LightProbeUsage: 1
m_ReflectionProbeUsage: 1
m_RayTracingMode: 2
m_RayTraceProcedural: 0
m_RenderingLayerMask: 1
m_RendererPriority: 0
m_Materials:
- {fileID: 2100000, guid: c83c86eecb501964d9e4fd4074683016, type: 2}
m_StaticBatchInfo:
firstSubMesh: 0
subMeshCount: 0
m_StaticBatchRoot: {fileID: 0}
m_ProbeAnchor: {fileID: 0}
m_LightProbeVolumeOverride: {fileID: 0}
m_ScaleInLightmap: 1
m_ReceiveGI: 1
m_PreserveUVs: 0
m_IgnoreNormalsForChartDetection: 0
m_ImportantGI: 0
m_StitchLightmapSeams: 1
m_SelectedEditorRenderState: 3
m_MinimumChartSize: 4
m_AutoUVMaxDistance: 0.5
m_AutoUVMaxAngle: 89
m_LightmapParameters: {fileID: 0}
m_SortingLayerID: 0
m_SortingLayer: 0
m_SortingOrder: 0
m_AdditionalVertexStreams: {fileID: 0}
--- !u!1 &5122915782100933114
GameObject:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
serializedVersion: 6
m_Component:
- component: {fileID: 2660791421672615984}
- component: {fileID: 7425139233737877139}
- component: {fileID: 8150853676422519226}
m_Layer: 0
m_Name: Right wheel
m_TagString: Untagged
m_Icon: {fileID: 0}
m_NavMeshLayer: 0
m_StaticEditorFlags: 0
m_IsActive: 1
--- !u!4 &2660791421672615984
Transform:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 5122915782100933114}
serializedVersion: 2
m_LocalRotation: {x: -0, y: -0, z: -0, w: 1}
m_LocalPosition: {x: 0.08, y: 0, z: 0}
m_LocalScale: {x: 1, y: 1, z: 1}
m_ConstrainProportionsScale: 0
m_Children:
- {fileID: 2324127387642107303}
m_Father: {fileID: 6798369561388671537}
m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0}
--- !u!114 &7425139233737877139
MonoBehaviour:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 5122915782100933114}
m_Enabled: 1
m_EditorHideFlags: 0
m_Script: {fileID: 11500000, guid: ddd5065d5e866894cbcb569c3a898ccb, type: 3}
m_Name:
m_EditorClassIdentifier:
participant: {fileID: 0}
maxSpeed: 5
rotationSpeed: 0
--- !u!135 &8150853676422519226
SphereCollider:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 5122915782100933114}
m_Material: {fileID: 13400000, guid: 6311a2373d42743449d6eb1130ee618a, type: 2}
m_IncludeLayers:
serializedVersion: 2
m_Bits: 0
m_ExcludeLayers:
serializedVersion: 2
m_Bits: 0
m_LayerOverridePriority: 0
m_IsTrigger: 0
m_ProvidesContacts: 0
m_Enabled: 1
serializedVersion: 3
m_Radius: 0.00001
m_Center: {x: 0, y: 0, z: 0}
--- !u!1 &5663058822615269368
GameObject:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
serializedVersion: 6
m_Component:
- component: {fileID: 2324127387642107303}
- component: {fileID: 7927909525546489266}
- component: {fileID: 1038362976985791207}
m_Layer: 0
m_Name: Cube
m_TagString: Untagged
m_Icon: {fileID: 0}
m_NavMeshLayer: 0
m_StaticEditorFlags: 0
m_IsActive: 1
--- !u!4 &2324127387642107303
Transform:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 5663058822615269368}
serializedVersion: 2
m_LocalRotation: {x: -0, y: -0, z: 7e-45, w: 1}
m_LocalPosition: {x: 0, y: 0, z: 0}
m_LocalScale: {x: 0.01, y: 0.049999997, z: 0.049999997}
m_ConstrainProportionsScale: 0
m_Children: []
m_Father: {fileID: 2660791421672615984}
m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0}
--- !u!33 &7927909525546489266
MeshFilter:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 5663058822615269368}
m_Mesh: {fileID: 10202, guid: 0000000000000000e000000000000000, type: 0}
--- !u!23 &1038362976985791207
MeshRenderer:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 5663058822615269368}
m_Enabled: 1
m_CastShadows: 1
m_ReceiveShadows: 1
m_DynamicOccludee: 1
m_StaticShadowCaster: 0
m_MotionVectors: 1
m_LightProbeUsage: 1
m_ReflectionProbeUsage: 1
m_RayTracingMode: 2
m_RayTraceProcedural: 0
m_RenderingLayerMask: 1
m_RendererPriority: 0
m_Materials:
- {fileID: 2100000, guid: c83c86eecb501964d9e4fd4074683016, type: 2}
m_StaticBatchInfo:
firstSubMesh: 0
subMeshCount: 0
m_StaticBatchRoot: {fileID: 0}
m_ProbeAnchor: {fileID: 0}
m_LightProbeVolumeOverride: {fileID: 0}
m_ScaleInLightmap: 1
m_ReceiveGI: 1
m_PreserveUVs: 0
m_IgnoreNormalsForChartDetection: 0
m_ImportantGI: 0
m_StitchLightmapSeams: 1
m_SelectedEditorRenderState: 3
m_MinimumChartSize: 4
m_AutoUVMaxDistance: 0.5
m_AutoUVMaxAngle: 89
m_LightmapParameters: {fileID: 0}
m_SortingLayerID: 0
m_SortingLayer: 0
m_SortingOrder: 0
m_AdditionalVertexStreams: {fileID: 0}

View File

@ -1,14 +0,0 @@
%YAML 1.1
%TAG !u! tag:unity3d.com,2011:
--- !u!134 &13400000
PhysicMaterial:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_Name: SlidingWheel
dynamicFriction: 0.02
staticFriction: 0.01
bounciness: 0
frictionCombine: 1
bounceCombine: 0

View File

@ -1,182 +0,0 @@
%YAML 1.1
%TAG !u! tag:unity3d.com,2011:
--- !u!1 &1535520457298351474
GameObject:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
serializedVersion: 6
m_Component:
- component: {fileID: 1122722937167266542}
- component: {fileID: 8409364771467476437}
- component: {fileID: 6632295589629461102}
m_Layer: 0
m_Name: Sphere
m_TagString: Untagged
m_Icon: {fileID: 0}
m_NavMeshLayer: 0
m_StaticEditorFlags: 0
m_IsActive: 1
--- !u!4 &1122722937167266542
Transform:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 1535520457298351474}
serializedVersion: 2
m_LocalRotation: {x: 0, y: 0, z: 0, w: 1}
m_LocalPosition: {x: 0, y: 0, z: 0}
m_LocalScale: {x: 0.01, y: 0.01, z: 0.01}
m_ConstrainProportionsScale: 0
m_Children: []
m_Father: {fileID: 839661735326876684}
m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0}
--- !u!33 &8409364771467476437
MeshFilter:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 1535520457298351474}
m_Mesh: {fileID: 10207, guid: 0000000000000000e000000000000000, type: 0}
--- !u!23 &6632295589629461102
MeshRenderer:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 1535520457298351474}
m_Enabled: 1
m_CastShadows: 1
m_ReceiveShadows: 1
m_DynamicOccludee: 1
m_StaticShadowCaster: 0
m_MotionVectors: 1
m_LightProbeUsage: 1
m_ReflectionProbeUsage: 1
m_RayTracingMode: 2
m_RayTraceProcedural: 0
m_RenderingLayerMask: 1
m_RendererPriority: 0
m_Materials:
- {fileID: 10303, guid: 0000000000000000f000000000000000, type: 0}
m_StaticBatchInfo:
firstSubMesh: 0
subMeshCount: 0
m_StaticBatchRoot: {fileID: 0}
m_ProbeAnchor: {fileID: 0}
m_LightProbeVolumeOverride: {fileID: 0}
m_ScaleInLightmap: 1
m_ReceiveGI: 1
m_PreserveUVs: 0
m_IgnoreNormalsForChartDetection: 0
m_ImportantGI: 0
m_StitchLightmapSeams: 1
m_SelectedEditorRenderState: 3
m_MinimumChartSize: 4
m_AutoUVMaxDistance: 0.5
m_AutoUVMaxAngle: 89
m_LightmapParameters: {fileID: 0}
m_SortingLayerID: 0
m_SortingLayer: 0
m_SortingOrder: 0
m_AdditionalVertexStreams: {fileID: 0}
--- !u!1 &6521541507066528382
GameObject:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
serializedVersion: 6
m_Component:
- component: {fileID: 839661735326876684}
- component: {fileID: 4006928432304472165}
- component: {fileID: 5295705618145761524}
- component: {fileID: 5884202444353424411}
m_Layer: 0
m_Name: TouchSensor
m_TagString: Untagged
m_Icon: {fileID: 0}
m_NavMeshLayer: 0
m_StaticEditorFlags: 0
m_IsActive: 1
--- !u!4 &839661735326876684
Transform:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 6521541507066528382}
serializedVersion: 2
m_LocalRotation: {x: 0, y: 0, z: 0, w: 1}
m_LocalPosition: {x: 0, y: -0, z: 0}
m_LocalScale: {x: 1, y: 1, z: 1}
m_ConstrainProportionsScale: 0
m_Children:
- {fileID: 1122722937167266542}
m_Father: {fileID: 0}
m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0}
--- !u!114 &4006928432304472165
MonoBehaviour:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 6521541507066528382}
m_Enabled: 1
m_EditorHideFlags: 0
m_Script: {fileID: 11500000, guid: ab969221c3007d441b18dd7387cf22d4, type: 3}
m_Name:
m_EditorClassIdentifier:
owner: {fileID: 0}
touchedSomething: 0
--- !u!54 &5295705618145761524
Rigidbody:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 6521541507066528382}
serializedVersion: 4
m_Mass: 1
m_Drag: 0
m_AngularDrag: 0.05
m_CenterOfMass: {x: 0, y: 0, z: 0}
m_InertiaTensor: {x: 1, y: 1, z: 1}
m_InertiaRotation: {x: 0, y: 0, z: 0, w: 1}
m_IncludeLayers:
serializedVersion: 2
m_Bits: 0
m_ExcludeLayers:
serializedVersion: 2
m_Bits: 0
m_ImplicitCom: 1
m_ImplicitTensor: 1
m_UseGravity: 1
m_IsKinematic: 1
m_Interpolate: 0
m_Constraints: 0
m_CollisionDetection: 0
--- !u!135 &5884202444353424411
SphereCollider:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 6521541507066528382}
m_Material: {fileID: 0}
m_IncludeLayers:
serializedVersion: 2
m_Bits: 0
m_ExcludeLayers:
serializedVersion: 2
m_Bits: 0
m_LayerOverridePriority: 0
m_IsTrigger: 1
m_ProvidesContacts: 0
m_Enabled: 1
serializedVersion: 3
m_Radius: 0.01
m_Center: {x: 0, y: 0, z: 0}

View File

@ -1,30 +1,22 @@
#if UNITY_5_3_OR_NEWER #if UNITY_5_3_OR_NEWER
using System; using System;
using System.Collections.Generic;
using UnityEngine; using UnityEngine;
namespace RoboidControl.Unity { namespace RoboidControl.Unity {
public class SiteServer : Participant { public class SiteServer : MonoBehaviour {
public int port = 7681;
public RoboidControl.SiteServer site => this.coreParticipant as RoboidControl.SiteServer; public RoboidControl.SiteServer site;
public string modelURL;
private RoboidControl.Thing model; public Queue<RoboidControl.Thing> thingQueue = new();
protected virtual void Awake() { protected virtual void Awake() {
#if RC_DEBUG
Console.SetOut(new UnityLogWriter()); Console.SetOut(new UnityLogWriter());
#endif
this.coreParticipant = new RoboidControl.SiteServer(port); site = new RoboidControl.SiteServer(port);
RoboidControl.Thing.OnNewThing += HandleNewThing;
#if GLTF
if (!string.IsNullOrEmpty(modelURL)) {
model = new() {
name = "Model",
modelUrl = this.modelURL
};
}
#endif
} }
void OnApplicationQuit() { void OnApplicationQuit() {
@ -32,36 +24,16 @@ namespace RoboidControl.Unity {
site.Close(); site.Close();
} }
protected override void Update() { public void HandleNewThing(RoboidControl.Thing thing) {
if (site == null) //Debug.Log($"Handle New thing event for {thing}");
return; //site.Add(thing, false);
thingQueue.Enqueue(thing);
while (site.updateQueue.TryDequeue(out RoboidControl.Participant.UpdateEvent e))
HandleUpdateEvent(e);
site.Update();
} }
private void HandleUpdateEvent(RoboidControl.Participant.UpdateEvent e) { protected virtual void Update() {
switch (e.messageId) { site.Update((ulong)(Time.time * 1000));
case ParticipantMsg.Id: while (thingQueue.TryDequeue(out RoboidControl.Thing thing))
GameObject remoteParticipant = new GameObject("RemoteParticipant"); thing.CreateComponent();
Participant participant = remoteParticipant.AddComponent<Participant>();
participant.coreParticipant = e.participant;
participant.coreParticipant.component = participant;
if (participant.coreParticipant is ParticipantUDP participantUDP) {
participant.ipAddress = participantUDP.ipAddress;
participant.port = participantUDP.port;
}
// foreach (RoboidControl.Thing thing in this.site.things)
// participant.coreParticipant.SendThingInfo(thing);
break;
case ThingMsg.id:
HandleThingEvent(e);
break;
}
} }
} }

View File

@ -2,33 +2,42 @@
using System.Collections; using System.Collections;
using UnityEngine; using UnityEngine;
using UnityEngine.Networking; using UnityEngine.Networking;
#if GLTF
using GLTFast;
#endif
namespace RoboidControl.Unity { namespace RoboidControl.Unity {
/// <summary> /// <summary>
/// The Unity representation fo a Roboid Control Thing /// The representation of a Thing in Unity
/// </summary> /// </summary>
public class Thing : MonoBehaviour { public class Thing : MonoBehaviour {
/// <summary> /// <summary>
/// The core C# thing /// The core C# thing
/// </summary> /// </summary>
[field: SerializeField]
public RoboidControl.Thing core { get; set; } public RoboidControl.Thing core { get; set; }
/// <summary> public SiteServer participant;
/// The owner of this thing
/// </summary> private string modelUrl = null;
public Participant owner;
/// <summary> /// <summary>
/// Create a Unity representation of a Thing /// Set the core C# thing
/// </summary> /// </summary>
/// <param name="core">The core of the thing</param> protected void SetCoreThing(RoboidControl.Thing thing) {
/// <returns>The created thing</returns> core = thing;
core.component = this;
SiteServer siteServer = FindAnyObjectByType<SiteServer>();
if (siteServer == null || siteServer.site == null) {
Debug.LogWarning("No site server found");
return;
}
siteServer.site.Add(thing);
core.OnPoseChanged += PoseChanged;
}
public static Thing Create(RoboidControl.Thing core) { public static Thing Create(RoboidControl.Thing core) {
// Debug.Log("Creating new Unity thing");
GameObject gameObj = string.IsNullOrEmpty(core.name) ? GameObject gameObj = string.IsNullOrEmpty(core.name) ?
new("Thing") : new("Thing") :
new(core.name); new(core.name);
@ -37,117 +46,71 @@ namespace RoboidControl.Unity {
return component; return component;
} }
/// <summary> protected void Init(RoboidControl.Thing core) {
/// Initialize the Thing
/// </summary>
/// <param name="core">The core of the thing</param>
/// This affects the parent and pose of the thing
public void Init(RoboidControl.Thing core) {
this.core = core; this.core = core;
this.core.component = this; this.participant = FindAnyObjectByType<SiteServer>();
// This is wrong, it should get the owner, which is not the siteserver if (core.parent != null && core.parent.component != null)
// this.owner = FindAnyObjectByType<SiteServer>(); this.transform.SetParent(core.parent.component.transform, false);
// core.owner = this.owner.coreParticipant;
this.owner = core.owner.component;
if (core.parent != null && core.parent.component != null) {
this.transform.SetParent(core.parent.component.transform, false);
this.transform.localPosition = Vector3.zero;
}
else if (core.owner.component != null) {
this.transform.SetParent(core.owner.component.transform, false);
}
if (core.position != null) if (core.position != null)
this.transform.localPosition = core.position.ToVector3(); this.transform.localPosition = core.position.ToVector3();
if (core.orientation != null) if (core.orientation != null)
this.transform.localRotation = core.orientation.ToQuaternion(); this.transform.localRotation = core.orientation.ToQuaternion();
core.OnPoseChanged += this.PoseChanged;
} }
/// <summary> /// <summary>
/// Update the Unity rendering /// Update the Unity representation
/// </summary> /// </summary>
protected virtual void Update() { protected virtual void Update() {
if (core == null) if (core == null) {
// Debug.Log("Core thing is gone, self destruct in 0 seconds...");
Destroy(this);
return; return;
}
if (core.linearVelocity != null && core.linearVelocity.distance != 0) { if (core.linearVelocity != null && core.linearVelocity.distance != 0) {
Vector3 direction = Quaternion.AngleAxis(core.linearVelocity.direction.horizontal, Vector3.up) * Vector3.forward; Vector3 direction = Quaternion.AngleAxis(core.linearVelocity.direction.horizontal, Vector3.up) * Vector3.forward;
this.transform.Translate(core.linearVelocity.distance * Time.deltaTime * direction, Space.Self); this.transform.Translate(core.linearVelocity.distance * Time.deltaTime * direction, Space.Self);
// core.position = LinearAlgebra.Spherical.FromVector3(this.transform.localPosition);
} }
if (core.angularVelocity != null && core.angularVelocity.distance != 0) { if (core.angularVelocity != null && core.angularVelocity.distance != 0) {
Vector3 axis = core.angularVelocity.direction.ToVector3(); Vector3 axis = core.angularVelocity.direction.ToVector3();
this.transform.localRotation *= Quaternion.AngleAxis(core.angularVelocity.distance * Time.deltaTime, axis); this.transform.localRotation *= Quaternion.AngleAxis(core.angularVelocity.distance * Time.deltaTime, axis);
// core.orientation = LinearAlgebra.SwingTwist.FromQuaternion(this.transform.localRotation);
} }
}
/// <summary> if (!string.IsNullOrEmpty(core.modelUrl) && this.modelUrl == null) {
/// Update the Unity state (just calls UpdateThing) string extension = core.modelUrl.Substring(core.modelUrl.LastIndexOf("."));
/// </summary> if (extension == ".jpg" || extension == ".png") {
protected virtual void FixedUpdate() { StartCoroutine(LoadJPG());
UpdateThing(); }
// if (core != null) {
// // This is new....
// core.orientation = LinearAlgebra.SwingTwist.FromQuaternion(this.transform.localRotation);
// }
}
/// <summary> this.modelUrl = core.modelUrl;
/// Update the Unity state
/// </summary>
public void UpdateThing() {
if (core == null) {
// Debug.Log($"{this} core thing is gone, self destruct in 0 seconds...");
// Destroy(this);
return;
} }
if (core.updateQueue == null) if (core.nameChanged) {
return; if (this.gameObject.name != core.name)
while (core.updateQueue.TryDequeue(out RoboidControl.Thing.CoreEvent e))
HandleCoreEvent(e);
}
/// <summary>
/// Handle events from the core thing
/// </summary>
/// <param name="coreEvent">The core event to handle</param>
private void HandleCoreEvent(RoboidControl.Thing.CoreEvent coreEvent) {
switch (coreEvent.messageId) {
case ThingMsg.id:
if (core.parent == null)
this.transform.SetParent(core.owner.component.transform, true);
else if (core.parent.component != null)
this.transform.SetParent(core.parent.component.transform, true);
break;
case NameMsg.Id:
this.gameObject.name = core.name; this.gameObject.name = core.name;
break; core.nameChanged = false;
case ModelUrlMsg.Id: }
string extension = core.modelUrl[core.modelUrl.LastIndexOf(".")..]; if (core.hierarchyChanged) {
if (extension == ".jpg" || extension == ".png") // Debug.Log("Parent changed");
StartCoroutine(LoadJPG()); if (core.parent == null)
#if GLTF this.transform.SetParent(null, true);
else if (extension == ".gltf" || extension == ".glb") else
ProcessGltfModel(core); this.transform.SetParent(core.parent.component.transform, true);
#endif core.hierarchyChanged = false;
break;
case PoseMsg.Id:
this.HandlePose();
break;
case BinaryMsg.Id:
this.HandleBinary();
break;
} }
} }
/// <summary> private void PoseChanged() {
/// Load and attach a JPG sprite visualization of the thing //Debug.Log($"{this} pose changed");
/// </summary> if (core.positionUpdated)
/// <returns></returns> this.transform.localPosition = core.position.ToVector3();
if (core.orientationUpdated)
this.transform.localRotation = core.orientation.ToQuaternion();
}
private IEnumerator LoadJPG() { private IEnumerator LoadJPG() {
UnityWebRequest request = UnityWebRequestTexture.GetTexture(core.modelUrl); UnityWebRequest request = UnityWebRequestTexture.GetTexture(core.modelUrl);
yield return request.SendWebRequest(); yield return request.SendWebRequest();
@ -175,124 +138,6 @@ namespace RoboidControl.Unity {
} }
} }
#if GLTF
bool loadingModel = false;
private async void ProcessGltfModel(RoboidControl.Thing coreThing) {
if (!loadingModel) {
loadingModel = true;
#if DEBUG
Debug.Log("Loading GLTF model from :" + coreThing.modelUrl);
#endif
GltfImport gltfImport = new GltfImport();
bool success = await gltfImport.Load(coreThing.modelUrl);
if (success) {
Transform parentTransform = this.transform;
Thing[] things = FindObjectsOfType<Thing>();
Thing parentThing = null;
foreach (Thing thing in things) {
if (thing.core != null && thing.core.owner.networkId == coreThing.owner.networkId && thing.core.id == coreThing.id) {
parentTransform = thing.transform;
parentThing = thing;
}
}
await gltfImport.InstantiateMainSceneAsync(parentTransform);
SkinnedMeshRenderer[] meshRenderers = parentTransform.GetComponentsInChildren<SkinnedMeshRenderer>();
parentTransform.localScale = Vector3.one;
if (meshRenderers.Length > 0) {
foreach (SkinnedMeshRenderer meshRenderer in meshRenderers) {
if (meshRenderer.rootBone != null) {
// Debug.Log("Found a skinned mesh with bones");
ScanForThings(meshRenderer.rootBone);
break;
}
}
}
else
ScanForThings(parentTransform);
AddMeshColliders(parentTransform); }
else {
this.transform.localScale = Vector3.one * 1;
}
}
loadingModel = true;
}
#endif
private void ScanForThings(Transform rootTransform) {
RoboidControl.Thing[] thingArray = this.core.owner.things.ToArray();
for (int thingIx = 0; thingIx < thingArray.Length; thingIx++) {
RoboidControl.Thing thing = thingArray[thingIx];
GameObject foundObj = FindThingByName(thing, rootTransform);
if (foundObj != null && (thing.component != null && foundObj != thing.component.gameObject)) {
Thing foundThing = foundObj.GetComponent<Thing>();
if (foundThing == null) {
// Debug.Log($"move thing [{thing.owner.networkId}/{thing.id}] to {foundObj.name}");
foundThing = foundObj.AddComponent<Thing>();
foundThing.core = thing;
foundThing.core.position = LinearAlgebra.Spherical.FromVector3(foundObj.transform.localPosition);
foundThing.core.orientation = LinearAlgebra.SwingTwist.FromQuaternion(foundObj.transform.localRotation);
Destroy(thing.component.gameObject);
thing.component = foundThing;
}
else {
Debug.LogWarning($"Could not find [{thing.owner.networkId}/{thing.id}]");
}
}
}
}
private GameObject FindThingByName(RoboidControl.Thing thing, Transform rootTransform) {
if (rootTransform == null || thing == null)
return null;
if (rootTransform.name == thing.name)
return rootTransform.gameObject;
for (int childIx = 0; childIx < rootTransform.childCount; childIx++) {
Transform child = rootTransform.GetChild(childIx);
GameObject foundObj = FindThingByName(thing, child);
if (foundObj != null)
return foundObj;
}
return null;
}
private void AddMeshColliders(Transform rootTransform) {
MeshRenderer[] meshRenderers = rootTransform.GetComponentsInChildren<MeshRenderer>();
foreach (MeshRenderer meshRenderer in meshRenderers) {
MeshFilter meshFilter = meshRenderer.GetComponent<MeshFilter>();
MeshCollider meshCollider = meshRenderer.gameObject.AddComponent<MeshCollider>();
meshCollider.sharedMesh = meshFilter.sharedMesh;
meshCollider.convex = true;
}
}
/// <summary>
/// Handle a Pose event
/// </summary>
/// This can update the position and/or orientation when the velocity of the thing is zero.
/// If a velocity is not zero, the position and/or orientation update will be ignored
protected virtual void HandlePose() {
this.transform.localRotation = core.orientation.ToQuaternion();
this.transform.localPosition = core.position.ToVector3();
// if (core.linearVelocity.distance == 0)
// this.transform.localPosition = core.position.ToVector3();
// if (core.angularVelocity.distance == 0)
// this.transform.localRotation = core.orientation.ToQuaternion();
}
/// <summary>
/// Handle a Binary event
/// </summary>
protected virtual void HandleBinary() { }
} }

View File

@ -4,76 +4,87 @@ using UnityEngine;
namespace RoboidControl.Unity { namespace RoboidControl.Unity {
/// <summary> /// <summary>
/// The Unity representation of a Roboid Control touch sensor /// The Unity representation of the TouchSensor
/// </summary> /// </summary>
public class TouchSensor : Thing { public class TouchSensor : Thing {
// public SiteServer participant;
/// <summary> /// <summary>
/// The core touch sensor /// The core touch sensor
/// </summary> /// </summary>
public RoboidControl.TouchSensor coreSensor => base.core as RoboidControl.TouchSensor; public RoboidControl.TouchSensor coreSensor {
get => (RoboidControl.TouchSensor)base.core;
}
SphereCollider collider = null;
/// <summary> /// <summary>
/// Create the Unity representation of the touch sensor /// Start the Unity represention
/// </summary> /// </summary>
/// <param name="coreSensor">The core touch sensor</param> protected virtual void Start() {
if (core == null) {
participant = FindAnyObjectByType<SiteServer>();
SetCoreThing(new RoboidControl.TouchSensor(participant.site));
}
collider = GetComponent<SphereCollider>();
}
/// <summary>
/// Create the Unity representation
/// </summary>
/// <param name="core">The core touch sensor</param>
/// <returns>The Unity representation of the touch sensor</returns> /// <returns>The Unity representation of the touch sensor</returns>
/// This uses a 'TouchSensor' resource when available for the Unity representation. public static TouchSensor Create(RoboidControl.TouchSensor core) {
/// If this is not available, a default representation is created. GameObject gameObj = core.name != null ?
public static TouchSensor Create(RoboidControl.TouchSensor coreSensor) { new(core.name) :
TouchSensor touchSensor; new("Touch Sensor");
GameObject prefab = (GameObject)Resources.Load("TouchSensor"); TouchSensor component = gameObj.AddComponent<TouchSensor>();
if (prefab != null) { component.Init(core);
// Use resource prefab when available
GameObject gameObj = Instantiate(prefab);
touchSensor = gameObj.GetComponent<TouchSensor>();
touchSensor.Init(coreSensor);
}
else {
// Default implementation
GameObject gameObj = new(coreSensor.name);
touchSensor = gameObj.AddComponent<TouchSensor>();
touchSensor.Init(coreSensor);
Rigidbody rb = gameObj.AddComponent<Rigidbody>(); Rigidbody rb = gameObj.AddComponent<Rigidbody>();
rb.isKinematic = true; rb.isKinematic = true;
SphereCollider collider = gameObj.AddComponent<SphereCollider>(); SphereCollider collider = gameObj.AddComponent<SphereCollider>();
collider.radius = 0.01f; collider.radius = 0.01f;
collider.isTrigger = true; collider.isTrigger = true;
if (gameObj.transform.parent != null && gameObj.transform.localPosition.magnitude > 0) {
collider.radius = Vector3.Distance(gameObj.transform.position, gameObj.transform.parent.position) / 2;
gameObj.transform.position = (gameObj.transform.position + gameObj.transform.parent.position) / 2;
} }
return touchSensor;
return component;
} }
public bool touchedSomething = false; protected override void Update() {
base.Update();
if (collider.radius == 0.01f &&
this.transform.parent != null && this.transform.localPosition.magnitude > 0
) {
collider.radius = Vector3.Distance(this.transform.position, this.transform.parent.position) / 2;
this.transform.position = (this.transform.position + this.transform.parent.position) / 2;
}
}
/// <summary>
/// Handle touch trigger collider enter event
/// </summary>
/// <param name="other">The collider which entered our trigger collider</param>
private void OnTriggerEnter(Collider other) { private void OnTriggerEnter(Collider other) {
// Don't detect trigger colliders // Debug.Log("Touch?");
if (other.isTrigger) if (other.isTrigger) {
// Debug.Log($" was trigger {other.name}");
return; return;
// Don't touch yourself }
if (this.transform.root == other.transform.root) if (this.transform.root == other.transform.root) {
Debug.Log($" was myself {other.name}");
return; return;
}
Debug.Log("TOUCH!"); Debug.Log($"*** {this} Touch");
this.touchedSomething = true;
this.coreSensor.touchedSomething = true; this.coreSensor.touchedSomething = true;
//this.core.updateQueue.Enqueue(new RoboidControl.Thing.CoreEvent(BinaryMsg.Id));
} }
/// <summary>
/// Handl touch trigger collider exit event
/// </summary>
/// <param name="other">The collider which exited our trigger collider </param>
private void OnTriggerExit(Collider other) { private void OnTriggerExit(Collider other) {
if (other.isTrigger) if (other.isTrigger)
return; return;
Debug.Log("TOUCH END!"); Debug.Log($"*** {this} Touch end");
this.touchedSomething = false;
this.coreSensor.touchedSomething = false; this.coreSensor.touchedSomething = false;
} }
} }

View File

@ -1,97 +0,0 @@
#if UNITY_5_3_OR_NEWER
using UnityEngine;
namespace RoboidControl.Unity {
/// <summary>
/// The Unity representation of a Roboid Control wheel
/// </summary>
public class Wheel : Thing {
/// <summary>
/// Create the Unity representation
/// </summary>
/// <param name="core">The core motor</param>
/// <returns>The Unity representation of a motorised wheel</returns>
public static new Wheel Create(RoboidControl.Thing core) {
GameObject prefab = (GameObject)Resources.Load("Wheel");
if (prefab != null) {
// Use resource prefab when available
GameObject gameObj = Instantiate(prefab);
Wheel component = gameObj.GetComponent<Wheel>();
if (component != null)
component.core = core;
return component;
}
else {
// Fallback implementation
GameObject gameObj = new(core.name);
Wheel component = gameObj.AddComponent<Wheel>();
component.Init(core);
Debug.Log("Create " + core.name);
return component;
}
}
public static Wheel Create(Transform parent, byte thingId) {
GameObject prefab = (GameObject)Resources.Load("Wheel");
if (prefab != null) {
// Use resource prefab when available
GameObject gameObj = Instantiate(prefab);
Wheel component = gameObj.GetComponent<Wheel>();
if (component != null) {
component.core = new RoboidControl.Thing() {
type = RoboidControl.Thing.Type.UncontrolledMotor
};
}
//component.core = new RoboidControl.Thing(RoboidControl.Thing.Type.UncontrolledMotor, false);
return component;
}
else {
// Fallback implementation
GameObject gameObj = new("Wheel");
gameObj.transform.parent = parent;
Wheel component = gameObj.AddComponent<Wheel>();
SiteServer participant = FindAnyObjectByType<SiteServer>();
RoboidControl.Participant owner = participant.coreParticipant;
RoboidControl.Thing core = owner.Get(owner.networkId, thingId);
if (core == null) {
core = new(participant.coreParticipant.root) {
id = thingId,
type = RoboidControl.Thing.Type.UncontrolledMotor,
};
}
//core = new(participant.coreParticipant, RoboidControl.Thing.Type.UncontrolledMotor, thingId, false);
else {
;
}
component.Init(core);
SphereCollider collider = gameObj.AddComponent<SphereCollider>();
collider.radius = 0.00001f;
collider.material = slidingWheel;
Debug.Log("Create placeholder Wheel ");
return component;
}
}
public float wheelRadius = 0;
private static PhysicMaterial _slidingWheel;
public static PhysicMaterial slidingWheel {
get {
if (_slidingWheel == null) {
_slidingWheel = new() {
dynamicFriction = 0.02f, // Dynamic friction
staticFriction = 0.01f, // Static friction
bounciness = 0f, // Bounciness (bounciness value between 0 and 1)
// Set the friction combine and bounce combine methods
frictionCombine = PhysicMaterialCombine.Minimum, // How to combine friction
bounceCombine = PhysicMaterialCombine.Average // How to combine bounciness
};
}
return _slidingWheel;
}
}
}
}
#endif

View File

@ -35,19 +35,8 @@ namespace RoboidControl {
/// <summary> /// <summary>
/// Create an empty message for sending /// Create an empty message for sending
/// </summary> /// </summary>
/// <param name="thingId">The thing sending the binary message</param> /// <param name="networkId">The netowork ID of the thing</param>
public BinaryMsg(Thing thing) : base() { /// <param name="thingId">The ID of the thing</param>
this.networkId = thing.owner.networkId;
this.thingId = thing.id;
this.thing = thing;
this.data = this.thing.GenerateBinary();
this.dataLength = (byte)this.data.Length;
}
/// <summary>
/// Create an empty message for sending
/// </summary>
/// <param name="networkId">The network ID of the thing</param>
/// <param name="thingId">The thing sending the binary message</param>
public BinaryMsg(byte networkId, Thing thing) : base() { public BinaryMsg(byte networkId, Thing thing) : base() {
this.networkId = networkId; this.networkId = networkId;
this.thingId = thing.id; this.thingId = thing.id;
@ -72,7 +61,7 @@ namespace RoboidControl {
return 0; return 0;
#if DEBUG #if DEBUG
// System.Console.WriteLine($"Send BinaryMsg [{this.networkId}/{this.thingId}] {this.dataLength}"); System.Console.WriteLine($"Send BinaryMsg [{this.networkId}/{this.thingId}] {this.dataLength}");
#endif #endif
byte ix = 0; byte ix = 0;
buffer[ix++] = BinaryMsg.Id; buffer[ix++] = BinaryMsg.Id;

View File

@ -34,33 +34,25 @@ namespace RoboidControl {
buffer[ix++] = (byte)qw; buffer[ix++] = (byte)qw;
} }
public static Quat32 ReceiveQuat32(byte[] data, ref byte ix) { public static Quat32 ReceiveQuat32(byte[] data, ref byte ix) {
Quat32 q32 = new Quat32( Quat32 q = new Quat32(
(data[ix++] - 128.0F) / 127.0F, (data[ix++] - 128.0F) / 127.0F,
(data[ix++] - 128.0F) / 127.0F, (data[ix++] - 128.0F) / 127.0F,
(data[ix++] - 128.0F) / 127.0F, (data[ix++] - 128.0F) / 127.0F,
data[ix++] / 255.0F); data[ix++] / 255.0F);
System.Console.Write($"receive q32: {q32.x} {q32.y} {q32.z} {q32.w}"); return q;
return q32;
} }
public static void SendQuat32(byte[] buffer, ref byte ix, SwingTwist s) { public static void SendQuat32(byte[] buffer, ref byte ix, SwingTwist s) {
Quat32 q32 = Quat32.FromSwingTwist(s); Quat32 q32 = Quat32.FromSwingTwist(s);
SendQuat32(buffer, ref ix, q32); SendQuat32(buffer, ref ix, q32);
}
public static void SendSwingTwist(byte[] buffer, ref byte ix, SwingTwist r) {
SendAngle8(buffer, ref ix, r.swing.horizontal);
SendAngle8(buffer, ref ix, r.swing.vertical);
SendAngle8(buffer, ref ix, r.twist);
} }
public static SwingTwist ReceiveSwingTwist(byte[] data, ref byte ix) { public static SwingTwist ReceiveSwingTwist(byte[] data, ref byte ix) {
float horizontal = ReceiveAngle8(data, ref ix); Quat32 q32 = ReceiveQuat32(data, ref ix);
float vertical = ReceiveAngle8(data, ref ix); // UnityEngine.Quaternion q = new(q32.x, q32.y, q32.z, q32.w);
float twist = ReceiveAngle8(data, ref ix); // SwingTwist r = new(q.eulerAngles.y, q.eulerAngles.x, q.eulerAngles.z);
// System.Console.Write($"receive st: {horizontal} {vertical} {twist}");
SwingTwist r = SwingTwist.Degrees(horizontal, vertical, twist); SwingTwist r = SwingTwist.FromQuat32(q32);
return r; return r;
} }

View File

@ -14,7 +14,7 @@ namespace RoboidControl {
/// <summary> /// <summary>
/// The length of the message /// The length of the message
/// </summary> /// </summary>
public byte length = 4 + 4 + 4; public const byte length = 4 + 4 + 4;
/// <summary> /// <summary>
/// The network ID of the thing /// The network ID of the thing
/// </summary> /// </summary>
@ -108,19 +108,18 @@ namespace RoboidControl {
if ((this.poseType & Pose_Position) != 0) if ((this.poseType & Pose_Position) != 0)
this.position = LowLevelMessages.ReceiveSpherical(buffer, ref ix); this.position = LowLevelMessages.ReceiveSpherical(buffer, ref ix);
if ((this.poseType & Pose_Orientation) != 0) if ((this.poseType & Pose_Orientation) != 0)
this.orientation = LowLevelMessages.ReceiveSwingTwist(buffer, ref ix); this.orientation = SwingTwist.FromQuat32(LowLevelMessages.ReceiveQuat32(buffer, ref ix));
if ((this.poseType & Pose_LinearVelocity) != 0) if ((this.poseType & Pose_LinearVelocity) != 0)
this.linearVelocity = LowLevelMessages.ReceiveSpherical(buffer, ref ix); this.linearVelocity = LowLevelMessages.ReceiveSpherical(buffer, ref ix);
if ((this.poseType & Pose_AngularVelocity) != 0) if ((this.poseType & Pose_AngularVelocity) != 0)
this.angularVelocity = LowLevelMessages.ReceiveSpherical(buffer, ref ix); this.angularVelocity = LowLevelMessages.ReceiveSpherical(buffer, ref ix);
this.length = ix;
} }
/// @copydoc Passer::RoboidControl::IMessage::Serialize /// @copydoc Passer::RoboidControl::IMessage::Serialize
public override byte Serialize(ref byte[] buffer) { public override byte Serialize(ref byte[] buffer) {
if (poseType == 0) if (poseType == 0)
return 0; return 0;
#if DEBUG2 #if DEBUG
System.Console.WriteLine($"Send PoseMsg [{this.networkId}/{this.thingId}] {this.poseType}"); System.Console.WriteLine($"Send PoseMsg [{this.networkId}/{this.thingId}] {this.poseType}");
#endif #endif
@ -133,9 +132,9 @@ namespace RoboidControl {
if ((poseType & Pose_Position) != 0) if ((poseType & Pose_Position) != 0)
LowLevelMessages.SendSpherical(buffer, ref ix, this.position); LowLevelMessages.SendSpherical(buffer, ref ix, this.position);
if ((poseType & Pose_Orientation) != 0) if ((poseType & Pose_Orientation) != 0)
LowLevelMessages.SendSwingTwist(buffer, ref ix, this.orientation); LowLevelMessages.SendQuat32(buffer, ref ix, this.orientation);
if ((poseType & Pose_LinearVelocity) != 0) if ((poseType & Pose_LinearVelocity) != 0)
LowLevelMessages.SendSpherical(buffer, ref ix, this.linearVelocity); LowLevelMessages.SendSpherical(buffer, ref ix, this.linearVelocity);
if ((poseType & Pose_AngularVelocity) != 0) if ((poseType & Pose_AngularVelocity) != 0)
LowLevelMessages.SendSpherical(buffer, ref ix, this.angularVelocity); LowLevelMessages.SendSpherical(buffer, ref ix, this.angularVelocity);
return ix; return ix;

View File

@ -1,8 +1,5 @@
using System; using System;
using System.Collections.Generic; using System.Collections.Generic;
using System.Collections.Concurrent;
using System.Net;
using System.Net.Sockets;
namespace RoboidControl { namespace RoboidControl {
@ -14,79 +11,30 @@ namespace RoboidControl {
/// It also maintains the communcation information to contact the participant. /// It also maintains the communcation information to contact the participant.
/// It is used as a basis for the local participant, but also as a reference to remote participants. /// It is used as a basis for the local participant, but also as a reference to remote participants.
public class Participant { public class Participant {
#region Init
/// <summary>
/// Create a generic participant
/// </summary>
public Participant() {
Thing.CreateRoot(this);
}
/// <summary> /// <summary>
/// Create a new participant with the given communcation info /// Create a new participant with the given communcation info
/// </summary> /// </summary>
/// <param name="ipAddress">The IP address of the participant</param> /// <param name="ipAddress">The IP address of the participant</param>
/// <param name="port">The UDP port of the participant</param> /// <param name="port">The UDP port of the participant</param>
/// <remarks>This does not belong here, it should move to ParticipantUDP or something like that in the future public Participant(string ipAddress, int port) {
public Participant(string ipAddress, int port, Participant localParticipant = null) { this.ipAddress = ipAddress;
// this.ipAddress = ipAddress; this.port = port;
// this.port = port;
Thing.CreateRoot(this);
// if (localParticipant != null)
// this.udpClient = localParticipant.udpClient;
} }
/// <summary>
/// The local participant for this application
/// </summary>
public static Participant localParticipant = new();
/// <summary>
/// Replace the local participant
/// </summary>
/// <param name="newParticipant">The new local participant</param>
public static void ReplaceLocalParticipant(Participant newParticipant) {
Participant.localParticipant = newParticipant;
}
#endregion Init
#region Properties
/*
/// <summary> /// <summary>
/// The Ip Address of a participant. When the participant is local, this contains 0.0.0.0 /// The Ip Address of a participant. When the participant is local, this contains 0.0.0.0
/// </summary> /// </summary>
/// <remarks>This does not belong here, it should move to ParticipantUDP or something like that in the future public string ipAddress = "0.0.0.0";
protected string ipAddress = "0.0.0.0";
/// <summary> /// <summary>
/// The port number for UDP communication with the participant. This is 0 for isolated participants. /// The port number for UDP communication with the participant. This is 0 for isolated participants.
/// </summary> /// </summary>
/// <remarks>This does not belong here, it should move to ParticipantUDP or something like that in the future public int port = 0;
protected int port = 0;
/// <summary> /// <summary>
/// The udpClient for this participant /// he network Id to identify the participant
/// </summary>
/// <remarks>This does not belong here, it should move to ParticipantUDP or something like that in the future
public UdpClient udpClient = null;
*/
/// <summary>
/// The network Id to identify the participant
/// </summary> /// </summary>
public byte networkId = 0; public byte networkId = 0;
public bool isRemote = false;
/// <summary>
/// The root thing for this participant
/// </summary>
public Thing root = null;
/// <summary> /// <summary>
/// The things managed by this participant /// The things managed by this participant
/// </summary> /// </summary>
@ -97,7 +45,6 @@ namespace RoboidControl {
/// </summary> /// </summary>
/// <param name="thingId">The ID of the thing</param> /// <param name="thingId">The ID of the thing</param>
/// <returns>The thing when it is found, null in other cases.</returns> /// <returns>The thing when it is found, null in other cases.</returns>
/*
public Thing Get(byte thingId) { public Thing Get(byte thingId) {
Thing thing = things.Find(aThing => aThing.id == thingId); Thing thing = things.Find(aThing => aThing.id == thingId);
//Thing thing = things.Find(aThing => Thing.IsThing(aThing, networkId, thingId)); //Thing thing = things.Find(aThing => Thing.IsThing(aThing, networkId, thingId));
@ -105,16 +52,6 @@ namespace RoboidControl {
// Console.WriteLine($"Could not find thing {ipAddress}:{port}[{networkId}/{thingId}]"); // Console.WriteLine($"Could not find thing {ipAddress}:{port}[{networkId}/{thingId}]");
return thing; return thing;
} }
*/
public Thing Get(byte networkId, byte thingId) {
Thing thing = things.Find(aThing =>
aThing.owner.networkId == networkId &&
aThing.id == thingId
);
// if (thing == null)
// Console.WriteLine($"Unknown Thing {this.networkId} [{networkId}/{thingId}]");
return thing;
}
/// <summary> /// <summary>
/// Add a new thing for this participant /// Add a new thing for this participant
@ -122,17 +59,14 @@ namespace RoboidControl {
/// <param name="thing">The thing to add</param> /// <param name="thing">The thing to add</param>
/// <param name="checkId">If true, the thing.id is regenerated if it is zero /// <param name="checkId">If true, the thing.id is regenerated if it is zero
public void Add(Thing thing, bool checkId = true) { public void Add(Thing thing, bool checkId = true) {
// Console.WriteLine("Add Thing to participant");
if (checkId && thing.id == 0) { if (checkId && thing.id == 0) {
thing.id = (byte)(this.things.Count + 1); thing.id = (byte)(this.things.Count + 1);
this.things.Add(thing); this.things.Add(thing);
} }
else { else {
Thing foundThing = Get(thing.owner.networkId, thing.id); Thing foundThing = Get(thing.id);
if (foundThing == null) { if (foundThing == null)
Console.WriteLine($"Added Thing to participant {this.networkId} [{thing.owner.networkId}/{thing.id}]");
this.things.Add(thing); this.things.Add(thing);
}
} }
} }
@ -144,84 +78,19 @@ namespace RoboidControl {
this.things.Remove(thing); this.things.Remove(thing);
} }
#if UNITY_5_3_OR_NEWER
/// <summary>
/// A reference to the representation of the thing in Unity
/// </summary>
[NonSerialized]
public Unity.Participant component = null;
#endif
#endregion properties
#region Update
/// <summary> /// <summary>
/// Update all things for this participant /// Update all things for this participant
/// </summary> /// </summary>
public virtual void Update() { /// <param name="currentTimeMS">The current time in milliseconds (optional)</param>
public virtual void Update(ulong currentTimeMS = 0) {
int n = this.things.Count; int n = this.things.Count;
for (int ix = 0; ix < n; ix++) { for (int ix = 0; ix < n; ix++) {
Thing thing = this.things[ix]; Thing thing = this.things[ix];
if (thing != null) if (thing != null)
thing.Update(true); thing.Update(currentTimeMS, true);
} }
} }
/// <summary>
/// Event for a participant
/// </summary>
public class UpdateEvent {
/// <summary>
/// The type of event happened.
/// </summary>
/// This value is filled with the Ids of the communication messages.
public int messageId; // see the communication messages
/// <summary>
/// The thing relevant fo the event
/// </summary>
public Thing thing;
public Participant participant;
}
/// <summary>
/// Queue containing events happened to this participant
/// </summary>
public ConcurrentQueue<UpdateEvent> updateQueue = new();
#endregion Update
#region Send
// Would be nice if this could be shared between all participants....
public byte[] buffer = new byte[1024];
public virtual bool Send(IMessage msg) {
return false;
// int bufferSize = msg.Serialize(ref this.buffer);
// if (bufferSize <= 0)
// return true;
// IPEndPoint participantEndpoint = new IPEndPoint(IPAddress.Parse(this.ipAddress), this.port);
// // Console.WriteLine($"msg to remote participant {participantEndpoint.Address.ToString()} {participantEndpoint.Port}");
// if (udpClient != null) {
// //Console.WriteLine("sending...");
// this.udpClient?.Send(this.buffer, bufferSize, participantEndpoint);
// }
// return true;
}
public void SendThingInfo(Thing thing) {
this.Send(new ThingMsg(thing.owner.networkId, thing));
this.Send(new NameMsg(thing.owner.networkId, thing));
this.Send(new ModelUrlMsg(thing.owner.networkId, thing));
this.Send(new PoseMsg(thing.owner.networkId, thing));
this.Send(new BinaryMsg(thing.owner.networkId, thing));
}
#endregion Send
#region Participant Registry
/// <summary> /// <summary>
/// The collection of known participants. /// The collection of known participants.
/// </summary> /// </summary>
@ -233,14 +102,14 @@ namespace RoboidControl {
/// <param name="ipAddress">The ip address of the participant</param> /// <param name="ipAddress">The ip address of the participant</param>
/// <param name="port">The port number used to send messages to the participant</param> /// <param name="port">The port number used to send messages to the participant</param>
/// <returns>The participant or null if it is not found.</returns> /// <returns>The participant or null if it is not found.</returns>
// public static Participant GetParticipant(string ipAddress, int port) { public static Participant GetParticipant(string ipAddress, int port) {
// //Console.WriteLine($"Get Participant {ipAddress}:{port}"); //Console.WriteLine($"Get Participant {ipAddress}:{port}");
// foreach (Participant participant in Participant.participants) { foreach (Participant participant in Participant.participants) {
// if (participant.ipAddress == ipAddress && participant.port == port) if (participant.ipAddress == ipAddress && participant.port == port)
// return participant; return participant;
// } }
// return null; return null;
// } }
/// <summary> /// <summary>
/// Retrieve a participant using a network ID /// Retrieve a participant using a network ID
/// </summary> /// </summary>
@ -255,21 +124,20 @@ namespace RoboidControl {
return null; return null;
} }
// /// <summary> /// <summary>
// /// Add a new participant to the collection of participants /// Add a new participant to the collection of participants
// /// </summary> /// </summary>
// /// <param name="ipAddress">The IP address of the participant</param> /// <param name="ipAddress">The IP address of the participant</param>
// /// <param name="port">The port used to send messages to this participant</param> /// <param name="port">The port used to send messages to this participant</param>
// /// <returns>The added participant</returns> /// <returns>The added participant</returns>
// public static Participant AddParticipant(string ipAddress, int port, Participant localParticipant = null) { public static Participant AddParticipant(string ipAddress, int port) {
// Console.WriteLine($"New Participant {ipAddress}:{port}"); Console.WriteLine($"New Participant {ipAddress}:{port}");
// // This code is only valid for site, because those can distribute networkIds..... Participant participant = new(ipAddress, port) {
// Participant participant = new(ipAddress, port, localParticipant) { networkId = (byte)(Participant.participants.Count + 1)
// networkId = (byte)(Participant.participants.Count + 1) };
// }; Participant.participants.Add(participant);
// Participant.participants.Add(participant); return participant;
// return participant; }
// }
/// <summary> /// <summary>
/// Add a new participant to the collection of participants /// Add a new participant to the collection of participants
/// </summary> /// </summary>
@ -281,7 +149,6 @@ namespace RoboidControl {
Participant.participants.Add(participant); Participant.participants.Add(participant);
} }
#endregion Participant Registery
} }
} }

View File

@ -35,7 +35,6 @@ namespace RoboidControl {
if (this.port == 0) if (this.port == 0)
this.isIsolated = true; this.isIsolated = true;
Participant.AddParticipant(this); Participant.AddParticipant(this);
Participant.ReplaceLocalParticipant(this);
} }
/// <summary> /// <summary>
/// Create a participant which will try to connect to a site. /// Create a participant which will try to connect to a site.
@ -44,8 +43,12 @@ namespace RoboidControl {
/// <param name="port">The port number of the site server</param> /// <param name="port">The port number of the site server</param>
/// <param name="localPort">The port used by the local participant</param> /// <param name="localPort">The port used by the local participant</param>
public ParticipantUDP(string ipAddress, int port = 7681, int localPort = 7681) : base("127.0.0.1", localPort) { public ParticipantUDP(string ipAddress, int port = 7681, int localPort = 7681) : base("127.0.0.1", localPort) {
this.ipAddress = ipAddress; if (this.port == 0)
this.port = port; this.isIsolated = true;
else
this.remoteSite = new Participant(ipAddress, port);
Participant.AddParticipant(this);
// Determine local IP address // Determine local IP address
IPAddress localIpAddress = null; IPAddress localIpAddress = null;
@ -77,56 +80,32 @@ namespace RoboidControl {
this.udpClient = new UdpClient(localPort); this.udpClient = new UdpClient(localPort);
this.udpClient.BeginReceive(new AsyncCallback(result => ReceiveUDP(result)), null); this.udpClient.BeginReceive(new AsyncCallback(result => ReceiveUDP(result)), null);
if (this.port == 0)
this.isIsolated = true;
else
this.remoteSite = new ParticipantUDP(ipAddress, port, this);
Participant.AddParticipant(this);
Participant.ReplaceLocalParticipant(this);
} }
public ParticipantUDP(string ipAddress, int port, ParticipantUDP localParticipant) : base(ipAddress, port, localParticipant) { private static ParticipantUDP isolatedParticipant = null;
this.ipAddress = ipAddress;
this.port = port;
if (localParticipant != null)
this.udpClient = localParticipant.udpClient;
/// <summary>
/// Isolated participant is used when the application is run without networking
/// </summary>
/// <returns>A participant without networking support</returns>
public static ParticipantUDP Isolated() {
if (isolatedParticipant == null)
isolatedParticipant = new ParticipantUDP(0);
return isolatedParticipant;
} }
#endregion Init #endregion Init
#region Properties
/// <summary> /// <summary>
/// The name of the participant /// The name of the participant
/// </summary> /// </summary>
public string name = "ParticipantUDP"; public string name = "ParticipantUDP";
/// <summary>
/// The Ip Address of a participant. When the participant is local, this contains 0.0.0.0
/// </summary>
/// <remarks>This does not belong here, it should move to ParticipantUDP or something like that in the future
public string ipAddress = "0.0.0.0";
/// <summary>
/// The port number for UDP communication with the participant. This is 0 for isolated participants.
/// </summary>
/// <remarks>This does not belong here, it should move to ParticipantUDP or something like that in the future
public int port = 0;
/// <summary>
/// The udpClient for this participant
/// </summary>
/// <remarks>This does not belong here, it should move to ParticipantUDP or something like that in the future
public UdpClient udpClient = null;
/// <summary> /// <summary>
/// True if the participant is running isolated. /// True if the participant is running isolated.
/// </summary> /// </summary>
/// Isolated participants do not communicate with other participants /// Isolated participants do not communicate with other participants
public bool isIsolated = false; public bool isIsolated = false;
/// <summary> /// <summary>
/// The remote site when this participant is connected to a site /// The remote site when this participant is connected to a site
/// </summary> /// </summary>
@ -135,10 +114,12 @@ namespace RoboidControl {
/// <summary> /// <summary>
/// The interval in milliseconds for publishing (broadcasting) data on the local network /// The interval in milliseconds for publishing (broadcasting) data on the local network
/// </summary> /// </summary>
public ulong publishIntervalMS = 3000; // = 3 seconds public ulong publishInterval = 3000; // = 3 seconds
public ulong sendUpdateIntervalMS = 100; // = 0.1 seconds for object updates
public byte[] buffer = new byte[1024];
public IPEndPoint endPoint = null; public IPEndPoint endPoint = null;
public UdpClient udpClient = null;
public string broadcastIpAddress = "255.255.255.255"; public string broadcastIpAddress = "255.255.255.255";
public readonly ConcurrentQueue<IMessage> messageQueue = new ConcurrentQueue<IMessage>(); public readonly ConcurrentQueue<IMessage> messageQueue = new ConcurrentQueue<IMessage>();
@ -158,68 +139,61 @@ namespace RoboidControl {
IPAddress broadcastAddress = new(broadcastBytes); IPAddress broadcastAddress = new(broadcastBytes);
this.broadcastIpAddress = broadcastAddress.ToString(); this.broadcastIpAddress = broadcastAddress.ToString();
// Console.WriteLine($"Subnet mask: {subnetMask.ToString()}"); Console.WriteLine($"Subnet mask: {subnetMask.ToString()}");
// Console.WriteLine($"Broadcast address: {this.broadcastIpAddress}"); Console.WriteLine($"Broadcast address: {this.broadcastIpAddress}");
} }
#endregion Properties
#region Update #region Update
public override void Update() { protected ulong nextPublishMe = 0;
ulong currentTimeMS = Thing.GetTimeMs();
if (this.isIsolated == false && this.isRemote == false) { public override void Update(ulong currentTimeMS = 0) {
if (this.publishIntervalMS > 0 && currentTimeMS > this.nextPublishMe) { if (currentTimeMS == 0)
ParticipantMsg msg = new(this.networkId); currentTimeMS = Thing.GetTimeMs();
if (this.isIsolated == false) {
if (this.publishInterval > 0 && currentTimeMS > this.nextPublishMe) {
ParticipantMsg msg = new ParticipantMsg(this.networkId);
if (this.remoteSite == null) if (this.remoteSite == null)
this.Publish(msg); this.Publish(msg);
else else
this.remoteSite.Send(msg); this.Send(this.remoteSite, msg);
this.nextPublishMe = currentTimeMS + this.publishIntervalMS; this.nextPublishMe = currentTimeMS + this.publishInterval;
} }
} }
UpdateMyThings(currentTimeMS); UpdateMyThings(currentTimeMS);
if (this.isRemote == false) UpdateOtherThings(currentTimeMS);
UpdateOtherThings(currentTimeMS);
} }
protected ulong nextPublishMe = 0;
protected ulong nextSendUpdate = 0;
protected virtual void UpdateMyThings(ulong currentTimeMS) { protected virtual void UpdateMyThings(ulong currentTimeMS) {
foreach (Thing thing in this.things) { foreach (Thing thing in this.things) {
if (thing == null) if (thing == null)
continue; continue;
// if (thing.hierarchyChanged && !(this.isIsolated || this.networkId == 0)) { if (thing.hierarchyChanged && !(this.isIsolated || this.networkId == 0)) {
// ThingMsg thingMsg = new(this.networkId, thing); ThingMsg thingMsg = new(this.networkId, thing);
// // this.Send(this.remoteSite, thingMsg); this.Send(this.remoteSite, thingMsg);
// this.remoteSite.Send(thingMsg); }
// }
// 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(false); thing.Update(currentTimeMS, false);
if (!(this.isIsolated || this.networkId == 0)) { if (!(this.isIsolated || this.networkId == 0)) {
if (thing.terminate) { if (thing.terminate) {
DestroyMsg destroyMsg = new(this.networkId, thing); DestroyMsg destroyMsg = new(this.networkId, thing);
// this.Send(this.remoteSite, destroyMsg); this.Send(this.remoteSite, destroyMsg);
this.remoteSite.Send(destroyMsg); }
else {
// Send to remote site
PoseMsg poseMsg = new(thing.owner.networkId, thing);
this.Send(this.remoteSite, poseMsg);
BinaryMsg binaryMsg = new(thing.owner.networkId, thing);
this.Send(this.remoteSite, binaryMsg);
} }
// else {
// // Send to remote site
// // PoseMsg poseMsg = new(thing.owner.networkId, thing);
// // this.Send(this.remoteSite, poseMsg);
// // BinaryMsg binaryMsg = new(thing.owner.networkId, thing);
// // this.Send(this.remoteSite, binaryMsg);
// this.remoteSite.Send(new PoseMsg(thing.owner.networkId, thing));
// this.remoteSite.Send(new BinaryMsg(thing.owner.networkId, thing));
// }
} }
if (thing.terminate) if (thing.terminate)
this.Remove(thing); this.Remove(thing);
@ -228,51 +202,39 @@ namespace RoboidControl {
protected virtual void UpdateOtherThings(ulong currentTimeMS) { protected virtual void UpdateOtherThings(ulong currentTimeMS) {
for (int ownerIx = 0; ownerIx < Participant.participants.Count; ownerIx++) { for (int ownerIx = 0; ownerIx < Participant.participants.Count; ownerIx++) {
Participant owner = Participant.participants[ownerIx]; Participant participant = Participant.participants[ownerIx];
if (owner == null || owner == this) if (participant == null || participant == this)
continue; continue;
owner.Update(); participant.Update(currentTimeMS);
// if (this.isIsolated) if (this.isIsolated)
// continue; continue;
// if (currentTimeMS > this.nextSendUpdate) { for (int thingIx = 0; thingIx < participant.things.Count; thingIx++) {
// for (int thingIx = 0; thingIx < owner.things.Count; thingIx++) { Thing thing = participant.things[thingIx];
// Thing thing = owner.things[thingIx]; if (thing == null)
// if (thing == null) continue;
// continue;
// foreach (Participant participant in Participant.participants) { PoseMsg poseMsg = new(thing.owner.networkId, thing);
// if (participant == this || participant == owner) this.Send(participant, poseMsg);
// continue; BinaryMsg binaryMsg = new(thing.owner.networkId, thing);
this.Send(participant, binaryMsg);
// Console.WriteLine($"[{thing.owner.networkId}/{thing.id}] Pose ---> {participant.networkId}"); }
// PoseMsg poseMsg = new(thing.owner.networkId, thing, true);
// participant.Send(poseMsg);
// }
// }
// }
} }
// if (currentTimeMS > this.nextSendUpdate)
// this.nextSendUpdate = currentTimeMS + this.sendUpdateIntervalMS;
} }
#endregion Update #endregion Update
#region Send #region Send
public override bool Send(IMessage msg) { public void SendThingInfo(Participant owner, Thing thing) {
int bufferSize = msg.Serialize(ref this.buffer); // Console.WriteLine("Send thing info");
if (bufferSize <= 0) this.Send(owner, new ThingMsg(this.networkId, thing));
return true; this.Send(owner, new NameMsg(this.networkId, thing));
this.Send(owner, new ModelUrlMsg(this.networkId, thing));
IPEndPoint participantEndpoint = new IPEndPoint(IPAddress.Parse(this.ipAddress), this.port); this.Send(owner, new PoseMsg(this.networkId, thing));
// Console.WriteLine($"msg to remote participant {participantEndpoint.Address.ToString()} {participantEndpoint.Port}"); this.Send(owner, new BinaryMsg(this.networkId, thing));
if (udpClient != null) {
//Console.WriteLine("sending...");
this.udpClient?.Send(this.buffer, bufferSize, participantEndpoint);
}
return true;
} }
public void PublishThingInfo(Thing thing) { public void PublishThingInfo(Thing thing) {
@ -284,12 +246,23 @@ namespace RoboidControl {
this.Publish(new BinaryMsg(this.networkId, thing)); this.Publish(new BinaryMsg(this.networkId, thing));
} }
public bool Send(Participant owner, IMessage msg) {
int bufferSize = msg.Serialize(ref this.buffer);
if (bufferSize <= 0)
return true;
IPEndPoint participantEndpoint = new IPEndPoint(IPAddress.Parse(owner.ipAddress), owner.port);
// Console.WriteLine($"msg to {participantEndpoint.Address.ToString()} {participantEndpoint.Port}");
this.udpClient?.Send(this.buffer, bufferSize, participantEndpoint);
return true;
}
public bool Publish(IMessage msg) { public bool Publish(IMessage msg) {
int bufferSize = msg.Serialize(ref this.buffer); int bufferSize = msg.Serialize(ref this.buffer);
if (bufferSize <= 0) if (bufferSize <= 0)
return true; return true;
Console.WriteLine($"publish to {broadcastIpAddress.ToString()} {this.port}"); // Console.WriteLine($"publish to {broadcastIpAddress.ToString()} {this.port}");
this.udpClient?.Send(this.buffer, bufferSize, this.broadcastIpAddress, this.port); this.udpClient?.Send(this.buffer, bufferSize, this.broadcastIpAddress, this.port);
return true; return true;
} }
@ -299,110 +272,60 @@ namespace RoboidControl {
#region Receive #region Receive
protected void ReceiveUDP(IAsyncResult result) { protected void ReceiveUDP(IAsyncResult result) {
try { // UnityEngine.Debug.Log("received");
if (this.udpClient == null) if (this.udpClient == null) // || this.endPoint == null)
return; return;
byte[] data = { }; byte[] data = this.udpClient.EndReceive(result, ref endPoint);
try { // This does not yet take multi-packet messages into account!
data = this.udpClient.EndReceive(result, ref endPoint); if (endPoint == null)
} return;
catch (SocketException e) {
if (e.ErrorCode != 10054)
throw;
#if DEBUG
else
Console.WriteLine($"No receiver found for the previously sent UDP packet");
#endif
}
// This does not yet take multi-packet messages into account!
if (endPoint == null)
return;
if (data.Length > 0) { // We can receive our own publish (broadcast) packages. How do we recognize them????
// We can receive our own publish (broadcast) packages. How do we recognize them???? // It is hard to determine our source port
// It is hard to determine our source port string ipAddress = endPoint.Address.ToString();
string ipAddress = endPoint.Address.ToString(); if (ipAddress != this.ipAddress) {
if (ipAddress != this.ipAddress) { Participant remoteParticipant = GetParticipant(ipAddress, endPoint.Port);
Participant sender = GetParticipant(ipAddress, endPoint.Port); remoteParticipant ??= AddParticipant(ipAddress, endPoint.Port);
if (sender == null) {
sender = AddParticipant(ipAddress, endPoint.Port, this);
sender.isRemote = true;
ReceiveData(data, remoteParticipant);
UpdateEvent e = new() {
messageId = NetworkIdMsg.Id,
participant = sender
};
this.updateQueue.Enqueue(e);
}
ReceiveData(data, sender);
}
}
udpClient.BeginReceive(new AsyncCallback(callbackResult => ReceiveUDP(callbackResult)), null);
}
catch (Exception e) {
Console.WriteLine($"Exception in communication thread: {e.Message}");
Console.WriteLine($"Stack trace: {e.StackTrace}");
} }
udpClient.BeginReceive(new AsyncCallback(callbackResult => ReceiveUDP(callbackResult)), null);
} }
public void ReceiveData(byte[] data, Participant sender) { public void ReceiveData(byte[] data, Participant sender) {
int dataIx = 0; byte msgId = data[0];
byte msgId = data[dataIx];
if (msgId == 0xFF) { if (msgId == 0xFF) {
// Timeout // Timeout
return; return;
} }
switch (msgId) { switch (msgId) {
case ParticipantMsg.Id: { // 0xA0 / 160 case ParticipantMsg.Id: // 0xA0 / 160
ParticipantMsg msg = new(data); this.Process(sender, new ParticipantMsg(data));
this.Process(sender, msg);
dataIx += ParticipantMsg.length;
}
break; break;
case NetworkIdMsg.Id: {// 0xA1 / 161 case NetworkIdMsg.Id: // 0xA1 / 161
NetworkIdMsg msg = new(data); this.Process(sender, new NetworkIdMsg(data));
this.Process(sender, msg);
dataIx += NetworkIdMsg.length;
}
break; break;
case InvestigateMsg.Id: // 0x81 case InvestigateMsg.Id: // 0x81
// result = await InvestigateMsg.Receive(dataStream, client, packetSize); // result = await InvestigateMsg.Receive(dataStream, client, packetSize);
break; break;
case ThingMsg.id: { // 0x80 / 128 case ThingMsg.id: // 0x80 / 128
ThingMsg msg = new(data); this.Process(sender, new ThingMsg(data));
this.Process(sender, msg);
dataIx += ThingMsg.length;
}
break; break;
case NameMsg.Id: { // 0x91 / 145 case NameMsg.Id: // 0x91 / 145
NameMsg msg = new(data); this.Process(sender, new NameMsg(data));
this.Process(sender, msg);
dataIx += NameMsg.length + msg.nameLength;
}
break; break;
case ModelUrlMsg.Id: { // 0x90 / 144 case ModelUrlMsg.Id: // 0x90 / 144
ModelUrlMsg msg = new(data); this.Process(sender, new ModelUrlMsg(data));
this.Process(sender, msg);
dataIx += ModelUrlMsg.length + msg.urlLength;
}
break; break;
case PoseMsg.Id: { // 0x10 / 16 case PoseMsg.Id: // 0x10 / 16
PoseMsg msg = new(data); this.Process(sender, new PoseMsg(data));
this.Process(sender, msg); // result = await PoseMsg.Receive(dataStream, client, packetSize);
dataIx += msg.length;
}
break; break;
case BinaryMsg.Id: { // 0xB1 / 177 case BinaryMsg.Id: // 0xB1 / 177
BinaryMsg msg = new(data); this.Process(sender, new BinaryMsg(data));
this.Process(sender, msg);
dataIx += BinaryMsg.length + msg.dataLength;
}
break; break;
case TextMsg.Id: // 0xB0 / 176 case TextMsg.Id: // 0xB0 / 176
// result = await TextMsg.Receive(dataStream, client, packetSize); // result = await TextMsg.Receive(dataStream, client, packetSize);
@ -414,8 +337,6 @@ namespace RoboidControl {
default: default:
break; break;
} }
if (dataIx < data.Length)
Console.WriteLine($"####### Buffer not fully read, remaining {data.Length - dataIx}");
} }
protected virtual void Process(Participant sender, ParticipantMsg msg) { protected virtual void Process(Participant sender, ParticipantMsg msg) {
@ -432,11 +353,7 @@ namespace RoboidControl {
if (this.networkId != msg.networkId) { if (this.networkId != msg.networkId) {
this.networkId = msg.networkId; this.networkId = msg.networkId;
foreach (Thing thing in this.things) //Thing.GetAllThings()) foreach (Thing thing in this.things) //Thing.GetAllThings())
sender.SendThingInfo(thing); this.SendThingInfo(sender, thing);
// HACK to get the networkId for sites corrected to 0.
// This is needed because AddParticipant assigns a networkId for non-sites
sender.networkId = 0;
} }
} }
@ -450,58 +367,6 @@ namespace RoboidControl {
#if DEBUG #if DEBUG
Console.WriteLine($"{this.name}: Process ThingMsg [{msg.networkId}/{msg.thingId}] {msg.thingType} {msg.parentId}"); Console.WriteLine($"{this.name}: Process ThingMsg [{msg.networkId}/{msg.thingId}] {msg.thingType} {msg.parentId}");
#endif #endif
Participant owner = GetParticipant(msg.networkId);
if (owner == null) {
owner = new() {
networkId = msg.networkId
};
AddParticipant(owner);
UpdateEvent e = new() {
messageId = ParticipantMsg.Id,
participant = owner
};
this.updateQueue.Enqueue(e);
Console.WriteLine("Added Participant");
}
Thing thing = owner.Get(msg.networkId, msg.thingId);
if (thing != null) {
UpdateEvent e = new() {
messageId = ThingMsg.id,
thing = thing
};
owner.updateQueue.Enqueue(e);
}
else {
bool isRemote = sender.networkId != owner.networkId;
thing = ProcessNewThing(owner, msg, isRemote);
}
if (msg.parentId != 0) {
thing.parent = owner.Get(msg.networkId, msg.parentId);
if (thing.parent == null)
Console.WriteLine($"Could not find parent [{msg.networkId}/{msg.parentId}]");
}
else {
// Console.Write($"Dropped {thing.id}");
thing.parent = null;
}
ForwardMessage(sender, msg);
}
protected virtual Thing ProcessNewThing(Participant owner, ThingMsg msg, bool isRemote) {
// Console.WriteLine("--- New Thing");
Thing newThing = msg.thingType switch {
Thing.Type.DistanceSensor => new DistanceSensor(owner.root),
Thing.Type.TouchSensor => new TouchSensor(owner.root),
Thing.Type.DifferentialDrive => new DifferentialDrive(owner.root),
_ => new Thing(owner.root)
};
newThing.id = msg.thingId;
newThing.type = msg.thingType;
newThing.isRemote = isRemote;
return newThing;
} }
protected virtual void Process(Participant sender, NameMsg msg) { protected virtual void Process(Participant sender, NameMsg msg) {
@ -509,12 +374,9 @@ namespace RoboidControl {
Console.WriteLine($"{this.name}: Process NameMsg [{msg.networkId}/{msg.thingId}] {msg.nameLength} {msg.name}"); Console.WriteLine($"{this.name}: Process NameMsg [{msg.networkId}/{msg.thingId}] {msg.nameLength} {msg.name}");
#endif #endif
Participant owner = GetParticipant(msg.networkId); Thing thing = sender.Get(msg.thingId);
Thing thing = owner.Get(msg.networkId, msg.thingId);
if (thing != null) if (thing != null)
thing.name = msg.name; thing.name = msg.name;
ForwardMessage(sender, msg);
} }
protected virtual void Process(Participant sender, ModelUrlMsg msg) { protected virtual void Process(Participant sender, ModelUrlMsg msg) {
@ -522,11 +384,9 @@ namespace RoboidControl {
Console.WriteLine($"{this.name}: Process ModelUrlMsg [{msg.networkId}/{msg.thingId}] {msg.urlLength} {msg.url}"); Console.WriteLine($"{this.name}: Process ModelUrlMsg [{msg.networkId}/{msg.thingId}] {msg.urlLength} {msg.url}");
#endif #endif
Thing thing = sender.Get(msg.networkId, msg.thingId); Thing thing = sender.Get(msg.thingId);
if (thing != null) if (thing != null)
thing.modelUrl = msg.url; thing.modelUrl = msg.url;
ForwardMessage(sender, msg);
} }
protected virtual void Process(Participant sender, PoseMsg msg) { protected virtual void Process(Participant sender, PoseMsg msg) {
@ -537,7 +397,7 @@ namespace RoboidControl {
if (owner == null) if (owner == null)
return; return;
Thing thing = owner.Get(msg.networkId, msg.thingId); Thing thing = owner.Get(msg.thingId);
if (thing == null) if (thing == null)
return; return;
@ -553,9 +413,9 @@ namespace RoboidControl {
protected virtual void Process(Participant sender, BinaryMsg msg) { protected virtual void Process(Participant sender, BinaryMsg msg) {
#if DEBUG #if DEBUG
// Console.WriteLine($"{this.name}: Process BinaryMsg [{msg.networkId}/{msg.thingId}] {msg.dataLength}"); Console.WriteLine($"{this.name}: Process BinaryMsg [{msg.networkId}/{msg.thingId}] {msg.dataLength}");
#endif #endif
Thing thing = sender.Get(msg.networkId, msg.thingId); Thing thing = sender.Get(msg.thingId);
thing?.ProcessBinary(msg.data); thing?.ProcessBinary(msg.data);
} }
@ -570,7 +430,7 @@ namespace RoboidControl {
#if DEBUG #if DEBUG
Console.WriteLine($"Participant: Process Destroy Msg [{msg.networkId}/{msg.thingId}]"); Console.WriteLine($"Participant: Process Destroy Msg [{msg.networkId}/{msg.thingId}]");
#endif #endif
Thing thing = sender.Get(msg.networkId, msg.thingId); Thing thing = sender.Get(msg.thingId);
if (thing != null) if (thing != null)
this.Remove(thing); this.Remove(thing);
#if UNITY_5_3_OR_NEWER #if UNITY_5_3_OR_NEWER
@ -578,51 +438,17 @@ namespace RoboidControl {
#endif #endif
} }
private void ForwardMessage(Participant sender, IMessage msg) { private void ForwardMessage(IMessage msg) {
foreach (Participant participant in Participant.participants) { // foreach (Participant client in senders) {
if (participant == this || participant == sender) // if (client == this)
continue; // continue;
// //UnityEngine.Debug.Log($"---> {client.ipAddress}");
// Console.WriteLine($"---> {participant.networkId}"); // //IMessage.SendMsg(client, msg);
participant.Send(msg); // msg.Serialize(ref client.buffer);
} // client.SendBuffer(client.buffer.Length);
// }
} }
#endregion #endregion
#region Participant Registry
/// <summary>
/// Retrieve a participant using ip address and port number
/// </summary>
/// <param name="ipAddress">The ip address of the participant</param>
/// <param name="port">The port number used to send messages to the participant</param>
/// <returns>The participant or null if it is not found.</returns>
public static ParticipantUDP GetParticipant(string ipAddress, int port) {
//Console.WriteLine($"Get Participant {ipAddress}:{port}");
foreach (Participant participant in Participant.participants) {
ParticipantUDP participantUDP = participant as ParticipantUDP;
if (participantUDP.ipAddress == ipAddress && participantUDP.port == port)
return participantUDP;
}
return null;
}
/// <summary>
/// Add a new participant to the collection of participants
/// </summary>
/// <param name="ipAddress">The IP address of the participant</param>
/// <param name="port">The port used to send messages to this participant</param>
/// <returns>The added participant</returns>
public static ParticipantUDP AddParticipant(string ipAddress, int port, ParticipantUDP localParticipant = null) {
Console.WriteLine($"New Participant {ipAddress}:{port}");
// This code is only valid for site, because those can distribute networkIds.....
ParticipantUDP participant = new(ipAddress, port, localParticipant) {
networkId = (byte)(Participant.participants.Count + 1)
};
Participant.participants.Add(participant);
return participant;
}
#endregion
} }
} }

View File

@ -63,13 +63,6 @@ namespace RoboidControl {
#region Update #region Update
public override void Update() {
ulong currentTimeMS = Thing.GetTimeMs();
UpdateMyThings(currentTimeMS);
UpdateOtherThings(currentTimeMS);
}
protected override void UpdateMyThings(ulong currentTimeMS) { protected override void UpdateMyThings(ulong currentTimeMS) {
// We don't use foreach to prevent the 'Collection was modified' error // We don't use foreach to prevent the 'Collection was modified' error
int n = this.things.Count; int n = this.things.Count;
@ -79,52 +72,23 @@ namespace RoboidControl {
if (thing == null) if (thing == null)
continue; continue;
thing.Update(false); thing.Update(currentTimeMS, false);
if (this.isIsolated == false) { if (this.isIsolated == false) {
// Send to all other participants // Send to all other participants
//foreach (Participant participant in Participant.participants) {
for (int participantIx = 0; participantIx < Participant.participants.Count; participantIx++) { for (int participantIx = 0; participantIx < Participant.participants.Count; participantIx++) {
Participant participant = Participant.participants[participantIx]; Participant participant = Participant.participants[participantIx];
if (participant == null || participant == this) if (participant == null || participant == this)
continue; continue;
participant.Send(new PoseMsg(thing.owner.networkId, thing));
participant.Send(new BinaryMsg(thing.owner.networkId, thing));
}
}
}
}
protected override void UpdateOtherThings(ulong currentTimeMS) {
for (int ownerIx = 0; ownerIx < Participant.participants.Count; ownerIx++) {
Participant owner = Participant.participants[ownerIx];
if (owner == null || owner == this)
continue;
owner.Update();
if (currentTimeMS < this.nextSendUpdate)
continue;
// for (int thingIx = 0; thingIx < owner.things.Count; thingIx++) {
// Thing thing = owner.things[thingIx];
foreach (Thing thing in owner.things) {
if (thing == null)
continue;
foreach (Participant participant in Participant.participants) {
if (participant == this || participant == owner)
continue;
PoseMsg poseMsg = new(thing.owner.networkId, thing); PoseMsg poseMsg = new(thing.owner.networkId, thing);
if (poseMsg.poseType != 0) this.Send(participant, poseMsg);
Console.WriteLine($"[{thing.owner.networkId}/{thing.id}] Pose ---> {participant.networkId}"); BinaryMsg binaryMsg = new(thing.owner.networkId, thing);
participant.Send(poseMsg); this.Send(participant, binaryMsg);
} }
} }
} }
if (currentTimeMS > this.nextSendUpdate)
this.nextSendUpdate = currentTimeMS + this.sendUpdateIntervalMS;
} }
#endregion Update #endregion Update
@ -133,46 +97,41 @@ namespace RoboidControl {
protected override void Process(Participant sender, ParticipantMsg msg) { protected override void Process(Participant sender, ParticipantMsg msg) {
base.Process(sender, msg); base.Process(sender, msg);
if (msg.networkId == sender.networkId) if (msg.networkId != sender.networkId) {
return; //Console.WriteLine($"{this.name} received New Participant -> {sender.networkId}");
this.Send(sender, new NetworkIdMsg(sender.networkId));
if (sender.component != null) {
Console.WriteLine("Already created Unity participant");
return;
}
sender.Send(new NetworkIdMsg(sender.networkId));
UpdateEvent e = new() {
messageId = ParticipantMsg.Id,
participant = sender
};
this.updateQueue.Enqueue(e);
foreach (Thing thing in this.things)
sender.SendThingInfo(thing);
foreach (Participant owner in Participant.participants) {
if (owner == null || owner == this)
continue;
Console.WriteLine($"send thinginfo for {owner.things.Count} things");
foreach (Thing thing in owner.things) {
if (thing == null)
continue;
foreach (Participant participant in Participant.participants) {
if (participant == this || participant == owner)
continue;
Console.WriteLine($"[{thing.owner.networkId}/{thing.id}] Thing Info ---> {participant.networkId}");
participant.SendThingInfo(thing);
}
}
} }
} }
protected override void Process(Participant sender, NetworkIdMsg msg) { } protected override void Process(Participant sender, NetworkIdMsg msg) { }
protected override void Process(Participant sender, ThingMsg msg) {
Console.WriteLine($"SiteServer: Process thing [{msg.networkId}/{msg.thingId}] {msg.thingType} {msg.parentId} ");
Thing thing = sender.Get(msg.thingId);
if (thing == null) {
switch (msg.thingType) {
case (byte)Thing.Type.TouchSensor:
new TouchSensor(sender, msg.thingId);
break;
}
}
if (thing == null)
thing = new Thing(sender, msg.thingType, msg.thingId);
if (msg.parentId != 0) {
thing.parent = sender.Get(msg.parentId);
if (thing.parent == null)
Console.WriteLine($"Could not find parent [{msg.networkId}/{msg.parentId}]");
}
else {
// Console.Write($"Dropped {thing.id}");
thing.parent = null;
}
}
#endregion Receive #endregion Receive
} }

View File

@ -1,6 +1,5 @@
using System; using System;
using System.Collections.Generic; using System.Collections.Generic;
using System.Collections.Concurrent;
using LinearAlgebra; using LinearAlgebra;
namespace RoboidControl { namespace RoboidControl {
@ -26,11 +25,9 @@ namespace RoboidControl {
public const byte ControlledMotor = 0x06; public const byte ControlledMotor = 0x06;
public const byte UncontrolledMotor = 0x07; public const byte UncontrolledMotor = 0x07;
public const byte Servo = 0x08; public const byte Servo = 0x08;
public const byte RelativeEncoder = 0x19;
// Other // Other
public const byte Root = 0x10;
public const byte Roboid = 0x09; public const byte Roboid = 0x09;
public const byte Humanoid = 0x0A; public const byte HUmanoid = 0x0A;
public const byte ExternalSensor = 0x0B; public const byte ExternalSensor = 0x0B;
public const byte Animator = 0x0C; public const byte Animator = 0x0C;
public const byte DifferentialDrive = 0x0D; public const byte DifferentialDrive = 0x0D;
@ -39,92 +36,80 @@ namespace RoboidControl {
#region Init #region Init
/// <summary> /// <summary>
/// Create a new Thing /// Create a new thing without communication abilities
/// </summary> /// </summary>
/// <param name="parent">(optional) The parent thing</param> /// <param name="thingType">The type of thing (can use \ref RoboidControl::Thing::Type "Thing.Type")</param>
/// <note>The owner will be the same as the owner of the parent thing, it will /// <param name="invokeEvent">Invoke a OnNewThing event when the thing has been created</param>
/// be Participant.LocalParticipant if the parent is not specified. A thing public Thing(byte thingType = Type.Undetermined, bool invokeEvent = true) : this(ParticipantUDP.Isolated(), thingType, 0, invokeEvent) {
/// without a parent will be connected to the root thing.
/// </note>
public Thing(Thing parent = default) {
this.type = Type.Undetermined;
this.positionUpdated = true;
this.orientationUpdated = true;
this.hierarchyChanged = true;
if (parent == default)
this.parent = Participant.localParticipant.root;
else
this.parent = parent;
this.owner = this.parent.owner;
this.owner.Add(this, true);
Participant.UpdateEvent e = new() {
messageId = ThingMsg.id,
thing = this
};
this.owner.updateQueue.Enqueue(e);
} }
/// <summary> /// <summary>
/// Constructor to create a root thing /// Create a new thing for a participant
/// </summary> /// </summary>
/// <param name="owner">The participant who will own this root thing</param> /// <param name="owner">The owning participant</param>
/// <remarks>This function is private because CreateRoot() should be used instead</remarks> /// <param name="thingType">The type of thing (can use \ref RoboidControl::Thing::Type "Thing.Type")</param>
private Thing(Participant owner) { /// <param name="thingId">The ID of the thing, leave out or set to zero to generate an ID</param>
this.type = Type.Root; /// <param name="invokeEvent">Invoke a OnNewThing event when the thing has been created</param>
this.name = "Root"; public Thing(Participant owner, byte thingType = Type.Undetermined, byte thingId = 0, bool invokeEvent = true) {
this.positionUpdated = true;
this.orientationUpdated = true;
this.hierarchyChanged = true;
this.owner = owner; this.owner = owner;
this.parent = null; this.id = thingId;
this.owner.Add(this); this.type = thingType;
this.id = 0; // Root always has id 0 if (this.owner != null)
this.owner.Add(this);
if (invokeEvent)
InvokeNewThing(this);
} }
/// <summary> /// <summary>
/// Create a root Thing for a participant /// Create a new child thing
/// </summary> /// </summary>
/// <param name="owner">The participant who will own this root thing</param> /// <param name="parent">The parent thing</param>
public static void CreateRoot(Participant owner) { /// <param name="thingType">The type of thing (can use \ref RoboidControl::Thing::Type "Thing.Type")</param>
owner.root = new Thing(owner); /// <param name="thingId">The ID of the thing, leave out or set to zero to generate an ID</param>
/// <param name="invokeEvent">Invoke a OnNewThing event when the thing has been created</param>
/// <note>The owner will be the same as the owner of the parent thing</note>
public Thing(Thing parent, byte thingType = Type.Undetermined, byte thingId = 0, bool invokeEvent = true) : this(parent.owner, thingType, thingId, invokeEvent) {
this.parent = parent;
} }
/// <summary> // /// <summary>
/// The root thing for the local participant // /// Create a new thing for the given participant
/// </summary> // /// </summary>
public static Thing localRoot { // /// <param name="owner">The participant owning the thing</param>
get { // /// <param name="networkId">The network ID of the thing</param>
Participant participant = Participant.localParticipant; // /// <param name="thingId">The ID of the thing</param>
return participant.root; // /// <param name="thingType">The type of thing</param>
} // public Thing(Participant owner, byte networkId, byte thingId, byte thingType = 0) {
} // this.owner = owner;
// this.id = thingId;
// this.type = thingType;
// this.networkId = networkId;
// // Console.Write($"New thing added to {owner}");
// this.owner.Add(this);
// InvokeNewThing(this);
// }
/// <summary> /// <summary>
/// Function which can be used to create components in external engines. /// Function which can be used to create components in external engines.
/// </summary> /// </summary>
/// Currently this is used to create GameObjects in Unity /// Currently this is used to create GameObjects in Unity
// public virtual void CreateComponent() { public virtual void CreateComponent() {
// #if UNITY_5_3_OR_NEWER #if UNITY_5_3_OR_NEWER
// this.component = Unity.Thing.Create(this); this.component = Unity.Thing.Create(this);
// this.component.core = this; this.component.core = this;
// #endif #endif
// } }
#endregion Init #endregion Init
/// <summary>
/// Terminated things are no longer updated
/// </summary>
public bool terminate = false; public bool terminate = false;
#region Properties #region Properties
/// <summary>
/// The participant owning this thing
/// </summary>
public Participant owner = null;
/// <summary> /// <summary>
/// The ID of this thing /// The ID of this thing
/// </summary> /// </summary>
@ -136,13 +121,6 @@ namespace RoboidControl {
/// This can be either a \ref RoboidControl::Thing::Type "Thing.Type" or a byte value for custom types. /// This can be either a \ref RoboidControl::Thing::Type "Thing.Type" or a byte value for custom types.
public byte type = Type.Undetermined; public byte type = Type.Undetermined;
public bool isRemote = false;
/// <summary>
/// The participant owning this thing
/// </summary>
public Participant owner = null;
private string _name = ""; private string _name = "";
/// <summary> /// <summary>
/// The name of the thing /// The name of the thing
@ -153,28 +131,20 @@ namespace RoboidControl {
if (_name != value) { if (_name != value) {
_name = value; _name = value;
nameChanged = true; nameChanged = true;
this.updateQueue.Enqueue(new CoreEvent(NameMsg.Id)); OnNameChanged?.Invoke();
} }
} }
} }
/// <summary>
/// Event which is triggered when the name changes
/// </summary>
public event ChangeHandler OnNameChanged = delegate { };
public bool nameChanged = false; public bool nameChanged = false;
private string _modelUrl = "";
/// <summary> /// <summary>
/// An URL pointing to the location where a model of the thing can be found /// An URL pointing to the location where a model of the thing can be found
/// </summary> /// </summary>
/// <remarks>Although the roboid implementation is not dependent on the model, public string modelUrl = "";
/// the only official supported model formats are .png (sprite), .gltf and .glb
/// </remarks>
public string modelUrl {
get => _modelUrl;
set {
if (value != _modelUrl) {
_modelUrl = value;
this.updateQueue.Enqueue(new CoreEvent(ModelUrlMsg.Id));
}
}
}
#if UNITY_5_3_OR_NEWER #if UNITY_5_3_OR_NEWER
/// <summary> /// <summary>
@ -206,16 +176,9 @@ namespace RoboidControl {
value.AddChild(this); value.AddChild(this);
} }
this.hierarchyChanged = true; this.hierarchyChanged = true;
this.updateQueue.Enqueue(new CoreEvent(ThingMsg.id));
} }
} }
/// <summary>
/// Indication whether this is a root thing
/// </summary>
public bool isRoot {
get => this == localRoot || this.parent == null;
}
/// <summary> /// <summary>
/// The children of this thing /// The children of this thing
@ -307,19 +270,19 @@ namespace RoboidControl {
if (_position != value) { if (_position != value) {
_position = value; _position = value;
positionUpdated = true; positionUpdated = true;
updateQueue.Enqueue(new CoreEvent(PoseMsg.Id)); //OnPositionChanged?.Invoke();
} }
} }
} }
/// <summary> /// <summary>
/// Event triggered when the pose has changed
/// </summary>
public event ChangeHandler OnPoseChanged = delegate { };
/// <summary>
/// Boolean indicating that the thing has an updated position /// Boolean indicating that the thing has an updated position
/// </summary> /// </summary>
public bool positionUpdated = false; public bool positionUpdated = false;
public void ReplacePosition(Spherical newPosition) {
this._position = newPosition;
}
private SwingTwist _orientation = SwingTwist.zero; private SwingTwist _orientation = SwingTwist.zero;
/// <summary> /// <summary>
/// The orientation of the thing in local space /// The orientation of the thing in local space
@ -330,7 +293,6 @@ namespace RoboidControl {
if (_orientation != value) { if (_orientation != value) {
_orientation = value; _orientation = value;
orientationUpdated = true; orientationUpdated = true;
updateQueue.Enqueue(new CoreEvent(PoseMsg.Id));
//OnOrientationChanged?.Invoke(); //OnOrientationChanged?.Invoke();
} }
} }
@ -340,13 +302,6 @@ namespace RoboidControl {
/// </summary> /// </summary>
public bool orientationUpdated = false; public bool orientationUpdated = false;
public void ReplaceOrientation(SwingTwist newOrientation) {
if (newOrientation != this._orientation) {
this._orientation = newOrientation;
orientationUpdated = true;
}
}
private Spherical _linearVelocity = Spherical.zero; private Spherical _linearVelocity = Spherical.zero;
/// <summary> /// <summary>
/// The linear velocity of the thing in local space in meters per second /// The linear velocity of the thing in local space in meters per second
@ -357,11 +312,15 @@ namespace RoboidControl {
if (_linearVelocity != value) { if (_linearVelocity != value) {
_linearVelocity = value; _linearVelocity = value;
linearVelocityUpdated = true; linearVelocityUpdated = true;
updateQueue.Enqueue(new CoreEvent(PoseMsg.Id)); OnLinearVelocityChanged?.Invoke(_linearVelocity);
} }
} }
} }
/// <summary> /// <summary>
/// Event triggered when the linear velocity has changed
/// </summary>
public event SphericalHandler OnLinearVelocityChanged = delegate { };
/// <summary>
/// Boolean indicating the thing has an updated linear velocity /// Boolean indicating the thing has an updated linear velocity
/// </summary> /// </summary>
public bool linearVelocityUpdated = false; public bool linearVelocityUpdated = false;
@ -376,11 +335,15 @@ namespace RoboidControl {
if (_angularVelocity != value) { if (_angularVelocity != value) {
_angularVelocity = value; _angularVelocity = value;
angularVelocityUpdated = true; angularVelocityUpdated = true;
updateQueue.Enqueue(new CoreEvent(PoseMsg.Id)); OnAngularVelocityChanged?.Invoke(_angularVelocity);
} }
} }
} }
/// <summary> /// <summary>
/// Event triggered when the angular velocity has changed
/// </summary>
public event SphericalHandler OnAngularVelocityChanged = delegate { };
/// <summary>
/// Boolean indicating the thing has an updated angular velocity /// Boolean indicating the thing has an updated angular velocity
/// </summary> /// </summary>
public bool angularVelocityUpdated = false; public bool angularVelocityUpdated = false;
@ -389,47 +352,6 @@ namespace RoboidControl {
#region Update #region Update
/// <summary>
/// Update de state of the thing
/// </summary>
/// <param name="recurse">When true, this will Update the descendants recursively</param>
public virtual void Update(bool recurse = false) {
this.positionUpdated = false;
this.orientationUpdated = false;
this.linearVelocityUpdated = false;
this.angularVelocityUpdated = false;
this.hierarchyChanged = false;
// should recurse over children...
if (recurse) {
for (byte childIx = 0; childIx < this.children.Count; childIx++) {
Thing child = this.children[childIx];
if (child == null)
continue;
child.Update(recurse);
}
}
}
/// <summary>
/// An event happened to this event
/// </summary>
/// <note>The messageId indicates which kind of event happened
public class CoreEvent {
public CoreEvent(int messageId) {
this.messageId = messageId;
}
/// <summary>
/// The type of event happened.
/// </summary>
/// This value is filled with the Ids of the communication messages.
public int messageId;
};
/// <summary>
/// Queue containing events happened to this thing
/// </summary>
public ConcurrentQueue<CoreEvent> updateQueue = new();
/// <summary> /// <summary>
/// Get the current time in milliseconds /// Get the current time in milliseconds
/// </summary> /// </summary>
@ -442,6 +364,55 @@ namespace RoboidControl {
#endif #endif
} }
/// <summary>
/// Update de state of the thing
/// </summary>
/// <param name="recurse">When true, this will Update the descendants recursively</param>
public void Update(bool recurse = false) {
Update(GetTimeMs(), recurse);
}
// #endif
/// <summary>
/// Update this thing
/// </summary>
/// <param name="currentTime">he current clock time in milliseconds; if this is zero, the current time is retrieved automatically</param>
/// <param name="recurse">When true, this will Update the descendants recursively</param>
public virtual void Update(ulong currentTimeMs, bool recurse = false) {
if (this.positionUpdated || this.orientationUpdated)
OnPoseChanged?.Invoke();
this.positionUpdated = false;
this.orientationUpdated = false;
this.linearVelocityUpdated = false;
this.angularVelocityUpdated = false;
//this.hierarchyChanged = false;
// should recurse over children...
if (recurse) {
for (byte childIx = 0; childIx < this.children.Count; childIx++) {
Thing child = this.children[childIx];
if (child == null)
continue;
child.Update(currentTimeMs, recurse);
}
}
}
public delegate void ChangeHandler();
public delegate void SphericalHandler(Spherical v);
public delegate void ThingHandler(Thing t);
/// <summary>
/// Event triggered when a new thing has been created
/// </summary>
public static event ThingHandler OnNewThing = delegate { };
/// <summary>
/// Trigger the creation for the given thing
/// </summary>
/// <param name="thing">The created thing</param>
public static void InvokeNewThing(Thing thing) {
OnNewThing?.Invoke(thing);
}
#endregion Update #endregion Update
/// <summary> /// <summary>

View File

@ -1,85 +0,0 @@
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.
public class ControlledMotor : Motor {
public ControlledMotor(Thing parent, RelativeEncoder encoder) : base(parent) {
this.encoder = encoder;
}
// Upgrade an existing motor with an encoder
public ControlledMotor(Motor motor, RelativeEncoder encoder) : base(motor.parent) {
this.motor = motor;
this.encoder = encoder;
}
readonly RelativeEncoder encoder;
readonly Motor motor;
public override float targetSpeed {
get {
if (this.motor != null)
return this.motor.targetSpeed;
else
return base.targetSpeed;
}
set {
if (this.motor != null)
this.motor.targetSpeed = value;
else
base.targetSpeed = value;
}
}
private float _targetAngularSpeed; // In degrees per second
public virtual float targetAngularSpeed {
get => _targetAngularSpeed;
set {
if (value != this._targetAngularSpeed) {
this._targetAngularSpeed = value;
updateQueue.Enqueue(new CoreEvent(BinaryMsg.Id));
owner.Send(new BinaryMsg(this));
}
}
}
/// @brief Get the actual speed from the encoder
/// @return The speed in angle per second
public virtual float actualAngularSpee {
get => encoder.angularSpeed;
}
float pidP = 0.1F;
float pidD = 0.0F;
//float pidI = 0.0F;
public override void Update(bool recurse = false) {
float actualSpeed = this.encoder.angularSpeed;
// Simplified rotation direction, shouldbe improved
// This goes wrong when the target speed is inverted and the motor axcle is still turning in the old direction
if (this.targetAngularSpeed < 0)
actualSpeed = -actualSpeed;
ulong currentTimeMs = Thing.GetTimeMs();
float deltaTime = (currentTimeMs - this.lastUpdateTime) / 1000.0f;
float error = this.targetAngularSpeed - actualSpeed;
float errorChange = (error - lastError) * deltaTime;
float delta = error * pidP + errorChange * pidD;
// Update the motor speed
if (motor != null)
motor.targetSpeed += delta;
else
base.targetSpeed += delta;
this.lastUpdateTime = currentTimeMs;
}
ulong lastUpdateTime = 0;
float lastError = 0;
// enum Direction { Forward = 1, Reverse = -1 };
// Direction rotationDirection;
};
} // namespace RoboidControl

View File

@ -1,4 +1,3 @@
using System;
using LinearAlgebra; using LinearAlgebra;
namespace RoboidControl { namespace RoboidControl {
@ -7,14 +6,25 @@ namespace RoboidControl {
/// ///
/// @sa @link https://en.wikipedia.org/wiki/Differential_wheeled_robot @endlink /// @sa @link https://en.wikipedia.org/wiki/Differential_wheeled_robot @endlink
public class DifferentialDrive : Thing { public class DifferentialDrive : Thing {
/// <summary> /// <summary>
/// Create a new differential drive /// Create a differential drive without communication abilities
/// </summary
/// <param name="invokeEvent">Invoke a OnNewThing event when the thing has been created</param>
public DifferentialDrive(bool invokeEvent = true) : base(Type.DifferentialDrive, invokeEvent) { }
/// <summary>
/// Create a differential drive for a participant
/// </summary>
/// <param name="owner">The owning participant</param>
/// <param name="thingId">The ID of the thing, leave out or set to zero to generate an ID</param>
/// <param name="invokeEvent">Invoke a OnNewThing event when the thing has been created</param>
public DifferentialDrive(ParticipantUDP participant, byte thingId = 0, bool invokeEvent = true) : base(participant, Type.DifferentialDrive, thingId, invokeEvent) { }
/// <summary>
/// Create a new child differential drive
/// </summary> /// </summary>
/// <param name="parent">The parent thing</param> /// <param name="parent">The parent thing</param>
public DifferentialDrive(Thing parent = default) : base(parent) { /// <param name="thingId">The ID of the thing, leave out or set to zero to generate an ID</param>
this.type = Type.DifferentialDrive; /// <param name="invokeEvent">Invoke a OnNewThing event when the thing has been created</param>
} public DifferentialDrive(Thing parent, byte thingId = 0, bool invokeEvent = true) : base(parent, Type.DifferentialDrive, thingId, invokeEvent) { }
/// @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
@ -23,38 +33,31 @@ namespace RoboidControl {
/// These values are used to compute the desired wheel speed from the set /// These values are used to compute the desired wheel speed from the set
/// linear and angular velocity. /// linear and angular velocity.
/// @sa SetLinearVelocity SetAngularVelocity /// @sa SetLinearVelocity SetAngularVelocity
public void SetDriveDimensions(float wheelDiameter, float wheelSeparation = 0) { public void SetDriveDimensions(float wheelDiameter, float wheelSeparation) {
this._wheelRadius = wheelDiameter > 0 ? wheelDiameter / 2 : -wheelDiameter / 2; this.wheelRadius = wheelDiameter > 0 ? wheelDiameter / 2 : -wheelDiameter / 2;
this.rpsToMs = wheelDiameter * (float)Math.PI; this.wheelSeparation = wheelSeparation > 0 ? wheelSeparation : -wheelSeparation;
this.rpsToMs = wheelDiameter * Angle.pi;
if (wheelSeparation > 0) { float distance = this.wheelSeparation / 2;
wheelSeparation = wheelSeparation > 0 ? wheelSeparation : -wheelSeparation; if (this.leftWheel != null)
float distance = wheelSeparation / 2; this.leftWheel.position = new Spherical(distance, Direction.left);
if (this.leftWheel != null) if (this.rightWheel != null)
this.leftWheel.position = new Spherical(distance, Direction.left); this.rightWheel.position = new Spherical(distance, Direction.right);
if (this.rightWheel != null)
this.rightWheel.position = new Spherical(distance, Direction.right);
}
} }
/// @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
public void SetMotors(Motor leftWheel, Motor rightWheel) { public void SetMotors(Thing leftWheel, Thing rightWheel) {
// float distance = this.wheelSeparation / 2; float distance = this.wheelSeparation / 2;
this.leftWheel = leftWheel; this.leftWheel = leftWheel;
this.leftWheel.parent = this; if (this.leftWheel != null)
// if (this.leftWheel != null) this.leftWheel.position = new Spherical(distance, Direction.left);
// this.leftWheel.position = new Spherical(distance, Direction.left);
this.rightWheel = rightWheel; this.rightWheel = rightWheel;
this.rightWheel.parent = this; if (this.rightWheel != null)
// if (this.rightWheel != null) this.rightWheel.position = new Spherical(distance, Direction.right);
// this.rightWheel.position = new Spherical(distance, Direction.right);
owner.Send(new BinaryMsg(owner.networkId, this));
this.updateQueue.Enqueue(new CoreEvent(BinaryMsg.Id));
} }
/// @brief Directly specify the speeds of the motors /// @brief Directly specify the speeds of the motors
@ -63,30 +66,14 @@ namespace RoboidControl {
/// @param speedRight The speed of the right wheel in degrees per second. /// @param speedRight The speed of the right wheel in degrees per second.
/// Positive moves the robot in the forward direction. /// Positive moves the robot in the forward direction.
public void SetWheelVelocity(float speedLeft, float speedRight) { public void SetWheelVelocity(float speedLeft, float speedRight) {
if (this.leftWheel != null) { if (this.leftWheel != null)
this.leftWheel.targetSpeed = speedLeft; this.leftWheel.angularVelocity = new Spherical(speedLeft, Direction.left);
//this.leftWheel.angularVelocity = new Spherical(speedLeft, Direction.left); if (this.rightWheel != null)
} this.rightWheel.angularVelocity = new Spherical(speedRight, Direction.right);
if (this.rightWheel != null) {
this.rightWheel.targetSpeed = speedRight;
//this.rightWheel.angularVelocity = new Spherical(speedRight, Direction.right);
}
}
/// @brief Directly specify the speeds of the motors
/// @param speedLeft The speed of the left wheel in degrees per second.
/// Positive moves the robot in the forward direction.
/// @param speedRight The speed of the right wheel in degrees per second.
/// Positive moves the robot in the forward direction.
public void SetWheelAngularVelocity(float angularSpeedLeft, float angularSpeedRight) {
// This only works when the motor is a motor with encoder
if (this.leftWheel is ControlledMotor leftMotor)
leftMotor.targetAngularSpeed = angularSpeedLeft;
if (this.rightWheel is ControlledMotor rightMotor)
rightMotor.targetAngularSpeed = angularSpeedRight;
} }
/// @copydoc RoboidControl::Thing::Update(unsigned long) /// @copydoc RoboidControl::Thing::Update(unsigned long)
public override void Update(bool recursive = true) { public override void Update(ulong currentMs, bool recursive = true) {
if (this.linearVelocityUpdated) { if (this.linearVelocityUpdated) {
// this assumes forward velocity only.... // this assumes forward velocity only....
float linearVelocity = this.linearVelocity.distance; float linearVelocity = this.linearVelocity.distance;
@ -97,58 +84,25 @@ namespace RoboidControl {
if (angularVelocity.direction.horizontal < 0) if (angularVelocity.direction.horizontal < 0)
angularSpeed = -angularSpeed; angularSpeed = -angularSpeed;
// This assumes that the left wheel position has Direction.left // wheel separation can be replaced by this.leftwheel.position.distance
// and the right wheel position has Direction.Right... float speedLeft = (linearVelocity + angularSpeed * this.wheelSeparation / 2) / this.wheelRadius * Angle.Rad2Deg;
float speedLeft = (linearVelocity + angularSpeed * this.leftWheel.position.distance) / this.wheelRadius * Angle.Rad2Deg; float speedRight = (linearVelocity - angularSpeed * this.wheelSeparation / 2) / this.wheelRadius * Angle.Rad2Deg;
float speedRight = (linearVelocity - angularSpeed * this.rightWheel.position.distance) / this.wheelRadius * Angle.Rad2Deg;
this.SetWheelVelocity(speedLeft, speedRight); this.SetWheelVelocity(speedLeft, speedRight);
} }
} }
/// @brief The radius of a wheel in meters /// @brief The radius of a wheel in meters
private float _wheelRadius = 0.0f; protected float wheelRadius = 1.0f;
public float wheelRadius { get => _wheelRadius; }
/// @brief The distance between the wheels in meters /// @brief The distance between the wheels in meters
// private float _wheelSeparation = 0.0f; protected float wheelSeparation = 1.0f;
// public float wheelSeparation { get => _wheelSeparation; }
/// @brief Convert revolutions per second to meters per second /// @brief Convert revolutions per second to meters per second
protected float rpsToMs = 1.0f; protected float rpsToMs = 1.0f;
/// @brief The left wheel /// @brief The left wheel
public Motor leftWheel = null; protected Thing leftWheel = null;
/// @brief The right wheel /// @brief The right wheel
public Motor rightWheel = null; protected Thing rightWheel = null;
bool sendBinary = false;
public override byte[] GenerateBinary() {
if (!sendBinary)
return System.Array.Empty<byte>();
byte[] data = new byte[4];
byte ix = 0;
data[ix++] = leftWheel.id;
data[ix++] = rightWheel.id;
LowLevelMessages.SendFloat16(data, ref ix, wheelRadius);
//LowLevelMessages.SendFloat16(data, ref ix, wheelSeparation);
sendBinary = false;
return data;
}
public override void ProcessBinary(byte[] data) {
byte ix = 0;
byte leftWheelId = data[ix++];
this.leftWheel = this.owner.Get(this.owner.networkId, leftWheelId) as Motor;
this.leftWheel ??= new Motor(this) { id = leftWheelId };
byte rightWheelId = data[ix++];
this.rightWheel = this.owner.Get(this.owner.networkId, rightWheelId) as Motor;
this.rightWheel ??= new Motor(this) { id = rightWheelId };
this._wheelRadius = LowLevelMessages.ReceiveFloat16(data, ref ix);
//this._wheelSeparation = LowLevelMessages.ReceiveFloat16(data, ref ix);
this.updateQueue.Enqueue(new CoreEvent(BinaryMsg.Id));
}
}; };
} // namespace RoboidControl } // namespace RoboidControl

View File

@ -6,7 +6,6 @@ namespace RoboidControl {
/// A sensor which can detect touches /// A sensor which can detect touches
/// </summary> /// </summary>
public class DigitalSensor : Thing { public class DigitalSensor : Thing {
/*
/// <summary> /// <summary>
/// Create a digital sensor without communication abilities /// Create a digital sensor without communication abilities
/// </summary> /// </summary>
@ -19,16 +18,13 @@ namespace RoboidControl {
/// <param name="thingId">The ID of the thing, leave out or set to zero to generate an ID</param> /// <param name="thingId">The ID of the thing, leave out or set to zero to generate an ID</param>
/// <param name="invokeEvent">Invoke a OnNewThing event when the thing has been created</param> /// <param name="invokeEvent">Invoke a OnNewThing event when the thing has been created</param>
public DigitalSensor(Participant owner, byte thingId = 0, bool invokeEvent = true) : base(owner, Type.Switch, thingId, invokeEvent) { } public DigitalSensor(Participant owner, byte thingId = 0, bool invokeEvent = true) : base(owner, Type.Switch, thingId, invokeEvent) { }
*/
/// <summary> /// <summary>
/// Create a new child digital sensor /// Create a new child digital sensor
/// </summary> /// </summary>
/// <param name="parent">The parent thing</param> /// <param name="parent">The parent thing</param>
/// <param name="thingId">The ID of the thing, leave out or set to zero to generate an ID</param> /// <param name="thingId">The ID of the thing, leave out or set to zero to generate an ID</param>
/// <param name="invokeEvent">Invoke a OnNewThing event when the thing has been created</param> /// <param name="invokeEvent">Invoke a OnNewThing event when the thing has been created</param>
public DigitalSensor(Thing parent) : base(parent) { public DigitalSensor(Thing parent, byte thingId = 0, bool invokeEvent = true) : base(parent, Type.Switch, thingId, invokeEvent) { }
this.type = Type.Switch;
}
/// <summary> /// <summary>
/// Value which is true when the sensor is touching something, false otherwise /// Value which is true when the sensor is touching something, false otherwise

View File

@ -1,72 +1,42 @@
using System;
namespace RoboidControl { namespace RoboidControl {
/// <summary> /// <summary>
/// A sensor measuring distance /// A sensor measuring the distance in the forward direction
/// </summary> /// </summary>
public class DistanceSensor : Thing { public class DistanceSensor : Thing {
/// <summary>
/// The current measured distance
/// </summary>
public float distance = 0;
/// <summary> /// <summary>
/// Create a new distance sensor /// Constructor for a new distance sensor
/// </summary> /// </summary>
/// <param name="parent">The parent thing</param> /// <param name="participant">The participant for which the sensor is needed</param>
public DistanceSensor(Thing parent) : base(parent) { public DistanceSensor(Participant participant) : base(participant, Type.Undetermined) { }
this.type = Type.DistanceSensor;
this.name = "Distance sensor";
}
public float _internalDistance = float.PositiveInfinity;
public float internalDistance {
get { return _internalDistance; }
set {
if (value != _internalDistance) {
_internalDistance = value;
distanceUpdated = true;
owner.Send(new BinaryMsg(this));
}
}
}
protected float externalDistance = float.PositiveInfinity;
/// <summary> /// <summary>
/// The current distance /// Create a distance sensor with the given ID
/// </summary> /// </summary>
public float distance { /// <param name="owner">The participant for with the sensor is needed</param>
get { /// <param name="networkId">The network ID of the sensor</param>
if (this.externalDistance < this.internalDistance) /// <param name="thingId">The ID of the thing</param>
return this.externalDistance; public DistanceSensor(Participant owner, byte thingId) : base(owner, Type.TemperatureSensor, thingId) {
else
return this.internalDistance;
}
}
protected bool distanceUpdated;
// #if UNITY_5_3_OR_NEWER
// /// @copydoc Passer::RoboidControl::Thing::CreateComponent
// public override void CreateComponent() {
// this.component = Unity.DistanceSensor.Create(this);
// this.component.core = this;
// }
// #endif
public override byte[] GenerateBinary() {
if (!distanceUpdated)
return Array.Empty<byte>();
byte[] bytes = new byte[2];
byte ix = 0;
LowLevelMessages.SendFloat16(bytes, ref ix, this.internalDistance);
distanceUpdated = false;
return bytes;
} }
#if UNITY_5_3_OR_NEWER
/// @copydoc Passer::RoboidControl::Thing::CreateComponent
public override void CreateComponent() {
this.component = Unity.DistanceSensor.Create(this);
this.component.core = this;
}
#endif
/// <summary> /// <summary>
/// Function to extract the distance received in the binary message /// Function to extract the distance received in the binary message
/// </summary> /// </summary>
/// <param name="bytes">The byte array</param> /// <param name="bytes">The byte array</param>
public override void ProcessBinary(byte[] bytes) { public override void ProcessBinary(byte[] bytes) {
byte ix = 0; byte ix = 0;
this.externalDistance = LowLevelMessages.ReceiveFloat16(bytes, ref ix); this.distance = LowLevelMessages.ReceiveFloat16(bytes, ref ix);
} }
} }

View File

@ -1,85 +0,0 @@
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 EncoderMotor : Motor {
public EncoderMotor(Thing parent, RelativeEncoder encoder) : base(parent) {
this.encoder = encoder;
}
// Upgrade an existing motor with an encoder
public EncoderMotor(Motor motor, RelativeEncoder encoder) : base(motor.parent) {
this.motor = motor;
this.encoder = encoder;
}
readonly RelativeEncoder encoder;
readonly Motor motor;
public override float targetSpeed {
get {
if (this.motor != null)
return this.motor.targetSpeed;
else
return base.targetSpeed;
}
set {
if (this.motor != null)
this.motor.targetSpeed = value;
else
base.targetSpeed = value;
}
}
private float _targetAngularSpeed; // In degrees per second
public virtual float targetAngularSpeed {
get => _targetAngularSpeed;
set {
if (value != this._targetAngularSpeed) {
this._targetAngularSpeed = value;
updateQueue.Enqueue(new CoreEvent(BinaryMsg.Id));
owner.Send(new BinaryMsg(this));
}
}
}
/// @brief Get the actual speed from the encoder
/// @return The speed in angle per second
public virtual float actualAngularSpee {
get => encoder.angularSpeed;
}
float pidP = 0.1F;
float pidD = 0.0F;
//float pidI = 0.0F;
public override void Update(bool recurse = false) {
float actualSpeed = this.encoder.angularSpeed;
// Simplified rotation direction, shouldbe improved
// This goes wrong when the target speed is inverted and the motor axcle is still turning in the old direction
if (this.targetAngularSpeed < 0)
actualSpeed = -actualSpeed;
ulong currentTimeMs = Thing.GetTimeMs();
float deltaTime = (currentTimeMs - this.lastUpdateTime) / 1000.0f;
float error = this.targetAngularSpeed - actualSpeed;
float errorChange = (error - lastError) * deltaTime;
float delta = error * pidP + errorChange * pidD;
// Update the motor speed
if (motor != null)
motor.targetSpeed += delta;
else
base.targetSpeed += delta;
this.lastUpdateTime = currentTimeMs;
}
ulong lastUpdateTime = 0;
float lastError = 0;
// enum Direction { Forward = 1, Reverse = -1 };
// Direction rotationDirection;
};
} // namespace RoboidControl

View File

@ -1,48 +0,0 @@
using LinearAlgebra;
namespace RoboidControl {
public class Motor : Thing {
public Motor(Thing parent) : base(parent) {
this.type = Type.UncontrolledMotor;
this.name = "Motor";
}
/// @brief Motor turning direction
public enum Direction {
Clockwise = 1,
CounterClockwise = -1
};
/// @brief The forward turning direction of the motor
public Direction direction = Direction.Clockwise;
protected float currentTargetSpeed = 0;
private float _targetSpeed = 0;
/// <summary>
/// The speed between -1 (full reverse), 0 (stop) and 1 (full forward)
/// </summary>
public virtual float targetSpeed {
get => _targetSpeed;
set {
if (value != _targetSpeed) {
_targetSpeed = Float.Clamp(value, -1, 1);
updateQueue.Enqueue(new CoreEvent(BinaryMsg.Id));
owner.Send(new BinaryMsg(this));
}
}
}
public override byte[] GenerateBinary() {
byte[] data = new byte[1];
byte ix = 0;
data[ix++] = (byte)(this.targetSpeed * 127);
return data;
}
public override void ProcessBinary(byte[] data) {
this._targetSpeed = (float)(sbyte)data[0] / 127;
updateQueue.Enqueue(new CoreEvent(BinaryMsg.Id));
}
}
}

View File

@ -1,45 +0,0 @@
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.
public class RelativeEncoder : Thing {
/// @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
/*
public RelativeEncoder(bool invokeEvent = true) : base(Type.IncrementalEncoder, invokeEvent) { }
*/
public RelativeEncoder(Thing parent = default) : base(parent) {
this.type = Type.RelativeEncoder;
}
protected float _rotationSpeed = 0;
/// @brief Get the rotation speed since the previous call
/// @param currentTimeMs The clock time in milliseconds
/// @return The speed in rotations per second
public virtual float angularSpeed {
get => _rotationSpeed;
set {
if (_rotationSpeed != value) {
_rotationSpeed = value;
this.owner.Send(new BinaryMsg(this));
}
}
}
public override byte[] GenerateBinary() {
byte[] data = new byte[1];
byte ix = 0;
data[ix++] = (byte)(this._rotationSpeed * 127);
return data;
}
public override void ProcessBinary(byte[] data) {
this._rotationSpeed = (float)data[0] / 127;
}
};
} // namespace RoboidControl

View File

@ -6,7 +6,6 @@ namespace RoboidControl {
/// A temperature sensor /// A temperature sensor
/// </summary> /// </summary>
public class TemperatureSensor : Thing { public class TemperatureSensor : Thing {
/*
/// <summary> /// <summary>
/// Create a temperature sensor without communication abilities /// Create a temperature sensor without communication abilities
/// </summary> /// </summary>
@ -19,16 +18,14 @@ namespace RoboidControl {
/// <param name="thingId">The ID of the thing</param> /// <param name="thingId">The ID of the thing</param>
/// <param name="invokeEvent">Invoke a OnNewThing event when the thing has been created</param> /// <param name="invokeEvent">Invoke a OnNewThing event when the thing has been created</param>
public TemperatureSensor(Participant owner, byte thingId = 0, bool invokeEvent = true) : base(owner, Type.TemperatureSensor, thingId, invokeEvent) { } public TemperatureSensor(Participant owner, byte thingId = 0, bool invokeEvent = true) : base(owner, Type.TemperatureSensor, thingId, invokeEvent) { }
*/
/// <summary> /// <summary>
/// Create a new child temperature sensor /// Create a new child temperature sensor
/// </summary> /// </summary>
/// <param name="parent">The parent thing</param> /// <param name="parent">The parent thing</param>
/// <param name="thingId">The ID of the thing, leave out or set to zero to generate an ID</param> /// <param name="thingId">The ID of the thing, leave out or set to zero to generate an ID</param>
/// <param name="invokeEvent">Invoke a OnNewThing event when the thing has been created</param> /// <param name="invokeEvent">Invoke a OnNewThing event when the thing has been created</param>
public TemperatureSensor(Thing parent) : base(parent) { public TemperatureSensor(Thing parent, byte thingId = 0, bool invokeEvent = true) : base(parent, Type.TemperatureSensor, thingId, invokeEvent) { }
this.type = Type.TemperatureSensor;
}
/// <summary> /// <summary>
/// The measured temperature /// The measured temperature

View File

@ -6,14 +6,25 @@ namespace RoboidControl {
/// A sensor which can detect touches /// A sensor which can detect touches
/// </summary> /// </summary>
public class TouchSensor : Thing { public class TouchSensor : Thing {
/// <summary>
/// Create a touch sensor without communication abilities
/// </summary>
/// <param name="invokeEvent">Invoke a OnNewThing event when the thing has been created</param>
public TouchSensor(bool invokeEvent = true) : base(Type.TouchSensor, invokeEvent) { }
/// <summary>
/// Create a touch sensor for a participant
/// </summary>
/// <param name="owner">The owning participant</param>
/// <param name="thingId">The ID of the thing, leave out or set to zero to generate an ID</param>
/// <param name="invokeEvent">Invoke a OnNewThing event when the thing has been created</param>
public TouchSensor(Participant owner, byte thingId = 0, bool invokeEvent = true) : base(owner, Type.TouchSensor, thingId, invokeEvent) { }
/// <summary> /// <summary>
/// Create a new child touch sensor /// Create a new child touch sensor
/// </summary> /// </summary>
/// <param name="parent">The parent thing</param> /// <param name="parent">The parent thing</param>
public TouchSensor(Thing parent) : base(parent) { /// <param name="thingId">The ID of the thing, leave out or set to zero to generate an ID</param>
this.type = Type.TouchSensor; /// <param name="invokeEvent">Invoke a OnNewThing event when the thing has been created</param>
this.name = "TouchSensor"; public TouchSensor(Thing parent, byte thingId = 0, bool invokeEvent = true) : base(parent, Type.TouchSensor, thingId, invokeEvent) { }
}
/// <summary> /// <summary>
/// Value which is true when the sensor is touching something, false otherwise /// Value which is true when the sensor is touching something, false otherwise
@ -24,50 +35,41 @@ namespace RoboidControl {
set { set {
if (_touchedSomething != value) { if (_touchedSomething != value) {
_touchedSomething = value; _touchedSomething = value;
owner.Send(new BinaryMsg(this));
} }
touchUpdated = true; touchUpdated = true;
} }
} }
private bool touchUpdated = false; private bool touchUpdated = false;
// #if UNITY_5_3_OR_NEWER #if UNITY_5_3_OR_NEWER
// /// @copydoc Passer::RoboidControl::Thing::CreateComponent /// @copydoc Passer::RoboidControl::Thing::CreateComponent
// public override void CreateComponent() { public override void CreateComponent() {
// // System.Console.Write("Create touch sensor component"); // System.Console.Write("Create touch sensor component");
// this.component = Unity.TouchSensor.Create(this); this.component = Unity.TouchSensor.Create(this);
// this.component.core = this; this.component.core = this;
// } }
// #endif #endif
/// <summary> /// <summary>
/// Function used to generate binary data for this touch sensor /// Function used to generate binary data for this touch sensor
/// </summary> /// </summary>
/// <returns>A byte array with the binary data</returns> /// <returns>A byte array with the binary data</returns>
/// <remark>The byte array will be empty when the touch status has not changed</remark> /// <remark>The byte array will be empty when the touch status has not changed</remark>
public override byte[] GenerateBinary() { public override byte[] GenerateBinary() {
#if UNITY_5_3_OR_NEWER if (!touchUpdated)
// We use the unity component because we only want to send the state of what is generated in the simulation
Unity.TouchSensor touchComponent = this.component as Unity.TouchSensor;
if (touchComponent == null || !touchUpdated)
return Array.Empty<byte>(); return Array.Empty<byte>();
byte[] bytes = new byte[1]; byte[] bytes = new byte[1];
bytes[0] = (byte)(touchComponent.touchedSomething ? 1 : 0); bytes[0] = (byte)(touchedSomething ? 1 : 0);
touchUpdated = false; touchUpdated = false;
return bytes; return bytes;
#else
return Array.Empty<byte>();
#endif
} }
private bool externalTouch = false;
/// <summary> /// <summary>
/// Function used to process binary data received for this touch sensor /// Function used to process binary data received for this touch sensor
/// </summary> /// </summary>
/// <param name="bytes">The binary data to process</param> /// <param name="bytes">The binary data to process</param>
public override void ProcessBinary(byte[] bytes) { public override void ProcessBinary(byte[] bytes) {
//this.touchedSomething |= (bytes[0] == 1); this.touchedSomething |= (bytes[0] == 1);
this.externalTouch = (bytes[0] == 1);
} }
} }
} }

View File

@ -18,7 +18,7 @@ namespace RoboidControl.test {
ulong milliseconds = (ulong)DateTimeOffset.UtcNow.ToUnixTimeMilliseconds(); ulong milliseconds = (ulong)DateTimeOffset.UtcNow.ToUnixTimeMilliseconds();
ulong startTime = milliseconds; ulong startTime = milliseconds;
while (milliseconds < startTime + 7000) { while (milliseconds < startTime + 7000) {
participant.Update(); participant.Update(milliseconds);
Thread.Sleep(100); Thread.Sleep(100);
milliseconds = (ulong)DateTimeOffset.UtcNow.ToUnixTimeMilliseconds(); milliseconds = (ulong)DateTimeOffset.UtcNow.ToUnixTimeMilliseconds();
@ -34,7 +34,7 @@ namespace RoboidControl.test {
ulong milliseconds = (ulong)DateTimeOffset.UtcNow.ToUnixTimeMilliseconds(); ulong milliseconds = (ulong)DateTimeOffset.UtcNow.ToUnixTimeMilliseconds();
ulong startTime = milliseconds; ulong startTime = milliseconds;
while (milliseconds < startTime + 7000) { while (milliseconds < startTime + 7000) {
siteServer.Update(); siteServer.Update(milliseconds);
Thread.Sleep(100); Thread.Sleep(100);
milliseconds = (ulong)DateTimeOffset.UtcNow.ToUnixTimeMilliseconds(); milliseconds = (ulong)DateTimeOffset.UtcNow.ToUnixTimeMilliseconds();
@ -51,8 +51,8 @@ namespace RoboidControl.test {
ulong milliseconds = (ulong)DateTimeOffset.UtcNow.ToUnixTimeMilliseconds(); ulong milliseconds = (ulong)DateTimeOffset.UtcNow.ToUnixTimeMilliseconds();
ulong startTime = milliseconds; ulong startTime = milliseconds;
while (milliseconds < startTime + 1000) { while (milliseconds < startTime + 1000) {
siteServer.Update(); siteServer.Update(milliseconds);
participant.Update(); participant.Update(milliseconds);
Thread.Sleep(100); Thread.Sleep(100);
milliseconds = (ulong)DateTimeOffset.UtcNow.ToUnixTimeMilliseconds(); milliseconds = (ulong)DateTimeOffset.UtcNow.ToUnixTimeMilliseconds();
@ -65,7 +65,7 @@ namespace RoboidControl.test {
public void Test_ThingMsg() { public void Test_ThingMsg() {
SiteServer siteServer = new(7681); SiteServer siteServer = new(7681);
ParticipantUDP participant = new("127.0.0.1", 7681, 7682); ParticipantUDP participant = new("127.0.0.1", 7681, 7682);
Thing thing = new() { Thing thing = new(participant) {
name = "First Thing", name = "First Thing",
modelUrl = "https://passer.life/extras/ant.jpg" modelUrl = "https://passer.life/extras/ant.jpg"
}; };
@ -73,8 +73,8 @@ namespace RoboidControl.test {
ulong milliseconds = (ulong)DateTimeOffset.UtcNow.ToUnixTimeMilliseconds(); ulong milliseconds = (ulong)DateTimeOffset.UtcNow.ToUnixTimeMilliseconds();
ulong startTime = milliseconds; ulong startTime = milliseconds;
while (milliseconds < startTime + 7000) { while (milliseconds < startTime + 7000) {
siteServer.Update(); siteServer.Update(milliseconds);
participant.Update(); participant.Update(milliseconds);
Thread.Sleep(100); Thread.Sleep(100);
milliseconds = (ulong)DateTimeOffset.UtcNow.ToUnixTimeMilliseconds(); milliseconds = (ulong)DateTimeOffset.UtcNow.ToUnixTimeMilliseconds();