Skip to content

Commit

Permalink
Merge pull request #52 from lge-ros2/develop
Browse files Browse the repository at this point in the history
Merge 'develop' branch into 'main'
  • Loading branch information
hyunseok-yang authored Jan 23, 2021
2 parents bcb1849 + eec1e4a commit 564b8f9
Show file tree
Hide file tree
Showing 84 changed files with 275 additions and 268 deletions.
8 changes: 0 additions & 8 deletions Assets/Plugins/AssimpNet.4.1.0/build.meta

This file was deleted.

24 changes: 0 additions & 24 deletions Assets/Plugins/AssimpNet.4.1.0/build/AssimpNet.targets

This file was deleted.

7 changes: 0 additions & 7 deletions Assets/Plugins/AssimpNet.4.1.0/build/AssimpNet.targets.meta

This file was deleted.

12 changes: 6 additions & 6 deletions Assets/Scenes/MainScene.unity
Original file line number Diff line number Diff line change
Expand Up @@ -777,10 +777,10 @@ MonoBehaviour:
m_GameObject: {fileID: 249819585}
m_Enabled: 1
m_EditorHideFlags: 0
m_Script: {fileID: 11500000, guid: c6aaa9474a43dce5a9841e90e5846a04, type: 3}
m_Script: {fileID: 11500000, guid: a6319b2d05cfd18189eb02f180656d91, type: 3}
m_Name:
m_EditorClassIdentifier:
defaultPipeAddress: 127.0.0.1
bridgeAddress: 127.0.0.1
--- !u!114 &249819589
MonoBehaviour:
m_ObjectHideFlags: 0
Expand Down Expand Up @@ -811,7 +811,7 @@ MonoBehaviour:
m_Name:
m_EditorClassIdentifier:
defaultWebSocketAddress: 127.0.0.1
defaultWebSocketPort: 8080
defaultWebSocketServicePort: 8080
--- !u!114 &249819592
MonoBehaviour:
m_ObjectHideFlags: 0
Expand Down Expand Up @@ -3085,9 +3085,9 @@ MonoBehaviour:
m_Name:
m_EditorClassIdentifier:
blockControl: 0
mainSpeed: 12
shiftAdd: 10
maxShift: 100
mainSpeed: 3
shiftAdd: 5
maxShift: 50
camSens: 0.25
edgeWidth: 30
edgeSens: 0.05
Expand Down
16 changes: 7 additions & 9 deletions Assets/Scripts/Connection/DeviceTransporter.cs
Original file line number Diff line number Diff line change
Expand Up @@ -12,19 +12,17 @@ public partial class DeviceTransporter : MonoBehaviour
{
public const bool isTCP = true; // Currently, NetMQ does not support UDP protocol
private ushort tagSize = 8;
public string defaultPipeAddress = "127.0.0.1";
public string bridgeAddress = "127.0.0.1";
private int highwatermark = 1000;

protected void InitializeTransporter()
{
var enviromentPipeAddress = Environment.GetEnvironmentVariable("SIM_BRIDGE_IP");
var enviromentBridgeAddress = Environment.GetEnvironmentVariable("CLOISIM_BRIDGE_IP");

if (!string.IsNullOrEmpty(enviromentPipeAddress))
if (!string.IsNullOrEmpty(enviromentBridgeAddress))
{
defaultPipeAddress = enviromentPipeAddress;
SetPipeAddress(enviromentBridgeAddress);
}

SetPipeAddress(defaultPipeAddress);
}

protected void DestroyTransporter()
Expand All @@ -45,14 +43,14 @@ public void SetTagSize(in ushort value)
tagSize = value;
}

public void SetPipeAddress(in string pipeAddress)
public void SetPipeAddress(in string address)
{
defaultPipeAddress = pipeAddress;
bridgeAddress = address;
}

private string GetAddress(in ushort port)
{
return ((isTCP)?"tcp":"udp") + "://" + defaultPipeAddress + ":" + port;
return ((isTCP)?"tcp":"udp") + "://" + bridgeAddress + ":" + port;
}

private bool StoreTag(ref byte[] targetBuffer, in byte[] targetTag)
Expand Down
10 changes: 7 additions & 3 deletions Assets/Scripts/Connection/SimulationService.cs
Original file line number Diff line number Diff line change
Expand Up @@ -16,14 +16,14 @@ public class SimulationService : MonoBehaviour
public const string Delimiter = "!%!";

public string defaultWebSocketAddress = "127.0.0.1";
public int defaultWebSocketPort = 8080;
public int defaultWebSocketServicePort = 8080;

private WebSocketServer wsServer = null;

void Awake()
{
var wsAddress = IPAddress.Parse(defaultWebSocketAddress);
wsServer = new WebSocketServer(wsAddress, defaultWebSocketPort);
wsServer = new WebSocketServer(wsAddress, defaultWebSocketServicePort);
}

