Skip to content

Commit

Permalink
Merge pull request #133 from immersive-command-system/hotfix/mesh-sca…
Browse files Browse the repository at this point in the history
…ling

Flight Tests Success Bug Fix Patch
  • Loading branch information
erwang01 authored Aug 11, 2020
2 parents 370b31c + 3f30991 commit 419edca
Show file tree
Hide file tree
Showing 4 changed files with 103 additions and 38 deletions.
45 changes: 13 additions & 32 deletions Assets/Scenes/Main.unity

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

2 changes: 1 addition & 1 deletion Assets/Scripts/Drone Scripts/DroneProperties.cs
Original file line number Diff line number Diff line change
Expand Up @@ -169,7 +169,7 @@ private bool reachedCurrentDestination()
{
return true;
}
Debug.Log(Vector3.Distance(currentLocation, currentDestination));
// Debug.Log(Vector3.Distance(currentLocation, currentDestination));
return false;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -285,7 +285,7 @@ public void StartMission()
Vector3 unityCoord = waypoint.gameObjectPointer.transform.localPosition;
GPSCoordinate rosCoord = WorldProperties.UnityCoordToGPSCoord(unityCoord);

MissionWaypointMsg new_waypoint = new MissionWaypointMsg(rosCoord.Lat, rosCoord.Lng, (float)rosCoord.Alt, 3.0f, 0, 0, MissionWaypointMsg.TurnMode.CLOCKWISE, 0, 30, new MissionWaypointActionMsg(0, command_list, command_params));
MissionWaypointMsg new_waypoint = new MissionWaypointMsg(rosCoord.Lat, rosCoord.Lng, (float)(rosCoord.Alt - home_position.GetAltitude()), 3.0f, 0, 0, MissionWaypointMsg.TurnMode.CLOCKWISE, 0, 30, new MissionWaypointActionMsg(0, command_list, command_params));
Debug.Log("Adding waypoint at: " + new_waypoint);
missionMsgList.Add(new_waypoint);
}
Expand Down Expand Up @@ -473,7 +473,7 @@ public void UpdateMissionHelper(UpdateMissionAction action)
Vector3 unityCoord = waypoint.gameObjectPointer.transform.localPosition;
GPSCoordinate rosCoord = WorldProperties.UnityCoordToGPSCoord(unityCoord);

MissionWaypointMsg new_waypoint = new MissionWaypointMsg(rosCoord.Lat, rosCoord.Lng, (float)rosCoord.Alt, 3.0f, 0, 0, MissionWaypointMsg.TurnMode.CLOCKWISE, 0, 30, new MissionWaypointActionMsg(0, command_list, command_params));
MissionWaypointMsg new_waypoint = new MissionWaypointMsg(rosCoord.Lat, rosCoord.Lng, (float)(rosCoord.Alt - home_position.GetAltitude()), 3.0f, 0, 0, MissionWaypointMsg.TurnMode.CLOCKWISE, 0, 30, new MissionWaypointActionMsg(0, command_list, command_params));
Debug.Log("Adding waypoint at: " + new_waypoint);
missionMsgList.Add(new_waypoint);
}
Expand Down Expand Up @@ -510,7 +510,7 @@ public void UpdateMissionHelper(UpdateMissionAction action)
Vector3 unityCoord = waypoint.gameObjectPointer.transform.localPosition;
GPSCoordinate rosCoord = WorldProperties.UnityCoordToGPSCoord(unityCoord);

MissionWaypointMsg new_waypoint = new MissionWaypointMsg(rosCoord.Lat, rosCoord.Lng, (float)rosCoord.Alt, 3.0f, 0, 0, MissionWaypointMsg.TurnMode.CLOCKWISE, 0, 30, new MissionWaypointActionMsg(0, command_list, command_params));
MissionWaypointMsg new_waypoint = new MissionWaypointMsg(rosCoord.Lat, rosCoord.Lng, (float)(rosCoord.Alt - home_position.GetAltitude()), 3.0f, 0, 0, MissionWaypointMsg.TurnMode.CLOCKWISE, 0, 30, new MissionWaypointActionMsg(0, command_list, command_params));
Debug.Log("Adding waypoint at: " + new_waypoint);
missionMsgList.Add(new_waypoint);
}
Expand Down
88 changes: 86 additions & 2 deletions Assets/Scripts/WorldProperties.cs
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ public class WorldProperties : MonoBehaviour
[Header("Misc. State variables")]
public static GameObject worldObject;
public static GameObject placementPlane;
public static bool DJI_SIM = true;
public static bool DJI_SIM = false;

public static Vector3 actualScale;
public static Vector3 currentScale;
Expand Down Expand Up @@ -105,8 +105,92 @@ void Start()
MeshEarthPrefab.transform.localPosition = GPSCoordToUnityCoord(new GPSCoordinate(MeshLatitude, MeshLongitude, MeshAltitude));
MeshEarthPrefab.transform.localRotation = Quaternion.Euler(MeshRotation);
MeshEarthPrefab.transform.localScale = MeshScale;

/*
// close wall & road & field intersection.
GameObject meshScale1 = GameObject.CreatePrimitive(PrimitiveType.Sphere);
meshScale1.name = "meshScale2";
meshScale1.transform.parent = this.transform;
meshScale1.transform.localPosition = WorldProperties.GPSCoordToUnityCoord(new GPSCoordinate(37.915317, -122.337779, 5.226));
meshScale1.transform.localScale = Vector3.one * (0.5f);
GameObject aircraft2 = GameObject.CreatePrimitive(PrimitiveType.Sphere);
aircraft2.name = "aircraft 2";
aircraft2.transform.parent = this.transform;
aircraft2.transform.localPosition = WorldProperties.GPSCoordToUnityCoord(new GPSCoordinate(37.915070, -122.337683, 5.488));
aircraft2.transform.localScale = Vector3.one * (0.05f);
// Tree branch parkinglot corner.
GameObject meshScale2 = GameObject.CreatePrimitive(PrimitiveType.Sphere);
meshScale2.name = "meshScale1";
meshScale2.transform.parent = this.transform;
meshScale2.transform.localPosition = WorldProperties.GPSCoordToUnityCoord(new GPSCoordinate(37.915008, -122.337913, 4.338));
meshScale2.transform.localScale = Vector3.one * (0.5f);
GameObject aircraft = GameObject.CreatePrimitive(PrimitiveType.Sphere);
aircraft.name = "aircraft 1";
aircraft.transform.parent = this.transform;
aircraft.transform.localPosition = WorldProperties.GPSCoordToUnityCoord(new GPSCoordinate(37.915028, -122.337692, 4.668));
aircraft.transform.localScale = Vector3.one * (0.05f);
// Far wall & road & field instersection.
GameObject meshScale3 = GameObject.CreatePrimitive(PrimitiveType.Sphere);
meshScale3.name = "meshScale3";
meshScale3.transform.parent = this.transform;
meshScale3.transform.localPosition = WorldProperties.GPSCoordToUnityCoord(new GPSCoordinate(37.915683, -122.337788, 4.022));
meshScale3.transform.localScale = Vector3.one * (0.5f);
GameObject aircraft3 = GameObject.CreatePrimitive(PrimitiveType.Sphere);
aircraft3.name = "aircraft 3";
aircraft3.transform.parent = this.transform;
aircraft3.transform.localPosition = WorldProperties.GPSCoordToUnityCoord(new GPSCoordinate(37.915051, -122.337695, 3.997));
aircraft3.transform.localScale = Vector3.one * (0.05f);
// Far tree
GameObject meshScale4 = GameObject.CreatePrimitive(PrimitiveType.Sphere);
meshScale4.name = "meshScale4";
meshScale4.transform.parent = this.transform;
meshScale4.transform.localPosition = WorldProperties.GPSCoordToUnityCoord(new GPSCoordinate(37.915880, -122.338171, 6.902));
meshScale4.transform.localScale = Vector3.one * (0.5f);
// Stump near the tree closest to the house.
GameObject meshScale5 = GameObject.CreatePrimitive(PrimitiveType.Sphere);
meshScale5.name = "meshScale5";
meshScale5.transform.parent = this.transform;
meshScale5.transform.localPosition = WorldProperties.GPSCoordToUnityCoord(new GPSCoordinate(37.915376, -122.338201, 1.459));
meshScale5.transform.localScale = Vector3.one * (0.5f);
GameObject aircraft5 = GameObject.CreatePrimitive(PrimitiveType.Sphere);
aircraft5.name = "aircraft 5";
aircraft5.transform.parent = this.transform;
aircraft5.transform.localPosition = WorldProperties.GPSCoordToUnityCoord(new GPSCoordinate(37.915028, -122.337711, 1.858));
aircraft5.transform.localScale = Vector3.one * (0.05f);
// Power pole near the fork in the road.
GameObject meshScale7 = GameObject.CreatePrimitive(PrimitiveType.Sphere);
meshScale7.name = "meshScale7";
meshScale7.transform.parent = this.transform;
meshScale7.transform.localPosition = WorldProperties.GPSCoordToUnityCoord(new GPSCoordinate(37.914904, -122.337333, 2.237));
meshScale7.transform.localScale = Vector3.one * (0.5f);
GameObject aircraft7 = GameObject.CreatePrimitive(PrimitiveType.Sphere);
aircraft7.name = "aircraft 7";
aircraft7.transform.parent = this.transform;
aircraft7.transform.localPosition = WorldProperties.GPSCoordToUnityCoord(new GPSCoordinate(37.915058, -122.337716, 2.631));
aircraft7.transform.localScale = Vector3.one * (0.05f);
// Stump at the entrance to the parking lot.
GameObject meshScale6 = GameObject.CreatePrimitive(PrimitiveType.Sphere);
meshScale6.name = "meshScale6";
meshScale6.transform.parent = this.transform;
meshScale6.transform.localPosition = WorldProperties.GPSCoordToUnityCoord(new GPSCoordinate(37.915007, -122.337491, 2.522));
meshScale6.transform.localScale = Vector3.one * (0.5f);
GameObject aircraft6 = GameObject.CreatePrimitive(PrimitiveType.Sphere);
aircraft6.name = "aircraft 6";
aircraft6.transform.parent = this.transform;
aircraft6.transform.localPosition = WorldProperties.GPSCoordToUnityCoord(new GPSCoordinate(37.915048, -122.337703, 2.948));
aircraft6.transform.localScale = Vector3.one * (0.05f);
*/
//AddClipShader(this.transform);

}

/// <summary>
Expand Down

0 comments on commit 419edca

Please sign in to comment.