Skip to content

Commit

Permalink
rc_cessna: increase drag and reduce motor torque (#59)
Browse files Browse the repository at this point in the history
* rc_cessna: increase drag and reduce motor torque

* rc_cessna model improvements:

- Add wheels friction
- Motor power tweak
  • Loading branch information
StefanoColli authored Oct 31, 2024
1 parent 536305a commit 448ef6f
Showing 1 changed file with 7 additions and 4 deletions.
11 changes: 7 additions & 4 deletions models/rc_cessna/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -692,6 +692,7 @@
<upper>1.79769e+308</upper>
</limit>
<dynamics>
<friction>0.02</friction>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
Expand All @@ -708,6 +709,7 @@
<upper>1.79769e+308</upper>
</limit>
<dynamics>
<friction>0.02</friction>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
Expand All @@ -724,6 +726,7 @@
<upper>1.79769e+308</upper>
</limit>
<dynamics>
<friction>0.02</friction>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
Expand All @@ -732,7 +735,7 @@
<plugin filename="gz-sim-lift-drag-system" name="gz::sim::systems::LiftDrag">
<a0>0.05984281113</a0>
<cla>4.752798721</cla>
<cda>0.6417112299</cda>
<cda>1.5</cda>
<cma>0.0</cma>
<alpha_stall>0.3391428111</alpha_stall>
<cla_stall>-3.85</cla_stall>
Expand All @@ -756,7 +759,7 @@
<plugin filename="gz-sim-lift-drag-system" name="gz::sim::systems::LiftDrag">
<a0>0.05984281113</a0>
<cla>4.752798721</cla>
<cda>0.6417112299</cda>
<cda>1.5</cda>
<cma>0.0</cma>
<alpha_stall>0.3391428111</alpha_stall>
<cla_stall>-3.85</cla_stall>
Expand Down Expand Up @@ -847,7 +850,7 @@
<cda_stall>-0.9233984055</cda_stall>
<cma_stall>0</cma_stall>
<cp>-0.5 0 0.05</cp>
<area>0.02</area>
<area>0.1</area>
<air_density>1.2041</air_density>
<forward>1 0 0</forward>
<upward>0 1 0</upward>
Expand All @@ -868,7 +871,7 @@
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1000</maxRotVelocity>
<motorConstant>2.44858e-05</motorConstant>
<motorConstant>1.2e-05</motorConstant>
<momentConstant>0.016</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>0</motorNumber>
Expand Down

0 comments on commit 448ef6f

Please sign in to comment.