大緻思路
- 感興趣區域roi設定
- 映射點到像素上
- 移動坐标原點
- 根據高度值填充像素值
環境配置conda+ros
- 因為ros中的包是依賴Python2的,但是我們想用Python3b程式設計,是以需要安裝一個conda環境。
- 在.bashrc中修改預設的conda環境變量。
打開終端預設還是python2,輸入condapy3才進入python環境。# Conda # export PATH=/home/s/anaconda3/bin:$PATH # 注釋掉conda的環境變量 alias condapy3='. /home/s/anaconda3/etc/profile.d/conda.sh && conda activate py3.7' # 建立Python3.7的環境
- 在py3.7環境中安裝包
這樣就可以通過虛拟環境編譯script檔案了pip install catkin-tools pip install rospkg
-
以這個package為例,使用 catkin_make ,然後rosrun script檔案時,要在conda環境下,這樣使用的一些package才是指向該conda環境中的package的對應檔案。
我們這個conda環境中的opencv版本如下
是以在執行script檔案時列印出來是對應的版本:點雲生成鳥瞰圖(Python)大緻思路環境配置conda+rosros實作(Python)可視化完整代碼參考 (py3.7) ➜ catkin_ws clear (py3.7) ➜ catkin_ws echo $ROS_PACKAGE_PATH /home/s/catkin_ws/src:/home/s/ros_study/src:/opt/ros/kinetic/share (py3.7) ➜ catkin_ws rosrun aiimooc_syz2 aiimooc_syz2.py opencv: 4.2.0 open3d:0.7.0.0
ros實作(Python)
因為cv2和ros自帶的cv有沖突,我們想使用conda中自己安裝的cv2,是以在import之前,先把ros中路徑移除,在import之後在導入。
bird_eyes.py
#!/usr/bin/env python3
# use python3 in current conda env!!!
# import cv2 in conda rather than in ros
import sys
sys.path.remove('/opt/ros/kinetic/lib/python2.7/dist-packages')
import cv2
# 使用完cv2後再導入ros路徑
sys.path.append('/opt/ros/kinetic/lib/python2.7/dist-packages')
from cv_bridge import CvBridge
import numpy as np
import rospy
from sensor_msgs.msg import PointCloud2,Image
import sensor_msgs.point_cloud2 as pc2
import open3d
import os
class pt2brid_eye:
def __init__(self):
self.image_pub = rospy.Publisher('/bird_eyes', Image, queue_size=10)
self.pt_sub=rospy.Subscriber("/rslidar_points", PointCloud2, self.callback)
self.bridge = CvBridge()
def callback(self,lidar):
lidar = pc2.read_points(lidar)
points = np.array(list(lidar))
im = self.point_cloud_2_birdseye(points) # im is a numpy array
self.image_pub.publish(self.bridge.cv2_to_imgmsg(im))
print("convert!")
def point_cloud_2_birdseye(self,points):
x_points = points[:, 0]
y_points = points[:, 1]
z_points = points[:, 2]
f_filt = np.logical_and((x_points > -50), (x_points < 50))
s_filt = np.logical_and((y_points > -50), (y_points < 50))
filter = np.logical_and(f_filt, s_filt)
indices = np.argwhere(filter)
x_points = x_points[indices]
y_points = y_points[indices]
z_points = z_points[indices]
x_img = (-y_points*10).astype(np.int32)+500
y_img = (-x_points *10).astype(np.int32)+500
pixel_values = np.clip(z_points,-2,2)
pixel_values = ((pixel_values +2) / 4.0) * 255
im=np.zeros([1001,1001],dtype=np.uint8)
im[y_img, x_img] = pixel_values
return im
# def cloud_subscribe():
# rospy.init_node('cloud_subscribe_node')
# pub = rospy.Publisher('/bird_eyes', Image, queue_size=10)
# rospy.Subscriber("/rslidar_points", PointCloud2, callback)
# rospy.spin()
if __name__ == '__main__':
print("opencv: {}".format(cv2.__version__))
print("open3d:{}".format(open3d.__version__))
# cloud_subscribe()
pt2img=pt2brid_eye()
rospy.init_node('pt_to_brid_eyeImage_node')
rospy.spin()
可視化
完整代碼
https://github.com/suyunzzz/aiimooc_lesson/tree/master/aiimooc_syz2
參考
http://ronny.rest/tutorials/module/pointclouds_01/point_cloud_birdseye/
http://ronny.rest/blog/post_2017_03_26_lidar_birds_eye/
https://blog.csdn.net/qq_33801763/article/details/78923310#t10
ROS 訂閱雷達話題,擷取點雲資料,可視化,生成鳥瞰圖
ConvertingBetweenROSImagesAndOpenCVImagesPython
Python中常出現TabError: inconsistent use of tabs and spaces in indentation錯誤解決方法