Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add REST API to ArduPilotManager #119

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
45 changes: 26 additions & 19 deletions core/services/ardupilot_manager/ArduPilotManager.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
from firmware_download.FirmwareDownload import FirmwareDownload, Vehicle
from flight_controller_detector.Detector import Detector as BoardDetector
from flight_controller_detector.Detector import FlightControllerType
from mavlink_proxy.Endpoint import Endpoint
from mavlink_proxy.Endpoint import Endpoint, EndpointType
from mavlink_proxy.Manager import Manager as MavlinkManager
from settings import Settings
from Singleton import Singleton
Expand Down Expand Up @@ -58,7 +58,7 @@ def start_navigator(self) -> None:
except Exception as error:
raise RuntimeError(f"Failed to start navigator: {error}") from error

local_endpoint = "tcp:0.0.0.0:5766"
local_endpoint = "tcp:0.0.0.0:5760"
self.subprocess = subprocess.Popen(
[
firmware,
Expand All @@ -79,20 +79,13 @@ def start_navigator(self) -> None:
# does not accept TCP master endpoints
# self.start_mavlink_manager(Endpoint(local_endpoint))

rafaellehmkuhl marked this conversation as resolved.
Show resolved Hide resolved
# Check if subprocess is running and wait until it finishes
# Necessary since we don't have mavlink_manager running for navigator yet
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

minor detail, you don't need to fix it, but these comments should have come out in the previous commit :)

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Good catch!
Solved!

while self.subprocess.poll() is None:
time.sleep(1)

def start_serial(self, device: str) -> None:
self.start_mavlink_manager(Endpoint(f"serial:{device}:115200"))
self.start_mavlink_manager(Endpoint("serial", device, 115200))

def start_mavlink_manager(self, device: Endpoint) -> None:
self.add_endpoint(Endpoint("udpin:0.0.0.0:14550"))
self.add_endpoint(Endpoint("udpin", "0.0.0.0", 14550))
self.mavlink_manager.set_master_endpoint(device)
self.mavlink_manager.start()
while self.mavlink_manager.is_running():
time.sleep(1)

def start_board(self, boards: List[Tuple[FlightControllerType, str]]) -> bool:
if not boards:
Expand All @@ -108,38 +101,52 @@ def start_board(self, boards: List[Tuple[FlightControllerType, str]]) -> bool:

if FlightControllerType.Navigator == flight_controller_type:
self.start_navigator()
elif FlightControllerType.Serial == flight_controller_type:
return True
if FlightControllerType.Serial == flight_controller_type:
self.start_serial(place)
else:
raise RuntimeError("Invalid board type: {boards}")

return False
return True
raise RuntimeError("Invalid board type: {boards}")

def restart(self) -> bool:
return self.mavlink_manager.restart()

def _load_endpoints(self) -> None:
"""Load endpoints from the configuration file to the mavlink manager."""
if "endpoints" not in self.configuration:
self.configuration["endpoints"] = []
else:
endpoints = self.configuration["endpoints"]
self.mavlink_manager.add_endpoints([Endpoint(e) for e in endpoints])
for endpoint in endpoints:
if not self.add_endpoint(Endpoint(**endpoint)):
warn(f"Could not load endpoint {endpoint}")

def get_endpoints(self) -> List[Endpoint]:
"""Get all endpoints from the mavlink manager."""
return self.mavlink_manager.endpoints()

def add_endpoint(self, endpoint: Endpoint) -> bool:
"""Add endpoint to the mavlink manager."""
if endpoint.connection_type == EndpointType.File.value:
rafaellehmkuhl marked this conversation as resolved.
Show resolved Hide resolved
endpoint.place = os.path.join(self.settings.file_endpoints_path, endpoint.place)
if not self.mavlink_manager.add_endpoint(endpoint):
return False
self.configuration.get("endpoints", []).append(endpoint.__dict__)
return True

def add_new_endpoint(self, endpoint: Endpoint) -> bool:
"""Add endpoint to the mavlink manager and save it on the configuration file."""
self.configuration.get("endpoints", []).append(endpoint.asdict())
if not self.add_endpoint(endpoint):
self.configuration.get("endpoints", []).remove(endpoint.asdict())
return False
self.settings.save(self.configuration)
return True

def remove_endpoint(self, endpoint: Endpoint) -> bool:
"""Remove endpoint from the mavlink manager and save it on the configuration file."""
if not self.mavlink_manager.remove_endpoint(endpoint):
return False
try:
self.configuration.get("endpoints", []).remove(endpoint.__dict__)
self.configuration.get("endpoints", []).remove(endpoint.asdict())
self.settings.save(self.configuration)
return True
except Exception as error:
Expand Down
46 changes: 44 additions & 2 deletions core/services/ardupilot_manager/main.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,48 @@
#! /usr/bin/env python3
import json
from typing import Any, Dict, List

import uvicorn
from ArduPilotManager import ArduPilotManager
from fastapi import Body, FastAPI, Response, status
from mavlink_proxy.Endpoint import Endpoint
from starlette.responses import Response as StarletteResponse


class PrettyJSONResponse(StarletteResponse):
media_type = "application/json"

def render(self, content: Any) -> bytes:
return json.dumps(
content,
ensure_ascii=False,
allow_nan=False,
indent=2,
separators=(", ", ": "),
).encode("utf-8")


app = FastAPI(default_response_class=PrettyJSONResponse)
autopilot = ArduPilotManager()


@app.get("/endpoints", response_model=List[Dict[str, Any]])
def get_available_endpoints() -> Any:
return [endpoint.asdict() for endpoint in autopilot.get_endpoints()]


@app.post("/endpoint", status_code=status.HTTP_201_CREATED)
def create_new_endpoint(response: Response, endpoint: Endpoint = Body(...)) -> Any:
if not autopilot.add_new_endpoint(endpoint):
response.status_code = status.HTTP_409_CONFLICT


@app.delete("/endpoint", status_code=status.HTTP_204_NO_CONTENT)
def remove_endpoint(response: Response, endpoint: Endpoint = Body(...)) -> Any:
if not autopilot.remove_endpoint(endpoint):
response.status_code = status.HTTP_404_NOT_FOUND


if __name__ == "__main__":
ardupilot_manager = ArduPilotManager()
ardupilot_manager.run()
autopilot.run()
uvicorn.run(app, host="0.0.0.0", port=8000)
138 changes: 70 additions & 68 deletions core/services/ardupilot_manager/mavlink_proxy/Endpoint.py
Original file line number Diff line number Diff line change
@@ -1,76 +1,78 @@
from dataclasses import dataclass
from enum import IntEnum
from typing import Dict, Optional, Union
from enum import Enum
from typing import Any, Dict, Optional, Type

import validators
from pydantic import dataclasses, root_validator

class EndpointType(IntEnum):
Undefined = 0
UDPServer = 1
UDPClient = 2
TCP = 3
Serial = 4
File = 5

class EndpointType(str, Enum):
UDPServer = "udpin"
UDPClient = "udpout"
TCP = "tcp"
Serial = "serial"
File = "file"
rafaellehmkuhl marked this conversation as resolved.
Show resolved Hide resolved
patrickelectric marked this conversation as resolved.
Show resolved Hide resolved

@dataclass

@dataclasses.dataclass
class Endpoint:
connection_type: str
place: str
argument: Optional[str]
connType: EndpointType = EndpointType.Undefined

_connTypeMap = [
(["udpin"], EndpointType.UDPServer),
(["udp", "udpout"], EndpointType.UDPClient),
(["tcp"], EndpointType.TCP),
(["serial"], EndpointType.Serial),
(["file"], EndpointType.File),
]

def __init__(self, constructor: Union[str, Dict[str, str]] = "") -> None:
if isinstance(constructor, dict):
self.from_dict(constructor)
else:
self.from_str(constructor)

def from_str(self, pattern: str) -> "Endpoint":
args = pattern.split(":")
if len(args) != 2 and len(args) != 3:
raise RuntimeError("Wrong format for endpoint creation.")

for stringType, endpointType in self._connTypeMap:
if args[0] in stringType:
self.connType = endpointType
break
else:
self.connType = EndpointType.Undefined

self.place = args[1]
self.argument = args[2] if len(args) == 3 else None

return self

def from_dict(self, pattern: Dict[str, str]) -> "Endpoint":
if not {"connType", "place"}.issubset(pattern.keys()):
diff = {"connType", "place"}.difference(pattern.keys())
raise RuntimeError(f"Wrong format for endpoint creation, missing the following: {diff}.")

for stringType, endpointType in self._connTypeMap:
if pattern["connType"] in stringType:
self.connType = endpointType
break
else:
self.connType = EndpointType.Undefined

self.place = pattern["place"]
self.argument = pattern["argument"] if pattern["argument"] else None

return self
argument: Optional[int] = None

@root_validator
@classmethod
def is_mavlink_endpoint(cls: Type["Endpoint"], values: Any) -> Any:
connection_type, place, argument = (values.get("connection_type"), values.get("place"), values.get("argument"))

if connection_type in [EndpointType.UDPServer, EndpointType.UDPClient, EndpointType.TCP]:
rafaellehmkuhl marked this conversation as resolved.
Show resolved Hide resolved
rafaellehmkuhl marked this conversation as resolved.
Show resolved Hide resolved
if not (validators.domain(place) or validators.ipv4(place) or validators.ipv6(place)):
raise ValueError(f"Invalid network address: {place}")
if not argument in range(1, 65536):
raise ValueError(f"Ports must be in the range 1:65535. Received {argument}.")
return values

if connection_type == EndpointType.Serial.value:
rafaellehmkuhl marked this conversation as resolved.
Show resolved Hide resolved
if not place.startswith("/") or place.endswith("/"):
raise ValueError(f"Bad serial address: {place}. Make sure to use an absolute path.")
if not argument in VALID_SERIAL_BAUDRATES:
raise ValueError(f"Invalid serial baudrate: {argument}. Valid option are {VALID_SERIAL_BAUDRATES}.")
return values

if connection_type == EndpointType.File.value:
rafaellehmkuhl marked this conversation as resolved.
Show resolved Hide resolved
if "/" in place:
raise ValueError(f"Bad filename: {place}. Valid filenames do not contain '/' characters.")
if argument is not None:
raise ValueError(f"File endpoint should have no argument. Received {argument}.")
return values

raise ValueError(
f"Invalid connection_type: {connection_type}. Valid types are: {[e.value for e in EndpointType]}."
)

def __str__(self) -> str:
connTypeString = "Undefined"
for stringType, endpointType in self._connTypeMap:
if endpointType == self.connType:
connTypeString = stringType[0]
break

return ":".join([connTypeString, self.place, self.argument if self.argument else ""])
return ":".join([self.connection_type, self.place, str(self.argument)])

def asdict(self) -> Dict[str, Any]:
return {
"connection_type": self.connection_type,
"place": self.place,
"argument": self.argument,
}


VALID_SERIAL_BAUDRATES = [
3000000,
2000000,
1000000,
921600,
570600,
460800,
257600,
250000,
230400,
115200,
57600,
38400,
19200,
9600,
]
Original file line number Diff line number Diff line change
Expand Up @@ -24,15 +24,15 @@ def _get_version(self) -> Optional[str]:
def assemble_command(self, master: Endpoint) -> str:
# Convert endpoint format to mavlink-router format
def convert_endpoint(endpoint: Endpoint) -> str:
if endpoint.connType != EndpointType.TCP:
if endpoint.connection_type != EndpointType.TCP:
return str(endpoint)[str(endpoint).find(":") + 1 :]
# TCP uses a special argument and only works with localhost
port = str(endpoint).split(":")[2]
return f"-t {port}"

endpoints = " ".join(["--endpoint " + convert_endpoint(endpoint) for endpoint in self.endpoints()])

if master.connType not in [
if master.connection_type not in [
EndpointType.UDPServer,
EndpointType.UDPClient,
EndpointType.Serial,
Expand All @@ -53,7 +53,7 @@ def binary_name() -> str:

@staticmethod
def _validate_endpoint(endpoint: Endpoint) -> bool:
return endpoint.connType in [
return endpoint.connection_type in [
EndpointType.UDPServer,
EndpointType.UDPClient,
EndpointType.Serial,
Expand Down
2 changes: 1 addition & 1 deletion core/services/ardupilot_manager/mavlink_proxy/MAVProxy.py
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ def assemble_command(self, master: Endpoint) -> str:
endpoints = " ".join(["--out=" + endpoint.__str__() for endpoint in self.endpoints()])

master_string = str(master)
if master.connType == EndpointType.Serial:
if master.connection_type == EndpointType.Serial:
master_args = str(master).split(":")
if len(master_args) == 2:
master_string = f"{master_args[1]}"
Expand Down
9 changes: 4 additions & 5 deletions core/services/ardupilot_manager/mavlink_proxy/main.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,6 @@
sys.path.append(str(Path(__file__).absolute().parent.parent))

from mavlink_proxy.AbstractRouter import AbstractRouter
from mavlink_proxy.Endpoint import Endpoint
from mavlink_proxy.Manager import Manager

if __name__ == "__main__":
Expand All @@ -19,7 +18,7 @@
parser.add_argument(
"--master",
dest="master",
type=Endpoint,
type=str,
required=True,
help="Master endpoint that follow the format: udp/udpout/tcp/serial:ip/device:port/baudrate",
)
Expand All @@ -28,7 +27,7 @@
"--out",
dest="output",
nargs="*",
type=Endpoint,
type=str,
required=True,
metavar="endpoint",
help="List of endpoints that will be used to connect or allow connection.",
Expand All @@ -49,8 +48,8 @@
print(f"Starting {tool.name()} version {tool.version()}.")

manager.use(tool)
manager.add_endpoints(args.output)
manager.set_master_endpoint(args.master)
manager.add_endpoints(args.output.split(":"))
manager.set_master_endpoint(args.master.split(":"))

print(f"Command: {manager.command_line()}")
manager.start()
Expand Down