Hi everyone. Im new to simulations and trying to figure out how to create and control multiple drones in PX4 + gazebo classic using Python MAVSDK. In single drone simulations everything is working ok.
Im starting multiple simulations by executing
Tools/simulation/gazebo-classic/sitl_multiple_run.sh -m iris -n 2
Next i`m running following script but only one drone is taking off. Tried everything and can make this work correctly. Thanks for any help
import asyncio
from mavsdk import System
async def connect_drone(port):
drone = System()
await drone.connect(system_address=f"udp://:{port}")
async for state in drone.core.connection_state():
if state.is_connected:
print(f"Connected to drone on port {port}")
break
async for health in drone.telemetry.health():
if health.is_global_position_ok and health.is_home_position_ok:
print(f"Drone on port {port} is ready to arm")
break
id = await drone.info.get_identification()
print(f"UUID of drone : {id}")
return drone
async def run():
ports = [14541, 14542]
drones = await asyncio.gather(*(connect_drone(port) for port in ports))
# Arm all drones
await asyncio.gather(*(d.action.arm() for d in drones))
print("All drones armed")
# Take off
await asyncio.gather(*(d.action.takeoff() for d in drones))
print("All drones taking off")
await asyncio.sleep(10)
asyncio.run(run())
PS running on Windows11 with WSL2 and Ubuntu 20.04
I am actually working on the same problem. But today i figured that if we sequentially run them we can move them one after another - But my requirement is to be able to control multiple together even groups together.
I’m running on windows 11 with WSL and ubuntu 24.04.
Code:
import asyncio
from mavsdk import System
from mavsdk.offboard import OffboardError, VelocityNedYaw
async def run_mission(port: int):
drone = System()
print(f"Connecting to drone at port {port}...")
await drone.connect(system_address=f"udp://:{port}")
# Wait until the drone is connected.
async for state in drone.core.connection_state():
if state.is_connected:
print(f"Drone on port {port} connected!")
break
# Wait until global and home positions are set.
async for health in drone.telemetry.health():
if health.is_global_position_ok and health.is_home_position_ok:
print(f"Drone on port {port} is healthy and ready!")
break
print(f"Arming drone on port {port}...")
await drone.action.arm()
print(f"Taking off drone on port {port}...")
await drone.action.takeoff()
await asyncio.sleep(10) # Wait for takeoff altitude
print(f"Setting initial offboard setpoint (zero velocity) on port {port}...")
await drone.offboard.set_velocity_ned(VelocityNedYaw(0.0, 0.0, 0.0, 0.0))
print(f"Starting offboard mode on port {port}...")
try:
await drone.offboard.start()
except OffboardError as error:
print(f"Failed to start offboard mode on port {port}: {error._result.result}")
print("Disarming drone...")
await drone.action.disarm()
return
print(f"Sending velocity command: move forward at 1 m/s on port {port}...")
await drone.offboard.set_velocity_ned(VelocityNedYaw(1.0, 0.0, 0.0, 0.0))
await asyncio.sleep(10)
print(f"Stopping drone on port {port}...")
await drone.offboard.set_velocity_ned(VelocityNedYaw(0.0, 0.0, 0.0, 0.0))
await asyncio.sleep(5)
print(f"Landing drone on port {port}...")
await drone.action.land()
await asyncio.sleep(10)
print(f"Disarming drone on port {port}...")
await drone.action.disarm()
print(f"Mission sequence for drone on port {port} completed.")
async def main():
# Run mission for the drone on port 14541 first.
await run_mission(14541)
print("Waiting 5 seconds before starting mission for the next drone...")
await asyncio.sleep(5)
# Then run mission for the drone on port 14540.
await run_mission(14540)
if __name__ == "__main__":
asyncio.run(main())
I was able to find solution. I used gz harmonic and Ubuntu 22.04 on WSL
We can use different ports for System()
. And it works
async def connect_drone(system_address, i):
drone = System(port=50051 + i)
await drone.connect(system_address=system_address)
print(f"[{system_address}] Waiting for connection...")
async for state in drone.core.connection_state():
if state.is_connected:
print(f"[{system_address}] Drone connected!")
break
print(f"[{system_address}] Waiting for global position estimate...")
async for health in drone.telemetry.health():
if health.is_global_position_ok and health.is_home_position_ok:
print(f"[{system_address}] Global position is OK.")
break
return drone
async def arm_and_takeoff(drone, system_address, height):
print(f"[{system_address}] Arming...")
await drone.action.arm()
print(f"[{system_address}] Taking off...")
await drone.action.set_takeoff_altitude(height)
await drone.action.takeoff()
async for position in drone.telemetry.position():
current = position.relative_altitude_m
if abs(current - height) < threshold:
break
print(f"[{system_address}] Height {height} reached...")
async def land_and_disarm(drone, system_address):
await drone.action.land()
async for position in drone.telemetry.position():
current = position.relative_altitude_m
if abs(current) < threshold:
break
print(f"[{system_address}] Landed...")
async def main():
# Addresses for PX4 SITL instances
address_1 = "udp://:14541"
address_2 = "udp://:14542"
# Connect to both drones
drone1_task = connect_drone(address_1, 0)
drone2_task = connect_drone(address_2, 1)
drone1, drone2 = await asyncio.gather(drone1_task, drone2_task)
# Arm and take off both drones concurrently
await asyncio.gather(
arm_and_takeoff(drone1, address_1, 5),
arm_and_takeoff(drone2, address_2, 10)
)
await asyncio.gather(
land_and_disarm(drone1, address_1),
land_and_disarm(drone2, address_2),
)
Thank you so much!! This works- i have been struggling with this since 3 days and even started trying QGroundControl.
Thanks again for your help!
I also was trying everything for several days) glad i could help