首先,我们打开Gazebo仿真环境(否则你摄像头里没东西)
export TURTLEBOT3_MODEL=waffle
roslaunch turtlebot3_gazebo turtlebot3_world.launch
然后,我们可以观察一个名为/camera/rgb/image_raw
的Topic,它使用的msg类型为sensor_msgs/Image
,具体定义如下:
std_msgs/Header header
uint32 seq
time stamp
string frame_id
uint32 height
uint32 width
string encoding
uint8 is_bigendian
uint32 step
uint8[] data
我们下一步的目的就是通过OpenCV将这个图像绘制出来。
OpenCV库的安装
我们在自己的一个pkg(我的叫mytest)的scripts里面新建一个python文件,名字为displayAnIMG.py
#!/usr/bin/env python
from __future__ import print_function
import sys
import rospy
import cv2
from std_msgs.msg import String
from sensor_msgs.msg import Image # 这是我们/camera/rgb/image_raw使用的消息类型
from cv_bridge import CvBridge, CvBridgeError
class image_converter:
def __init__(self):
self.bridge = CvBridge()
self.image_sub = rospy.Subscriber("/camera/rgb/image_raw",Image,self.callback)
def callback(self,data):
try:
# 实现了我们摄像头数据到opencv数据(nd.array())的转化
cv_image = self.bridge.imgmsg_to_cv2(data, "bgr8")
except CvBridgeError as e:
print(e)
# Image processing below
(rows,cols,channels) = cv_image.shape
if cols > 60 and rows > 60 :
cv2.circle(cv_image, (50,50), 10, 255) #这个画的是左上角的蓝色的圆圈
cv2.imshow("Image window", cv_image)
cv2.waitKey(3)
def main(args):
ic = image_converter()
rospy.init_node('image_converter', anonymous=True)
try:
rospy.spin()
except KeyboardInterrupt:
print("Shutting down")
cv2.destroyAllWindows()
if __name__ == '__main__':
main(sys.argv)
然后用chmod +x displayAnimg,py
,catkin_make
,最后用
rosrun mytest displayAnimg.py
即可得到如下的结果:
这个图像是实时更新的,我们可以在开着它的情况下用键盘操控我们的机器人:
export TURTLEBOT3_MODEL=waffle
roslaunch turtlebot3_teleop turtlebot3_teleop_key.launch
我们还可以在画面中心画一个矩形:
cv2.rectangle(img, pt1, pt2, color[], thickness[], lineType[], shift[])
图像的尺寸
rows,cols = 1080,1920
注意,在画图的时候,cols是x,rows是y,所以我们要用
cv2.rectangle(img, (960-100,540-100),(960+100,540+100))
#!/usr/bin/env python
from __future__ import print_function
import sys
import rospy
import cv2
import numpy as np
from std_msgs.msg import String
from sensor_msgs.msg import Image
from cv_bridge import CvBridge, CvBridgeError
class image_saver:
def __init__(self):
self.bridge = CvBridge()
self.image_sub = rospy.Subscriber("/camera/rgb/image_raw",Image,self.callback)
def callback(self,data):
try:
cv_image = self.bridge.imgmsg_to_cv2(data, "bgr8")
except CvBridgeError as e:
print(e)
np.save("/home/frank/Desktop/IMG.npy",cv_image)
def main(args):
imageSaver = image_saver()
rospy.init_node('image_save', anonymous=True) # We dont have rosspin since we only do it once.
print('Done')
cv2.destroyAllWindows()
if __name__ == '__main__':
main(sys.argv)
代码
效果:
原图:
灰度后的原图;
Canny边缘检测:
在Canny边缘检测后用Hough Transforamtion提取线条覆盖在原图上: