Compare commits

...

5 Commits

20 changed files with 973 additions and 64 deletions

View File

@ -106,7 +106,7 @@ namespace LinearAlgebra {
// }
public Vector3 ToVector3() {
float verticalRad = (float)(Math.PI / 2 - this.direction.vertical) * Angle.Deg2Rad;
float verticalRad = (float)(90 - this.direction.vertical) * Angle.Deg2Rad;
float horizontalRad = this.direction.horizontal * Angle.Deg2Rad;
float cosVertical = (float)Math.Cos(verticalRad);
float sinVertical = (float)Math.Sin(verticalRad);

83
Unity/Materials/Black.mat Normal file
View File

@ -0,0 +1,83 @@
%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: []

83
Unity/Materials/Gray.mat Normal file
View File

@ -0,0 +1,83 @@
%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

@ -0,0 +1,83 @@
%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

@ -0,0 +1,546 @@
%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: 2975045340952151157}
- 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 &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:
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

@ -55,7 +55,7 @@ namespace RoboidControl.Unity {
this.transform.SetParent(core.parent.component.transform, false);
this.transform.localPosition = Vector3.zero;
}
else {
else if (core.owner.component != null) {
this.transform.SetParent(core.owner.component.transform, false);
}

View File

@ -37,8 +37,11 @@ namespace RoboidControl.Unity {
// Use resource prefab when available
GameObject gameObj = Instantiate(prefab);
Wheel component = gameObj.GetComponent<Wheel>();
if (component != null)
component.core = new RoboidControl.Thing(RoboidControl.Thing.Type.UncontrolledMotor);
if (component != null) {
component.core = new RoboidControl.Thing {
type = RoboidControl.Thing.Type.UncontrolledMotor
};
}
return component;
}
else {
@ -48,9 +51,14 @@ namespace RoboidControl.Unity {
Wheel component = gameObj.AddComponent<Wheel>();
SiteServer participant = FindAnyObjectByType<SiteServer>();
RoboidControl.Thing core = participant.coreParticipant.Get(thingId);
if (core == null)
if (core == null) {
//core = new(participant.coreParticipant, RoboidControl.Thing.Type.UncontrolledMotor, thingId, false);
core = RoboidControl.Thing.CreateRemote(participant.coreParticipant, RoboidControl.Thing.Type.UncontrolledMotor, thingId);
//core = RoboidControl.Thing.CreateRemote(participant.coreParticipant, thingId);
core = new RoboidControl.Thing(participant.coreParticipant.root) {
id = thingId,
type = RoboidControl.Thing.Type.UncontrolledMotor
};
}
else {
;
}

View File

@ -72,7 +72,7 @@ namespace RoboidControl {
return 0;
#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
byte ix = 0;
buffer[ix++] = BinaryMsg.Id;

View File

@ -145,9 +145,9 @@ namespace RoboidControl {
return true;
IPEndPoint participantEndpoint = new IPEndPoint(IPAddress.Parse(this.ipAddress), this.port);
Console.WriteLine($"msg to remote participant {participantEndpoint.Address.ToString()} {participantEndpoint.Port}");
// Console.WriteLine($"msg to remote participant {participantEndpoint.Address.ToString()} {participantEndpoint.Port}");
if (udpClient != null) {
Console.WriteLine("sending...");
//Console.WriteLine("sending...");
this.udpClient?.Send(this.buffer, bufferSize, participantEndpoint);
}
return true;

View File

@ -115,7 +115,8 @@ namespace RoboidControl {
/// <summary>
/// The interval in milliseconds for publishing (broadcasting) data on the local network
/// </summary>
public ulong publishInterval = 3000; // = 3 seconds
public ulong publishIntervalMS = 3000; // = 3 seconds
public ulong sendUpdateIntervalMS = 100; // for object updates
//public byte[] buffer = new byte[1024];
@ -147,21 +148,22 @@ namespace RoboidControl {
#region Update
protected ulong nextPublishMe = 0;
protected ulong nextSendUpdate = 0;
public override void Update(ulong currentTimeMS = 0) {
if (currentTimeMS == 0)
currentTimeMS = Thing.GetTimeMs();
if (this.isIsolated == false) {
if (this.publishInterval > 0 && currentTimeMS > this.nextPublishMe) {
ParticipantMsg msg = new ParticipantMsg(this.networkId);
if (this.publishIntervalMS > 0 && currentTimeMS > this.nextPublishMe) {
ParticipantMsg msg = new(this.networkId);
if (this.remoteSite == null)
this.Publish(msg);
else
//this.Send(this.remoteSite, msg);
this.remoteSite.Send(msg);
this.nextPublishMe = currentTimeMS + this.publishInterval;
this.nextPublishMe = currentTimeMS + this.publishIntervalMS;
}
}
@ -216,17 +218,20 @@ namespace RoboidControl {
if (this.isIsolated)
continue;
for (int thingIx = 0; thingIx < participant.things.Count; thingIx++) {
Thing thing = participant.things[thingIx];
if (thing == null)
continue;
if (currentTimeMS > this.nextSendUpdate) {
for (int thingIx = 0; thingIx < participant.things.Count; thingIx++) {
Thing thing = participant.things[thingIx];
if (thing == null)
continue;
// PoseMsg poseMsg = new(thing.owner.networkId, thing);
// this.Send(participant, poseMsg);
// BinaryMsg binaryMsg = new(thing.owner.networkId, thing);
// this.Send(participant, binaryMsg);
participant.Send(new PoseMsg(thing.owner.networkId, thing));
participant.Send(new BinaryMsg(thing.owner.networkId, thing));
// PoseMsg poseMsg = new(thing.owner.networkId, thing);
// this.Send(participant, poseMsg);
// BinaryMsg binaryMsg = new(thing.owner.networkId, thing);
// this.Send(participant, binaryMsg);
participant.Send(new PoseMsg(thing.owner.networkId, thing));
participant.Send(new BinaryMsg(thing.owner.networkId, thing));
}
this.nextSendUpdate = currentTimeMS + this.sendUpdateIntervalMS;
}
}
@ -285,26 +290,32 @@ namespace RoboidControl {
#region Receive
protected void ReceiveUDP(IAsyncResult result) {
// UnityEngine.Debug.Log("received");
if (this.udpClient == null) // || this.endPoint == null)
return;
try {
// UnityEngine.Debug.Log("received");
if (this.udpClient == null) // || this.endPoint == null)
return;
byte[] data = this.udpClient.EndReceive(result, ref endPoint);
// This does not yet take multi-packet messages into account!
if (endPoint == null)
return;
byte[] data = this.udpClient.EndReceive(result, ref endPoint);
// This does not yet take multi-packet messages into account!
if (endPoint == null)
return;
// We can receive our own publish (broadcast) packages. How do we recognize them????
// It is hard to determine our source port
string ipAddress = endPoint.Address.ToString();
if (ipAddress != this.ipAddress) {
Participant remoteParticipant = GetParticipant(ipAddress, endPoint.Port);
remoteParticipant ??= AddParticipant(ipAddress, endPoint.Port, this);
// We can receive our own publish (broadcast) packages. How do we recognize them????
// It is hard to determine our source port
string ipAddress = endPoint.Address.ToString();
if (ipAddress != this.ipAddress) {
Participant remoteParticipant = GetParticipant(ipAddress, endPoint.Port);
remoteParticipant ??= AddParticipant(ipAddress, endPoint.Port, this);
ReceiveData(data, remoteParticipant);
ReceiveData(data, remoteParticipant);
}
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) {
@ -426,7 +437,7 @@ namespace RoboidControl {
protected virtual void Process(Participant sender, BinaryMsg msg) {
#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
Thing thing = sender.Get(msg.thingId);
thing?.ProcessBinary(msg.data);

View File

@ -131,12 +131,14 @@ namespace RoboidControl {
}
protected virtual Thing ProcessNewThing(Participant sender, ThingMsg msg) {
return msg.thingType switch {
//Thing.Type.TouchSensor => new TouchSensor(sender, msg.thingId),
//Thing.Type.DifferentialDrive => new DifferentialDrive(sender, msg.thingId),
_ => Thing.CreateRemote(sender, msg.thingType, msg.thingId)
Thing newThing = msg.thingType switch {
Thing.Type.TouchSensor => new TouchSensor(sender.root),
Thing.Type.DifferentialDrive => new DifferentialDrive(sender.root),
_ => new Thing(sender.root)
};
newThing.id = msg.thingId;
newThing.type = msg.thingType;
return newThing;
}
#endregion Receive

View File

@ -105,8 +105,8 @@ namespace RoboidControl {
this.parent = parent;
}
*/
public Thing(byte thingType = Type.Undetermined, Thing parent = default) {
this.type = thingType;
public Thing(Thing parent = default) {
this.type = Type.Undetermined;
this.positionUpdated = true;
this.orientationUpdated = true;
@ -127,12 +127,12 @@ namespace RoboidControl {
this.owner.updateQueue.Enqueue(e);
}
public static Thing CreateRemote(Participant owner, byte thingType, byte thingId) {
Thing remoteThing = new(thingType, owner.root) {
id = thingId
};
return remoteThing;
}
// public static Thing CreateRemote(Participant owner, byte thingId) {
// Thing remoteThing = new(owner.root) {
// id = thingId
// };
// return remoteThing;
// }
/// <summary>
/// Function which can be used to create components in external engines.

View File

@ -40,7 +40,9 @@ namespace RoboidControl {
/// <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="invokeEvent">Invoke a OnNewThing event when the thing has been created</param>
public DifferentialDrive(Thing parent) : base(Type.DifferentialDrive, parent) { }
public DifferentialDrive(Thing parent) : base(parent) {
this.type = Type.DifferentialDrive;
}
/// @brief Configures the dimensions of the drive
/// @param wheelDiameter The diameter of the wheels in meters

View File

@ -26,7 +26,9 @@ namespace RoboidControl {
/// <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="invokeEvent">Invoke a OnNewThing event when the thing has been created</param>
public DigitalSensor(Thing parent) : base(Type.Switch, parent) { }
public DigitalSensor(Thing parent) : base(parent) {
this.type = Type.Switch;
}
/// <summary>
/// Value which is true when the sensor is touching something, false otherwise

View File

@ -24,7 +24,9 @@ namespace RoboidControl {
/// <param name="thingId">The ID of the thing</param>
public DistanceSensor(Participant owner, byte thingId) : base(owner, Type.TemperatureSensor, thingId) {}
*/
public DistanceSensor(Thing parent): base(Type.DistanceSensor, parent) {}
public DistanceSensor(Thing parent) : base(parent) {
this.type = Type.DistanceSensor;
}
#if UNITY_5_3_OR_NEWER

View File

@ -0,0 +1,84 @@
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(ulong currentTimeMs, 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;
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

@ -4,7 +4,9 @@ namespace RoboidControl {
public class Motor : Thing {
//public Motor(bool invokeEvent = true) : base(Type.UncontrolledMotor, invokeEvent) { }
public Motor(Thing parent) : base(Type.UncontrolledMotor, parent) { }
public Motor(Thing parent) : base(parent) {
this.type = Type.UncontrolledMotor;
}
/// @brief Motor turning direction
public enum Direction {

View File

@ -12,8 +12,8 @@ namespace RoboidControl {
/*
public RelativeEncoder(bool invokeEvent = true) : base(Type.IncrementalEncoder, invokeEvent) { }
*/
public RelativeEncoder(Thing parent = default) : base(Type.RelativeEncoder, parent) {
public RelativeEncoder(Thing parent = default) : base(parent) {
this.type = Type.RelativeEncoder;
}
protected float _rotationSpeed = 0;

View File

@ -26,7 +26,9 @@ namespace RoboidControl {
/// <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="invokeEvent">Invoke a OnNewThing event when the thing has been created</param>
public TemperatureSensor(Thing parent) : base(Type.TemperatureSensor, parent) { }
public TemperatureSensor(Thing parent) : base(parent) {
this.type = Type.TemperatureSensor;
}
/// <summary>
/// The measured temperature

View File

@ -24,11 +24,10 @@ namespace RoboidControl {
/// Create a new child touch sensor
/// </summary>
/// <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="invokeEvent">Invoke a OnNewThing event when the thing has been created</param>
public TouchSensor(Thing parent) : base(Type.TouchSensor, parent) {
public TouchSensor(Thing parent) : base(parent) {
this.type = Type.TouchSensor;
this.name = "TouchSensor";
}
}
/// <summary>
/// Value which is true when the sensor is touching something, false otherwise