5 from sensor_msgs.msg
import CameraInfo
6 from sensor_msgs.msg
import Image
9 with open(yaml_fname,
"r")
as file_handle:
10 first_line = file_handle.readline()
11 if "%YAML:" not in first_line:
13 calib_data = yaml.load(file_handle, Loader=yaml.FullLoader)
15 camera_info_msg = CameraInfo()
16 camera_info_msg.width = calib_data[
"image_width"]
17 camera_info_msg.height = calib_data[
"image_height"]
18 camera_info_msg.K = calib_data[
"camera_matrix"][
"data"]
19 camera_info_msg.D = calib_data[
"distortion_coefficients"][
"data"]
20 camera_info_msg.R = calib_data[
"rectification_matrix"][
"data"]
21 camera_info_msg.P = calib_data[
"projection_matrix"][
"data"]
22 camera_info_msg.distortion_model = calib_data[
"distortion_model"]
23 return camera_info_msg
27 global camera_info_msg
29 camera_info_msg.header = image.header
31 camera_info_msg.header.frame_id = frameId
32 publisher.publish(camera_info_msg)
34 if __name__ ==
"__main__":
36 rospy.init_node(
"yaml_to_camera_info", anonymous=
True)
38 yaml_path = rospy.get_param(
'~yaml_path',
'')
39 scale = rospy.get_param(
'~scale', 1.0)
41 print(
'yaml_path parameter should be set to path of the calibration file!')
44 frameId = rospy.get_param(
'~frame_id',
'')
48 camera_info_msg.K[0] = camera_info_msg.K[0]*scale
49 camera_info_msg.K[2] = camera_info_msg.K[2]*scale
50 camera_info_msg.K[4] = camera_info_msg.K[4]*scale
51 camera_info_msg.K[5] = camera_info_msg.K[5]*scale
52 camera_info_msg.P[0] = camera_info_msg.P[0]*scale
53 camera_info_msg.P[2] = camera_info_msg.P[2]*scale
54 camera_info_msg.P[3] = camera_info_msg.P[3]*scale
55 camera_info_msg.P[5] = camera_info_msg.P[5]*scale
56 camera_info_msg.P[6] = camera_info_msg.P[6]*scale
57 camera_info_msg.width = int(camera_info_msg.width*scale)
58 camera_info_msg.height = int(camera_info_msg.height*scale)
60 publisher = rospy.Publisher(
"camera_info", CameraInfo, queue_size=1)
61 rospy.Subscriber(
"image", Image, callback, queue_size=1)