Hi Naruto Uzumaki,
We are working on adding support for popular camera models, like the OpenCV plump_bob. In the current release of Isaac Sim, this model is not supported directly by the RTX renderer. But, the following workaround could be used, to allow fitting an existing OpenCV distortion model into the supported by Isaac Sim fTheta model.
Please, refer to the following example. Please, don’t hesitate to contact us, if you need clarification or have further questions.
%pip install opencv-python scipy
import cv2, numpy as np
from scipy.optimize import curve_fit
# Given the OpenCV camera matrix and distortion coefficients calculate the Isaac Sim fisheyePolynomial distortion
width, height = 1920, 1200
camera_matrix = [[958.8, 0.0, 957.8], [0.0, 956.7, 589.5], [0.0, 0.0, 1.0]]
distortion_coefficients = [0.14, -0.03, -0.0002, -0.00003, 0.009, 0.5, -0.07, 0.017]
((fx,_,cx),(_,fy,cy),(_,_,_)) = camera_matrix
def DistortPoint(x, y, camera_matrix, distortion_coefficients):
((fx,_,cx),(_,fy,cy),(_,_,_)) = camera_matrix
pt_x, pt_y, pt_z = (x-cx)/fx, (y-cy)/fy, np.full(x.shape, 1.0)
points3d = np.stack((pt_x, pt_y, pt_z), axis = -1)
rvecs, tvecs = np.array([0.0,0.0,0.0]), np.array([0.0,0.0,0.0])
cameraMatrix, distCoeffs = np.array(camera_matrix), np.array(distortion_coefficients)
points, jac = cv2.projectPoints(points3d, rvecs, tvecs, cameraMatrix, distCoeffs)
return np.array([points[:,0,0], points[:,0,1]])
def Theta(x, y, camera_matrix):
((fx,_,cx),(_,fy,cy),(_,_,_)) = camera_matrix
pt_x, pt_y, pt_z = (x-cx)/fx, (y-cy)/fy, 1.0
r2 = pt_x * pt_x + pt_y * pt_y
theta = np.arctan2(np.sqrt(r2), 1.0)
return theta
def poly4_00(theta, b, c, d, e):
return b*theta + c*np.power(theta,2) + d*np.power(theta,3) + e*np.power(theta, 4)
# Fit the fTheta model for the points on the diagonal.
X = np.linspace(cx,width, width)
Y = np.linspace(cy,height, width)
theta = Theta(X, Y, camera_matrix)
r = np.linalg.norm(DistortPoint(X, Y, camera_matrix, distortion_coefficients) - np.array([[cx], [cy]]), axis=0)
order4_00_coeffs, _ = curve_fit(poly4_00, r, theta)
# The coefficient 'a' of the Ftheta model is set to zero, so that angle 0 is at pixel distance (aka radius) 0
Ftheta_A = [0.0] + list(order4_00_coeffs)
Dfov = np.rad2deg(2*poly4_00(np.linalg.norm([height/2,width/2]) , *order4_00_coeffs))
print('hfov {}'.format(np.rad2deg(2*poly4_00(width/2, *order4_00_coeffs)))) # assumes fisheye center is image center
print('vfov {}'.format(np.rad2deg(2*poly4_00(height/2, *order4_00_coeffs))))
print('dfov {}'.format(np.rad2deg(2*poly4_00(np.linalg.norm([height/2,width/2]) , *order4_00_coeffs))))
print('Ftheta_A:', Ftheta_A)
# To set the distortion model in the Isaac Sim, please refer to:
# https://docs.omniverse.nvidia.com/app_isaacsim/app_isaacsim/isaac_sim_sensors_camera.html
# And set the parameters either using the GUI Example or define the polynomial by adding to the Python Example
#
# Pixel_size = 3 # in µm
# camera.set_resolution((width, height))
# camera.set_focal_length((fx * Pixel_size * 1e-3 + fy * Pixel_size * 1e-3) / 2) # in mm
# camera.set_horizontal_aperture(Pixel_size * 1e-3 * width) # in mm
# camera.set_vertical_aperture(Pixel_size * 1e-3 * height) # in mm
#
# camera.set_projection_mode("perspective")
# camera.set_projection_type("fisheyePolynomial")
# camera.set_stereo_role("left")
#
# camera.set_fisheye_polynomial_properties(
# nominal_width=width, nominal_height=height,
# optical_centre_x=cx, optical_centre_y=cy,
# max_fov = Dfov, polynomial = Ftheta_A)