Paparazzi UAS  v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
simple_quad_sim.py
Go to the documentation of this file.
1 import pybullet as p
2 import pybullet_data
3 import numpy as np
4 import time
5 import os
6 
7 
8 PPRZ_HOME = os.getenv("PAPARAZZI_HOME", os.getcwd())
9 PYBULLET_CONF_PATH = os.path.join(PPRZ_HOME, "conf/simulator/pybullet")
10 
11 
12 class BulletFDM():
13  def __init__(self, dt=0.02, GUI=True, debug=False, urdf="robobee.urdf"):
14  print(f"Hello from PyBullet ! dt={dt}, GUI={GUI} debug={debug}")
15 
16  pprz_src = os.getenv("PAPARAZZI_SRC")
17  print(f"pprz_src = {pprz_src}")
18 
19  # self.last_time_print = 0
20 
21  # dt : Time step
22  self.dtdt=dt
23  if GUI:
24  self.physicsClientphysicsClient = p.connect(p.GUI)
25  else:
26  self.physicsClientphysicsClient = p.connect(p.DIRECT)
27 
28  # Add path for pybullet assests e.g : plane and grid...
29  p.setAdditionalSearchPath(pybullet_data.getDataPath())
30 
31  self.planeIdplaneId = p.loadURDF("plane.urdf")
32  self.textureIdtextureId = p.loadTexture("checker_grid.jpg")
33 
34  self.vehicle_start_posvehicle_start_pos = [0, 0, 0.2]
35  self.vehicle_start_orientationvehicle_start_orientation = p.getQuaternionFromEuler([0, 0, 0])
36 
37  vehicule_urdf = os.path.join(PYBULLET_CONF_PATH, urdf)
38  self.vehiclevehicle = p.loadURDF(vehicule_urdf, self.vehicle_start_posvehicle_start_pos, self.vehicle_start_orientationvehicle_start_orientation)
39 
40  # Bullet physics uses ENU frame
41  p.setGravity(0, 0, -9.81, physicsClientId=self.physicsClientphysicsClient)
42  # Real time simulation should be off in order to apply external force and moments !
43  p.setRealTimeSimulation(0, physicsClientId=self.physicsClientphysicsClient)
44  # dt : Time step
45  p.setTimeStep(self.dtdt, physicsClientId=self.physicsClientphysicsClient)
46  # Orient the camera if needed
47  p.resetDebugVisualizerCamera( cameraDistance=3.5, cameraYaw=-80, cameraPitch=-40, cameraTargetPosition=[0.0, 0.0, 0.0])
48  # Vehicle properties
49  self.KFKF = 0.01 ; self.KMKM = 0.001
50  # Initialte velocity and acceleration vectors
51  self.velvel = np.zeros(3)
52  self.accelaccel = np.zeros(3)
53  # Initialte angular velocity and acceleration vectors
54  self.ang_velang_vel = np.zeros(3)
55  self.ang_accelang_accel = np.zeros(3)
56 
57  # State
58  self.observationobservation = {}
59 
60  # For debug purposes
61  if debug:
62  p.setGravity(0, 0, 0, physicsClientId=self.physicsClientphysicsClient)
63  self.roll_Idroll_Id = p.addUserDebugParameter("roll_cmd", -0.01, 0.01, 0)
64  self.pitch_Idpitch_Id = p.addUserDebugParameter("pitch_cmd", -0.01, 0.01, 0)
65  self.yaw_Idyaw_Id = p.addUserDebugParameter("yaw_cmd", -0.01, 0.01, 0)
66 
67  def apply_force_and_moments(self,rpm):
68  ''' rpm = [ quadrotor prop rpms ]'''
69  forces = np.array(rpm**2)*self.KFKF
70  torques = np.array(rpm**2)*self.KMKM
71 
72  f_noise = np.random.normal(0, 0.01, len(rpm))
73  m_noise = np.random.normal(0, 0.001,len(rpm))
74 
75  # f_noise = np.zeros(4)
76  # m_noise = np.zeros(4)
77 
78  forces += f_noise
79  torques += m_noise
80 
81  z_torque = (torques[0] - torques[1] + torques[2] - torques[3])
82  for i in range(4): #FIXME : decide according to commands length
83  p.applyExternalForce(self.vehiclevehicle,
84  i,
85  forceObj=[f_noise[0], f_noise[1], forces[i]],
86  posObj=[0, 0, 0],
87  flags=p.LINK_FRAME,
88  physicsClientId=self.physicsClientphysicsClient
89  )
90  p.applyExternalTorque(self.vehiclevehicle,
91  -1, # FIXME : this is not correct , use center of mass !!!
92  torqueObj=[m_noise[0], m_noise[1], z_torque],
93  flags=p.LINK_FRAME,
94  physicsClientId=self.physicsClientphysicsClient
95  )
96 
97  def step(self,commands):
98 
99  if not isinstance(commands, np.ndarray):
100  commands = np.array(commands)
101 
102  # little hack to scale commands. It should probably be in the URDF file.
103  commands *= 30
104 
105  # t = time.time()
106  # if (t - self.last_time_print) > 0.5:
107  # self.last_time_print = t
108  # print(f"{commands[0]:.2f} {commands[1]:.2f} {commands[2]:.2f} {commands[3]:.2f}")
109 
110  self.apply_force_and_momentsapply_force_and_moments(commands)
111  p.stepSimulation(physicsClientId=self.physicsClientphysicsClient)
112  return self.get_observationget_observation()
113 
114  def step_debug(self,commands):
115  # commands are not used...
116  roll_cmd = p.readUserDebugParameter(self.roll_Idroll_Id)
117  pitch_cmd = p.readUserDebugParameter(self.pitch_Idpitch_Id)
118  yaw_cmd = p.readUserDebugParameter(self.yaw_Idyaw_Id)
119 
120  # p.applyExternalForce(self.vehicle,
121  # -1,
122  # forceObj=[0, 0, 9 + yaw_cmd*100],
123  # posObj=[0, 0, 0],
124  # flags=p.LINK_FRAME,
125  # physicsClientId=self.physicsClient
126  # )
127 
128  p.applyExternalTorque(self.vehiclevehicle,
129  -1, # FIXME : this is not correct , use center of mass !!!
130  torqueObj=[roll_cmd, pitch_cmd, yaw_cmd],
131  flags=p.LINK_FRAME,
132  physicsClientId=self.physicsClientphysicsClient
133  )
134 
135  p.stepSimulation(physicsClientId=self.physicsClientphysicsClient)
136  return self.get_observationget_observation()
137 
138  def get_observation(self):
139  # Get observation
140  v_pos, v_quat = p.getBasePositionAndOrientation(self.vehiclevehicle)
141  # print(v_Pos, type(v_Pos))
142  v_rpy = p.getEulerFromQuaternion(v_quat)
143  v_vel, v_ang_v = p.getBaseVelocity(self.vehiclevehicle)
144 
145  self.accelaccel = (np.array(v_vel) - self.velvel)/self.dtdt
146  self.velvel = np.array(v_vel)
147  self.ang_accelang_accel = (np.array(v_ang_v) - self.ang_velang_vel)/self.dtdt
148  self.ang_velang_vel = np.array(v_ang_v)
149 
150  self.observationobservation = {'pos':v_pos,
151  'quat':v_quat,
152  'rpy':v_rpy,
153  'vel':tuple(self.velvel),
154  'ang_v':tuple(self.ang_velang_vel),
155  'accel':tuple(self.accelaccel),
156  'ang_accel':tuple(self.ang_accelang_accel)
157  }
158  return self.observationobservation
159 
160  def reset(self):
161  # Reset the simulation and the state
162  # p.resetSimulation(physicsClientId=self.physicsClient) # FIXME : this is not the correct way to reset the simulation
163  p.resetBasePositionAndOrientation(self.vehiclevehicle, self.vehicle_start_posvehicle_start_pos, self.vehicle_start_orientationvehicle_start_orientation)
164  p.resetBaseVelocity(self.vehiclevehicle, [0, 0, 0], [0, 0, 0])
165 
166  return self.get_observationget_observation()
167 
168 
169 
170 if __name__ == "__main__":
171  from time import sleep
172  debug = True
173  m = BulletFDM(GUI=True, debug=debug)
174 
175  # An example simulation loop with random commands generation
176  while 1:
177  for i in range(200):
178  # commands = np.array([10., 10., 10., 10.]) # fixed rpms
179  commands = np.random.normal(13., 0.5, 4) # random rpms
180  if debug:
181  m.step_debug(commands)
182  else:
183  m.step(commands)
184  sleep(0.05) # FIXME : checck the computation time and sleep to sync realtime...
185  m.reset()
def apply_force_and_moments(self, rpm)
def step(self, commands)
def step_debug(self, commands)
def __init__(self, dt=0.02, GUI=True, debug=False, urdf="robobee.urdf")