Skip to content

Commit

Permalink
Multidrone in BetaAviary using different UDP ports
Browse files Browse the repository at this point in the history
  • Loading branch information
JacopoPan committed Oct 11, 2023
1 parent 645b7d5 commit 65fbd1c
Show file tree
Hide file tree
Showing 2 changed files with 22 additions and 16 deletions.
34 changes: 20 additions & 14 deletions gym_pybullet_drones/envs/BetaAviary.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,10 @@
from gym_pybullet_drones.envs.BaseAviary import BaseAviary
from gym_pybullet_drones.utils.enums import DroneModel, Physics

BASE_PORT_PWM=9002 # In
BASE_PORT_STATE=9003 # Out
BASE_PORT_RC=9004 # Out

class BetaAviary(BaseAviary):
"""Multi-drone environment class for use of BetaFlight controller."""

Expand Down Expand Up @@ -80,13 +84,15 @@ def __init__(self,
self.ARM_TIME = 1
self.TRAJ_TIME = 1.5

self.sock = socket.socket(socket.AF_INET, # Internet
socket.SOCK_DGRAM) # UDP

self.sock_pwm = socket.socket(socket.AF_INET, # Internet
socket.SOCK_DGRAM) # UDP
self.sock_pwm.bind((self.UDP_IP, 9002))
self.sock_pwm.settimeout(0.0)
self.sock = []
self.sock_pwm = []
for i in range(self.NUM_DRONES):
self.sock.append(socket.socket(socket.AF_INET, # Internet
socket.SOCK_DGRAM)) # UDP
self.sock_pwm.append(socket.socket(socket.AF_INET, # Internet
socket.SOCK_DGRAM)) # UDP
self.sock_pwm[i].bind((self.UDP_IP, BASE_PORT_PWM + 10 * (i))) # drone0 will be on 9002, drone1 on 9012, etc.
self.sock_pwm[i].settimeout(0.0)

self.beta_action = np.zeros((self.NUM_DRONES, 4))

Expand All @@ -100,7 +106,7 @@ def step(self, action, i):
for j in range(self.NUM_DRONES): #TODO: add multi-drone support

#### State message to Betaflight ###########################
o = obs[0] # p, q, euler, v, w, rpm (all in world frame)
o = obs[j,:] # p, q, euler, v, w, rpm (all in world frame)
p = o[:3]
q = np.array([o[6], o[3], o[4], o[5]]) # w, x, y, z
v = o[10:13]
Expand All @@ -118,7 +124,7 @@ def step(self, action, i):
0, 0, 0, # double position_xyz[3]
1.0 # double pressure;
)
self.sock.sendto(fdm_packet, (self.UDP_IP, 9003))
self.sock[j].sendto(fdm_packet, (self.UDP_IP, BASE_PORT_STATE + 10 * (j))) # drone0 will be on 9003, drone1 on 9013, etc.

# Action is (thro, roll, pitch, yaw)
thro = 1000 # Positive up
Expand All @@ -127,7 +133,7 @@ def step(self, action, i):
roll = 1500 # Positive right/forward in y

if t > self.TRAJ_TIME:
thro, roll, pitch, yaw = self.ctbr2beta(*action[0])
thro, roll, pitch, yaw = self.ctbr2beta(*action[j,:])

#### RC message to Betaflight ##############################
aux1 = 1000 if t < self.ARM_TIME else 1500 # Arm
Expand All @@ -140,18 +146,18 @@ def step(self, action, i):
1000, 1000, 1000, 1000
)
# print("rc", struct.unpack('@dHHHHHHHHHHHHHHHH', rc_packet))
self.sock.sendto(rc_packet, (self.UDP_IP, 9004))
self.sock[j].sendto(rc_packet, (self.UDP_IP, BASE_PORT_RC + 10 * (j))) # drone0 will be on 9004, drone1 on 9014, etc.

#### PWMs message from Betaflight ##########################
try:
data, addr = self.sock_pwm.recvfrom(16) # buffer size is 100 bytes (servo_packet size 16)
data, addr = self.sock_pwm[j].recvfrom(16) # buffer size is 100 bytes (servo_packet size 16)
except socket.error as msg:
_action = self.beta_action
_action = self.beta_action[j,:]
pass
else:
# print("received message: ", data)
_action = np.array(struct.unpack('@ffff', data)).reshape((1,4))
self.beta_action = _action
self.beta_action[j,:] = _action

return obs, reward, terminated, truncated, info

Expand Down
4 changes: 2 additions & 2 deletions gym_pybullet_drones/examples/beta.py
Original file line number Diff line number Diff line change
Expand Up @@ -54,8 +54,8 @@
DEFAULT_CONTROL_FREQ_HZ = 500
DEFAULT_DURATION_SEC = 20
DEFAULT_OUTPUT_FOLDER = 'results'
NUM_DRONES = 1
INIT_XYZ = np.array([[.5*i, .5*i, .1] for i in range(NUM_DRONES)])
NUM_DRONES = 2
INIT_XYZ = np.array([[.3*i, .3*i, .1] for i in range(NUM_DRONES)])
INIT_RPY = np.array([[.0, .0, .0] for _ in range(NUM_DRONES)])

def run(
Expand Down

0 comments on commit 65fbd1c

Please sign in to comment.