// Start is called before the first frame update
Expand Down Expand Up @@ -57,12 +57,16 @@ private void InitializeServices()

wsServer.AddWebSocketService<SimulationControlService>("/control", () => new SimulationControlService()
{
IgnoreExtensions = true,
modelLoader = modelLoaderComponent,
bridgeManager = bridgeManagerComponent
});

var markerVisualizer = gameObject.GetComponent<MarkerVisualizer>();
wsServer.AddWebSocketService<MarkerVisualizerService>("/markers", () => new MarkerVisualizerService(markerVisualizer));
wsServer.AddWebSocketService<MarkerVisualizerService>("/markers", () => new MarkerVisualizerService(markerVisualizer)
{
IgnoreExtensions = true
});
}

void OnDestroy()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@

using UnityEngine;

public class UnityRosWorld : DevicePlugin
public class CLOiSimWorld : DevicePlugin
{
private Clock clock = null;

Expand All @@ -18,7 +18,7 @@ protected override void OnAwake()
clock = gameObject.AddComponent<Clock>();

modelName = "World";
partName = "unity_ros";
partName = "cloisim_ros";
}

protected override void OnStart()
Expand Down

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

4 changes: 2 additions & 2 deletions Assets/Scripts/DevicePlugins/DevicePlugin.InfoService.cs
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,8 @@
using System.IO;
using UnityEngine;
using ProtoBuf;
using messages = gazebo.msgs;
using Any = gazebo.msgs.Any;
using messages = cloisim.msgs;
using Any = cloisim.msgs.Any;

