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

Remove truck controls, set obj id and class id #70

Merged
merged 4 commits into from
Oct 13, 2021
Merged
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
102 changes: 55 additions & 47 deletions KomatsuSimulator/Assets/Scenes/Scenario2.unity
Original file line number Diff line number Diff line change
Expand Up @@ -1478,108 +1478,116 @@ PrefabInstance:
objectReference: {fileID: 0}
- target: {fileID: 6100550845703879732, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchorMax.y
value: 0
value: 1
objectReference: {fileID: 0}
- target: {fileID: 6100550845703879732, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchorMin.y
value: 0
value: 1
objectReference: {fileID: 0}
- target: {fileID: 6100550845703879732, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_SizeDelta.x
value: 0
value: 160
objectReference: {fileID: 0}
- target: {fileID: 6100550845703879732, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_SizeDelta.y
value: 0
value: 31.504831
objectReference: {fileID: 0}
- target: {fileID: 6100550845703879732, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchoredPosition.x
value: 0
value: 10
objectReference: {fileID: 0}
- target: {fileID: 6100550845703879732, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchoredPosition.y
value: 0
value: -10
objectReference: {fileID: 0}
- target: {fileID: 6100550846288094405, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchorMax.x
value: 0
objectReference: {fileID: 0}
- target: {fileID: 6100550846288094405, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchorMax.y
value: 0
value: 1
objectReference: {fileID: 0}
- target: {fileID: 6100550846288094405, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchorMin.y
value: 0
value: 1
objectReference: {fileID: 0}
- target: {fileID: 6100550846288094405, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_SizeDelta.x
value: 0
value: 140
objectReference: {fileID: 0}
- target: {fileID: 6100550846288094405, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_SizeDelta.y
value: 0
value: 26.50483
objectReference: {fileID: 0}
- target: {fileID: 6100550846288094405, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchoredPosition.x
value: 0
value: 10
objectReference: {fileID: 0}
- target: {fileID: 6100550846288094405, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchoredPosition.y
value: 0
value: -129.5145
objectReference: {fileID: 0}
- target: {fileID: 6100550846340665528, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchorMax.x
value: 0
objectReference: {fileID: 0}
- target: {fileID: 6100550846340665528, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchorMax.y
value: 0
value: 1
objectReference: {fileID: 0}
- target: {fileID: 6100550846340665528, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchorMin.y
value: 0
value: 1
objectReference: {fileID: 0}
- target: {fileID: 6100550846340665528, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_SizeDelta.x
value: 0
value: 160
objectReference: {fileID: 0}
- target: {fileID: 6100550846340665528, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_SizeDelta.y
value: 0
value: 166.01932
objectReference: {fileID: 0}
- target: {fileID: 6100550846340665528, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchoredPosition.x
value: 0
value: 10
objectReference: {fileID: 0}
- target: {fileID: 6100550846340665528, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchoredPosition.y
value: -93.00966
objectReference: {fileID: 0}
- target: {fileID: 6100550846391146277, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_IsActive
value: 0
objectReference: {fileID: 0}
- target: {fileID: 6100550846391146282, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchorMax.y
value: 0
value: 1
objectReference: {fileID: 0}
- target: {fileID: 6100550846391146282, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchorMin.y
value: 0
value: 1
objectReference: {fileID: 0}
- target: {fileID: 6100550846391146282, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_SizeDelta.y
value: 0
value: 269.029
objectReference: {fileID: 0}
- target: {fileID: 6100550846391146282, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchoredPosition.x
value: 0
value: 10
objectReference: {fileID: 0}
- target: {fileID: 6100550846391146282, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchoredPosition.y
value: 0
value: -10
objectReference: {fileID: 0}
- target: {fileID: 6100550846582550105, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_Name
value: UI
objectReference: {fileID: 0}
- target: {fileID: 6100550846582550105, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_IsActive
value: 1
objectReference: {fileID: 0}
- target: {fileID: 6100550846582550109, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_Pivot.x
value: 0
Expand Down Expand Up @@ -1690,111 +1698,111 @@ PrefabInstance:
objectReference: {fileID: 0}
- target: {fileID: 6100550846614828753, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchorMax.y
value: 0
value: 1
objectReference: {fileID: 0}
- target: {fileID: 6100550846614828753, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchorMin.y
value: 0
value: 1
objectReference: {fileID: 0}
- target: {fileID: 6100550846614828753, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_SizeDelta.x
value: 0
value: 140
objectReference: {fileID: 0}
- target: {fileID: 6100550846614828753, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_SizeDelta.y
value: 0
value: 26.50483
objectReference: {fileID: 0}
- target: {fileID: 6100550846614828753, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchoredPosition.x
value: 0
value: 10
objectReference: {fileID: 0}
- target: {fileID: 6100550846614828753, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchoredPosition.y
value: 0
value: -10
objectReference: {fileID: 0}
- target: {fileID: 6100550846872089348, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchorMax.x
value: 0
objectReference: {fileID: 0}
- target: {fileID: 6100550846872089348, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchorMax.y
value: 0
value: 1
objectReference: {fileID: 0}
- target: {fileID: 6100550846872089348, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchorMin.y
value: 0
value: 1
objectReference: {fileID: 0}
- target: {fileID: 6100550846872089348, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_SizeDelta.x
value: 0
value: 160
objectReference: {fileID: 0}
- target: {fileID: 6100550846872089348, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_SizeDelta.y
value: 0
value: 31.504831
objectReference: {fileID: 0}
- target: {fileID: 6100550846872089348, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchoredPosition.x
value: 0
value: 10
objectReference: {fileID: 0}
- target: {fileID: 6100550846872089348, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchoredPosition.y
value: 0
value: -51.50483
objectReference: {fileID: 0}
- target: {fileID: 6100550847257495159, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchorMax.x
value: 0
objectReference: {fileID: 0}
- target: {fileID: 6100550847257495159, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchorMax.y
value: 0
value: 1
objectReference: {fileID: 0}
- target: {fileID: 6100550847257495159, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchorMin.y
value: 0
value: 1
objectReference: {fileID: 0}
- target: {fileID: 6100550847257495159, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_SizeDelta.x
value: 0
value: 140
objectReference: {fileID: 0}
- target: {fileID: 6100550847257495159, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_SizeDelta.y
value: 0
value: 31.50483
objectReference: {fileID: 0}
- target: {fileID: 6100550847257495159, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchoredPosition.x
value: 0
value: 10
objectReference: {fileID: 0}
- target: {fileID: 6100550847257495159, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchoredPosition.y
value: 0
value: -88.00966
objectReference: {fileID: 0}
- target: {fileID: 6100550847513206136, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchorMax.x
value: 0
objectReference: {fileID: 0}
- target: {fileID: 6100550847513206136, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchorMax.y
value: 0
value: 1
objectReference: {fileID: 0}
- target: {fileID: 6100550847513206136, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchorMin.y
value: 0
value: 1
objectReference: {fileID: 0}
- target: {fileID: 6100550847513206136, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_SizeDelta.x
value: 0
value: 140
objectReference: {fileID: 0}
- target: {fileID: 6100550847513206136, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_SizeDelta.y
value: 0
value: 31.50483
objectReference: {fileID: 0}
- target: {fileID: 6100550847513206136, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchoredPosition.x
value: 0
value: 10
objectReference: {fileID: 0}
- target: {fileID: 6100550847513206136, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchoredPosition.y
value: 0
value: -46.50483
objectReference: {fileID: 0}
- target: {fileID: 6543429262768960798, guid: ca81b5e5df6f29051a9653b63cba8147, type: 3}
propertyPath: m_AnchorMax.y
Expand Down Expand Up @@ -3526,7 +3534,7 @@ MonoBehaviour:
ScanAngleStartDegrees: -90
ScanAngleEndDegrees: 90
ScanOffsetAfterPublish: 0
NumMeasurementsPerScan: 180
NumMeasurementsPerScan: 90
TimeBetweenMeasurementsSeconds: 0
markerPrefab: {fileID: 7151730531324999659, guid: 32e2a897b3516fe70a4665a0b7d92eb2, type: 3}
LayerMaskName: Shovel
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,16 @@ private RosMessageTypes.BuiltinInterfaces.TimeMsg GetRosTime()
return new RosMessageTypes.BuiltinInterfaces.TimeMsg((int)span.TotalSeconds, (uint)(span.Ticks * 100));
}

private string RemoveParenNumber(string nameIn)
{
var li = nameIn.LastIndexOf('(');

if(0 > li)
return nameIn;

return nameIn.Substring(0,li).Trim();
}

public RosMessageTypes.Vision.Detection3DArrayMsg FindAllObjects(string tagName)
{
RosMessageTypes.Vision.Detection3DArrayMsg detectedObjectArray =
Expand Down Expand Up @@ -111,11 +121,12 @@ public RosMessageTypes.Vision.Detection3DArrayMsg FindAllObjects(string tagName)
detectedObjectArray.detections[index].header = new RosMessageTypes.Std.HeaderMsg(rosTime, rosFrame);
detectedObjectArray.detections[index].bbox = new RosMessageTypes.Vision.BoundingBox3DMsg(center, size);
detectedObjectArray.detections[index].results = new RosMessageTypes.Vision.ObjectHypothesisWithPoseMsg[1];
detectedObjectArray.detections[index].id = go.name;

//*** TODO : game object name is not correct here. We want an object type, like 'person' or 'truck'. Maybe we
//*** can use a tag for this.

var hyp = new RosMessageTypes.Vision.ObjectHypothesisMsg(go.name, 1.0);
var hyp = new RosMessageTypes.Vision.ObjectHypothesisMsg(RemoveParenNumber(go.name), 1.0);
var pwc = new RosMessageTypes.Geometry.PoseWithCovarianceMsg(center, covariance);

detectedObjectArray.detections[index].results[0] =
Expand Down
21 changes: 8 additions & 13 deletions KomatsuSimulator/Assets/Scripts/Sensors/ImagePublisher.cs
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@ public class ImagePublisher : MonoBehaviour

//private MessageTypes.Sensor.CompressedImage message;
private Texture2D texture2D;
private Texture2D texture2DFlipped;
private Rect rect;
private const int isBigEndian = 1;
private const int step = 3;
Expand All @@ -27,7 +28,7 @@ public class ImagePublisher : MonoBehaviour
/// Arg original: incoming texture
/// Returns: void
//*************************************************************************
public static void FlipTextureVerticallyInplace(Texture2D original)
public void FlipTextureVerticallyInplace(Texture2D original)
{
var originalPixels = original.GetPixels();

Expand All @@ -53,25 +54,18 @@ public static void FlipTextureVerticallyInplace(Texture2D original)
/// Arg original: incoming texture
/// Returns: Flipped texture
//*************************************************************************
public static Texture2D FlipTextureVertically(Texture2D original)
public Texture2D FlipTextureVertically(Texture2D original)
{
Texture2D flipped = new Texture2D(
original.width, original.height, original.format, false);

int xN = original.width;
int yN = original.height;

for (int i = 0; i < xN; i++)
{
for (int j = 0; j < yN; j++)
{
flipped.SetPixel(i, yN - j - 1, original.GetPixel(i, j));
}
}
texture2DFlipped.SetPixel(i, yN - j - 1, original.GetPixel(i, j));

flipped.Apply();
texture2DFlipped.Apply();

return flipped;
return texture2DFlipped;
}

//************************************************************************
Expand Down Expand Up @@ -105,6 +99,7 @@ private void InitializeGameObject()
{
ImageCamera.enabled = true;
texture2D = new Texture2D(resolutionWidth, resolutionHeight, TextureFormat.RGB24, false);
texture2DFlipped = new Texture2D(resolutionWidth, resolutionHeight, TextureFormat.RGB24, false);
rect = new Rect(0, 0, resolutionWidth, resolutionHeight);
ImageCamera.targetTexture = new RenderTexture(resolutionWidth, resolutionHeight, 24);
}
Expand All @@ -121,7 +116,7 @@ private void InitializeMessage()

//************************************************************************
/// Description: Update message, send to ROS
/// Returns: void
/// Returns: void
//*************************************************************************
public IEnumerator UpdateMessage()
{
Expand Down
Loading