Python / C++
接上一篇博客,Theta S相机连通到ROS系统后,图像矩阵发布到了 /image_raw话题上。我们先启动一下上一篇博客中的 libuvc_camera.launch 文件,这时图像已经传到了 /image_raw 话题上,开一个新的终端用rostopic list
查看一下存在的话题。
图像信息就在 /image_raw 话题上, 写一个下面这样的程序订阅一下。原图像就可以看到是下面这样的。
#!/usr/bin/env python2.7
# -*- coding: utf-8 -*
import rospy
from sensor_msgs.msg import Image
import cv2
import cv_bridge
class ImgTran:
def __init__(self):
self.bridge = cv_bridge.CvBridge()
self.image_sub = rospy.Subscriber('/image_raw', Image, self.image_callback)
def image_callback(self,msg):
image = self.bridge.imgmsg_to_cv2(msg,desired_encoding='bgr8')
cv2.imshow("a",image)
cv2.waitKey(1)
if __name__ == "__main__":
rospy.init_node('Transform')
it = ImgTran()
rospy.spin()
然而,这样的图像并不是全景图像,只是Theta S相机正反两个镜头的鱼眼图像。需要对两个图像进行变换, 具体方法在一个日本博客上找到了方法有好几种(总共有5种),数学原理没怎么仔细看懂,但是博主写的python程序效率偏低(基本全是for循环),实时变换效果不好。我把原程序改进了一下每张图片变换速度差不多提升了n多倍。程序如下。
#!/usr/bin/env python2.7
# -*- coding: utf-8 -*
import rospy
from sensor_msgs.msg import Image
import cv2
import cv_bridge
import numpy as np
# 全局变量
vertex = 640
map_x = np.zeros((vertex, vertex*2))
map_y = np.zeros((vertex, vertex*2))
def initMatrix():
src_cx = 319
src_cy = 319
src_r = 283
src_cx2 = 961
range_arr_y = np.array([range(vertex)])
range_arr_x = np.array([range(vertex*2)])
phi1 = (np.pi * range_arr_x) / vertex
theta1 = (np.pi * range_arr_y.T) / vertex
X = np.sin(theta1) * np.cos(phi1)
Y = np.sin(theta1) * np.sin(phi1)
Z = np.cos(theta1)
phi2 = np.arccos(