Skip to content
Snippets Groups Projects
Commit 92d3e367 authored by Amos's avatar Amos
Browse files

optical modified

parent 79d5f093
No related branches found
No related tags found
No related merge requests found
# optical_flow_node.py
import rclpy
from rclpy.node import Node
from sensor_msgs.msg import CompressedImage
......@@ -23,26 +21,25 @@ class OpticalFlowNode(Node):
image = cv2.imdecode(np_arr, cv2.IMREAD_COLOR)
gray_image = cv2.cvtColor(image, cv2.COLOR_BGR2GRAY)
# 读取当前帧和上一帧的强度曲线
if not hasattr(self, 'previous_gray_image'):
self.previous_gray_image = gray_image
return
curve1 = self.previous_gray_image[100, :] # 选取水平线作为曲线1
curve2 = gray_image[100, :] # 当前帧作为曲线2
row_index = 100
curve1 = self.previous_gray_image[row_index, :]
curve2 = gray_image[row_index, :]
# 计算局部位移
shifts = local_shift_computation(curve1, curve2)
draw_function(image, shifts, hmin=0, hmax=image.shape[0], ymin=-50, ymax=50, color=(255, 0, 0), thickness=1)
# 显示图像
draw_function(image, curve1, hmin=0, hmax=image.shape[0], ymin=0, ymax=255, color=(255, 0, 0), thickness=1)
draw_function(image, curve2, hmin=0, hmax=image.shape[0], ymin=0, ymax=255, color=(0, 165, 255), thickness=1)
cv2.imshow("Optical Flow Image", image)
cv2.waitKey(1)
print("Press Enter to view the next frame...")
cv2.waitKey(0) # Wait for Enter key
# 更新上一帧
self.previous_gray_image = gray_image
def main(args=None):
rclpy.init(args=args)
optical_flow_node = OpticalFlowNode()
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment