Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Change LiDAR default return mode to SingleReturnLast #375

Open
wants to merge 3 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -240,7 +240,7 @@ MonoBehaviour:
- topic: lidar/pointcloud_ex
publish: 1
fieldsPreset: 2
fields: 01000000030000000c0000000b0000000a00000009000000080000000e000000
fields: 01000000030000000c0000000b000000090000000a000000080000000e000000
radarScanPublishers: []
--- !u!114 &9115279251508973176
MonoBehaviour:
Expand Down Expand Up @@ -280,7 +280,7 @@ MonoBehaviour:
m_EditorClassIdentifier:
AutomaticCaptureHz: 10
modelPreset: 8
returnMode: 16777220
returnMode: 16777218
applyDistanceGaussianNoise: 1
applyAngularGaussianNoise: 1
applyVelocityDistortion: 0
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -143,7 +143,7 @@ MonoBehaviour:
- topic: lidar/pointcloud_ex
publish: 1
fieldsPreset: 2
fields: 01000000030000000c0000000b0000000a00000009000000080000000e000000
fields: 01000000030000000c0000000b000000090000000a000000080000000e000000
radarScanPublishers: []
--- !u!114 &2398431948632788025
MonoBehaviour:
Expand Down Expand Up @@ -183,7 +183,7 @@ MonoBehaviour:
m_EditorClassIdentifier:
AutomaticCaptureHz: 10
modelPreset: 11
returnMode: 16777220
returnMode: 16777218
applyDistanceGaussianNoise: 1
applyAngularGaussianNoise: 1
applyVelocityDistortion: 0
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -469,7 +469,7 @@ MonoBehaviour:
- topic: lidar/pointcloud_ex
publish: 1
fieldsPreset: 2
fields: 01000000030000000c0000000b0000000a00000009000000080000000e000000
fields: 01000000030000000c0000000b000000090000000a000000080000000e000000
radarScanPublishers: []
--- !u!114 &7675420128049466981
MonoBehaviour:
Expand Down Expand Up @@ -509,7 +509,7 @@ MonoBehaviour:
m_EditorClassIdentifier:
AutomaticCaptureHz: 10
modelPreset: 6
returnMode: 16777220
returnMode: 16777218
applyDistanceGaussianNoise: 1
applyAngularGaussianNoise: 1
applyVelocityDistortion: 0
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -372,7 +372,7 @@ MonoBehaviour:
- topic: lidar/pointcloud_ex
publish: 1
fieldsPreset: 2
fields: 01000000030000000c0000000b0000000a00000009000000080000000e000000
fields: 01000000030000000c0000000b000000090000000a000000080000000e000000
radarScanPublishers: []
--- !u!114 &1430391258634731476
MonoBehaviour:
Expand Down Expand Up @@ -412,7 +412,7 @@ MonoBehaviour:
m_EditorClassIdentifier:
AutomaticCaptureHz: 10
modelPreset: 5
returnMode: 16777220
returnMode: 16777218
applyDistanceGaussianNoise: 1
applyAngularGaussianNoise: 1
applyVelocityDistortion: 0
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -280,7 +280,7 @@ MonoBehaviour:
m_EditorClassIdentifier:
AutomaticCaptureHz: 10
modelPreset: 9
returnMode: 16777220
returnMode: 16777218
applyDistanceGaussianNoise: 1
applyAngularGaussianNoise: 1
applyVelocityDistortion: 0
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ MonoBehaviour:
- topic: lidar/pointcloud_ex
publish: 1
fieldsPreset: 2
fields: 01000000030000000c0000000b0000000a00000009000000080000000e000000
fields: 01000000030000000c0000000b000000090000000a000000080000000e000000
radarScanPublishers: []
--- !u!114 &1429064023790827067
MonoBehaviour:
Expand Down Expand Up @@ -101,7 +101,7 @@ MonoBehaviour:
m_EditorClassIdentifier:
AutomaticCaptureHz: 10
modelPreset: 10
returnMode: 16777220
returnMode: 16777218
applyDistanceGaussianNoise: 1
applyAngularGaussianNoise: 1
applyVelocityDistortion: 0
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,7 @@ MonoBehaviour:
m_EditorClassIdentifier:
AutomaticCaptureHz: 20
modelPreset: 7
returnMode: 16777220
returnMode: 16777218
applyDistanceGaussianNoise: 1
applyAngularGaussianNoise: 1
applyVelocityDistortion: 0
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ MonoBehaviour:
- topic: lidar/pointcloud_ex
publish: 1
fieldsPreset: 2
fields: 01000000030000000c0000000b0000000a00000009000000080000000e000000
fields: 01000000030000000c0000000b000000090000000a000000080000000e000000
radarScanPublishers: []
--- !u!114 &4572956135196922574
MonoBehaviour:
Expand Down Expand Up @@ -101,7 +101,7 @@ MonoBehaviour:
m_EditorClassIdentifier:
AutomaticCaptureHz: 10
modelPreset: 2
returnMode: 16777220
returnMode: 16777218
applyDistanceGaussianNoise: 1
applyAngularGaussianNoise: 1
applyVelocityDistortion: 0
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ MonoBehaviour:
- topic: lidar/pointcloud_ex
publish: 1
fieldsPreset: 2
fields: 01000000030000000c0000000b0000000a00000009000000080000000e000000
fields: 01000000030000000c0000000b000000090000000a000000080000000e000000
radarScanPublishers: []
--- !u!114 &6422033487030486066
MonoBehaviour:
Expand Down Expand Up @@ -101,7 +101,7 @@ MonoBehaviour:
m_EditorClassIdentifier:
AutomaticCaptureHz: 10
modelPreset: 3
returnMode: 16777220
returnMode: 16777218
applyDistanceGaussianNoise: 1
applyAngularGaussianNoise: 1
applyVelocityDistortion: 0
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -509,7 +509,7 @@ MonoBehaviour:
m_EditorClassIdentifier:
AutomaticCaptureHz: 10
modelPreset: 4
returnMode: 16777220
returnMode: 16777218
applyDistanceGaussianNoise: 1
applyAngularGaussianNoise: 1
applyVelocityDistortion: 0
Expand Down
15 changes: 14 additions & 1 deletion Assets/RGLUnityPlugin/Scripts/LidarSensor.cs
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

using System;
using System.Collections.Generic;
using UnityEngine;
using UnityEngine.Serialization;
Expand Down Expand Up @@ -47,7 +48,7 @@ public class LidarSensor : MonoBehaviour
public LidarModel modelPreset = LidarModel.RangeMeter;

[Tooltip("Allows to select between LiDAR return modes")]
public RGLReturnMode returnMode = RGLReturnMode.SingleReturnFirst;
public RGLReturnMode returnMode = RGLReturnMode.SingleReturnLast;

[Tooltip("Allows to quickly enable/disable distance gaussian noise")]
public bool applyDistanceGaussianNoise = true;
Expand Down Expand Up @@ -229,6 +230,13 @@ private void ApplyConfiguration(BaseLidarConfiguration newConfig)
{
rglGraphLidar.ConfigureNodeRaytraceBeamDivergence(lidarRaytraceNodeId, 0.0f, 0.0f);
}

if (!simulateBeamDivergence && IsDualReturnMode(returnMode))
{
Debug.LogWarning(
$"{name}: Dual return mode without {nameof(simulateBeamDivergence)} enabled may not take desired effect." +
"Please refer to documentation if the return mode is desired.");
}

rglGraphLidar.ConfigureNodeRaytraceReturnMode(lidarRaytraceNodeId, returnMode);

Expand Down Expand Up @@ -472,5 +480,10 @@ private void SetVelocityToRaytrace()

rglGraphLidar.ConfigureNodeRaytraceVelocity(lidarRaytraceNodeId, localLinearVelocity, localAngularVelocity);
}

private bool IsDualReturnMode(RGLReturnMode mode)
{
return ((Convert.ToInt32(mode) & (int)RGLReturnCount.DualReturn) == (int)RGLReturnCount.DualReturn);
}
}
}
Loading