StanfordVL / JRMOT_ROS

Source code for JRMOT: A Real-Time 3D Multi-Object Tracker and a New Large-Scale Dataset
MIT License
145 stars 35 forks source link

Velodyne points to camera image Result #16

Closed rttariverdi67 closed 3 years ago

rttariverdi67 commented 3 years ago

hi, thank you for this repository, I'm really new in this track and have some questions, I want to project JRDB point clouds to RGB image and have some problems. considering stitched image and its point cloud I want to have something like this, how can I do such projection. I tried project_ref_to_image_torch, project_velo_to_ref, move_lidar_to_camera_frame and did :

def print_projection_plt(points, image):
    """ project converted velodyne points into camera image """

    hsv_image = cv2.cvtColor(image, cv2.COLOR_BGR2HSV)

    for i in range(points.shape[1]):
        cv2.circle(hsv_image, (np.int64(points[0][i]),np.int64(points[1][i])),5, (0,0,255),-1)

    return cv2.cvtColor(hsv_image, cv2.COLOR_HSV2RGB)

pcd = o3d.io.read_point_cloud(pcd_path)
pointcloud = np.asarray(pcd.points)
pointcloud = torch.tensor(pointcloud)

pnt = OmniCalibration(calib_folder='calib').project_ref_to_image_torch(pointcloud)
pnt = np.asarray(pnt).T[:, 1::5] # one point in 5 points

image = cv2.imread(img_path)

image = print_projection_plt(points=pnt, image=image)

but results are not correct. thank you

abhijeetshenoi commented 3 years ago

Hello,

Could you post some examples of the incorrect output that you have? The code that projects from point cloud to image makes assumptions about the coordinate frame of the point clouds.

If the Pointcloud is in standard format (x forward, y to the right and z pointing up), then first using project_velo_to_ref and then using project_ref_to_image will likely give you your desired result.

Edit: I meant standard format (x forward, y to the left and z pointing up)

rttariverdi67 commented 3 years ago

@abhijeetshenoi Thank you for your reply, my result image at first was Screenshot from 2021-02-03 13-12-55


however after following your comment, i got this for upper Screenshot from 2021-02-03 13-13-511


for lower Screenshot from 2021-02-03 13-13-51 __

the part to generate image and Pointcloud is done like

image = cv2.imread(img_path)

pcd = o3d.io.read_point_cloud(pcd_path)
pointcloud = np.asarray(pcd.points)
pnt = torch.tensor(pointcloud)

velo2ref = OmniCalibration(calib_folder='calib').project_velo_to_ref(pnt)

ref2img = OmniCalibration(calib_folder='calib').project_ref_to_image_torch(velo2ref)
ref2img = ref2img.T[:, 1::10]# one point in 10 points

result = print_projection_plt(points=ref2img, image=image)

but still i'm not sure about the incorrectness of output that i have.

abhijeetshenoi commented 3 years ago

In addition to this, you need to move the velodyne points to the camera coordinates (the velodyne sensors are displaced from the physical camera)


First, if the original point cloud is x forward, y to the left and z upward, we perform the following operations:

https://github.com/StanfordVL/JRMOT_ROS/blob/9cbb1e2acf4dff8152f65dd32a1b6f5961fc5125/src/3d_detector.py#L78



At this point, z is facing forward, x is right ward, y is downward (KITTI convention):

 

https://github.com/StanfordVL/JRMOT_ROS/blob/9cbb1e2acf4dff8152f65dd32a1b6f5961fc5125/src/featurepointnet_model_util.py#L515

 

 

To debug, you might want to check the extent of LiDAR points in all three dimensions. The dimension along which the range is within +=2m is likely to be the vertical axis, maybe that will help you debug

rttariverdi67 commented 3 years ago

I checked the extend of Lidar points and here is what I can see, I use o3d.io.read_point_cloud() to get (x, y, z) of given .pcd file lets call it original point cloud, the range of each dimension is 47.76, 26.18 and 7.09. I think 47.76 is correspond to x, 26.18 is for y and 7.09 is for y so I believe it is in standard format. with this assumption I process this array(x,y,z) (original point cloud)as follows: First : give this array to move_lidar_to_camera_frame it changes sign and order of dimensions! Second : the output of first step goes to project_velo_to_refit changes sign and order of dimensions again! Third : the out put of second step goes to project_ref_to_image_torch , this gives 2D array like (v, u) at the end in order to match dimensions of RGB image and result of third step I do transpose so I have (u, v). So I give Image and (u,v) array to my print_projection_plt function and got this result.

so in all steps I don't change dimensions! Screenshot from 2021-02-05 12-22-41 where do I do mistake?!

abhijeetshenoi commented 3 years ago

Could you visualise the point cloud in 3D at each intermediate step? There are plenty of utilities you can use that take .pcd files.

On Fri, Feb 5, 2021 at 3:52 AM, rttariverdi67 notifications@github.com wrote:

I checked the extend of Lidar points and there is what I can see, I use o3d.io.read_point_cloud() to get (x, y, z) of given .pcd file lets call it original point cloud, the range of each dimension is 47.76, 26.18 and 7.09. I think 47.76 is correspond to x, 26.18 is for y and 7.09 is for y so I believe it is in standard format. with this assumption I process this array(x,y,z) (original point cloud)as follows: First : give this array to move_lidar_to_camera_frame Second : the output of first step goes to project_velo_to_ref Third : the out put of second step goes to project_ref_to_image_torch at the end in order to match dimensions of RGB image and result of third step I do transport so I have (u, v). At the end I give Image and (u,v) array to my print_projection_plt function and got this result.

so in all steps I don't change dimensions! [image: Screenshot from 2021-02-05 12-22-41] https://user-images.githubusercontent.com/53265657/107030450-b9e3df80-67c1-11eb-8c09-1941c3f9e7ed.png

— You are receiving this because you were mentioned. Reply to this email directly, view it on GitHub https://github.com/StanfordVL/JRMOT_ROS/issues/16#issuecomment-773986981, or unsubscribe https://github.com/notifications/unsubscribe-auth/AIBNOJEQAVU7DXTNKQQR2LDS5PLYVANCNFSM4WVEY47A .

-- Best, Abhijeet

rttariverdi67 commented 3 years ago

Dear @abhijeetshenoi , here are visualizations from each steps: I used a helper points to show the coordinates better: helper


original ".pcd" file: pcd here format is: x forward, y to the left and z pointing up


first: "move_lidar_to_camera_frame", the format becomes: x forward, y to the downward and z pointing left move_lidar_to_camera_frame


second: "project_velo_to_ref", the format stays same: x forward, y to the downward and z pointing left project_velo_to_ref


third: "project_ref_to_image_torch" gives me 2D array(projection) which using function "print_projection_plt" which I mentioned before, I copy these 2D array to RGB image,


however by only changing coordinates of "move_lidar_to_camera_frame" 's result to (-y,-z,x) I got this output: image

the result for lower: lower and for upper: upper

many thanks for your supports!! bests; Rahim