Paparazzi UAS
v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
Toggle main menu visibility
Main Page
Related Pages
Topics
Data Structures
Data Structures
Data Structure Index
Data Fields
All
_
a
b
c
d
e
f
g
h
i
j
k
l
m
n
o
p
q
r
s
t
u
v
w
x
y
z
Functions
Variables
_
a
b
c
d
e
f
g
h
i
j
k
l
m
n
o
p
q
r
s
t
u
v
w
x
y
z
Enumerator
Files
File List
Globals
All
_
a
b
c
d
e
f
g
h
i
j
k
l
m
n
o
p
q
r
s
t
u
v
w
x
y
z
Functions
_
a
b
c
d
e
f
g
h
i
j
k
l
m
n
o
p
q
r
s
t
u
v
w
x
y
Variables
_
a
b
c
d
e
f
g
h
i
j
k
l
m
n
o
p
q
r
s
t
u
v
w
x
y
z
Typedefs
a
b
c
d
e
f
g
h
i
j
m
n
p
r
s
t
u
v
w
Enumerations
a
b
c
d
e
f
g
h
i
j
l
m
n
o
p
q
r
s
t
v
w
z
Enumerator
a
b
c
d
e
f
g
h
i
j
l
m
n
o
p
q
r
s
t
u
v
w
x
y
z
Macros
_
a
b
c
d
e
f
g
h
i
j
k
l
m
n
o
p
q
r
s
t
u
v
w
x
y
z
•
All
Data Structures
Namespaces
Files
Functions
Variables
Typedefs
Enumerations
Enumerator
Macros
Modules
Pages
Loading...
Searching...
No Matches
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.
dt
=dt
23
if
GUI:
24
self.
physicsClient
=
p.connect
(
p.GUI
)
25
else
:
26
self.
physicsClient
=
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.
planeId
=
p.loadURDF
(
"plane.urdf"
)
32
self.
textureId
=
p.loadTexture
(
"checker_grid.jpg"
)
33
34
self.
vehicle_start_pos
= [0, 0, 0.2]
35
self.
vehicle_start_orientation
=
p.getQuaternionFromEuler
([0, 0, 0])
36
37
vehicule_urdf =
os.path.join
(PYBULLET_CONF_PATH, urdf)
38
self.
vehicle
=
p.loadURDF
(vehicule_urdf, self.
vehicle_start_pos
, self.
vehicle_start_orientation
)
39
40
# Bullet physics uses ENU frame
41
p.setGravity
(0, 0, -9.81, physicsClientId=self.
physicsClient
)
42
# Real time simulation should be off in order to apply external force and moments !
43
p.setRealTimeSimulation
(0, physicsClientId=self.
physicsClient
)
44
# dt : Time step
45
p.setTimeStep
(self.
dt
, physicsClientId=self.
physicsClient
)
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.
KF
= 0.01 ; self.KM = 0.001
50
# Initialte velocity and acceleration vectors
51
self.
vel
=
np.zeros
(3)
52
self.
accel
=
np.zeros
(3)
53
# Initialte angular velocity and acceleration vectors
54
self.
ang_vel
=
np.zeros
(3)
55
self.
ang_accel
=
np.zeros
(3)
56
57
# State
58
self.
observation
= {}
59
60
# For debug purposes
61
if
debug:
62
p.setGravity
(0, 0, 0, physicsClientId=self.
physicsClient
)
63
self.
roll_Id
=
p.addUserDebugParameter
(
"roll_cmd"
, -0.01, 0.01, 0)
64
self.
pitch_Id
=
p.addUserDebugParameter
(
"pitch_cmd"
, -0.01, 0.01, 0)
65
self.
yaw_Id
=
p.addUserDebugParameter
(
"yaw_cmd"
, -0.01, 0.01, 0)
66
13
def
__init__
(self, dt=0.02, GUI=True, debug=False, urdf="robobee.urdf"):
…
67
def
apply_force_and_moments
(self,rpm):
68
''' rpm = [ quadrotor prop rpms ]'''
69
forces =
np.array
(rpm**2)*self.
KF
70
torques =
np.array
(rpm**2)*self.KM
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.
vehicle
,
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.
physicsClient
89
)
90
p.applyExternalTorque
(self.
vehicle
,
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.
physicsClient
95
)
96
67
def
apply_force_and_moments
(self,rpm):
…
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_moments
(commands)
111
p.stepSimulation
(physicsClientId=self.
physicsClient
)
112
return
self.
get_observation
()
113
97
def
step
(self,commands):
…
114
def
step_debug
(self,commands):
115
# commands are not used...
116
roll_cmd =
p.readUserDebugParameter
(self.
roll_Id
)
117
pitch_cmd =
p.readUserDebugParameter
(self.
pitch_Id
)
118
yaw_cmd =
p.readUserDebugParameter
(self.
yaw_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.
vehicle
,
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.
physicsClient
133
)
134
135
p.stepSimulation
(physicsClientId=self.
physicsClient
)
136
return
self.
get_observation
()
137
114
def
step_debug
(self,commands):
…
138
def
get_observation
(self):
139
# Get observation
140
v_pos, v_quat =
p.getBasePositionAndOrientation
(self.
vehicle
)
141
# print(v_Pos, type(v_Pos))
142
v_rpy =
p.getEulerFromQuaternion
(v_quat)
143
v_vel, v_ang_v =
p.getBaseVelocity
(self.
vehicle
)
144
145
self.
accel
= (
np.array
(v_vel) - self.
vel
)/self.
dt
146
self.
vel
=
np.array
(v_vel)
147
self.
ang_accel
= (
np.array
(v_ang_v) - self.
ang_vel
)/self.
dt
148
self.
ang_vel
=
np.array
(v_ang_v)
149
150
self.
observation
= {
'pos'
:v_pos,
151
'quat'
:v_quat,
152
'rpy'
:v_rpy,
153
'vel'
:
tuple
(self.
vel
),
154
'ang_v'
:
tuple
(self.
ang_vel
),
155
'accel'
:
tuple
(self.
accel
),
156
'ang_accel'
:
tuple
(self.
ang_accel
)
157
}
158
return
self.
observation
159
138
def
get_observation
(self):
…
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.
vehicle
, self.
vehicle_start_pos
, self.
vehicle_start_orientation
)
164
p.resetBaseVelocity
(self.
vehicle
, [0, 0, 0], [0, 0, 0])
165
166
return
self.
get_observation
()
167
168
169
160
def
reset
(self):
…
12
class
BulletFDM
():
…
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
()
reset
static uint8_t reset[3]
Definition
baro_MS5534A.c:83
simple_quad_sim.BulletFDM
Definition
simple_quad_sim.py:12
simple_quad_sim.BulletFDM.accel
accel
Definition
simple_quad_sim.py:52
simple_quad_sim.BulletFDM.dt
dt
Definition
simple_quad_sim.py:22
simple_quad_sim.BulletFDM.roll_Id
roll_Id
Definition
simple_quad_sim.py:63
simple_quad_sim.BulletFDM.yaw_Id
yaw_Id
Definition
simple_quad_sim.py:65
simple_quad_sim.BulletFDM.step_debug
step_debug(self, commands)
Definition
simple_quad_sim.py:114
simple_quad_sim.BulletFDM.physicsClient
physicsClient
Definition
simple_quad_sim.py:24
simple_quad_sim.BulletFDM.vel
vel
Definition
simple_quad_sim.py:51
simple_quad_sim.BulletFDM.textureId
textureId
Definition
simple_quad_sim.py:32
simple_quad_sim.BulletFDM.vehicle_start_pos
vehicle_start_pos
Definition
simple_quad_sim.py:34
simple_quad_sim.BulletFDM.apply_force_and_moments
apply_force_and_moments(self, rpm)
Definition
simple_quad_sim.py:67
simple_quad_sim.BulletFDM.ang_accel
ang_accel
Definition
simple_quad_sim.py:55
simple_quad_sim.BulletFDM.KF
KF
Definition
simple_quad_sim.py:49
simple_quad_sim.BulletFDM.planeId
planeId
Definition
simple_quad_sim.py:31
simple_quad_sim.BulletFDM.__init__
__init__(self, dt=0.02, GUI=True, debug=False, urdf="robobee.urdf")
Definition
simple_quad_sim.py:13
simple_quad_sim.BulletFDM.pitch_Id
pitch_Id
Definition
simple_quad_sim.py:64
simple_quad_sim.BulletFDM.ang_vel
ang_vel
Definition
simple_quad_sim.py:54
simple_quad_sim.BulletFDM.vehicle
vehicle
Definition
simple_quad_sim.py:38
simple_quad_sim.BulletFDM.vehicle_start_orientation
vehicle_start_orientation
Definition
simple_quad_sim.py:35
simple_quad_sim.BulletFDM.observation
observation
Definition
simple_quad_sim.py:58
simple_quad_sim.BulletFDM.get_observation
get_observation(self)
Definition
simple_quad_sim.py:138
foo
uint16_t foo
Definition
main_demo5.c:58
step
uint8_t step
Definition
max7456.c:141
sw
simulator
nps
pybullet
simple_quad_sim.py
Generated on Fri Apr 4 2025 14:56:52 for Paparazzi UAS by
1.9.8