Просмотр исходного кода

更新人脸跟踪配置参数

corvin 5 лет назад
Родитель
Сommit
3cd834c56b

+ 1 - 1
ros_code/src/arduino_servo_connect/cfg/arduino_params.cfg

@@ -18,6 +18,6 @@ gen = ParameterGenerator()
 gen.add("firmware_pub_rate", double_t, 0, "pub arduino firmware ver rate", 0.1, 0.01, 1.0)
 gen.add("default_x_deg", int_t, 0, "servo x default degree", 90, 0, 180)
 gen.add("default_y_deg", int_t, 0, "servo y default degree", 0, 0, 180)
-gen.add("servo_move_delay", int_t, 0, "when exit move servo delay", 50, 0, 150)
+gen.add("servo_move_delay", int_t, 0, "when exit move servo delay", 60, 0, 150)
 
 exit(gen.generate(PACKAGE, "arduino_dynamic_reconfig", "arduino_servo"))

+ 1 - 1
ros_code/src/arduino_servo_connect/cfg/config_params.yaml

@@ -16,7 +16,7 @@
 port: /dev/ttyUSB0
 baud: 57600
 timeout: 0.5
-servo_move_delay: 50
+servo_move_delay: 60
 version_pub_rate: 0.1
 default_x_deg: 90
 default_y_deg: 0

+ 1 - 1
ros_code/src/arduino_servo_connect/src/arduino_node.py

@@ -94,7 +94,7 @@ class ArduinoROS():
         self.servo_x_id = rospy.get_param("~servo_x_id", 3)
         self.servo_y_id = rospy.get_param("~servo_y_id", 4)
         self.pubRate = rospy.get_param("~version_pub_rate", 0.1)
-        self.move_delay = rospy.get_param("~servo_move_delay", 50)
+        self.move_delay = rospy.get_param("~servo_move_delay", 60)
         self.moveServoTopic = rospy.get_param("~move_servo_topic", "/arduino_servo_node/moveServoTopic")
         self.firmwareVerTopic = rospy.get_param("~firmware_version_topic", "/arduino_servo_node/firmwareVersionTopic")
         self.default_x_deg = rospy.get_param("~default_x_deg", 90)

+ 3 - 3
ros_code/src/face_location_tracker/cfg/faceLocationParams.cfg

@@ -20,12 +20,12 @@ gen.add("def_servo_x_max", int_t, 0, "default servo x max deg", 180, 0, 180)
 gen.add("def_servo_y_min", int_t, 0, "default servo y min deg", 0,   0, 180)
 gen.add("def_servo_y_max", int_t, 0, "default servo y max deg", 90,  0, 180)
 
-gen.add("def_servo_move_step",  int_t, 0, "servo default move step(degree)",  2, 1, 5)
-gen.add("face_tracker_move_delay", int_t, 0, "servo default move delay(ms)", 0, 0, 30)
+gen.add("def_servo_move_step",  int_t, 0, "servo default move step(degree)",  1, 1, 5)
+gen.add("face_tracker_move_delay", int_t, 0, "servo default move delay(ms)", 0, 0, 60)
 
 gen.add("def_image_center_x", int_t, 0, "location face center x", 320, 160, 480)
 gen.add("def_image_center_y", int_t, 0, "location face center y", 240, 120, 360)
-gen.add("def_check_tolerance", int_t, 0, "location face tolerance", 45, 40, 100)
+gen.add("def_check_tolerance", int_t, 0, "location face tolerance", 65, 40, 100)
 gen.add("face_detect_timeout", double_t, 0, "detect timeout will move org deg", 3.0, 0.5, 10.0)
 
 gen.add("topic_move_servo", bool_t, 0, "If move servo by topic or service", True)

+ 4 - 3
ros_code/src/face_location_tracker/cfg/face_location_params.yaml

@@ -28,6 +28,7 @@
 #       新增topic_move_servo参数,用来区分使用话题还是service方式
 #       来控制舵机移动.新增跟踪人脸速度的参数face_tracker_speed.
 ###################################################################
+camera_id: 1
 default_servo_x_min: 0
 default_servo_x_max: 180
 default_servo_y_min: 0
@@ -36,12 +37,12 @@ default_servo_y_max: 90
 default_servo_x_deg: 90
 default_servo_y_deg: 0
 
-default_servo_move_step: 2
-face_traker_move_delay: 0
+default_servo_move_step: 1
+face_traker_move_delay: 60
 
 default_image_center_x: 320
 default_image_center_y: 240
-default_check_tolerance: 45
+default_check_tolerance: 65
 face_detect_timeout: 3.0
 
 topic_move_servo: true

+ 4 - 3
ros_code/src/face_location_tracker/src/face_location.py

@@ -34,7 +34,7 @@ class FaceLocation():
         self.moveServoPub = rospy.Publisher(self.moveServoTopic, MoveServo, queue_size=2)
 
         # Get a reference to webcam #0 (the default one)
-        self.video_capture = cv2.VideoCapture(1)
+        self.video_capture = cv2.VideoCapture(self.camera_ID)
 
         # Initialize some variables
         face_locations = []
@@ -103,6 +103,7 @@ class FaceLocation():
         self.face_tracker_speed = paramList['face_tracker_speed']
 
     def get_config_param(self):
+        self.camera_ID = rospy.get_param("~camera_id", 1)
         self.servo_x_ID = rospy.get_param("~servo_x_id", 3)
         self.servo_y_ID = rospy.get_param("~servo_y_id", 4)
         self.servo_x_org_deg = rospy.get_param("~default_servo_x_deg", 90)
@@ -115,11 +116,11 @@ class FaceLocation():
         self.servo_y_min_pose = rospy.get_param("~default_servo_y_min", 0)
         self.servo_y_max_pose = rospy.get_param("~default_servo_y_max", 90)
 
-        self.servo_move_step = rospy.get_param("~default_servo_move_step", 2)
+        self.servo_move_step = rospy.get_param("~default_servo_move_step", 1)
         self.servo_move_delay = rospy.get_param("~face_tracker_move_delay", 0)
         self.image_center_x = rospy.get_param("~default_image_center_x", 320)
         self.image_center_y = rospy.get_param("~default_image_center_y", 240)
-        self.check_tolerance = rospy.get_param("~default_check_tolerance", 45)
+        self.check_tolerance = rospy.get_param("~default_check_tolerance", 65)
         self.moveServoTopic = rospy.get_param("~move_servo_topic", "/arduino_servo_node/moveServoTopic")
         self.topicMoveServoFlag = rospy.get_param("~topic_move_servo", True)
         self.face_tracker_speed = rospy.get_param("~face_tracker_speed", 5)