diff --git a/vision_opencv b/vision_opencv deleted file mode 160000 index 066793a..0000000 --- a/vision_opencv +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 066793a23e5d06d76c78ca3d69824a501c3554fd diff --git a/vision_opencv.zip b/vision_opencv.zip new file mode 100644 index 0000000..333db86 Binary files /dev/null and b/vision_opencv.zip differ diff --git a/yacyac_core/bt_xml/bt_yac_supply.xml b/yacyac_core/bt_xml/bt_yac_supply.xml index da4ddb0..9485bd7 100644 --- a/yacyac_core/bt_xml/bt_yac_supply.xml +++ b/yacyac_core/bt_xml/bt_yac_supply.xml @@ -12,14 +12,14 @@ - + - - + + diff --git a/yacyac_servo/yacyac_servo/action_servo_ctrl.py b/yacyac_servo/yacyac_servo/action_servo_ctrl.py index 566aca5..92b15d0 100644 --- a/yacyac_servo/yacyac_servo/action_servo_ctrl.py +++ b/yacyac_servo/yacyac_servo/action_servo_ctrl.py @@ -10,6 +10,7 @@ from yacyac_interface.action import Supply as SupplyAction from dynamixel_sdk_custom_interfaces.msg import SetPosition from dynamixel_sdk_custom_interfaces.srv import GetPosition +from std_msgs.msg import Int32 # 목적 포지션을 받으면 그에 맞게 서보를 움직임 # 목적 포지션에 도달하면 도착 메시지를 보냄 @@ -26,14 +27,29 @@ def __init__(self): # 현재 포지션을 서비스 클라이언트로 받아옴 self.cli = self.create_client(GetPosition, "/get_position") + + # 현재 알약 배출개수 펍 + self.pub_yac = self.create_publisher(Int32, "/yacyac/current_yac", 10) + self.cmd_pose_id = Servo() self.cnt = 0 + + self.current_yac = 0 + + + # 큰약 + # 목적 포지션 list + # 1023 to 300 degree + # 시계방향으로 돌아가는 포지션 리스트 + self.big_position_set = [0, 164, 328, 492, 656, 820] + + # 작은약 # 목적 포지션 list - # 1023 to 360 degree + # 1023 to 300 degree # 시계방향으로 돌아가는 포지션 리스트 - self.cw_position_set = [0, 164, 328, 492, 656, 820] + self.small_position_set = [60, 224, 388, 552, 716, 880] # 반 시계방향으로 돌아가는 포지션 리스트 - self.ccw_position_set = [915,751, 587,423, 259] + # 방향 flag self.position_flag = [0, 0, 0, 0, 0, 0, 0, 0, 0] # 현재 포지션 index @@ -45,11 +61,11 @@ def __init__(self): self.yac_cnt = 0 print ("init positioning...") - # for i in range(8): - # # 근처 포지션으로 이동합니다. - # self.init_position(i) - # # 원점 포지션으로 이동합니다. - # # self.reset_position(i) + for i in range(8): + # 근처 포지션으로 이동합니다. + self.init_position(i) + # 원점 포지션으로 이동합니다. + # self.reset_position(i) print ("init positioning done!!!") @@ -64,7 +80,7 @@ def execute_callback(self, goal_handle): for idx in range(len(supply_list)): if supply_list[idx] != 0: self.control_position(idx, supply_list[idx], goal_handle) - + self.current_yac = 0 goal_handle.succeed() result = SupplyAction.Result() @@ -77,7 +93,6 @@ def execute_callback(self, goal_handle): - def init_position(self, id): req = GetPosition.Request() req.id = id @@ -97,45 +112,54 @@ def init_position(self, id): cmd_pose = SetPosition() cmd_pose.id = id - flag = 0 - for i, val in enumerate(self.cw_position_set): - diff = abs(response.position - val) - if diff < min_diff: - min_diff = diff - closest_idx = i - cmd_pose.position = self.cw_position_set[closest_idx] - flag = 1 - for i, val in enumerate(self.ccw_position_set): - diff = abs(response.position - val) - if diff < min_diff: - min_diff = diff - closest_idx = i - cmd_pose.position = self.ccw_position_set[closest_idx] - flag = 0 - if flag == 0: - self.position_flag[id] = 1 - # print("cw") - else: - self.position_flag[id] = 0 + if id < 2 : + for i, val in enumerate(self.big_position_set): + diff = abs(response.position - val) + if diff < min_diff: + min_diff = diff + closest_idx = i + cmd_pose.position = self.big_position_set[closest_idx] + + if closest_idx > 3: + self.position_flag[id] = 1 + else: + self.position_flag[id] = 0 + # print("ccw") - # 리스트의 요소값과 같은 값이 있으면 그 인덱스를 반환 - if flag: - for i, val in enumerate(self.cw_position_set): + # 리스트의 요소값과 같은 값이 있으면 그 인덱스를 반환 + + for i, val in enumerate(self.big_position_set): if val == cmd_pose.position: - self.position_cnt[id] = i + self.position_cnt[id] = i break - else: - for i, val in enumerate(self.ccw_position_set): + + else : + for i, val in enumerate(self.small_position_set): + diff = abs(response.position - val) + if diff < min_diff: + min_diff = diff + closest_idx = i + cmd_pose.position = self.small_position_set[closest_idx] + + if closest_idx > 3: + self.position_flag[id] = 1 + else: + self.position_flag[id] = 0 + + # print("ccw") + # 리스트의 요소값과 같은 값이 있으면 그 인덱스를 반환 + + for i, val in enumerate(self.small_position_set): if val == cmd_pose.position: - self.position_cnt[id] = i - break + self.position_cnt[id] = i + break + self.pub.publish(cmd_pose) - time.sleep(0.1) + # time.sleep(0.1) else: self.get_logger().info(f"Service call for ID {id} failed") - def control_position(self, id, servo, goal_handle): # 제조할 약의 개수 yac_num = servo @@ -146,6 +170,10 @@ def control_position(self, id, servo, goal_handle): # 역방향 진행 yac_num -= 1 yac_cnt += 1 + self.current_yac += 1 + msg = Int32() + msg.data = self.current_yac + self.pub_yac.publish(msg) # yac_cnt print(id, "번 약 ", servo, "개중 ", yac_cnt, "개 배출중...") feedback_msg = SupplyAction.Feedback() @@ -153,46 +181,85 @@ def control_position(self, id, servo, goal_handle): feedback_msg.partial_sequence.append(self.yac_cnt) goal_handle.publish_feedback(feedback_msg) # self.get_logger().info('Feedback: {0}'.format(feedback_msg.partial_sequence)) - if self.position_flag[id] == 1: - cmd_pose = SetPosition() - self.position_cnt[id] += 1 - if self.position_cnt[id] >= len(self.ccw_position_set): - self.position_cnt[id] = 0 - self.position_flag[id] = 0 - cmd_pose.position = self.cw_position_set[self.position_cnt[id]] - cmd_pose.id = id - self.pub.publish(cmd_pose) - else: - cmd_pose.position = self.ccw_position_set[self.position_cnt[id]] - cmd_pose.id = id - self.pub.publish(cmd_pose) - else : - cmd_pose = SetPosition() - self.position_cnt[id] += 1 - if self.position_cnt[id] >= len(self.cw_position_set): - self.position_cnt[id] = 0 - self.position_flag[id] = 1 - cmd_pose.position = self.ccw_position_set[self.position_cnt[id]] - cmd_pose.id = id - self.pub.publish(cmd_pose) - else: - cmd_pose.position = self.cw_position_set[self.position_cnt[id]] - cmd_pose.id = id - self.pub.publish(cmd_pose) + + # print(id, "번 약 ", servo, "개중 ", yac_cnt, "개 배출중...") + + if id < 2: + print("큰약") + if self.position_flag[id] == 1: + cmd_pose = SetPosition() + self.position_cnt[id] += 1 + if self.position_cnt[id] == len(self.big_position_set): + self.position_cnt[id] = 4 + self.position_flag[id] = 0 + cmd_pose.position = self.big_position_set[self.position_cnt[id]] + cmd_pose.id = id + self.pub.publish(cmd_pose) + else: + cmd_pose.position = self.big_position_set[self.position_cnt[id]] + cmd_pose.id = id + self.pub.publish(cmd_pose) + # print(self.position_cnt) + else : + cmd_pose = SetPosition() + self.position_cnt[id] -= 1 + if self.position_cnt[id] < 0: + self.position_cnt[id] = 1 + self.position_flag[id] = 1 + cmd_pose.position = self.big_position_set[self.position_cnt[id]] + cmd_pose.id = id + self.pub.publish(cmd_pose) + else: + cmd_pose.position = self.big_position_set[self.position_cnt[id]] + cmd_pose.id = id + self.pub.publish(cmd_pose) + # print(self.position_cnt) + + + + else: + print("작은약") + if self.position_flag[id] == 1: + cmd_pose = SetPosition() + self.position_cnt[id] += 1 + if self.position_cnt[id] == len(self.small_position_set): + self.position_cnt[id] = 4 + self.position_flag[id] = 0 + cmd_pose.position = self.small_position_set[self.position_cnt[id]] + cmd_pose.id = id + self.pub.publish(cmd_pose) + else: + cmd_pose.position = self.small_position_set[self.position_cnt[id]] + cmd_pose.id = id + self.pub.publish(cmd_pose) + # print(self.position_cnt) + else : + cmd_pose = SetPosition() + self.position_cnt[id] -= 1 + if self.position_cnt[id] < 0: + self.position_cnt[id] = 1 + self.position_flag[id] = 1 + cmd_pose.position = self.small_position_set[self.position_cnt[id]] + cmd_pose.id = id + self.pub.publish(cmd_pose) + else: + cmd_pose.position = self.small_position_set[self.position_cnt[id]] + cmd_pose.id = id + self.pub.publish(cmd_pose) + # print(self.position_cnt) - - time.sleep(1) - + time.sleep(0.5) print(id, "번 약 배출이 완료되었습니다.") def reset_position(self, id): cmd_pose = SetPosition() cmd_pose.id = id - cmd_pose.position = self.cw_position_set[0] + if id < 2: + cmd_pose.position = self.big_position_set[0] + else: + cmd_pose.position = self.small_position_set[0] self.pub.publish(cmd_pose) - time.sleep(0.1) - @@ -205,7 +272,6 @@ def main(args=None): servo_node.destroy_node() rp.shutdown() - if __name__ == "__main__": print("start servo_node") main() diff --git a/yacyac_servo/yacyac_servo/servo_ctrl.py b/yacyac_servo/yacyac_servo/servo_ctrl.py index 0dd593f..cf39ca2 100644 --- a/yacyac_servo/yacyac_servo/servo_ctrl.py +++ b/yacyac_servo/yacyac_servo/servo_ctrl.py @@ -28,28 +28,26 @@ def __init__(self): # 목적 포지션 list # 1023 to 300 degree # 시계방향으로 돌아가는 포지션 리스트 - self.big_cw_position_set = [0, 164, 328, 492, 656, 820] - # 반 시계방향으로 돌아가는 포지션 리스트 - self.big_ccw_position_set = [915,751, 587,423, 259] - + self.big_position_set = [0, 164, 328, 492, 656, 820] + + # 작은약 # 목적 포지션 list # 1023 to 300 degree # 시계방향으로 돌아가는 포지션 리스트 - self.small_cw_position_set = [0, 164, 328, 492, 656, 820] + self.small_position_set = [60, 224, 388, 552, 716, 880] # 반 시계방향으로 돌아가는 포지션 리스트 - self.small_ccw_position_set = [915,751, 587,423, 259] # 방향 flag self.position_flag = [0, 0, 0, 0, 0, 0, 0, 0, 0] # 현재 포지션 index self.position_cnt = [0, 0, 0, 0, 0, 0, 0, 0, 0] - print ("init positioning...") + print ("init positioasdasning...") for i in range(8): # 근처 포지션으로 이동합니다. - # self.init_position(i) + self.init_position(i) # 원점 포지션으로 이동합니다. - self.reset_position(i) + # self.reset_position(i) print ("init positioning done!!!") @@ -72,71 +70,47 @@ def init_position(self, id): cmd_pose = SetPosition() cmd_pose.id = id - flag = 0 if id < 2 : - for i, val in enumerate(self.big_cw_position_set): + for i, val in enumerate(self.big_position_set): diff = abs(response.position - val) if diff < min_diff: min_diff = diff closest_idx = i - cmd_pose.position = self.big_cw_position_set[closest_idx] - flag = 1 - for i, val in enumerate(self.big_ccw_position_set): - diff = abs(response.position - val) - if diff < min_diff: - min_diff = diff - closest_idx = i - cmd_pose.position = self.big_ccw_position_set[closest_idx] - flag = 0 - if flag == 0: + cmd_pose.position = self.big_position_set[closest_idx] + + if closest_idx > 3: self.position_flag[id] = 1 - # print("cw") else: self.position_flag[id] = 0 - # print("ccw") + + # print("ccw") # 리스트의 요소값과 같은 값이 있으면 그 인덱스를 반환 - if flag: - for i, val in enumerate(self.big_cw_position_set): - if val == cmd_pose.position: - self.position_cnt[id] = i - break - else: - for i, val in enumerate(self.big_ccw_position_set): - if val == cmd_pose.position: - self.position_cnt[id] = i - break + + for i, val in enumerate(self.big_position_set): + if val == cmd_pose.position: + self.position_cnt[id] = i + break + else : - for i, val in enumerate(self.small_cw_position_set): - diff = abs(response.position - val) - if diff < min_diff: - min_diff = diff - closest_idx = i - cmd_pose.position = self.small_cw_position_set[closest_idx] - flag = 1 - for i, val in enumerate(self.small_ccw_position_set): + for i, val in enumerate(self.small_position_set): diff = abs(response.position - val) if diff < min_diff: min_diff = diff closest_idx = i - cmd_pose.position = self.small_ccw_position_set[closest_idx] - flag = 0 - if flag == 0: + cmd_pose.position = self.small_position_set[closest_idx] + + if closest_idx > 3: self.position_flag[id] = 1 - # print("cw") else: self.position_flag[id] = 0 - # print("ccw") + + # print("ccw") # 리스트의 요소값과 같은 값이 있으면 그 인덱스를 반환 - if flag: - for i, val in enumerate(self.small_cw_position_set): - if val == cmd_pose.position: - self.position_cnt[id] = i - break - else: - for i, val in enumerate(self.small_ccw_position_set): - if val == cmd_pose.position: - self.position_cnt[id] = i - break + + for i, val in enumerate(self.small_position_set): + if val == cmd_pose.position: + self.position_cnt[id] = i + break self.pub.publish(cmd_pose) # time.sleep(0.1) @@ -157,77 +131,89 @@ def control_position(self, id, servo): yac_cnt += 1 # yac_cnt - print(id, "번 약 ", servo, "개중 ", yac_cnt, "개 배출중...") + # print(id, "번 약 ", servo, "개중 ", yac_cnt, "개 배출중...") + if id < 2: + # print("큰약") if self.position_flag[id] == 1: cmd_pose = SetPosition() self.position_cnt[id] += 1 - if self.position_cnt[id] >= len(self.big_ccw_position_set): - self.position_cnt[id] = 0 + if self.position_cnt[id] == len(self.big_position_set): + self.position_cnt[id] = 4 self.position_flag[id] = 0 - cmd_pose.position = self.big_cw_position_set[self.position_cnt[id]] + cmd_pose.position = self.big_position_set[self.position_cnt[id]] cmd_pose.id = id self.pub.publish(cmd_pose) else: - cmd_pose.position = self.big_ccw_position_set[self.position_cnt[id]] + cmd_pose.position = self.big_position_set[self.position_cnt[id]] cmd_pose.id = id self.pub.publish(cmd_pose) + # print(self.position_cnt) else : cmd_pose = SetPosition() - self.position_cnt[id] += 1 - if self.position_cnt[id] >= len(self.big_cw_position_set): - self.position_cnt[id] = 0 + self.position_cnt[id] -= 1 + if self.position_cnt[id] < 0: + self.position_cnt[id] = 1 self.position_flag[id] = 1 - cmd_pose.position = self.big_ccw_position_set[self.position_cnt[id]] + cmd_pose.position = self.big_position_set[self.position_cnt[id]] cmd_pose.id = id self.pub.publish(cmd_pose) else: - cmd_pose.position = self.big_cw_position_set[self.position_cnt[id]] + cmd_pose.position = self.big_position_set[self.position_cnt[id]] cmd_pose.id = id self.pub.publish(cmd_pose) + # print(self.position_cnt) + + + else: + print("작은약") if self.position_flag[id] == 1: cmd_pose = SetPosition() self.position_cnt[id] += 1 - if self.position_cnt[id] >= len(self.small_ccw_position_set): - self.position_cnt[id] = 0 + if self.position_cnt[id] == len(self.small_position_set): + self.position_cnt[id] = 4 self.position_flag[id] = 0 - cmd_pose.position = self.small_cw_position_set[self.position_cnt[id]] + cmd_pose.position = self.small_position_set[self.position_cnt[id]] cmd_pose.id = id self.pub.publish(cmd_pose) else: - cmd_pose.position = self.small_ccw_position_set[self.position_cnt[id]] + cmd_pose.position = self.small_position_set[self.position_cnt[id]] cmd_pose.id = id self.pub.publish(cmd_pose) + # print(self.position_cnt) else : cmd_pose = SetPosition() - self.position_cnt[id] += 1 - if self.position_cnt[id] >= len(self.small_cw_position_set): - self.position_cnt[id] = 0 + self.position_cnt[id] -= 1 + if self.position_cnt[id] < 0: + self.position_cnt[id] = 1 self.position_flag[id] = 1 - cmd_pose.position = self.small_ccw_position_set[self.position_cnt[id]] + cmd_pose.position = self.small_position_set[self.position_cnt[id]] cmd_pose.id = id self.pub.publish(cmd_pose) else: - cmd_pose.position = self.small_cw_position_set[self.position_cnt[id]] + cmd_pose.position = self.small_position_set[self.position_cnt[id]] cmd_pose.id = id self.pub.publish(cmd_pose) - + # print(self.position_cnt) # time.sleep(1) - print(id, "번 약 배출이 완료되었습니다.") + # print(id, "번 약 배출이 완료되었습니다.") def reset_position(self, id): cmd_pose = SetPosition() cmd_pose.id = id - cmd_pose.position = self.big_cw_position_set[0] + if id < 2: + cmd_pose.position = self.big_position_set[0] + else: + cmd_pose.position = self.small_position_set[0] self.pub.publish(cmd_pose) # time.sleep(0.1) def callback_yac(self, msg): servo_list = list(msg.servo_list) - print("start position control") - print("list : ", servo_list) + # print("start position control") + # print("list : ", servo_list) for idx in range(len(servo_list)): if servo_list[idx] != 0: self.control_position(idx, servo_list[idx])