Skip to content

Commit

Permalink
Merge remote-tracking branch 'origin/main' into 180-forces-and-moment…
Browse files Browse the repository at this point in the history
…s-update
  • Loading branch information
iandareid committed Aug 5, 2024
2 parents f25c5a0 + 7acd3b3 commit ae1dfd6
Show file tree
Hide file tree
Showing 8 changed files with 106 additions and 1,374 deletions.
2 changes: 1 addition & 1 deletion rosflight_sim/launch/fixedwing.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ def generate_launch_description():
'ros_log_level', default_value=TextSubstitution(text='info')
)

aircraft = 'skyhunter' # default aircraft
aircraft = 'anaconda' # default aircraft

for arg in sys.argv:
if arg.startswith("aircraft:="):
Expand Down
96 changes: 96 additions & 0 deletions rosflight_sim/params/aerosonde_dynamics.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,96 @@
# Parameters for ROSflight software-in-the-loop simulation

# Mass and inertia parameters are defined in fixedwing.urdf.xacro.
# Mass: 11.0
# Jx: 0.8244
# Jy: 1.135
# Jz: 1.759
# Jxz: 0.1204

/fixedwing/rosflight_sil:
ros__parameters:
rho: 1.2682
mass: 11.0

wing_s: 0.55
wing_b: 2.8956
wing_c: 0.18994
wing_M: 50.0
wing_epsilon: 0.16
wing_alpha0: 0.47

D_prop : 0.508
CT_0 : 0.09357
CT_1 : -0.06044
CT_2 : -0.1079
CQ_0 : 0.005230
CQ_1 : 0.004970
CQ_2 : -0.01664
KV : 145.0 # Motor speed constant from datasheet in RPM/V
KQ : 0.06586 # ((1 /KV_rpm_per_volt) * 60 / (2 * M_PI))
# Back-emf constant, KV in V-s/rad, Motor torque constant, KQ in N-m/A
V_max : 44.4 # voltage for 12s battery at 3.7 volts per cell
R_motor : 0.042 # ohms
I_0 : 1.5 # no-load (zero torque) current (A)

servo_tau: .02

C_L_O: 0.23
C_L_alpha: 5.61
C_L_beta: 0.0
C_L_p: 0.0
C_L_q: 7.95
C_L_r: 0.0
C_L_delta_a: 0.0
C_L_delta_e: 0.13
C_L_delta_r: 0.0

C_D_O: 0.043
C_D_alpha: 0.03
C_D_beta: 0.0
C_D_p: 0.0
C_D_q: 0.0
C_D_r: 0.0
C_D_delta_a: 0.0
C_D_delta_e: 0.0135
C_D_delta_r: 0.0

C_ell_O: 0.0
C_ell_alpha: 0.00
C_ell_beta: -0.13
C_ell_p: -0.51
C_ell_q: 0.0
C_ell_r: 0.25
C_ell_delta_a: 0.17
C_ell_delta_e: 0.0
C_ell_delta_r: 0.0024

C_m_O: 0.0135
C_m_alpha: -2.74
C_m_beta: 0.0
C_m_p: 0.0
C_m_q: -38.21
C_m_r: 0.0
C_m_delta_a: 0.0
C_m_delta_e: -0.99
C_m_delta_r: 0.0

C_n_O: 0.0
C_n_alpha: 0.0
C_n_beta: 0.073
C_n_p: 0.069
C_n_q: 0.0
C_n_r: -0.095
C_n_delta_a: -0.011
C_n_delta_e: 0.0
C_n_delta_r: -0.069

C_Y_O: 0.0
C_Y_alpha: 0.00
C_Y_beta: -0.98
C_Y_p: 0.0
C_Y_q: 0.0
C_Y_r: 0.0
C_Y_delta_a: 0.075
C_Y_delta_e: 0.0
C_Y_delta_r: 0.19
96 changes: 0 additions & 96 deletions rosflight_sim/params/skyhunter_dynamics.yaml

This file was deleted.

4 changes: 2 additions & 2 deletions rosflight_sim/resources/runway.world
Original file line number Diff line number Diff line change
Expand Up @@ -51,8 +51,8 @@
<surface>
<friction>
<ode>
<mu>0.25</mu>
<mu2>0.25</mu2>
<mu>0.1</mu>
<mu2>0.1</mu2>
</ode>
</friction>
</surface>
Expand Down
Loading

0 comments on commit ae1dfd6

Please sign in to comment.