提交 4b9370a8 编写于 作者: F freeHackOfJeff 提交者: Xiangquan Xiao

Tools: fix deprecated file() with open()

上级 7baf08cf
......@@ -32,14 +32,12 @@ from modules.planning.proto import planning_pb2
g_args = None
def get_3d_trajectory(planning_pb):
x = [p.path_point.x for p in planning_pb.trajectory_point]
y = [p.path_point.y for p in planning_pb.trajectory_point]
z = [p.v for p in planning_pb.trajectory_point]
return (x, y, z)
def get_debug_paths(planning_pb):
if not planning_pb.HasField("debug"):
return None
......@@ -52,12 +50,11 @@ def get_debug_paths(planning_pb):
results.append((path.name, (x, y)))
return results
def plot_planning(ax, planning_file):
try:
fhandle = file(planning_file, 'r')
except:
print "Failed to open file %s" % (planning_file)
with open(planning_file, 'r') as fp:
except OSError:
print('Failed to open file %s' % (planning_file))
return
planning_pb = planning_pb2.ADCTrajectory()
text_format.Merge(fhandle.read(), planning_pb)
......@@ -73,22 +70,21 @@ def plot_planning(ax, planning_file):
ax.plot(path[0], path[1], label="%s:%s" % (name, planning_file))
ax.legend()
def press_key(event):
if event.key == 'c':
files = g_args.planning_files
if len(files) != 2:
print "Need more than two files"
print('Need more than two files.')
return
command = ["cp"]
for f in files:
command.append(f)
if call(command) == 0:
print "command success: %s" % " ".join(command)
print('command success: %s' % " ".join(command))
sys.exit(0)
else:
print "Failed to run command: %s " % " ".join(command)
print('Failed to run command: %s ' % " ".join(command))
sys.exit(1)
if __name__ == '__main__':
import argparse
......@@ -123,6 +119,6 @@ if __name__ == '__main__':
if g_args.figure:
plt.savefig(g_args.figure)
print("picture saved to %s" % g_args.figure)
print('picture saved to %s' % g_args.figure)
else:
plt.show()
......@@ -33,7 +33,6 @@ CHASSIS_TOPIC = "/apollo/canbus/chassis"
LOCALIZATION_TOPIC = "/apollo/localization/pose"
IS_AUTO_MODE = False
def chassis_callback(chassis_data):
global IS_AUTO_MODE
if chassis_data.driving_mode == chassis_pb2.Chassis.COMPLETE_AUTO_DRIVE:
......@@ -52,7 +51,6 @@ def localization_callback(localization_data):
GPS_X.append(localization_data.pose.position.x)
GPS_Y.append(localization_data.pose.position.y)
def setup_listener(node):
node.create_reader(CHASSIS_TOPIC, chassis_pb2.Chassis, chassis_callback)
node.create_reader(LOCALIZATION_TOPIC,
......@@ -61,7 +59,6 @@ def setup_listener(node):
while not cyber.is_shutdown():
time.sleep(0.002)
def update(frame_number):
global GPS_X
global GPS_Y
......@@ -69,7 +66,6 @@ def update(frame_number):
min_len = min(len(GPS_X), len(GPS_Y)) - 1
GPS_LINE.set_data(GPS_X[-min_len:], GPS_Y[-min_len:])
if __name__ == '__main__':
import argparse
parser = argparse.ArgumentParser(
......@@ -92,10 +88,9 @@ if __name__ == '__main__':
fig, ax = plt.subplots()
handle = file(args.trace, 'r')
trace_data = np.genfromtxt(handle, delimiter=',', names=True)
ax.plot(trace_data['x'], trace_data['y'], 'b-', alpha=0.5, linewidth=1)
handle.close()
with open(args.trace, 'r') as fp:
trace_data = np.genfromtxt(handle, delimiter=',', names=True)
ax.plot(trace_data['x'], trace_data['y'], 'b-', alpha=0.5, linewidth=1)
cyber.init()
node = cyber.Node("plot_trace")
......
......@@ -62,7 +62,7 @@ def extract_record(in_record, output):
print("Finished extracting from record {}".format(in_record))
def main(args):
out = file(args.output, 'w') if args.output or sys.stdout
out = open(args.output, 'w') if args.output or sys.stdout
for record_file in args.in_record:
extract_record(record_file, out)
out.close()
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册