728x90
using System.Collections;
using System.Collections.Generic;
using UnityEngine;
using Unity.Robotics.ROSTCPConnector;
using RosMessageTypes.Sensor;
public class For_points : MonoBehaviour
{
// 포인트 값 리스트에 저장
public List<Vector3> pointList = new List<Vector3>();
public uint total_number_of_points;
// point로 나타낼 obj를 위한 list 생성
public List<GameObject> pools = new List<GameObject>();
// Voxel grid sampling을 위한 매개변수
private Dictionary<Vector3, Vector3> voxelGrid = new Dictionary<Vector3, Vector3>(); // 격자 내 포인트 저장
public GameObject spherePrefab;
void Start()
{
ROSConnection.GetOrCreateInstance().Subscribe<PointCloud2Msg>("/ouster/points", Points);
// point로 나타낼 obj 미리 생성
for (int i = 0; i < 38000; i++)
{
GameObject point_obj = Instantiate(spherePrefab);
point_obj.gameObject.SetActive(false);
pools.Add(point_obj);
}
}
void Points(PointCloud2Msg popo)
{
pointList.Clear();
total_number_of_points = popo.height * popo.width;
// 포인트 하나의 사이즈
int pointSize = (int)popo.point_step;
for (int i = 0; i < total_number_of_points; i++)
{
// 각 포인트의 시작 인덱스 계산
int pointIndex = i * pointSize;
// 포인트의 x, y, z 좌표 읽어오기
float x = System.BitConverter.ToSingle(popo.data, pointIndex);
float y = System.BitConverter.ToSingle(popo.data, pointIndex + 4); // 4 바이트씩 건너뛰어야 함
float z = System.BitConverter.ToSingle(popo.data, pointIndex + 8); // 8 바이트씩 건너뛰어야 함
Vector3 point = new Vector3(-y, z, x);
pointList.Add(point);
// 시각화 하기 시작
pools[i].transform.position = pointList[i];
pools[i].transform.localScale = new Vector3(0.05f, 0.05f, 0.05f);
pools[i].SetActive(true);
}
}
private void Update()
{
Resources.UnloadUnusedAssets();
}
}
// popo.field[] 결과 0:x, 1:y, 2:z, 3:intensity, 4:t, 5:reflectivity, 6:ring, 7:ambient, 8:range
'LiDAR' 카테고리의 다른 글
Unity에서 LiDAR Pointcloud에 DBScan을 해보자 (0) | 2024.03.28 |
---|---|
Unity에서 Voxel grid sampling을 하자 (0) | 2024.03.28 |
Ouster LiDAR 정보를 Unity로 보내기 (0) | 2024.03.08 |
Ouster LiDAR pointcloud를 확인해보자 (2) | 2024.03.08 |
iOS LiDAR 화면 하단 영역만 PointCloud 검출 (0) | 2024.03.03 |