Skip to content

Commit

Permalink
Update kalibr_camera_focus
Browse files Browse the repository at this point in the history
solves #247
  • Loading branch information
nkhedekar authored and goldbattle committed May 2, 2022
1 parent 7b97ecc commit f7d42fd
Showing 1 changed file with 1 addition and 3 deletions.
4 changes: 1 addition & 3 deletions aslam_offline_calibration/kalibr/python/kalibr_camera_focus
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,6 @@
print("importing libraries")
import rospy
import cv2
import cv
import numpy as np
from sensor_msgs.msg import Image
from cv_bridge import CvBridge, CvBridgeError
Expand All @@ -12,7 +11,6 @@ class CameraFocus:
def __init__(self, topic):
self.topic = topic
self.windowNameOrig = "Camera: {0}".format(self.topic)
cv2.namedWindow(self.windowNameOrig, 2)
self.bridge = CvBridge()
self.image_sub = rospy.Subscriber(self.topic, Image, self.callback)

Expand Down Expand Up @@ -58,4 +56,4 @@ if __name__ == "__main__":
except KeyboardInterrupt:
print("Shutting down")

cv.DestroyAllWindows()
cv2.DestroyAllWindows()

0 comments on commit f7d42fd

Please # to comment.