ZEDSupportFunctions.cs 29 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627
  1. using UnityEngine;
  2. using System.Text;
  3. using System.IO;
  4. /// <summary>
  5. /// Holds numerous static functions for getting info about the real world in
  6. /// specific places, to compare to the virtual world in the same place.
  7. /// <para>Examples include knowing where a real-world point you click on is in Unity world space,
  8. /// knowing what direction a real-world surface is facing, checking for collisions with the real world.</para>
  9. /// </summary><remarks>
  10. /// Functions that take a Vector2 for screen space (usually named "pixel" or something similar) are great for
  11. /// when you want to click on the screen to test the real-world 'thing' you click on. To do this, use Input.mousePosition
  12. /// and make a Vector2 out of the X and Y of the Vector3 it returns.
  13. /// Most functions take a Camera as a parameter. Use the one providing the image on the screen -
  14. /// usually the left camera in the ZED rig, which can be easily retrieved using ZEDManager.GetLeftCameraTransform().
  15. /// </remarks>
  16. public class ZEDSupportFunctions
  17. {
  18. /***********************************************************************************************
  19. ******************** BASIC "GET" FUNCTIONS ****************************
  20. ***********************************************************************************************/
  21. public static bool IsVector3NaN(Vector3 input)
  22. {
  23. if (float.IsNaN (input.x) || float.IsNaN (input.y) || float.IsNaN (input.z))
  24. return true;
  25. else
  26. return false;
  27. }
  28. /// <summary>
  29. /// Gets the normal vector (the direction a surface is pointing) at a given screen-space pixel (i,j,0).
  30. /// The normal can be given relative to the camera or the world. Returns false if outside camera's view frustum.
  31. /// </summary>
  32. /// <param name="pixel">Pixel coordinates.</param>
  33. /// <param name="reference_frame">Reference frame given by the enum sl.REFERENCE_FRAME.</param>
  34. /// <param name="cam">Unity Camera used for world-camera space conversion.</param>
  35. /// <out>Normal to be filled.</out>
  36. /// <returns>True if successful, false otherwise.</returns>
  37. public static bool GetNormalAtPixel(sl.ZEDCamera zedCam,Vector3 pixel, sl.REFERENCE_FRAME reference_frame, Camera cam, out Vector3 normal)
  38. {
  39. normal = Vector3.zero;
  40. if (zedCam == null)
  41. return false;
  42. Vector4 n;
  43. bool r = zedCam.GetNormalValue(pixel, out n);
  44. switch (reference_frame) {
  45. case sl.REFERENCE_FRAME.CAMERA: //Relative to the provided camera.
  46. normal = n;
  47. break;
  48. case sl.REFERENCE_FRAME.WORLD: //Relative to the world.
  49. normal = cam.transform.TransformDirection(n);
  50. break;
  51. default :
  52. normal = Vector3.zero;
  53. break;
  54. }
  55. return r;
  56. }
  57. /// <summary>
  58. /// Gets the normal vector (the direction a surface is pointing) at a world position (x,y,z).
  59. /// The normal can be given relative to the camera or the world.
  60. /// </summary>
  61. /// <param name="position">World position.</param>
  62. /// <param name="reference_frame"> Reference frame given by the enum sl.REFERENCE_FRAME.</param>
  63. /// <param name="cam">Unity Camera used for world-camera space conversion (usually left camera)</param>
  64. /// <out>Normal vector to be filled.</out>
  65. /// <returns>True if successful, false otherwise.</returns>
  66. public static bool GetNormalAtWorldLocation(sl.ZEDCamera zedCam,Vector3 position, sl.REFERENCE_FRAME reference_frame,Camera cam, out Vector3 normal)
  67. {
  68. normal = Vector3.zero;
  69. if (zedCam == null)
  70. return false;
  71. Vector4 n;
  72. bool r = zedCam.GetNormalValue(cam.WorldToScreenPoint(position), out n);
  73. switch (reference_frame) {
  74. case sl.REFERENCE_FRAME.CAMERA:
  75. normal = n;
  76. break;
  77. case sl.REFERENCE_FRAME.WORLD :
  78. normal = cam.transform.TransformDirection(n);
  79. break;
  80. default :
  81. normal = Vector3.zero;
  82. break;
  83. }
  84. return r;
  85. }
  86. /// <summary>
  87. /// Gets forward distance (i.e. depth) value at a given image pixel.
  88. /// </summary><remarks>
  89. /// Forward distance/depth is distinct from Euclidean distance in that it only measures
  90. /// distance on the Z axis; the pixel's left/right or up/down position relative to the camera
  91. /// makes no difference to the depth value.
  92. /// </remarks>
  93. /// <param name="pixel">Pixel coordinates in screen space.</param>
  94. /// <param name="depth">Forward distance/depth to given pixel.</param>
  95. /// <returns></returns>
  96. public static bool GetForwardDistanceAtPixel(sl.ZEDCamera zedCam,Vector3 pixel, out float depth)
  97. {
  98. depth = 0.0f;
  99. if (zedCam == null)
  100. return false;
  101. float d = zedCam.GetDepthValue(pixel);
  102. depth = d;
  103. if (d == -1) return false;
  104. return true;
  105. }
  106. /// <summary>
  107. /// Gets forward distance (i.e. depth) at a given world position (x,y,z).
  108. /// </summary><remarks>
  109. /// Forward distance/depth is distinct from Euclidean distance in that it only measures
  110. /// distance on the Z axis; the pixel's left/right or up/down position relative to the camera
  111. /// makes no difference to the depth value.
  112. /// </remarks>
  113. /// <param name="position">World position to measure.</param>
  114. /// <param name="cam">Unity Camera used for world-camera space conversion (usually left camera)</param>
  115. /// <param name="depth">Forward distance/depth to given position.</out>
  116. /// <returns></returns>
  117. public static bool GetForwardDistanceAtWorldLocation(sl.ZEDCamera zedCam,Vector3 position, Camera cam, out float depth)
  118. {
  119. depth = 0.0f;
  120. if (zedCam == null)
  121. return false;
  122. Vector3 pixelPosition = cam.WorldToScreenPoint(position);
  123. depth = zedCam.GetDepthValue(pixelPosition);
  124. if (depth == -1) return false;
  125. return true;
  126. }
  127. /// <summary>
  128. /// Gets the Euclidean distance from the world position of a given image pixel.
  129. /// </summary><remarks>
  130. /// Euclidean distance is distinct from forward distance/depth in that it takes into account the point's X and Y position
  131. /// relative to the camera. It's the actual distance between the camera and the point in world space.
  132. /// </remarks>
  133. /// <param name="pixel">Pixel coordinates in screen space. Only x,y used</param>
  134. /// <param name="distance">Euclidean distance to given pixel.</param>
  135. /// <returns></returns>
  136. public static bool GetEuclideanDistanceAtPixel(sl.ZEDCamera zedCam,Vector3 pixel, out float distance)
  137. {
  138. distance = 0.0f;
  139. if (zedCam == null)
  140. return false;
  141. distance = zedCam.GetDistanceValue(pixel);
  142. if (distance == -1) return false;
  143. return true;
  144. }
  145. /// <summary>
  146. /// Gets the Euclidean distance from the given caera to a point in the world (x,y,z).
  147. /// </summary><remarks>
  148. /// Euclidean distance is distinct from forward distance/depth in that it takes into account the point's X and Y position
  149. /// relative to the camera. It's the actual distance between the camera and the point in world space.
  150. /// </remarks>
  151. /// <param name="position">World position to measure.</param>
  152. /// <param name="cam">Unity Camera used for world-camera space conversion (usually left camera)</param>
  153. /// <param name="distance">Euclidean distance to given position.</out>
  154. /// <returns></returns>
  155. public static bool GetEuclideanDistanceAtWorldLocation(sl.ZEDCamera zedCam,Vector3 position, Camera cam, out float distance)
  156. {
  157. distance = 0.0f;
  158. if (zedCam == null)
  159. return false;
  160. Vector3 pixelPosition = cam.WorldToScreenPoint (position);
  161. distance = zedCam.GetDistanceValue(new Vector3(pixelPosition.x, pixelPosition.y, 0));
  162. if (distance == -1) return false;
  163. return true;
  164. }
  165. /// <summary>
  166. /// Gets the world position of the given image pixel.
  167. /// </summary>
  168. /// <param name="pixel">Pixel coordinates in screen space.</param>
  169. /// <param name="cam">Unity Camera used for world-camera space conversion (usually left camera)</param>
  170. /// <param name="worldPos">Filled with the world position of the specified pixel.</param>
  171. /// <returns>True if it found a value, false otherwise (such as if it's outside the camera's view frustum)</returns>
  172. public static bool GetWorldPositionAtPixel(sl.ZEDCamera zedCam,Vector3 pixel, Camera cam, out Vector3 worldPos)
  173. {
  174. worldPos = Vector3.zero;
  175. if (zedCam == null)
  176. return false;
  177. float d;
  178. worldPos = Vector3.zero;
  179. if (!GetForwardDistanceAtPixel(zedCam,pixel, out d)) return false;
  180. //Extract world position using screen-to-world transform.
  181. worldPos = cam.ScreenToWorldPoint(new Vector3(pixel.x, pixel.y,d));
  182. return true;
  183. }
  184. /// <summary>
  185. /// Checks if a real-world location is visible from the camera (true) or masked by a virtual object (with a collider).
  186. /// </summary>
  187. /// <warning>The virtual object must have a collider for this to work as it uses a collision test.</warning>
  188. /// <param name="position">Position to check in world space. Must be in camera's view to check against the real world.</param>
  189. /// <param name="cam">Unity Camera used for world-camera space conversion (usually left camera)</param>
  190. /// <returns>True if visible, false if obscurred.</returns>
  191. public static bool IsLocationVisible(sl.ZEDCamera zedCam,Vector3 position, Camera cam)
  192. {
  193. if (zedCam == null)
  194. return false;
  195. RaycastHit hit;
  196. float d;
  197. GetForwardDistanceAtWorldLocation(zedCam,position, cam,out d);
  198. if (Physics.Raycast(cam.transform.position, position - cam.transform.position, out hit))
  199. {
  200. if (hit.distance < d) return false;
  201. }
  202. return true;
  203. }
  204. /// <summary>
  205. /// Checks if the real world at an image pixel is visible from the camera (true) or masked by a virtual object (with a collider).
  206. /// </summary>
  207. /// <warning>The virtual object must have a collider for this to work as it uses a collision test.</warning>
  208. /// <param name="pixel">Screen space coordinates of the real-world pixel.</param>
  209. /// <param name="cam">Unity Camera used for world-camera space conversion (usually left camera)</param>
  210. /// <returns>True if visible, false if obscurred.</returns>
  211. public static bool IsPixelVisible(sl.ZEDCamera zedCam, Vector3 pixel, Camera cam)
  212. {
  213. if (zedCam == null)
  214. return false;
  215. RaycastHit hit;
  216. float d;
  217. GetForwardDistanceAtPixel(zedCam, pixel,out d);
  218. Vector3 position = cam.ScreenToWorldPoint(new Vector3(pixel.x, pixel.y, d));
  219. if (Physics.Raycast(cam.transform.position, position - cam.transform.position, out hit))
  220. {
  221. if (hit.distance < d) return false;
  222. }
  223. return true;
  224. }
  225. /***********************************************************************************************
  226. ******************** HIT TEST FUNCTIONS ******************************
  227. ***********************************************************************************************/
  228. /// <summary>
  229. /// Static functions for checking collisions or 'hits' with the real world. This does not require
  230. /// scanning/spatial mapping or plane detection as it used the live depth map.
  231. /// Each is based on the premise that if a point is behind the real world, it has intersected with it (except when
  232. /// using realworldthickness). This is especially when checked each frame on a moving object, like a projectile.
  233. /// In each function, "countinvalidascollision" specifies if off-screen pixels or missing depth values should count as collisions.
  234. /// "realworldthickness" specifies how far back a point needs to be behind the real world before it's not considered a collision.
  235. /// </summary>
  236. /// <summary>
  237. /// Checks an individual point in world space to see if it's occluded by the real world.
  238. /// </summary>
  239. /// <param name="camera">Unity Camera used for world-camera space conversion (usually left camera).</param>
  240. /// <param name="point">3D point in the world that belongs to a virtual object.</param>
  241. /// <param name="countinvalidascollision">Whether a collision that can't be tested (such as when it's off-screen)
  242. /// is counted as hitting something.</param>
  243. /// <param name="realworldthickness">Sets the assumed thickness of the real world. Points further away than the world by
  244. /// more than this amount won't return true, considered "behind" the real world instead of inside it.</param>
  245. /// <returns>True if the test represents a valid hit test.</returns>
  246. public static bool HitTestAtPoint(sl.ZEDCamera zedCam, Camera camera, Vector3 point, bool countinvalidascollision = false, float realworldthickness = Mathf.Infinity)
  247. {
  248. if (zedCam == null)
  249. return false;
  250. //Transform the point into screen space.
  251. Vector3 screenpoint = camera.WorldToScreenPoint(point);
  252. //Make sure it's within our view frustrum (excluding clipping planes).
  253. if (!CheckScreenView (point, camera)) {
  254. return countinvalidascollision;
  255. }
  256. //Compare distance in virtual camera to corresponding point in distance map.
  257. float realdistance;
  258. GetEuclideanDistanceAtPixel(zedCam, screenpoint , out realdistance);
  259. //If we pass bad parameters, or we don't have an accurate reading on the depth, we can't test.
  260. if(realdistance <= 0f)
  261. {
  262. return countinvalidascollision; //We can't read the depth from that pixel.
  263. }
  264. if (realdistance <= Vector3.Distance(point, camera.transform.position) && Vector3.Distance(point, camera.transform.position) - realdistance <= realworldthickness)
  265. {
  266. return true; //The real pixel is closer or at the same depth as the virtual point. That's a collision (unless closer by more than realworldthickness).
  267. }
  268. else return false; //The real pixel is behind the virtual point.
  269. }
  270. /// <summary>
  271. /// Performs a "raycast" by checking for collisions/hit in a series of points on a ray.
  272. /// Calls HitTestAtPoint at each point on the ray, spaced apart by distbetweendots.
  273. /// </summary>
  274. /// <param name="camera">Unity Camera used for world-camera space conversion (usually left camera)</param>
  275. /// <param name="startpos">Starting position of the ray</param>
  276. /// <param name="rot">Direction of the ray.</param>
  277. /// <param name="maxdistance">Maximum distance of the ray</param>
  278. /// <param name="distbetweendots">Distance between sample dots. 1cm (0.01f) is recommended for most casses, but
  279. /// increase to improve performance at the cost of accuracy.</param>
  280. /// <param name="collisionpoint">Fills the point where the collision occurred, if any.</param>
  281. /// <param name="countinvalidascollision">Whether a collision that can't be tested (such as when it's off-screen)
  282. /// is counted as hitting something.</param>
  283. /// <param name="realworldthickness">Sets the assumed thickness of the real world. Points further away than the world by
  284. /// more than this amount won't return true, considered "behind" the real world instead of inside it.</param>
  285. /// <returns></returns>
  286. public static bool HitTestOnRay(sl.ZEDCamera zedCam, Camera camera, Vector3 startpos, Quaternion rot, float maxdistance, float distbetweendots, out Vector3 collisionpoint,
  287. bool countinvalidascollision = false, float realworldthickness = Mathf.Infinity)
  288. {
  289. collisionpoint = Vector3.zero;
  290. if (zedCam == null)
  291. return false;
  292. //Check for occlusion in a series of dots, spaced apart evenly.
  293. Vector3 lastvalidpoint = startpos;
  294. for (float i = 0; i < maxdistance; i += distbetweendots)
  295. {
  296. Vector3 pointtocheck = rot * new Vector3(0f, 0f, i);
  297. pointtocheck += startpos;
  298. bool hit = HitTestAtPoint(zedCam, camera, pointtocheck,countinvalidascollision, realworldthickness);
  299. if (hit)
  300. {
  301. //Return the last valid place before the collision.
  302. collisionpoint = lastvalidpoint;
  303. return true;
  304. }
  305. else
  306. {
  307. lastvalidpoint = pointtocheck;
  308. }
  309. }
  310. //There was no collision at any of the points checked.
  311. collisionpoint = lastvalidpoint;
  312. return false;
  313. }
  314. /// <summary>
  315. /// Checks if a spherical area is blocked above a given percentage. Useful for checking if a drone spawn point is valid.
  316. /// Works by checking random points around the sphere for occlusion, Monte Carlo-style, so more samples means greater accuracy.
  317. /// </summary><remarks>
  318. /// Unlike HitTestOnRay, you can allow some individual points to collide without calling the whole thing a collision. This is useful
  319. /// to account for noise, or to allow objects to "graze" the real world. Adjust this with blockedpercentagethreshold.
  320. /// See the Drone or DroneSpawner class for examples.</remarks>
  321. /// <param name="camera">Unity Camera used for world-camera space conversion (usually left camera)</param>
  322. /// <param name="centerpoint">Center point of the sphere.</param>
  323. /// <param name="radius">Radius of the sphere</param>
  324. /// <param name="numberofsamples">Number of dots in the sphere. Increase to improve accuracy at the cost of performance.</param>
  325. /// <param name="blockedpercentagethreshold">Percentage (0 - 1) that the number of hits must exceed for a collision.</param>
  326. /// <param name="countinvalidascollision">Whether a collision that can't be tested (such as when it's off-screen)
  327. /// is counted as hitting something.</param>
  328. /// <param name="realworldthickness">Sets the assumed thickness of the real world. Points further away than the world by
  329. /// more than this amount won't return true, considered "behind" the real world instead of inside it.</param>
  330. /// <returns>Whether the sphere is colliding with the real world.</returns>
  331. public static bool HitTestOnSphere(sl.ZEDCamera zedCam, Camera camera, Vector3 centerpoint, float radius, int numberofsamples, float blockedpercentagethreshold = 0.2f,
  332. bool countinvalidascollision = true, float realworldthickness = Mathf.Infinity)
  333. {
  334. int occludedpoints = 0;
  335. for (int i = 0; i < numberofsamples; i++)
  336. {
  337. //Find a random point along the bounds of a sphere and check if it's occluded.
  338. Vector3 randompoint = Random.onUnitSphere * radius + centerpoint;
  339. if(HitTestAtPoint(zedCam, camera, randompoint, countinvalidascollision, realworldthickness))
  340. {
  341. occludedpoints++;
  342. }
  343. }
  344. //See if the percentage of occluded pixels exceeds the threshold.
  345. float occludedpercent = occludedpoints / (float)numberofsamples;
  346. if (occludedpercent > blockedpercentagethreshold)
  347. {
  348. return true; //Occluded.
  349. }
  350. else return false;
  351. }
  352. /// <summary>
  353. /// Checks for collisions at each vertex of a given mesh with a given transform.
  354. /// Expensive on large meshes, and quality depends on density and distribution of the mesh's vertices.
  355. /// </summary><remarks>
  356. /// As a mesh's vertices are not typically designed to be tested in this way, it is almost always better
  357. /// to use a sphere or a raycast; areas inside large faces of the mesh won't register as colliding, and
  358. /// dense parts of the mesh will do more checks than is necessary. To make proper use of this feature, make a
  359. /// custom mesh with vertices spaced evenly, and use that in place of the mesh being used for rendering.
  360. /// </remarks>
  361. /// <param name="camera">Unity Camera used for world-camera space conversion (usually left camera)</param>
  362. /// <param name="mesh">Mesh to supply the vertices.</param>
  363. /// <param name="worldtransform">World position, rotation and scale of the mesh.</param>
  364. /// <param name="blockedpercentagethreshold">Percentage (0 - 1) that the number of hits must exceed for a collision.</param>
  365. /// <param name="meshsamplepercent">Percentage of the mesh's vertices to check for hits. Lower to improve performance
  366. /// at the cost of accuracy.</param>
  367. /// <param name="countinvalidascollision">Whether a collision that can't be tested (such as when it's off-screen)
  368. /// is counted as hitting something.</param>
  369. /// <param name="realworldthickness">Sets the assumed thickness of the real world. Points further away than the world by
  370. /// more than this amount won't return true, considered "behind" the real world instead of inside it.</param>
  371. /// <returns>True if the mesh collided with the real world.</returns>
  372. public static bool HitTestOnMesh(sl.ZEDCamera zedCam, Camera camera, Mesh mesh, Transform worldtransform, float blockedpercentagethreshold, float meshsamplepercent = 1,
  373. bool countinvalidascollision = false, float realworldthickness = Mathf.Infinity)
  374. {
  375. //Find how often we check samples, represented as an integer denominator.
  376. //For example, if meshamplepercent is 0.2, then we'll check every five vertices.
  377. int checkfrequency = Mathf.RoundToInt(1f / Mathf.Clamp01(meshsamplepercent));
  378. int totalchecks = Mathf.FloorToInt(mesh.vertices.Length / (float)checkfrequency);
  379. //Check the vertices in the mesh for a collision, skipping vertices to match the specified sample percentage.
  380. int intersections = 0;
  381. for(int i = 0; i < mesh.vertices.Length; i += checkfrequency)
  382. {
  383. if (HitTestAtPoint(zedCam, camera, worldtransform.TransformPoint(mesh.vertices[i]),countinvalidascollision, realworldthickness))
  384. {
  385. intersections++;
  386. }
  387. }
  388. //See if our total collisions exceeds the threshold to call it a collision.
  389. float blockedpercentage = (float)intersections / totalchecks;
  390. if(blockedpercentage > blockedpercentagethreshold)
  391. {
  392. return true;
  393. }
  394. return false;
  395. }
  396. /// <summary>
  397. /// Checks for collisions at each vertex of a given mesh with a given transform.
  398. /// Expensive on large meshes, and quality depends on density and distribution of the mesh's vertices.
  399. /// </summary><remarks>
  400. /// As a mesh's vertices are not typically designed to be tested in this way, it is almost always better
  401. /// to use a sphere or a raycast; areas inside large faces of the mesh won't register as colliding, and
  402. /// dense parts of the mesh will do more checks than is necessary. To make proper use of this feature, make a
  403. /// custom mesh with vertices spaced evenly, and use that in place of the mesh being used for rendering.
  404. /// </remarks>
  405. /// <param name="camera">Unity Camera used for world-camera space conversion (usually left camera)</param>
  406. /// <param name="meshfilter">MeshFilter whose mesh value will supply the vertices.</param>
  407. /// <param name="worldtransform">World position, rotation and scale of the mesh.</param>
  408. /// <param name="blockedpercentagethreshold">Percentage (0 - 1) that the number of hits must exceed for a collision.</param>
  409. /// <param name="meshsamplepercent">Percentage of the mesh's vertices to check for hits. Lower to improve performance
  410. /// at the cost of accuracy.</param>
  411. /// <param name="countinvalidascollision">Whether a collision that can't be tested (such as when it's off-screen)
  412. /// is counted as hitting something.</param>
  413. /// <param name="realworldthickness">Sets the assumed thickness of the real world. Points further away than the world by
  414. /// more than this amount won't return true, considered "behind" the real world instead of inside it.</param>
  415. /// <returns>True if the mesh collided with the real world.</returns>
  416. public static bool HitTestOnMesh(sl.ZEDCamera zedCam, Camera camera, MeshFilter meshfilter, float blockedpercentagethreshold, float meshsamplepercent = 1,
  417. bool countinvalidascollision = false, float realworldthickness = Mathf.Infinity)
  418. {
  419. return HitTestOnMesh(zedCam, camera, meshfilter.mesh, meshfilter.transform, blockedpercentagethreshold, meshsamplepercent, countinvalidascollision, realworldthickness);
  420. }
  421. /// <summary>
  422. /// Checks if a world space point is within our view frustum.
  423. /// Excludes near/far planes but returns false if the point is behind the camera.
  424. /// </summary>
  425. /// <param name="point">World space point to check.</param>
  426. /// <param name="camera">Unity Camera used for world-camera space conversion (usually left camera)</param>
  427. /// <returns></returns>
  428. public static bool CheckScreenView(Vector3 point, Camera camera)
  429. {
  430. //Transform the point into screen space
  431. Vector3 screenpoint = camera.WorldToScreenPoint(point);
  432. //Make sure it's within our view frustrum (except for clipping planes)
  433. if (screenpoint.z <= 0f)
  434. {
  435. return false; //No collision if it's behind us.
  436. }
  437. if (screenpoint.x < 0f || //Too far to the left
  438. screenpoint.y < 0f || //Too far to the bottom
  439. screenpoint.x >= camera.pixelWidth || //Too far to the right
  440. screenpoint.y >= camera.pixelHeight) //Too far to the top
  441. {
  442. return false;
  443. }
  444. return true;
  445. }
  446. /***********************************************************************************************
  447. ****************************** IMAGE UTILS **********************************
  448. ***********************************************************************************************/
  449. /// <summary>
  450. /// Saves a RenderTexture to a .png in the given relative path. Saved to Assets/image.png by default.
  451. /// Use this to take a picture of the ZED's final output.
  452. /// </summary><remarks>
  453. /// If in pass-through AR mode, you can pass ZEDRenderingPlane.target to this from the ZEDRenderingPlane
  454. /// components in the ZED's left eye. If not using AR, you can create your own RenderTexture, and use
  455. /// Graphics.Blit to copy to it in an OnRenderImage function of a component you attach to the camera.
  456. /// </remarks>
  457. /// <param name="rt">Source RenderTexture to be saved.</param>
  458. /// <param name="path">Path and filename to save the file.</param>
  459. /// <returns></returns>
  460. static public bool SaveImage(RenderTexture rt, string path = "Assets/image.png")
  461. {
  462. if (rt == null || path.Length == 0) return false;
  463. RenderTexture currentActiveRT = RenderTexture.active; //Cache the currently active RenderTexture to avoid interference.
  464. RenderTexture.active = rt; //Switch the source RenderTexture to the active one.
  465. Texture2D tex = new Texture2D(rt.width, rt.height); //Make a Texture2D copy of it and save it.
  466. tex.ReadPixels(new Rect(0, 0, tex.width, tex.height), 0, 0);
  467. System.IO.File.WriteAllBytes(path, tex.EncodeToPNG());
  468. RenderTexture.active = currentActiveRT; //Restore the old active RenderTexture.
  469. return true;
  470. }
  471. /***********************************************************************************************
  472. ****************************** MESH UTILS **********************************
  473. ***********************************************************************************************/
  474. public static string MeshToString(MeshFilter mf)
  475. {
  476. Mesh m = mf.mesh;
  477. Material[] mats = mf.GetComponent<Renderer>().sharedMaterials;
  478. StringBuilder sb = new StringBuilder();
  479. sb.Append("g ").Append(mf.name).Append("\n");
  480. foreach (Vector3 v in m.vertices)
  481. {
  482. sb.Append(string.Format("v {0} {1} {2}\n", v.x, v.y, v.z));
  483. }
  484. sb.Append("\n");
  485. foreach (Vector3 v in m.normals)
  486. {
  487. sb.Append(string.Format("vn {0} {1} {2}\n", v.x, v.y, v.z));
  488. }
  489. sb.Append("\n");
  490. foreach (Vector3 v in m.uv)
  491. {
  492. sb.Append(string.Format("vt {0} {1}\n", v.x, v.y));
  493. }
  494. for (int material = 0; material < m.subMeshCount; material++)
  495. {
  496. sb.Append("\n");
  497. sb.Append("usemtl ").Append(mats[material].name).Append("\n");
  498. sb.Append("usemap ").Append(mats[material].name).Append("\n");
  499. int[] triangles = m.GetTriangles(material);
  500. for (int i = 0; i < triangles.Length; i += 3)
  501. {
  502. sb.Append(string.Format("f {0}/{0}/{0} {1}/{1}/{1} {2}/{2}/{2}\n",
  503. triangles[i] + 1, triangles[i + 1] + 1, triangles[i + 2] + 1));
  504. }
  505. }
  506. return sb.ToString();
  507. }
  508. public static void MeshToFile(MeshFilter mf, string filename)
  509. {
  510. using (StreamWriter sw = new StreamWriter(filename))
  511. {
  512. sw.Write(MeshToString(mf));
  513. }
  514. }
  515. /***********************************************************************************************
  516. ****************************** MATH UTILS **********************************
  517. ***********************************************************************************************/
  518. public static float DistancePointLine(Vector3 point, Vector3 lineStartPoint, Vector3 lineEndPoint)
  519. {
  520. return Vector3.Magnitude(ProjectPointLine(point, lineStartPoint, lineEndPoint) - point);
  521. }
  522. public static Vector3 ProjectPointLine(Vector3 point, Vector3 lineStart, Vector3 lineEnd)
  523. {
  524. Vector3 rhs = point - lineStart;
  525. Vector3 vector2 = lineEnd - lineStart;
  526. float magnitude = vector2.magnitude;
  527. Vector3 lhs = vector2;
  528. if (magnitude > 1E-06f)
  529. {
  530. lhs = (Vector3)(lhs / magnitude);
  531. }
  532. float num2 = Mathf.Clamp(Vector3.Dot(lhs, rhs), 0f, magnitude);
  533. return (lineStart + ((Vector3)(lhs * num2)));
  534. }
  535. }