async def change_board(self, board: FlightController) -> None:
     logger.info(f"Trying to run with '{board.name}'.")
     if not board in BoardDetector.detect():
         raise ValueError(f"Cannot use '{board.name}'. Board not detected.")
     self.set_preferred_board(board)
     await self.kill_ardupilot()
     await self.start_ardupilot()
    def start_sitl(self, frame: SITLFrame = SITLFrame.VECTORED) -> None:
        self._current_board = BoardDetector.detect_sitl()
        if not self.firmware_manager.is_firmware_installed(self._current_board):
            self.firmware_manager.install_firmware_from_params(Vehicle.Sub, self._current_board)
        if frame == SITLFrame.UNDEFINED:
            frame = SITLFrame.VECTORED
            logger.warning(f"SITL frame is undefined. Setting {frame} as current frame.")
        self.current_sitl_frame = frame

        firmware_path = self.firmware_manager.firmware_path(self._current_board.platform)
        self.firmware_manager.validate_firmware(firmware_path, self._current_board.platform)

        # ArduPilot SITL binary will bind TCP port 5760 (server) and the mavlink router will connect to it as a client
        master_endpoint = Endpoint(
            "Master", self.settings.app_name, EndpointType.TCPServer, "127.0.0.1", 5760, protected=True
        )
        # pylint: disable=consider-using-with
        self.ardupilot_subprocess = subprocess.Popen(
            [
                firmware_path,
                "--model",
                self.current_sitl_frame.value,
                "--base-port",
                str(master_endpoint.argument),
                "--home",
                "-27.563,-48.459,0.0,270.0",
            ],
            shell=False,
            encoding="utf-8",
            errors="ignore",
            cwd=self.settings.firmware_folder,
        )

        self.start_mavlink_manager(master_endpoint)
    async def start_ardupilot(self) -> None:
        try:
            available_boards = BoardDetector.detect()
            if not available_boards:
                raise RuntimeError("No boards available.")
            if len(available_boards) > 1:
                logger.warning(f"More than a single board detected: {available_boards}")

            flight_controller = self.get_board_to_be_used(available_boards)
            logger.info(f"Using {flight_controller.name} flight-controller.")

            if flight_controller.platform == Platform.Navigator:
                self.start_navigator(flight_controller)
            elif flight_controller.platform.type == PlatformType.Serial:
                self.start_serial(flight_controller)
            elif flight_controller.platform == Platform.SITL:
                self.start_sitl(self.current_sitl_frame)
            else:
                raise RuntimeError(f"Invalid board type: {flight_controller}")
        finally:
            self.should_be_running = True
 def run_with_board(self) -> None:
     if not self.start_board(BoardDetector.detect()):
         logger.warning("Flight controller board not detected.")
示例#5
0
    def run(self) -> None:
        ArduPilotManager.check_running_as_root()

        while not self.start_board(BoardDetector.detect()):
            print("Flight controller board not detected, will try again.")
            time.sleep(2)
示例#6
0
def available_boards() -> Any:
    return BoardDetector.detect()
示例#7
0
    return BoardDetector.detect()


app = VersionedFastAPI(app,
                       version="1.0.0",
                       prefix_format="/v{major}.{minor}",
                       enable_latest=True)
app.mount("/", StaticFiles(directory=str(FRONTEND_FOLDER), html=True))

if __name__ == "__main__":
    loop = asyncio.new_event_loop()

    # # Running uvicorn with log disabled so loguru can handle it
    config = Config(app=app,
                    loop=loop,
                    host="0.0.0.0",
                    port=8000,
                    log_config=None)
    server = Server(config)

    if args.sitl:
        autopilot.set_preferred_board(BoardDetector.detect_sitl())
    try:
        loop.run_until_complete(autopilot.start_ardupilot())
    except Exception as start_error:
        logger.exception(start_error)
    loop.create_task(autopilot.auto_restart_ardupilot())
    loop.create_task(autopilot.start_mavlink_manager_watchdog())
    loop.run_until_complete(server.serve())
    loop.run_until_complete(autopilot.kill_ardupilot())