-
Notifications
You must be signed in to change notification settings - Fork 3
/
Copy pathrobot_camera_calibration.py
44 lines (35 loc) · 2.38 KB
/
robot_camera_calibration.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
import argparse
import rospy
from robot_arm_algos.src.robot_camera_calibration.robot_camera_calibrator import RobotCameraCalibrator
from robot_arm_algos.src.robot_arm.robot_frankapy import RobotFrankaPy
from robot_arm_algos.src.logger import logger
from robot_arm_algos.src.config_reader import get_robot_camera_calib_objects, read_yaml_file
def main(args):
config_dict = read_yaml_file(args.config_file)
if (config_dict["move_robot_automatically"] or config_dict["camera"]=="ros_camera"):
rospy.init_node("robot_camera_calibration")
tag_pose_collector, robot_pose_collector, camera = get_robot_camera_calib_objects(config_dict)
robot_arm_object = None
if(config_dict["move_robot_automatically"]):
robot_arm_object = robot_arm_object = RobotFrankaPy(init_node = False,
with_franka_gripper = config_dict["with_gripper"])
robot_camera_calibrator = RobotCameraCalibrator(robot_pose_collector,
tag_pose_collector,
camera,
output_file = config_dict["output_file"],
flag_camera_in_hand = config_dict["camera_in_hand"],
collect_data_and_calibrate = not(config_dict["only_calibration"]),
move_robot_automatically = config_dict["move_robot_automatically"],
robot_arm_object = robot_arm_object,
n_data = config_dict["n_data"],
fg_data_folder_path = config_dict["fg_optim_data_file_name"],
calib_data_file_name = config_dict["calib_data_file_name"])
robot_camera_calibrator.run_calibration()
if __name__ == "__main__":
parser = argparse.ArgumentParser(description='Robot Camera Calibration')
parser.add_argument("--config_file",
required = True,
type = str,
help = "path to config YAML file containing parameters and arguments required for running robot camera calibration")
args = parser.parse_args()
main(args)