Skip to content

Commit

Permalink
Fix flake8 error detect parking sign
Browse files Browse the repository at this point in the history
  • Loading branch information
iamjunyeong committed Feb 12, 2025
1 parent cc8b3fe commit 43b92a7
Showing 1 changed file with 18 additions and 12 deletions.
30 changes: 18 additions & 12 deletions turtlebot3_autorace_detect/src/detect_parking_sign.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,13 +19,13 @@

# Author: Leon Jung, Gilbert, Ashe Kim

import os
from enum import Enum
import os

import cv2
from cv_bridge import CvBridge
import numpy as np
import rclpy
from cv_bridge import CvBridge
from rclpy.node import Node
from sensor_msgs.msg import CompressedImage
from sensor_msgs.msg import Image
Expand Down Expand Up @@ -87,16 +87,22 @@ def fnPreproc(self):
self.kp_parking, self.des_parking = self.sift.detectAndCompute(self.img_parking, None)

FLANN_INDEX_KDTREE = 0
index_params = dict(algorithm=FLANN_INDEX_KDTREE, trees=5)
search_params = dict(checks=50)
index_params = {
'algorithm': FLANN_INDEX_KDTREE,
'trees': 5
}

search_params = {
'checks': 50
}

self.flann = cv2.FlannBasedMatcher(index_params, search_params)

def fnCalcMSE(self, arr1, arr2):
squared_diff = (arr1 - arr2) ** 2
sum = np.sum(squared_diff)
total_sum = np.sum(squared_diff)
num_all = arr1.shape[0] * arr1.shape[1] # cv_image_input and 2 should have same shape
err = sum / num_all
err = total_sum / num_all
return err

def cbFindTrafficSign(self, image_msg):
Expand Down Expand Up @@ -168,12 +174,12 @@ def cbFindTrafficSign(self, image_msg):
)

elif image_out_num == 2:
draw_params = dict(
matchColor=(255, 0, 0), # draw matches in green color
singlePointColor=None,
matchesMask=matchesMask_parking, # draw only inliers
flags=2
)
draw_params = {
'matchColor': (255, 0, 0), # draw matches in green color
'singlePointColor': None,
'matchesMask': matchesMask_parking, # draw only inliers
'flags': 2
}

final_parking = cv2.drawMatches(
cv_image_input,
Expand Down

0 comments on commit 43b92a7

Please sign in to comment.