Skip to content

Commit

Permalink
CLOiSim-2.7.6
Browse files Browse the repository at this point in the history
[Major Changes]

General: Upgrade Unity editor version -> 2020.3.30f1 (LTS)


[Minor Changes]

General: update package version
  - com.unity.ide.vscode: 1.2.4 -> 1.2.5
UI: add WaitForEndOfFrame() before start importing model from model list
UI: Determine model-deploying-yoffset from bounding box of model when deploy it from AddModel List
SensorDevice: Modify Clock class -> Change sequence of retrieving time for real time and sim time
SDF.Implement: Change default image format for depth camera when implement sensor
Sensor.Device: Modify declaration of variables for Parallel.For code in Lidar sensor
Sensor.Device: Set StopNaN=true for Camera sensor device
SDF.Importer/Parser/Implement: Modify and Update SDF.Parser, SDF.Importer And SDF.Implement
  - SDF.Root class
    - <pose>, <world>, <sensor>, <geometry>, <material>, <collision> and <joint>
  - Possible to parse only for SDF elements
    - <scene>, <state>


[Bug fix]

SensorDevice: modify CommandBuffer for DepthCamera -> prevent potential application freezing
  • Loading branch information
hyunseok-yang authored Mar 2, 2022
1 parent 3c99bba commit 21fdf64
Show file tree
Hide file tree
Showing 32 changed files with 1,012 additions and 276 deletions.
21 changes: 11 additions & 10 deletions Assets/Scripts/Devices/Camera.cs
Original file line number Diff line number Diff line change
Expand Up @@ -104,7 +104,7 @@ protected virtual void SetupTexture()
// Debug.Log("This is not a Depth Camera!");
targetRTname = "CameraColorTexture";

var pixelFormat = CameraData.GetPixelFormat(camParameter.image_format);
var pixelFormat = CameraData.GetPixelFormat(camParameter.image.format);
switch (pixelFormat)
{
case CameraData.PixelFormat.L_INT8:
Expand Down Expand Up @@ -135,17 +135,17 @@ protected override void InitializeMessages()
protected override void SetupMessages()
{
var image = imageStamped.Image;
var pixelFormat = CameraData.GetPixelFormat(camParameter.image_format);
image.Width = (uint)camParameter.image_width;
image.Height = (uint)camParameter.image_height;
var pixelFormat = CameraData.GetPixelFormat(camParameter.image.format);
image.Width = (uint)camParameter.image.width;
image.Height = (uint)camParameter.image.height;
image.PixelFormat = (uint)pixelFormat;
image.Step = image.Width * (uint)CameraData.GetImageDepth(pixelFormat);
image.Data = new byte[image.Height * image.Step];

sensorInfo.HorizontalFov = camParameter.horizontal_fov;
sensorInfo.ImageSize.X = camParameter.image_width;
sensorInfo.ImageSize.Y = camParameter.image_height;
sensorInfo.ImageFormat = camParameter.image_format;
sensorInfo.ImageSize.X = camParameter.image.width;
sensorInfo.ImageSize.Y = camParameter.image.height;
sensorInfo.ImageFormat = camParameter.image.format;
sensorInfo.NearClip = camParameter.clip.near;
sensorInfo.FarClip = camParameter.clip.far;
sensorInfo.SaveEnabled = camParameter.save_enabled;
Expand Down Expand Up @@ -182,8 +182,8 @@ private void SetupCamera()

RTHandles.SetHardwareDynamicResolutionState(true);
_rtHandle = RTHandles.Alloc(
width: camParameter.image_width,
height: camParameter.image_height,
width: camParameter.image.width,
height: camParameter.image.height,
slices: 1,
depthBufferBits: DepthBits.None,
colorFormat: targetColorFormat,
Expand Down Expand Up @@ -214,6 +214,7 @@ private void SetupCamera()
camSensor.projectionMatrix = projMatrix * invertMatrix;

_universalCamData.enabled = false;
_universalCamData.stopNaN = true;
_universalCamData.renderPostProcessing = false;
_universalCamData.allowXRRendering = false;
_universalCamData.volumeLayerMask = LayerMask.GetMask("Nothing");
Expand All @@ -227,7 +228,7 @@ private void SetupCamera()

// camSensor.hideFlags |= HideFlags.NotEditable;

camImageData = new CameraData.ImageData(camParameter.image_width, camParameter.image_height, camParameter.image_format);
camImageData = new CameraData.ImageData(camParameter.image.width, camParameter.image.height, camParameter.image.format);
}

protected new void OnDestroy()
Expand Down
2 changes: 1 addition & 1 deletion Assets/Scripts/Devices/Clock.cs
Original file line number Diff line number Diff line change
Expand Up @@ -88,8 +88,8 @@ protected override void InitializeMessages()

void FixedUpdate()
{
currentSimTime = Time.timeAsDouble - restartedSimTime;
currentRealTime = Time.realtimeSinceStartupAsDouble - restartedRealTime;
currentSimTime = Time.timeAsDouble - restartedSimTime;
}

void LateUpdate()
Expand Down
15 changes: 7 additions & 8 deletions Assets/Scripts/Devices/DepthCamera.cs
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,6 @@ public void FlipXDepthData(in bool flip)
// Debug.Log("OnDestroy(Depth Camera)");
Destroy(computeShader);
computeShader = null;

Resources.UnloadAsset(ComputeShaderDepthBuffer);
Resources.UnloadUnusedAssets();

Expand Down Expand Up @@ -75,7 +74,7 @@ protected override void SetupTexture()
if (camParameter.depth_camera_output.Equals("points"))
{
Debug.Log("Enable Point Cloud data mode - NOT SUPPORT YET!");
camParameter.image_format = "RGB_FLOAT32";
camParameter.image.format = "RGB_FLOAT32";
}

camSensor.backgroundColor = Color.white;
Expand All @@ -91,7 +90,7 @@ protected override void SetupTexture()
targetRTname = "CameraDepthTexture";
targetColorFormat = GraphicsFormat.R8G8B8A8_UNorm;

var pixelFormat = CameraData.GetPixelFormat(camParameter.image_format);
var pixelFormat = CameraData.GetPixelFormat(camParameter.image.format);
switch (pixelFormat)
{
case CameraData.PixelFormat.L_INT16:
Expand All @@ -104,18 +103,18 @@ protected override void SetupTexture()

case CameraData.PixelFormat.R_FLOAT32:
default:
Debug.Log("32bits depth format may cause application freezing.");
readbackDstFormat = TextureFormat.RFloat;
break;
}

var cb = new CommandBuffer();
cb.name = "CommandBufferForDepthShading";
var tempTextureId = Shader.PropertyToID("_RenderImageCameraDepthTexture");
cb.GetTemporaryRT(tempTextureId, -1, -1);
cb.Blit(BuiltinRenderTextureType.CameraTarget, tempTextureId);
cb.Blit(tempTextureId, BuiltinRenderTextureType.CameraTarget, depthMaterial);
camSensor.AddCommandBuffer(CameraEvent.AfterEverything, cb);

cb.ReleaseTemporaryRT(tempTextureId);
camSensor.AddCommandBuffer(CameraEvent.AfterEverything, cb);
cb.Release();
}

Expand All @@ -130,8 +129,8 @@ protected override void PostProcessing(ref byte[] buffer)
computeShader.SetBuffer(kernelIndex, "_Buffer", computeBuffer);
computeBuffer.SetData(buffer);

var threadGroupX = camParameter.image_width / threadGroupsX;
var threadGroupY = camParameter.image_height / threadGroupsY;
var threadGroupX = camParameter.image.width / threadGroupsX;
var threadGroupY = camParameter.image.height / threadGroupsY;
computeShader.Dispatch(kernelIndex, threadGroupX, threadGroupY, 1);
computeBuffer.GetData(buffer);
computeBuffer.Release();
Expand Down
10 changes: 5 additions & 5 deletions Assets/Scripts/Devices/Lidar.cs
Original file line number Diff line number Diff line change
Expand Up @@ -393,11 +393,6 @@ protected override void GenerateMessage()
DeviceHelper.SetVector3d(laserScan.WorldPose.Position, lidarPosition);
DeviceHelper.SetQuaternion(laserScan.WorldPose.Orientation, lidarRotation);

var srcBufferOffset = 0;
var dstBufferOffset = 0;
var copyLength = 0;
var doCopy = true;

const int BufferUnitSize = sizeof(double);
var laserSamplesH = (int)horizontal.samples;
var laserStartAngleH = (float)horizontal.angle.min;
Expand All @@ -419,6 +414,11 @@ protected override void GenerateMessage()
var dataEndAngleH = laserCamData.EndAngleH;
var dividedDataTotalAngleH = 1f / laserCamData.TotalAngleH;

var srcBufferOffset = 0;
var dstBufferOffset = 0;
var copyLength = 0;
var doCopy = true;

if (srcBuffer != null)
{
if (laserStartAngleH < 0 && dataEndAngleH > DEG180)
Expand Down
3 changes: 3 additions & 0 deletions Assets/Scripts/Devices/Modules/Noise.cs
Original file line number Diff line number Diff line change
Expand Up @@ -63,6 +63,9 @@ public void SetNoiseModel(in string sensorType)
{
case "camera":
case "depth":
case "depth_camera":
case "rgbd":
case "rgbd_camera":
case "multicamera":
case "wideanglecamera":
noiseModel = new ImageGaussianNoiseModel(this.parameter);
Expand Down
1 change: 1 addition & 0 deletions Assets/Scripts/Main.cs
Original file line number Diff line number Diff line change
Expand Up @@ -326,6 +326,7 @@ private IEnumerator LoadModel(string modelPath, string modelFileName)
// Debug.Log("Parsed: " + item.Key + ", " + item.Value.Item1 + ", " + item.Value.Item2);
model.Name = GetClonedModelName(model.Name);

yield return new WaitForEndOfFrame();
yield return StartCoroutine(sdfLoader.StartImport(model));

var targetObject = worldRoot.transform.Find(model.Name);
Expand Down
142 changes: 69 additions & 73 deletions Assets/Scripts/Tools/SDF/Implement/Implement.Sensor.cs
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,7 @@ public static Device AddCamera(in SDF.Camera element, in GameObject targetObject

if (element.noise != null)
{
camera.noise = new SensorDevices.Noise(element.noise, "camera");
camera.noise = new SensorDevices.Noise(element.noise, element.type);
}

return camera;
Expand All @@ -105,34 +105,35 @@ public static Device AddDepthCamera(in SDF.Camera element, in GameObject targetO
var depthCamera = newSensorObject.AddComponent<SensorDevices.DepthCamera>();
depthCamera.DeviceName = GetFrameName(newSensorObject);

if (string.IsNullOrEmpty(element.image_format))
switch (element.image.format)
{
element.image_format = "R_FLOAT32";
}
else
{
switch (element.image_format)
{
case "L16":
case "R_FLOAT16":
case "R_FLOAT32":
case "L_INT16":
case "L_UINT16":
// Debug.Log("Supporting data type for Depth camera");
break;

default:
Debug.LogWarningFormat("Not supporting data type({0}) for Depth camera", element.image_format);
element.image_format = "R_FLOAT32";
break;
}
case "L16":
case "R_FLOAT16":
case "R_FLOAT32":
case "L_INT16":
case "L_UINT16":
// Debug.Log("Supporting data type for Depth camera");
break;

default:
if (element.image.format.Equals(string.Empty))
{
Debug.LogWarning(element.name + " 'R_FLOAT16' will be set for Depth camera's image format");
}
else
{
Debug.LogWarningFormat("Not supporting data type({0}) for Depth camera", element.image.format);
}

element.image.format = "R_FLOAT16";
break;
}

depthCamera.SetCamParameter(element);

if (element.noise != null)
{
depthCamera.noise = new SensorDevices.Noise(element.noise, "depthcamera");
depthCamera.noise = new SensorDevices.Noise(element.noise, element.type);
}

return depthCamera;
Expand All @@ -148,22 +149,11 @@ public static Device AddMultiCamera(in SDF.Cameras element, in GameObject target

foreach (var camParam in element.cameras)
{
var newCamObject = new GameObject();
newCamObject.name = camParam.name;

AttachSensor(newCamObject, newSensorObject, camParam.Pose);

var newCam = newCamObject.AddComponent<SensorDevices.Camera>();
var newCam = AddCamera(camParam, newSensorObject);
newCam.Mode = Device.ModeType.NONE;
newCam.DeviceName = "MultiCamera::" + newCamObject.name;
newCam.SetCamParameter(camParam);
newCam.DeviceName = element.name + "::" + newCam.DeviceName;

if (camParam.noise != null)
{
newCam.noise = new SensorDevices.Noise(camParam.noise, "multicamera");
}

multicamera.AddCamera(newCam);
multicamera.AddCamera((SensorDevices.Camera)newCam);
}

return multicamera;
Expand Down Expand Up @@ -192,65 +182,71 @@ public static Device AddImu(in SDF.IMU element, in GameObject targetObject)
var imu = newSensorObject.AddComponent<SensorDevices.IMU>();
imu.DeviceName = GetFrameName(newSensorObject);

if (element.angular_velocity_x_noise != null)
if (element != null)
{
imu.angular_velocity_noises["x"] = new SensorDevices.Noise(element.angular_velocity_x_noise, "imu");
}
if (element.noise_angular_velocity.x != null)
{
imu.angular_velocity_noises["x"] = new SensorDevices.Noise(element.noise_angular_velocity.x, "imu");
}

if (element.angular_velocity_y_noise != null)
{
imu.angular_velocity_noises["y"] = new SensorDevices.Noise(element.angular_velocity_y_noise, "imu");
}
if (element.noise_angular_velocity.y != null)
{
imu.angular_velocity_noises["y"] = new SensorDevices.Noise(element.noise_angular_velocity.y, "imu");
}

if (element.angular_velocity_z_noise != null)
{
imu.angular_velocity_noises["z"] = new SensorDevices.Noise(element.angular_velocity_z_noise, "imu");
}
if (element.noise_angular_velocity.z != null)
{
imu.angular_velocity_noises["z"] = new SensorDevices.Noise(element.noise_angular_velocity.z, "imu");
}

if (element.linear_acceleration_x_noise != null)
{
imu.linear_acceleration_noises["x"] = new SensorDevices.Noise(element.linear_acceleration_x_noise, "imu");
}
if (element.noise_linear_acceleration.x != null)
{
imu.linear_acceleration_noises["x"] = new SensorDevices.Noise(element.noise_linear_acceleration.x, "imu");
}

if (element.linear_acceleration_y_noise != null)
{
imu.linear_acceleration_noises["y"] = new SensorDevices.Noise(element.linear_acceleration_y_noise, "imu");
}
if (element.noise_linear_acceleration.y != null)
{
imu.linear_acceleration_noises["y"] = new SensorDevices.Noise(element.noise_linear_acceleration.y, "imu");
}

if (element.linear_acceleration_z_noise != null)
{
imu.linear_acceleration_noises["z"] = new SensorDevices.Noise(element.linear_acceleration_z_noise, "imu");
if (element.noise_linear_acceleration.z != null)
{
imu.linear_acceleration_noises["z"] = new SensorDevices.Noise(element.noise_linear_acceleration.z, "imu");
}
}

return imu;
}

public static Device AddGps(in SDF.GPS element, in GameObject targetObject)
public static Device AddNavSat(in SDF.NavSat element, in GameObject targetObject)
{
var newSensorObject = new GameObject();
AttachSensor(newSensorObject, targetObject);

var gps = newSensorObject.AddComponent<SensorDevices.GPS>();
gps.DeviceName = GetFrameName(newSensorObject);

if (element.position_sensing.horizontal_noise != null)
if (element != null)
{
gps.position_sensing_noises["horizontal"] = new SensorDevices.Noise(element.position_sensing.horizontal_noise, "gps");
}
if (element.position_sensing.horizontal_noise != null)
{
gps.position_sensing_noises["horizontal"] = new SensorDevices.Noise(element.position_sensing.horizontal_noise, "gps");
}

if (element.position_sensing.vertical_noise != null)
{
gps.position_sensing_noises["vertical"] = new SensorDevices.Noise(element.position_sensing.vertical_noise, "gps");
}
if (element.position_sensing.vertical_noise != null)
{
gps.position_sensing_noises["vertical"] = new SensorDevices.Noise(element.position_sensing.vertical_noise, "gps");
}

if (element.velocity_sensing.horizontal_noise != null)
{
gps.velocity_sensing_noises["horizontal"] = new SensorDevices.Noise(element.velocity_sensing.horizontal_noise, "gps");
}
if (element.velocity_sensing.horizontal_noise != null)
{
gps.velocity_sensing_noises["horizontal"] = new SensorDevices.Noise(element.velocity_sensing.horizontal_noise, "gps");
}

if (element.velocity_sensing.vertical_noise != null)
{
gps.velocity_sensing_noises["vertical"] = new SensorDevices.Noise(element.velocity_sensing.vertical_noise, "gps");
if (element.velocity_sensing.vertical_noise != null)
{
gps.velocity_sensing_noises["vertical"] = new SensorDevices.Noise(element.velocity_sensing.vertical_noise, "gps");
}
}

return gps;
Expand Down
Loading

0 comments on commit 21fdf64

Please sign in to comment.