8 PPRZ_HOME = os.getenv(
"PAPARAZZI_HOME", os.getcwd())
9 PYBULLET_CONF_PATH = os.path.join(PPRZ_HOME,
"conf/simulator/pybullet")
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}")
16 pprz_src = os.getenv(
"PAPARAZZI_SRC")
17 print(f
"pprz_src = {pprz_src}")
29 p.setAdditionalSearchPath(pybullet_data.getDataPath())
31 self.
planeIdplaneId = p.loadURDF(
"plane.urdf")
32 self.
textureIdtextureId = p.loadTexture(
"checker_grid.jpg")
37 vehicule_urdf = os.path.join(PYBULLET_CONF_PATH, urdf)
41 p.setGravity(0, 0, -9.81, physicsClientId=self.
physicsClientphysicsClient)
43 p.setRealTimeSimulation(0, physicsClientId=self.
physicsClientphysicsClient)
45 p.setTimeStep(self.
dtdt, physicsClientId=self.
physicsClientphysicsClient)
47 p.resetDebugVisualizerCamera( cameraDistance=3.5, cameraYaw=-80, cameraPitch=-40, cameraTargetPosition=[0.0, 0.0, 0.0])
49 self.
KFKF = 0.01 ; self.
KMKM = 0.001
51 self.
velvel = np.zeros(3)
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)
68 ''' rpm = [ quadrotor prop rpms ]'''
69 forces = np.array(rpm**2)*self.
KFKF
70 torques = np.array(rpm**2)*self.
KMKM
72 f_noise = np.random.normal(0, 0.01, len(rpm))
73 m_noise = np.random.normal(0, 0.001,len(rpm))
81 z_torque = (torques[0] - torques[1] + torques[2] - torques[3])
83 p.applyExternalForce(self.
vehiclevehicle,
85 forceObj=[f_noise[0], f_noise[1], forces[i]],
90 p.applyExternalTorque(self.
vehiclevehicle,
92 torqueObj=[m_noise[0], m_noise[1], z_torque],
99 if not isinstance(commands, np.ndarray):
100 commands = np.array(commands)
111 p.stepSimulation(physicsClientId=self.
physicsClientphysicsClient)
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)
128 p.applyExternalTorque(self.
vehiclevehicle,
130 torqueObj=[roll_cmd, pitch_cmd, yaw_cmd],
135 p.stepSimulation(physicsClientId=self.
physicsClientphysicsClient)
140 v_pos, v_quat = p.getBasePositionAndOrientation(self.
vehiclevehicle)
142 v_rpy = p.getEulerFromQuaternion(v_quat)
143 v_vel, v_ang_v = p.getBaseVelocity(self.
vehiclevehicle)
145 self.
accelaccel = (np.array(v_vel) - self.
velvel)/self.
dtdt
146 self.
velvel = np.array(v_vel)
148 self.
ang_velang_vel = np.array(v_ang_v)
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)
164 p.resetBaseVelocity(self.
vehiclevehicle, [0, 0, 0], [0, 0, 0])
170 if __name__ ==
"__main__":
171 from time
import sleep
179 commands = np.random.normal(13., 0.5, 4)
181 m.step_debug(commands)
def apply_force_and_moments(self, rpm)
def step_debug(self, commands)
def __init__(self, dt=0.02, GUI=True, debug=False, urdf="robobee.urdf")
def get_observation(self)
vehicle_start_orientation