public abstract partial class DevicePlugin : DeviceTransporter, IDevicePlugin
{
Expand Down
4 changes: 2 additions & 2 deletions Assets/Scripts/DevicePlugins/ElevatorSystem.cs
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,8 @@
using System.IO;
using UnityEngine;
using ProtoBuf;
using Param = gazebo.msgs.Param;
using Any = gazebo.msgs.Any;
using Param = cloisim.msgs.Param;
using Any = cloisim.msgs.Any;

public partial class ElevatorSystem : DevicePlugin
{
Expand Down
4 changes: 2 additions & 2 deletions Assets/Scripts/DevicePlugins/MicomPlugin.cs
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,8 @@
using System.IO;
using ProtoBuf;
using Stopwatch = System.Diagnostics.Stopwatch;
using messages = gazebo.msgs;
using Any = gazebo.msgs.Any;
using messages = cloisim.msgs;
using Any = cloisim.msgs.Any;

public class MicomPlugin : DevicePlugin
{
Expand Down
4 changes: 2 additions & 2 deletions Assets/Scripts/DevicePlugins/MultiCameraPlugin.cs
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,8 @@
using System.IO;
using ProtoBuf;
using Stopwatch = System.Diagnostics.Stopwatch;
using messages = gazebo.msgs;
using Any = gazebo.msgs.Any;
using messages = cloisim.msgs;
using Any = cloisim.msgs.Any;

public class MultiCameraPlugin : DevicePlugin
{
Expand Down
4 changes: 2 additions & 2 deletions Assets/Scripts/DevicePlugins/RealSensePlugin.cs
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,8 @@
using System.IO;
using UnityEngine;
using ProtoBuf;
using messages = gazebo.msgs;
using Any = gazebo.msgs.Any;
using messages = cloisim.msgs;
using Any = cloisim.msgs.Any;

public class RealSensePlugin : DevicesPlugin
{
Expand Down
4 changes: 2 additions & 2 deletions Assets/Scripts/Devices/Camera.cs
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
using UnityEngine;
using UnityEngine.Rendering;
using Stopwatch = System.Diagnostics.Stopwatch;
using messages = gazebo.msgs;
using messages = cloisim.msgs;

namespace SensorDevices
{
Expand Down Expand Up @@ -167,7 +167,7 @@ private void SetupCamera()
var camVFov = DeviceHelper.HorizontalToVerticalFOV(camHFov, cam.aspect);
cam.fieldOfView = camVFov;

// Invert projection matrix for gazebo msg
// Invert projection matrix for cloisim msg
var projMatrix = DeviceHelper.MakeCustomProjectionMatrix(camHFov, camVFov, cam.nearClipPlane, cam.farClipPlane);
var invertMatrix = Matrix4x4.Scale(new Vector3(1, -1, 1));
cam.projectionMatrix = projMatrix * invertMatrix;
Expand Down
6 changes: 3 additions & 3 deletions Assets/Scripts/Devices/Clock.cs
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,8 @@

using System.Collections;
using UnityEngine;
using messages = gazebo.msgs;
using Any = gazebo.msgs.Any;
using messages = cloisim.msgs;
using Any = cloisim.msgs.Any;

public class Clock : Device
{
Expand All @@ -22,7 +22,7 @@ public class Clock : Device

protected override void OnAwake()
{
deviceName = "Unity Clock";
deviceName = "World Clock";
}

protected override void OnStart()
Expand Down
2 changes: 1 addition & 1 deletion Assets/Scripts/Devices/Contact.cs
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
using System;
using UnityEngine;
using Stopwatch = System.Diagnostics.Stopwatch;
using messages = gazebo.msgs;
using messages = cloisim.msgs;

namespace SensorDevices
{
Expand Down
2 changes: 1 addition & 1 deletion Assets/Scripts/Devices/DeviceHelper.Camera.cs
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@

using System.Runtime.InteropServices;
using UnityEngine;
using messages = gazebo.msgs;
using messages = cloisim.msgs;

public partial class DeviceHelper
{
Expand Down
12 changes: 6 additions & 6 deletions Assets/Scripts/Devices/DeviceHelper.cs
Original file line number Diff line number Diff line change
Expand Up @@ -6,11 +6,11 @@

using System.Runtime.InteropServices;
using UnityEngine;
using messages = gazebo.msgs;
using messages = cloisim.msgs;

public partial class DeviceHelper
{
static Clock clock = null;
private static Clock clock = null;

public static Clock GetGlobalClock()
{
Expand Down Expand Up @@ -59,11 +59,11 @@ public static string GetPartName(in GameObject targetObject)
[DllImport("StdHash")]
public static extern ulong GetStringHashCode(string value);

public static void SetCurrentTime(in messages.Time gazeboMsgsTime, in bool useRealTime = false)
public static void SetCurrentTime(in messages.Time msgTime, in bool useRealTime = false)
{
try
{
if (gazeboMsgsTime != null)
if (msgTime != null)
{
if (clock == null)
{
Expand All @@ -78,8 +78,8 @@ public static void SetCurrentTime(in messages.Time gazeboMsgsTime, in bool useRe
var realTime = (clock == null) ? Time.realtimeSinceStartup : clock.GetRealTime();

var timeNow = (useRealTime) ? realTime : simTime;
gazeboMsgsTime.Sec = (int)timeNow;
gazeboMsgsTime.Nsec = (int)((timeNow - (float)gazeboMsgsTime.Sec) * (float)1e+9);
msgTime.Sec = (int)timeNow;
msgTime.Nsec = (int)((timeNow - (float)msgTime.Sec) * (float)1e+9);
}
}
catch
Expand Down
4 changes: 2 additions & 2 deletions Assets/Scripts/Devices/GPS.cs
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
using System.Collections;
using UnityEngine;
using Stopwatch = System.Diagnostics.Stopwatch;
using messages = gazebo.msgs;
using messages = cloisim.msgs;

namespace SensorDevices
{
Expand Down Expand Up @@ -85,7 +85,7 @@ protected override void GenerateMessage()
{
DeviceHelper.SetCurrentTime(gps.Time);

// Get postion in Cartesian gazebo frame
// Get postion in Cartesian frame
var worldPosition = gpsLink.position;

// Apply position noise before converting to global frame
Expand Down
2 changes: 1 addition & 1 deletion Assets/Scripts/Devices/IMU.cs
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@

using System.Collections;
using UnityEngine;
using messages = gazebo.msgs;
using messages = cloisim.msgs;

namespace SensorDevices
{
Expand Down
2 changes: 1 addition & 1 deletion Assets/Scripts/Devices/Lidar.cs
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
using UnityEngine;
using UnityEngine.Rendering;
using Stopwatch = System.Diagnostics.Stopwatch;
using messages = gazebo.msgs;
using messages = cloisim.msgs;

namespace SensorDevices
{
Expand Down
2 changes: 1 addition & 1 deletion Assets/Scripts/Devices/MicomInput.cs
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@

using System.Collections;
using UnityEngine;
using messages = gazebo.msgs;
using messages = cloisim.msgs;

public class MicomInput : Device
{
Expand Down
2 changes: 1 addition & 1 deletion Assets/Scripts/Devices/MicomSensor.Odometry.cs
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
using System.Collections.Generic;
using System.Collections;
using UnityEngine;
using messages = gazebo.msgs;
using messages = cloisim.msgs;

public partial class MicomSensor : Device
{
Expand Down
2 changes: 1 addition & 1 deletion Assets/Scripts/Devices/MicomSensor.cs
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
using System.Collections;
using UnityEngine;
using Stopwatch = System.Diagnostics.Stopwatch;
using messages = gazebo.msgs;
using messages = cloisim.msgs;

public partial class MicomSensor : Device
{
Expand Down
Loading

0 comments on commit 564b8f9

Please sign in to comment.