Bug Fixes
This commit is contained in:
@@ -337,7 +337,40 @@ class RunRecorder:
|
||||
threading.Thread(target=self._upload_file, args=(path, filename), daemon=True).start()
|
||||
|
||||
def save_summary(self, search_mode="", altitude=0, markers=None, landed=False, ugv_dispatched=False, ugv_target=None, extra=None):
|
||||
pass
|
||||
duration = time.time() - self.start_time
|
||||
summary = {
|
||||
"search_mode": search_mode,
|
||||
"altitude": round(altitude, 2),
|
||||
"duration_seconds": round(duration, 1),
|
||||
"search_duration_seconds": round(self.search_duration, 1),
|
||||
"landed": landed,
|
||||
"ugv_dispatched": ugv_dispatched,
|
||||
"markers_found": 0,
|
||||
"markers": {},
|
||||
"timestamp": datetime.now().isoformat(),
|
||||
}
|
||||
if ugv_target:
|
||||
summary["ugv_target"] = ugv_target
|
||||
if markers:
|
||||
summary["markers_found"] = len(markers)
|
||||
for mid, info in markers.items():
|
||||
pos = info.get("uav_position", {})
|
||||
summary["markers"][int(mid)] = {
|
||||
"x": round(pos.get("x", 0), 2),
|
||||
"y": round(pos.get("y", 0), 2),
|
||||
"distance": round(info.get("distance", 0), 2),
|
||||
}
|
||||
if extra:
|
||||
summary.update(extra)
|
||||
|
||||
path = self.run_dir / "summary.yaml"
|
||||
try:
|
||||
with open(path, "w") as f:
|
||||
yaml.dump(summary, f, default_flow_style=False, sort_keys=False)
|
||||
print(f"[REC] Summary saved: {path}")
|
||||
threading.Thread(target=self._upload_file, args=(path, "summary.yaml"), daemon=True).start()
|
||||
except Exception as e:
|
||||
print(f"[REC] Failed to save summary: {e}")
|
||||
|
||||
def stop(self):
|
||||
self._recording = False
|
||||
|
||||
Reference in New Issue
Block a user