From 4b91e18c08add19880b572bf5089885c49953852 Mon Sep 17 00:00:00 2001 From: EndoNrak Date: Thu, 6 Jan 2022 22:06:28 +0900 Subject: [PATCH 1/5] fix puperun selectModeCallBack --- burger_war_dev/scripts/pupeRun.py | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/burger_war_dev/scripts/pupeRun.py b/burger_war_dev/scripts/pupeRun.py index 56f6f7b9..9d4b605b 100755 --- a/burger_war_dev/scripts/pupeRun.py +++ b/burger_war_dev/scripts/pupeRun.py @@ -21,9 +21,13 @@ def __init__(self, bot_name="NoName"): # mode self.mode = ActMode.basic self.mode_prev = ActMode.basic - self.navi = NaviBasic() self.modeDecider = ModeDecider() + #initialize navis + self.navi_basic = NaviBasic() + self.navi_attack = NaviAttack2() + self.navi = self.navi_basic + # subscriber self.imgInfo_sub = rospy.Subscriber('/img_info', ImgInfo, self.imgInfoCallBack) self.imgInfo = ImgInfo() @@ -59,11 +63,11 @@ def selectModeCallBack(self, state): print(self.mode, self.mode_prev) if self.mode != self.mode_prev: if self.mode==ActMode.basic: - self.navi = NaviBasic() + self.navi = self.navi_basic elif self.mode==ActMode.attack: # self.navi = NaviAttack() print("select attack mode") - self.navi = NaviAttack2() + self.navi = self.navi_attack self.mode_prev = self.mode From 24275a3a947769e815018b0c98151de51b50386d Mon Sep 17 00:00:00 2001 From: EndoNrak Date: Mon, 10 Jan 2022 14:38:22 +0900 Subject: [PATCH 2/5] add initialize func on points_depending_on_score to waypoint.py --- burger_war_dev/scripts/navi/waypoint.py | 27 ++++++++++--------------- burger_war_dev/scripts/pupeRun.py | 1 - 2 files changed, 11 insertions(+), 17 deletions(-) diff --git a/burger_war_dev/scripts/navi/waypoint.py b/burger_war_dev/scripts/navi/waypoint.py index 189d6cd4..1ccb1996 100644 --- a/burger_war_dev/scripts/navi/waypoint.py +++ b/burger_war_dev/scripts/navi/waypoint.py @@ -14,7 +14,6 @@ class Waypoint: next_lap_flag = False count_waypoint = 0 - waypoint_reverse_flag_for_blue = True def __init__(self, path_waypoints, path_waypoints_depending_on_score): @@ -30,33 +29,29 @@ def __init__(self, path_waypoints, path_waypoints_depending_on_score): lines = csv.reader(f) for l in lines: point = [float(i) for i in l] - # print(point) self.points.append(point[0:3]) with open(path_waypoints_depending_on_score) as f_score: lines_score = csv.reader(f_score) for l_score in lines_score: point_depending_on_score = [float(i_score) for i_score in l_score] - # print(point) self.points_depending_on_score.append(point_depending_on_score[0:3]) - - def warStateCallBack(self, data): - self.warState = data - print('get data!') - print(self.warState.enem_get_wall_marker_no) - if Waypoint.waypoint_reverse_flag_for_blue: - # blue side の場合は,180度ひっくり返す - if self.warState.my_side == 'b': - for i, point in enumerate(self.points_depending_on_score): + self.side = rospy.get_param('/send_id_to_judge/side') + self.change_points_depending_on_score_with_side() + + + def change_points_depending_on_score_with_side(self): + if self.side == "b": + # blue side の場合は,180度ひっくり返す + for i, _ in enumerate(self.points_depending_on_score): self.points_depending_on_score[i][0] *= -1 self.points_depending_on_score[i][1] *= -1 self.points_depending_on_score[i][2] -= 3.141592654 - - print('my side:', self.warState.my_side) - print(self.points_depending_on_score) - Waypoint.waypoint_reverse_flag_for_blue = False + def warStateCallBack(self, data): + self.warState = data + def get_next_waypoint(self): print(self.warState.enem_get_wall_marker_flag) Waypoint.count_waypoint = Waypoint.count_waypoint + 1 diff --git a/burger_war_dev/scripts/pupeRun.py b/burger_war_dev/scripts/pupeRun.py index 4a3e86ce..022306f9 100755 --- a/burger_war_dev/scripts/pupeRun.py +++ b/burger_war_dev/scripts/pupeRun.py @@ -65,7 +65,6 @@ def selectModeCallBack(self, state): if self.mode==ActMode.basic: self.navi = self.navi_basic elif self.mode==ActMode.attack: - # self.navi = NaviAttack() print("select attack mode") self.navi = self.navi_attack From 3d571e65442da91af7d578cff37c9228d8ce412e Mon Sep 17 00:00:00 2001 From: EndoNrak Date: Mon, 10 Jan 2022 15:14:05 +0900 Subject: [PATCH 3/5] add error handling about send_id_to_judge/side --- burger_war_dev/scripts/navi/waypoint.py | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/burger_war_dev/scripts/navi/waypoint.py b/burger_war_dev/scripts/navi/waypoint.py index 1ccb1996..79ce6da1 100644 --- a/burger_war_dev/scripts/navi/waypoint.py +++ b/burger_war_dev/scripts/navi/waypoint.py @@ -38,11 +38,14 @@ def __init__(self, path_waypoints, path_waypoints_depending_on_score): self.points_depending_on_score.append(point_depending_on_score[0:3]) self.side = rospy.get_param('/send_id_to_judge/side') - self.change_points_depending_on_score_with_side() + self.change_points_depending_on_score_with_side(self.side) - def change_points_depending_on_score_with_side(self): - if self.side == "b": + def change_points_depending_on_score_with_side(self, side): + if side not in ['r', 'b']: + raise ValueError("'side' param must be in ['r', 'b'], given: {}\n\ + please confirm with 'rosparam get /send_id_to_judge/side'".format(side)) + if side == "b": # blue side の場合は,180度ひっくり返す for i, _ in enumerate(self.points_depending_on_score): self.points_depending_on_score[i][0] *= -1 From 293a121749bcaa1604668f09eb3a6d4574b1d8d6 Mon Sep 17 00:00:00 2001 From: EndoNrak Date: Mon, 10 Jan 2022 15:40:14 +0900 Subject: [PATCH 4/5] fix --- burger_war_dev/scripts/navi/waypoint.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/burger_war_dev/scripts/navi/waypoint.py b/burger_war_dev/scripts/navi/waypoint.py index 79ce6da1..a67c7127 100644 --- a/burger_war_dev/scripts/navi/waypoint.py +++ b/burger_war_dev/scripts/navi/waypoint.py @@ -45,7 +45,7 @@ def change_points_depending_on_score_with_side(self, side): if side not in ['r', 'b']: raise ValueError("'side' param must be in ['r', 'b'], given: {}\n\ please confirm with 'rosparam get /send_id_to_judge/side'".format(side)) - if side == "b": + elif side == "b": # blue side の場合は,180度ひっくり返す for i, _ in enumerate(self.points_depending_on_score): self.points_depending_on_score[i][0] *= -1 From e4bfba7d0417bbb18f26f12d35dde209010aeda2 Mon Sep 17 00:00:00 2001 From: EndoNrak Date: Mon, 10 Jan 2022 17:36:18 +0900 Subject: [PATCH 5/5] add print for debug --- burger_war_dev/scripts/navi/waypoint.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/burger_war_dev/scripts/navi/waypoint.py b/burger_war_dev/scripts/navi/waypoint.py index a67c7127..e0912139 100644 --- a/burger_war_dev/scripts/navi/waypoint.py +++ b/burger_war_dev/scripts/navi/waypoint.py @@ -54,6 +54,8 @@ def change_points_depending_on_score_with_side(self, side): def warStateCallBack(self, data): self.warState = data + print('get enem_get_wall_marker_no data!') + print(self.warState.enem_get_wall_marker_no) def get_next_waypoint(self): print(self.warState.enem_get_wall_marker_flag)