This is the repository for Uav_control, an API for UAV autonomous flights. The Uav_control API enables UAV movement, telemetry and basic command execution such as RTL and TAKEOFF through HTTP requests, facilitating remote controlled flights, both programmatically and manually. In addition to that, Uav_control supports protocol execution for autonomous flights, oferring the same interface as gradysim-nextgen simulator. At last but not least, Uav_control can be used for simulations based on Ardupilot's SITL.
Python 3.10 is required If simulated flights are intended, installing Ardupilot's codebase is necessary. To do that follow the instructions at https://ardupilot.org/dev/docs/where-to-get-the-code.html (Don't forget to build the environment after cloning). In addition to that, following the steps for running the SITL is also required, which are stated at https://ardupilot.org/dev/docs/SITL-setup-landingpage.html
To install Uav_control simply clone this repository.
git clone git@github.com:Project-GrADyS/uav_control.git
To install required python packages run the command bellow from the root folder of the repository:
pip3 install -r requirements.txt
To start the uav_control API, run the following command:
python3 uav_api.py --port [port for API] --uav_connection [ardupilot_connection] --connection_type [udpin or updout] --sysid [sysid for ardupilot]
Alternatively, you can use a configuration file in the .ini format.
This file is located at flight_examples/config.ini
[API]
port = 8020
uav_connection = 127.0.0.1:17171
connection_type = udpin
sysid = 12
And run the command:
python3 uav_api.py --config flight_examples/config.ini
To get better insight on the arguments for uav_api.py
run the command bellow:
python3 uav_api --help
To verify the initialization of the API go to the endpoint localhost:[your_port]/docs
.
Once inside the web page, scroll to telemetry router and execute the telemetry/general
endpoint.
If everything is fine, the answer should look like this.
And that's it! You can start consuming the Uav_control API
To instantiate the API, run the script uav_api.py
through the following command:
python3 uav_api.py --simulated true
This command initiates both the SITL, and the Uav_control API. The connection addres of the SITL instance is 127.0.0.1:17171
and the api is hosted at localhost:8000 by default but both of this parameters can be modified by arguments.
To manually test the api access the auto-generated swagger endpoint at http://localhost:8000/docs
.
To get visual feedback of drone position and telemetry use Mission Planner, or any other ground station software of your preference, and connect to UDP port 15630
(for wsl users this may not work, check the parameters section for uav_api.py and search for gs_connection for more).
One of the perks of using Uav_control is simplifying UAV flights coordinated by scripts. Here are some examples:
This file is located at flight_examples/takeoff_land.py
import requests
base_url = "http://localhost:8000"
# Arming vehicle
arm_result = requests.get(f"{base_url}/command/arm")
if arm_result.status_code != 200:
print(f"Arm command fail. status_code={arm_result.status_code}")
exit()
print("Vehicle armed.")
# Taking off
params = {"alt": 30}
takeoff_result = requests.get(f"{base_url}/command/takeoff", params=params)
if takeoff_result.status_code != 200:
print(f"Take off command fail. status_code={takeoff_result.status_code}")
exit()
print("Vehicle took off")
# Landing...
land_result = requests.get(f"{base_url}/command/land")
if land_result.status_code != 200:
print(f"Land command fail. status_code={land_result.status_code}")
exit()
print("Vehicle landed.")
In this example the uav will move following a square with 100 meters side. This file is located at flight_examples/ned_square
.
import requests
base_url = "http://localhost:8000"
# Arming vehicle
arm_result = requests.get(f"{base_url}/command/arm")
if arm_result.status_code != 200:
print(f"Arm command fail. status_code={arm_result.status_code}")
exit()
print("Vehicle armed.")
# Taking off
params = {"alt": 30}
takeoff_result = requests.get(f"{base_url}/command/takeoff", params=params)
if takeoff_result.status_code != 200:
print(f"Take off command fail. status_code={takeoff_result.status_code}")
exit()
print("Vehicle took off")
square_points = [
(100, 100, -50),
(100, -100, -50),
(-100, -100, -50),
(-100, 100, -50)
]
# Moving
for point in square_points:
point_data = {
"x": point[0],
"y": point[1],
"z": point[2]
}
point_result = requests.post(f"{base_url}/movement/go_to_ned_wait", json=point_data)
if point_result.status_code != 200:
print(f"Go_to_ned_wait command fail. status_code={point_result.status_code} point={point}")
exit()
print(f"Vehicle at ({point[0]}, {point[1]}, {point[2]})")
# Returning to launch
rtl_result = requests.get(f"{base_url}/command/rtl")
if rtl_result.status_code != 200:
print(f"RTL command fail. status_code={rtl_result.status_code}")
exit()
print("Vehicle landed at launch.")
This example does the same thing as the last one but this time instead of using the go_to_ned_wait
endpoint we will take a polling aproach using go_to_ned
. While more verbose, this way of verifying position allows your program to do other things while the uav has not arrived to the specified location. This file is located at flight_examples/ned_square_polling.py
.
import requests
import time
import math
base_url = "http://localhost:8000"
def euclidean_distance(point1, point2):
return math.sqrt((point1[0] - point2[0])**2 + (point1[1] - point2[1])**2 + (point1[2] - point2[2])**2)
def wait_for_point(point, max_error, timeout):
start = time.time()
while time.time() < start + timeout:
ned_result = requests.get(f"{base_url}/telemetry/ned")
if ned_result.status_code != 200:
print(f"Ned telemetry fail. status_code={ned_result.status_code}")
exit()
ned_pos = ned_result.json()["info"]["position"]
print(ned_pos)
ned_point = (ned_pos["x"], ned_pos["y"], ned_pos["z"])
distance = euclidean_distance(point, ned_point)
if distance < max_error:
return True
return False
# Arming vehicle
arm_result = requests.get(f"{base_url}/command/arm")
if arm_result.status_code != 200:
print(f"Arm command fail. status_code={arm_result.status_code}")
exit()
print("Vehicle armed.")
# Taking off
params = {"alt": 30}
takeoff_result = requests.get(f"{base_url}/command/takeoff", params=params)
if takeoff_result.status_code != 200:
print(f"Take off command fail. status_code={takeoff_result.status_code}")
exit()
print("Vehicle took off")
square_points = [
(100, 100, -50),
(100, -100, -50),
(-100, -100, -50),
(-100, 100, -50)
]
# Moving
for point in square_points:
point_data = {
"x": point[0],
"y": point[1],
"z": point[2]
}
point_result = requests.post(f"{base_url}/movement/go_to_ned", json=point_data)
if point_result.status_code != 200:
print(f"Go_to_ned command fail. status_code={point_result.status_code} point={point}")
exit()
arrived = wait_for_point(point, max_error=3, timeout=60)
if not arrived:
print(f"Error while going to point {point}")
exit()
print(f"Vehicle at ({point[0]}, {point[1]}, {point[2]})")
# Returning to launch
rtl_result = requests.get(f"{base_url}/command/rtl")
if rtl_result.status_code != 200:
print(f"RTL command fail. status_code={rtl_result.status_code}")
exit()
print("Vehicle landed at launch.")