diff --git a/scripts/map_changer b/scripts/map_changer index ac41b6d..407a136 100755 --- a/scripts/map_changer +++ b/scripts/map_changer @@ -1,6 +1,5 @@ #!/usr/bin/env python3 import rospy -import numpy as np import ruamel.yaml from pathlib import Path from std_msgs.msg import UInt16 @@ -28,7 +27,6 @@ if ("change_map" in data["point"]): self.change_point_num.append(i+2) self.next_map_idx.append(data["point"]["change_map"]) - # self.change_point_num = np.array(self.change_point_num, dtype=np.uint16) ## Subscribe current waypoint number self.waypoint_num = 0 self.wp_num_sub = rospy.Subscriber("/waypoint_num", UInt16, self.waypoint_num_callback) @@ -41,7 +39,7 @@ def waypoint_num_callback(self, msg): - if (self.waypoint_num == msg.data): return + if (msg.data == self.waypoint_num): return try: idx = self.change_point_num.index(msg.data) self.current_map_num = self.next_map_idx[idx]