Skip to content
Snippets Groups Projects
Commit 914e9b9f authored by Tommy Persson's avatar Tommy Persson
Browse files

Work on qr code.

parent e6334a79
No related branches found
No related tags found
No related merge requests found
...@@ -17,6 +17,9 @@ from cv_bridge import CvBridge, CvBridgeError ...@@ -17,6 +17,9 @@ from cv_bridge import CvBridge, CvBridgeError
import numpy as np import numpy as np
import tf import tf
remembered_points = None
have_points = False
parser = OptionParser() parser = OptionParser()
parser.add_option ("", "--image-topic", action="store", type="string", dest="image_topic", help="Topic to take image from", default="/dji21/camera0/image_raw_orig") parser.add_option ("", "--image-topic", action="store", type="string", dest="image_topic", help="Topic to take image from", default="/dji21/camera0/image_raw_orig")
parser.add_option ("", "--image-frame", action="store", type="string", dest="image_frame", help="Topic to take image from", default="/dji0/camera0/image_frame") parser.add_option ("", "--image-frame", action="store", type="string", dest="image_frame", help="Topic to take image from", default="/dji0/camera0/image_frame")
...@@ -65,7 +68,7 @@ def stamp_to_json(data): ...@@ -65,7 +68,7 @@ def stamp_to_json(data):
return jobj return jobj
def image_callback(data): def image_callback(data):
global fifo global fifo, remembered_points, have_points
try: try:
# print("image_callback_main") # print("image_callback_main")
if options.compressed: if options.compressed:
...@@ -111,11 +114,13 @@ def image_callback(data): ...@@ -111,11 +114,13 @@ def image_callback(data):
frame_pil = PilImage.fromarray(scaledimg) frame_pil = PilImage.fromarray(scaledimg)
timestamp = time.time()
qr = qrcode.QRCode(box_size=2) qr = qrcode.QRCode(box_size=2)
# qr.add_data(str(timestamp)) if options.qr_time:
qr.add_data(json.dumps(jobj)) timestamp = time.time()
qr.make() qr.add_data(str(timestamp))
else:
qr.add_data(json.dumps(jobj))
qr.make()
img_qr = qr.make_image() img_qr = qr.make_image()
pos = (frame_pil.size[0] - img_qr.size[0] - 1, 1) #better result when 1 pixel in, thus -1 and +1 pos = (frame_pil.size[0] - img_qr.size[0] - 1, 1) #better result when 1 pixel in, thus -1 and +1
...@@ -146,11 +151,21 @@ def image_callback(data): ...@@ -146,11 +151,21 @@ def image_callback(data):
else: else:
msg = bridge.cv2_to_imgmsg(final_image) msg = bridge.cv2_to_imgmsg(final_image)
image_pub.publish(msg) image_pub.publish(msg)
if options.decode: if options.decode:
decoded_data, _ , _ = detector.detectAndDecode(final_image) retval, points = detector.detect(final_image)
print("DECODED DATA:", decoded_data) # print(retval, points)
if retval:
remembered_points = points
have_points = True
else:
print("FAILED TO FIND CODE, trying to use saved points")
if have_points:
decoded_data, _ = detector.decode(final_image, remembered_points)
if decoded_data:
print("DECODED DATA:", decoded_data)
else:
print("DECODING FAILED!!!!!!!!!")
#retval, points = detector.detect(final_image) #retval, points = detector.detect(final_image)
#print("DETECT:", retval, points) #print("DETECT:", retval, points)
...@@ -167,6 +182,8 @@ if __name__ == "__main__": ...@@ -167,6 +182,8 @@ if __name__ == "__main__":
rospy.init_node ("add_qr") rospy.init_node ("add_qr")
print(cv2.__version__)
listener = tf.TransformListener() listener = tf.TransformListener()
detector = cv2.QRCodeDetector() detector = cv2.QRCodeDetector()
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment