diff --git a/src/client.py b/src/client.py
old mode 100644
new mode 100755
diff --git a/src/creds.py b/src/creds.py
index f1d436c094fadcb7cabee25a930c8845a99c5fe3..ce5142d0034226ca35a6f135ddff446b1d6a7930 100644
--- a/src/creds.py
+++ b/src/creds.py
@@ -1,2 +1,2 @@
-device_id="***REMOVED***"
-token=***REMOVED***
+device_id="***REMOVED***"
+token=***REMOVED***
diff --git a/src/detect.py b/src/detect.py
index acccc62fb22f742f7b50cf8ec6477c9466c3484a..ea1c2dc85989052f919b867f52007b525aab6e11 100644
--- a/src/detect.py
+++ b/src/detect.py
@@ -3,7 +3,7 @@ load images taken by the camera, return bounding boxes
 
 customized based on Alexy/darknet_images.py
 '''
-import argparse
+from argparse import ArgumentParser, Namespace
 import os
 import glob
 import random
@@ -14,32 +14,6 @@ import cv2
 import numpy as np
 
 
-def parser():
-    parser = argparse.ArgumentParser(description="YOLO Object Detection")
-    parser.add_argument("--input", type=str, default="../img",
-                        help="image source. It can be a single image, a"
-                        "txt with paths to them, or a folder. Image valid"
-                        " formats are jpg, jpeg or png."
-                        "If no input is given, ")
-    parser.add_argument("--batch_size", default=1, type=int,
-                        help="number of images to be processed at the same time")
-    parser.add_argument("--weights", default="../weights/yolov3-vattenhallen_best.weights",
-                        help="yolo weights path")
-    parser.add_argument("--dont_show", action='store_true',
-                        help="windown inference display. For headless systems")
-    parser.add_argument("--ext_output", action='store_true',
-                        help="display bbox coordinates of detected objects")
-    parser.add_argument("--save_labels", action='store_true',
-                        help="save detections bbox for each image in yolo format")
-    parser.add_argument("--config_file", default="../cfg/yolov3-vattenhallen-test.cfg",
-                        help="path to config file")
-    parser.add_argument("--data_file", default="../data/vattenhallen.data",
-                        help="path to data file")
-    parser.add_argument("--thresh", type=float, default=.25,
-                        help="remove detections with lower confidence")
-    return parser.parse_args()
-
-
 def check_arguments_errors(args):
     assert 0 < args.thresh < 1, "Threshold should be a float between zero and one (non-inclusive)"
     if not os.path.exists(args.config_file):
@@ -120,8 +94,7 @@ def save_annotations(original_size, name, image, detections, class_names):
             f.write("{} {:.4f} {:.4f} {:.4f} {:.4f} {:.4f}\n".format(label, x*width, y*height, w*width, h*height, float(confidence)))
 
 
-def detect():
-    args = parser()
+def detect(args: Namespace)-> None:
     check_arguments_errors(args)
 
     random.seed(3)  # deterministic bbox colors
@@ -160,4 +133,29 @@ def detect():
 
 
 if __name__ == "__main__":
-    detect()
+    parser = ArgumentParser(description="YOLO Object Detection")
+    parser.add_argument("--input", type=str, default="../img",
+                        help="image source. It can be a single image, a"
+                        "txt with paths to them, or a folder. Image valid"
+                        " formats are jpg, jpeg or png."
+                        "If no input is given, ")
+    parser.add_argument("--batch_size", default=1, type=int,
+                        help="number of images to be processed at the same time")
+    parser.add_argument("--weights", default="../weights/yolov3-vattenhallen_best.weights",
+                        help="yolo weights path")
+    parser.add_argument("--dont_show", action='store_true',
+                        help="windown inference display. For headless systems")
+    parser.add_argument("--ext_output", action='store_true',
+                        help="display bbox coordinates of detected objects")
+    parser.add_argument("--save_labels", action='store_true',
+                        help="save detections bbox for each image in yolo format")
+    parser.add_argument("--config_file", default="../cfg/yolov3-vattenhallen-test.cfg",
+                        help="path to config file")
+    parser.add_argument("--data_file", default="../data/vattenhallen.data",
+                        help="path to data file")
+    parser.add_argument("--thresh", type=float, default=.25,
+                        help="remove detections with lower confidence")
+    parser.add_argument('-v', '--verbose', action='store_true', help='Verbose mode')
+    arguments = parser.parse_args()
+
+    detect(arguments)
diff --git a/src/location.py b/src/location.py
index 69a8b163d5d7cda4475321241476efaeabf727b4..856f8b566e4f79a96572e38131c177ae80aab58c 100644
--- a/src/location.py
+++ b/src/location.py
@@ -98,9 +98,12 @@ def read_locations(locations_path: Path) -> Optional[ndarray]:
         return None
 
     number_files = len(listdir(locations_path))
-    if number_files != 1:
+    if number_files > 1:
         _LOG.error('More than one file of locations found the {}'.format(locations_path))
-        return None
+        raise FileExistsError
+    elif number_files == 0:
+        _LOG.error('No file of locations found the {}'.format(locations_path))
+        raise FileNotFoundError
 
     locations_file = Path(locations_path, [file for file in listdir(locations_path)][0])    
     if not locations_file.suffix.lstrip('.') in _LOCATIONS_EXTENSIONS:
@@ -164,8 +167,8 @@ def cal_location(args: Namespace) -> ndarray:
     main function for this script
     '''
     cam_offset, gripper_offset = read_offsets(args.offset)
-    K_matrix = load_cam_matrix(args.camera_matrix)
-    list_location = read_locations(args.locations)
+    K_matrix = load_cam_matrix(args.camera_matrix) 
+    list_location = read_locations(args.locations) # 如果没有文件,会报错
     # iterate over each annotation file
     _LOG.info('Global coordinate calculation begins.')
     list_annotations = listdir(args.annotations)
@@ -201,15 +204,15 @@ def cal_location(args: Namespace) -> ndarray:
             center_x = detection[1]
             center_y = detection[2]
             category = detection[0]
+            confidence = detection[5]
             # pixel coordinate to camera coordinate
             local_coordinate = cam_coordinate(center_x, center_y, K_matrix)
 
             # camera coordinate to global coordinate
             global_x, global_y = global_coordinate(local_coordinate, 
                                 list_location[index_photo], cam_offset, gripper_offset)
-            list_global_coordinate.append([category, global_x, global_y])     
+            list_global_coordinate.append([category, global_x, global_y, confidence])     
             _LOG.debug(list_global_coordinate[-1])   
-    
     _LOG.info('Global coordinate calculation is done.')
     return array(list_global_coordinate)
 
diff --git a/src/main.py b/src/main.py
index d33fc3b8378bdad6605718becb488b1d534a2f76..5d876c21bba0f9771690391ba30a3b09eb23338c 100644
--- a/src/main.py
+++ b/src/main.py
@@ -5,7 +5,8 @@ The main script of the project, it calls scripts for movement, detection, and co
 '''
 from argparse import ArgumentParser, Namespace
 from logging import StringTemplateStyle
-import os
+from os import listdir, remove
+from os.path import join
 from pathlib import Path
 from typing import Tuple
 from numpy import sqrt
@@ -19,7 +20,9 @@ _Log = getLogger(__name__)
 
 GRIP_Z = -200 # measure!
 SCAN_Z = -100
-
+ORIGIN_X = 0
+ORIGIN_Y = 0
+ORIGIN_Z = 0
 
 def remove_overlap(table_coordinate:DataFrame, tolerance=50.00)->DataFrame:
     '''
@@ -45,8 +48,15 @@ def remove_overlap(table_coordinate:DataFrame, tolerance=50.00)->DataFrame:
     return table_coordinate              
 
 
-# 还要定期清理掉img下所有文件
-def remove_temp():
+
+def remove_temp(path: Path)-> None:
+    '''
+    Clean temporary files, i.e., photos, location.txt, annotations
+    '''
+    for filename in listdir(path):
+        file =Path(join(path, filename))
+        if file.is_file():
+            remove(file)
     return
 
 
@@ -54,15 +64,15 @@ def main(args: Namespace):
     # scan
     scan()
     # detect
-    detect()
+    detect(args)
     # calculate locations
-    list_global_coordinate = cal_location()
+    list_global_coordinate = cal_location(args)
     # choose class
     table_global_coordinate = DataFrame(list_global_coordinate, columns=['class', 'x', 'y', 'confidence'])
     # remove overlap
     table_global_coordinate = remove_overlap(table_global_coordinate)
     goal_class = table_global_coordinate[table_global_coordinate['class']==args.category]
-    # if there is no desiered class og plants
+    # if there is no desiered class of plants
     if goal_class.empty:
         _LOG.info("There is no {}".format(args.category))
     # move and grip
@@ -70,13 +80,16 @@ def main(args: Namespace):
     for i in range(num_goals):
         x, y = goal_class.loc[i, ['x','y']]
         simple_move(x, y, GRIP_Z, False)
-        gripper(True)
-        gripper(False) # 如何保证每次gripper都是开着的?
-        # 等待若干秒
-        # 回原点
-        simple_move(x, y, GRIP_Z, False)
+        gripper(True) # to ensure the gripper is open
+        gripper(False)  
+        
+        # go back to the origin
+        simple_move(ORIGIN_X, ORIGIN_Y, ORIGIN_Z, False)
         gripper(True)
     # clean temporary files if all the previous step work
+    remove_temp(args.input)
+    remove_temp(args.locations)
+    remove_temp(args.annotations)
     return
 
 
@@ -85,27 +98,27 @@ def main(args: Namespace):
 if __name__ == '__main__':
     parser = ArgumentParser(description="YOLOv3 detection on Farmbot")
     # parsers for detect
-    parser.add_argument(
-        '-w',
-        "--weights",
-        type=Path,
-        default="yolov4.weights",
-        help="yolo pretrained weights path"
-        )
-    parser.add_argument(
-        '-cfg',
-        "--config_file",
-        type = Path,
-        default = "./cfg/yolov4.cfg",
-        help = "path to config file"
-        )
-    parser.add_argument(
-        '-d',
-        "--data_file",
-        type = Path,
-        default="./cfg/coco.data",
-        help="path to data file"
-        )
+    parser.add_argument("--input", type=str, default="../img",
+                        help="image source. It can be a single image, a"
+                        "txt with paths to them, or a folder. Image valid"
+                        " formats are jpg, jpeg or png."
+                        "If no input is given, ")
+    parser.add_argument("--batch_size", default=1, type=int,
+                        help="number of images to be processed at the same time")
+    parser.add_argument("--weights", default="../weights/yolov3-vattenhallen_best.weights",
+                        help="yolo weights path")
+    parser.add_argument("--dont_show", action='store_true',
+                        help="windown inference display. For headless systems")
+    parser.add_argument("--ext_output", action='store_true',
+                        help="display bbox coordinates of detected objects")
+    parser.add_argument("--save_labels", action='store_true',
+                        help="save detections bbox for each image in yolo format")
+    parser.add_argument("--config_file", default="../cfg/yolov3-vattenhallen-test.cfg",
+                        help="path to config file")
+    parser.add_argument("--data_file", default="../data/vattenhallen.data",
+                        help="path to data file")
+    parser.add_argument("--thresh", type=float, default=.25,
+                        help="remove detections with lower confidence")
     # arguemtns for grip
     parser.add_argument(
         '-ca',
@@ -114,10 +127,42 @@ if __name__ == '__main__':
         help='Choose the class of fruits to be picked up. There are tomato, mushroom,\
         potato, carrot, beetroot, zucchini, hand'
     )
-    # parsers for move
     # arguments for location
-
-    
+    parser.add_argument(
+        '-cam',
+        '--camera_matrix',
+        type=Path,
+        default='../static/camera_no_distortion.mat',
+        help='Path to mat file that contains intrinsic camera matrix K'
+    )
+    parser.add_argument(
+        '-loc',
+        '--locations',
+        type=Path,
+        default='../img/locations/',
+        help='the path to txt files contains locations from encoders corresponds to each photo'
+    )
+    parser.add_argument(
+        '-a',
+        '--annotations',
+        type=Path,
+        default='../img/annotations',
+        help='the path to txt files contains annotations for each photo'
+    )
+    parser.add_argument(
+        '-o',
+        '--offset',
+        type=Path,
+        default='../static/distance.txt',
+        help='the txt contains distance offset for camera and gripper'
+    )
+    parser.add_argument(
+        '-l',
+        '--log',
+        type=Path,
+        default='../log/main.log',
+        help='Path to the log file'
+    )    
     parser.add_argument('-v', '--verbose', action='store_true', help='Verbose mode.')
     arguments = parser.parse_args()
 
diff --git a/src/move.py b/src/move.py
index 26fc55550d800e6d5b0f8b0481b4c35abfd04f4a..77d57d9807889521bf544aa6402776d2efd2f767 100644
--- a/src/move.py
+++ b/src/move.py
@@ -10,7 +10,7 @@ from logging import getLogger
 from os import path, makedirs
 from time  import sleep, time
 #from serial import Serial, PARITY_NONE, STOPBITS_ONE, EIGHTBITS 
-# from requests.api import delete
+from requests.api import delete
 from typing import List
 from pathlib import Path
 from logging import basicConfig, DEBUG, INFO, error, getLogger
@@ -38,7 +38,7 @@ class Opts:
         self.flag = flag
     
 
-def scan(min_x=0, max_x=1300, min_y=0, max_y=1000, delta=500, offset=0, flag=True) -> List: #里面的数字需要重新测量
+def scan(min_x=0, max_x=1300, min_y=0, max_y=1000, delta=500, offset=0, flag=True) -> List: #numbers need to be re-measured
     '''
     scan the bed at a certain height, first move along x axis, then y, like a zig zag;
     Taking pictures and record the location of the camera that corresponds to the picture
@@ -140,6 +140,7 @@ def simple_move(x: int, y: int, z: int, photo: bool) -> None:
 def gripper(open: bool) -> None:
     '''
     Use a serial port to drive the gripper to open or close
+    :param open: True: open False: Close
     '''
     ser = Serial(
     port = 'COM4',  # 这里不应为hard code
@@ -164,8 +165,16 @@ if __name__ == '__main__':
         type=int,
         help='Mode for FarmBot, 1 for simple move with an assigned detination, 2 for scaning' 
     )
-    
+    parser.add_argument(
+        '-l',
+        '--log',
+        type=Path,
+        default='../log/move.log',
+        help='Path to the log file'
+    )
+    parser.add_argument('-v', '--verbose', action='store_true', help='Verbose mode')
     arguments = parser.parse_args()
+    
 
     if arguments.mode == 1:
         Logger.info('Input the destination:')
@@ -175,9 +184,10 @@ if __name__ == '__main__':
         photo = True if input('Take a photo or not?[Y/N]:') == 'Y' else False 
         simple_move_start = time()
         simple_move(destination_x, destination_y, destination_z, photo)
-        Logger.info(f'time cost {time.time()-simple_move_start}')
+        Logger.info(f'time cost {time()-simple_move_start}')
     elif arguments.mode == 2:
         scan()
     else:
         Logger.error('Wrong mode number {arguments.mode}')
 
+
diff --git a/src/request_token.py b/src/request_token.py
new file mode 100755
index 0000000000000000000000000000000000000000..ef793f927a00fa57635ec4f13c74816e0a939bbd
--- /dev/null
+++ b/src/request_token.py
@@ -0,0 +1,28 @@
+#!/usr/bin/env python3
+
+# request a token (for creds.py)
+
+import argparse
+import json
+from urllib import request
+
+parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter)
+parser.add_argument('--email', type=str, help="user email for token request")
+parser.add_argument('--password', type=str, help="user password for token request")
+opts = parser.parse_args()
+print("opts %s" % opts)
+
+auth_info = {'user': {'email': opts.email, 'password': opts.password }}
+
+req = request.Request('https://my.farmbot.io/api/tokens')
+req.add_header('Content-Type', 'application/json')
+response = request.urlopen(req, data=json.dumps(auth_info).encode('utf-8'))
+
+token_info = json.loads(response.read().decode())
+
+print("mqtt host [%s]" % token_info['token']['unencoded']['mqtt'])
+
+print("rewriting creds.py")
+with open("creds.py", "w") as f:
+  f.write("device_id=\"%s\"\n" % token_info['token']['unencoded']['bot'])
+  f.write("token=\"%s\"\n" % token_info['token']['encoded'])
diff --git a/src/try.py b/src/try.py
new file mode 100644
index 0000000000000000000000000000000000000000..9f42d8e8956fddf9c0fa5cc0e27b7b2fda4c2000
--- /dev/null
+++ b/src/try.py
@@ -0,0 +1,14 @@
+from os import listdir, remove
+from os.path import join
+from pathlib import Path
+
+def remove_temp(path: Path)-> None:
+    # list file
+    for filename in listdir(path):
+        file =Path(join(path, filename))
+        if file.is_file():
+            remove(file)
+    return
+
+path = '../img'
+remove_temp(path)
\ No newline at end of file