Skip to content

Commit

Permalink
Revert "Pr liftdrag coefficients (#690)" (#730)
Browse files Browse the repository at this point in the history
This reverts commit 38224fb.

Co-authored-by: Pieter-Jan Dewitte <pj.dewitte@gmail.com>
  • Loading branch information
Jaeyoung-Lim and pjdewitte authored Mar 16, 2021
1 parent 6b6f474 commit b195315
Show file tree
Hide file tree
Showing 10 changed files with 180 additions and 198 deletions.
31 changes: 13 additions & 18 deletions include/liftdrag_plugin/liftdrag_plugin.h
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ namespace gazebo
/// where q (dynamic pressure) = 0.5 * rho * v^2
protected: double cma;

/// \brief angle of attack when airfoil stalls, relative to alpha0
/// \brief angle of attack when airfoil stalls
protected: double alphaStall;

/// \brief Cl-alpha rate after stall
Expand All @@ -84,6 +84,9 @@ namespace gazebo
/// \brief Cm-alpha rate after stall
protected: double cmaStall;

/// \breif Coefficient of Moment / control surface deflection angle slope
protected: double cm_delta;

/// \brief: \TODO: make a stall velocity curve
protected: double velocityStall;

Expand All @@ -101,19 +104,16 @@ namespace gazebo
/// \brief effective planeform surface area
protected: double area;

/// \brief angle of attack at which the lift is zero
protected: double alpha0;

/// \brief Cd at zero lift (zero-lift drag coefficient)
protected: double cd_alpha0;
/// \brief angle of sweep
protected: double sweep;

/// \brief Cm at zero lift (zero-lift moment coefficient)
protected: double cm_alpha0;
/// \brief initial angle of attack
protected: double alpha0;

/// \brief angle of attack, relative to alpha0
/// \brief angle of attack
protected: double alpha;

/// \brief center of pressure relative to the center of gravity of the link, in link local orientation
/// \brief center of pressure in link local coordinates
protected: ignition::math::Vector3d cp;

/// \brief Normally, this is taken as a direction parallel to the chord
Expand All @@ -132,14 +132,9 @@ namespace gazebo
/// this lifting body
protected: physics::JointPtr controlJoint;

/// \brief How much to change CL per radian of control surface deflection
protected: double cl_delta;

/// \brief How much to change CD per radian of control surface deflection
protected: double cd_delta;

/// \brief How much to change CM per radian of control surface deflection
protected: double cm_delta;
/// \brief how much to change CL per radian of control surface joint
/// value.
protected: double controlJointRadToCL;

/// \brief SDF for this plugin;
protected: sdf::ElementPtr sdf;
Expand Down
4 changes: 2 additions & 2 deletions models/matrice_100/matrice_100.sdf.jinja
Original file line number Diff line number Diff line change
Expand Up @@ -190,7 +190,7 @@
</joint>

<!--<plugin name="rotor_{{n}}_top_blade" filename="libLiftDragPlugin.so">-->
<!--<alpha0>{{rtr_a0}}</alpha0>-->
<!--<a0>{{rtr_a0}}</a0>-->
<!--<cla>{{rtr_cla}}</cla>-->
<!--<cda>{{rtr_cda}}</cda>-->
<!--<cma>{{rtr_cma}}</cma>-->
Expand All @@ -207,7 +207,7 @@
<!--</plugin>-->

<!--<plugin name="rotor_{{n}}_bottom_blade" filename="libLiftDragPlugin.so">-->
<!--<alpha0>{{rtr_a0}}</alpha0>-->
<!--<a0>{{rtr_a0}}</a0>-->
<!--<cla>{{rtr_cla}}</cla>-->
<!--<cda>{{rtr_cda}}</cda>-->
<!--<cma>{{rtr_cma}}</cma>-->
Expand Down
2 changes: 1 addition & 1 deletion models/parachute_small/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@
</link>

<plugin name="parachute_drag" filename="libLiftDragPlugin.so">
<alpha0>0</alpha0>
<a0>0</a0>
<cla>0</cla>
<cda>1.114</cda> <!-- Such that Cd = 1.75 at alpha = 90deg (= upright parachute) -->
<cma>0</cma>
Expand Down
96 changes: 40 additions & 56 deletions models/plane/plane.sdf.jinja
Original file line number Diff line number Diff line change
Expand Up @@ -187,7 +187,7 @@
</axis>
</joint>

<link name="left_aileron">
<link name="left_elevon">
<inertial>
<mass>0.00000001</mass>
<inertia>
Expand All @@ -200,7 +200,7 @@
</inertia>
<pose>0 0.3 0 0.00 0 0.0</pose>
</inertial>
<visual name='left_aileron_visual'>
<visual name='left_elevon_visual'>
<pose>0.07 0.0 -0.08 0.00 0 0.0</pose>
<geometry>
<mesh>
Expand All @@ -216,7 +216,7 @@
</material>
</visual>
</link>
<link name="right_aileron">
<link name="right_elevon">
<inertial>
<mass>0.00000001</mass>
<inertia>
Expand All @@ -229,7 +229,7 @@
</inertia>
<pose>0 -0.3 0 0.00 0 0.0</pose>
</inertial>
<visual name='right_aileron_visual'>
<visual name='right_elevon_visual'>
<pose>0.07 0.0 -0.08 0.00 0 0.0</pose>
<geometry>
<mesh>
Expand Down Expand Up @@ -361,9 +361,9 @@
</material>
</visual>
</link>
<joint name='left_aileron_joint' type='revolute'>
<joint name='left_elevon_joint' type='revolute'>
<parent>base_link</parent>
<child>left_aileron</child>
<child>left_elevon</child>
<pose>-0.07 0.4 0.08 0.00 0 0.0</pose>
<axis>
<xyz>0 1 0</xyz>
Expand All @@ -382,9 +382,9 @@
</ode>
</physics>
</joint>
<joint name='right_aileron_joint' type='revolute'>
<joint name='right_elevon_joint' type='revolute'>
<parent>base_link</parent>
<child>right_aileron</child>
<child>right_elevon</child>
<pose>-0.07 -0.4 0.08 0.00 0 0.0</pose>
<axis>
<xyz>0 1 0</xyz>
Expand Down Expand Up @@ -496,13 +496,11 @@
<child>gps::link</child>
<parent>base_link</parent>
</joint>
<plugin name="left_wing_liftdrag" filename="libLiftDragPlugin.so">
<alpha0>-0.009519322</alpha0>
<cd_alpha0>0.003</cd_alpha0>
<cm_alpha0>0.002072715</cm_alpha0>
<plugin name="left_wing" filename="libLiftDragPlugin.so">
<a0>0.05984281113</a0>
<cla>4.752798721</cla>
<cda>0.35</cda>
<cma>0.02</cma>
<cda>0.6417112299</cda>
<cma>0.0</cma>
<alpha_stall>0.3391428111</alpha_stall>
<cla_stall>-3.85</cla_stall>
<cda_stall>-0.9233984055</cda_stall>
Expand All @@ -514,21 +512,17 @@
<upward>0 0 1</upward>
<link_name>base_link</link_name>
<control_joint_name>
left_aileron_joint
left_elevon_joint
</control_joint_name>
<cl_delta>-0.5</cl_delta>
<cd_delta>0.05</cd_delta>
<cm_delta>0.005</cm_delta>
<control_joint_rad_to_cl>-0.5</control_joint_rad_to_cl>
<robotNamespace></robotNamespace>
<windSubTopic>world_wind</windSubTopic>
</plugin>
<plugin name="right_wing_liftdrag" filename="libLiftDragPlugin.so">
<alpha0>-0.009519322</alpha0>
<cd_alpha0>0.003</cd_alpha0>
<cm_alpha0>0.002072715</cm_alpha0>
<plugin name="right_wing" filename="libLiftDragPlugin.so">
<a0>0.05984281113</a0>
<cla>4.752798721</cla>
<cda>0.35</cda>
<cma>0.02</cma>
<cda>0.6417112299</cda>
<cma>0.0</cma>
<alpha_stall>0.3391428111</alpha_stall>
<cla_stall>-3.85</cla_stall>
<cda_stall>-0.9233984055</cda_stall>
Expand All @@ -540,21 +534,17 @@
<upward>0 0 1</upward>
<link_name>base_link</link_name>
<control_joint_name>
right_aileron_joint
right_elevon_joint
</control_joint_name>
<cl_delta>-0.5</cl_delta>
<cd_delta>0.05</cd_delta>
<cm_delta>0.005</cm_delta>
<control_joint_rad_to_cl>-0.5</control_joint_rad_to_cl>
<robotNamespace></robotNamespace>
<windSubTopic>world_wind</windSubTopic>
</plugin>
<plugin name="left_flap_liftdrag" filename="libLiftDragPlugin.so">
<alpha0>-0.009519322</alpha0>
<cd_alpha0>0.003</cd_alpha0>
<cm_alpha0>0.002072715</cm_alpha0>
<plugin name="left_flap" filename="libLiftDragPlugin.so">
<a0>0.05984281113</a0>
<cla>4.752798721</cla>
<cda>0.35</cda>
<cma>0.02</cma>
<cda>0.6417112299</cda>
<cma>0.0</cma>
<alpha_stall>0.3391428111</alpha_stall>
<cla_stall>-3.85</cla_stall>
<cda_stall>-0.9233984055</cda_stall>
Expand All @@ -568,19 +558,15 @@
<control_joint_name>
left_flap_joint
</control_joint_name>
<cl_delta>-0.5</cl_delta>
<cd_delta>0.05</cd_delta>
<cm_delta>0.005</cm_delta>
<control_joint_rad_to_cl>-0.5</control_joint_rad_to_cl>
<robotNamespace></robotNamespace>
<windSubTopic>world_wind</windSubTopic>
</plugin>
<plugin name="right_flap_liftdrag" filename="libLiftDragPlugin.so">
<alpha0>-0.009519322</alpha0>
<cd_alpha0>0.003</cd_alpha0>
<cm_alpha0>0.002072715</cm_alpha0>
<plugin name="right_flap" filename="libLiftDragPlugin.so">
<a0>0.05984281113</a0>
<cla>4.752798721</cla>
<cda>0.35</cda>
<cma>0.02</cma>
<cda>0.6417112299</cda>
<cma>0.0</cma>
<alpha_stall>0.3391428111</alpha_stall>
<cla_stall>-3.85</cla_stall>
<cda_stall>-0.9233984055</cda_stall>
Expand All @@ -594,14 +580,12 @@
<control_joint_name>
right_flap_joint
</control_joint_name>
<cl_delta>-0.5</cl_delta>
<cd_delta>0.05</cd_delta>
<cm_delta>0.005</cm_delta>
<control_joint_rad_to_cl>-0.5</control_joint_rad_to_cl>
<robotNamespace></robotNamespace>
<windSubTopic>world_wind</windSubTopic>
</plugin>
<plugin name="elevator_liftdrag" filename="libLiftDragPlugin.so">
<alpha0>-0.2</alpha0>
<plugin name="elevator" filename="libLiftDragPlugin.so">
<a0>-0.2</a0>
<cla>4.752798721</cla>
<cda>0.6417112299</cda>
<cma>0.0</cma>
Expand All @@ -618,12 +602,12 @@
<control_joint_name>
elevator_joint
</control_joint_name>
<cl_delta>-4.0</cl_delta>
<control_joint_rad_to_cl>-4.0</control_joint_rad_to_cl>
<robotNamespace></robotNamespace>
<windSubTopic>world_wind</windSubTopic>
</plugin>
<plugin name="rudder_liftdrag" filename="libLiftDragPlugin.so">
<alpha0>0.0</alpha0>
<plugin name="rudder" filename="libLiftDragPlugin.so">
<a0>0.0</a0>
<cla>4.752798721</cla>
<cda>0.6417112299</cda>
<cma>0.0</cma>
Expand All @@ -640,7 +624,7 @@
<control_joint_name>
rudder_joint
</control_joint_name>
<cl_delta>4.0</cl_delta>
<control_joint_rad_to_cl>4.0</control_joint_rad_to_cl>
<robotNamespace></robotNamespace>
<windSubTopic>world_wind</windSubTopic>
</plugin>
Expand Down Expand Up @@ -735,23 +719,23 @@
<joint_control_type>velocity</joint_control_type>
<joint_name>rotor_puller_joint</joint_name>
</channel>
<channel name="left_aileron">
<channel name="left_elevon">
<input_index>5</input_index>
<input_offset>0</input_offset>
<input_scaling>1</input_scaling>
<zero_position_disarmed>0</zero_position_disarmed>
<zero_position_armed>0</zero_position_armed>
<joint_control_type>position_kinematic</joint_control_type>
<joint_name>left_aileron_joint</joint_name>
<joint_name>left_elevon_joint</joint_name>
</channel>
<channel name="right_aileron">
<channel name="right_elevon">
<input_index>6</input_index>
<input_offset>0</input_offset>
<input_scaling>1</input_scaling>
<zero_position_disarmed>0</zero_position_disarmed>
<zero_position_armed>0</zero_position_armed>
<joint_control_type>position_kinematic</joint_control_type>
<joint_name>right_aileron_joint</joint_name>
<joint_name>right_elevon_joint</joint_name>
</channel>
<channel name="elevator">
<input_index>7</input_index>
Expand Down
14 changes: 7 additions & 7 deletions models/standard_vtol/standard_vtol.sdf.jinja
Original file line number Diff line number Diff line change
Expand Up @@ -723,7 +723,7 @@
<parent>base_link</parent>
</joint>
<plugin name="left_wing_lift" filename="libLiftDragPlugin.so">
<alpha0>0.05984281113</alpha0>
<a0>0.05984281113</a0>
<cla>4.752798721</cla>
<cda>0.6417112299</cda>
<cma>0.0</cma>
Expand All @@ -740,12 +740,12 @@
<control_joint_name>
left_elevon_joint
</control_joint_name>
<cl_delta>-1.0</cl_delta>
<control_joint_rad_to_cl>-1.0</control_joint_rad_to_cl>
<robotNamespace></robotNamespace>
<windSubTopic>world_wind</windSubTopic>
</plugin>
<plugin name="right_wing_lift" filename="libLiftDragPlugin.so">
<alpha0>0.05984281113</alpha0>
<a0>0.05984281113</a0>
<cla>4.752798721</cla>
<cda>0.6417112299</cda>
<cma>0.0</cma>
Expand All @@ -762,12 +762,12 @@
<control_joint_name>
right_elevon_joint
</control_joint_name>
<cl_delta>-1.0</cl_delta>
<control_joint_rad_to_cl>-1.0</control_joint_rad_to_cl>
<robotNamespace></robotNamespace>
<windSubTopic>world_wind</windSubTopic>
</plugin>
<plugin name="elevator_lift" filename="libLiftDragPlugin.so">
<alpha0>-0.2</alpha0>
<a0>-0.2</a0>
<cla>4.752798721</cla>
<cda>0.6417112299</cda>
<cma>0.0</cma>
Expand All @@ -784,12 +784,12 @@
<control_joint_name>
elevator_joint
</control_joint_name>
<cl_delta>-12.0</cl_delta>
<control_joint_rad_to_cl>-12.0</control_joint_rad_to_cl>
<robotNamespace></robotNamespace>
<windSubTopic>world_wind</windSubTopic>
</plugin>
<plugin name="rudder_lift" filename="libLiftDragPlugin.so">
<alpha0>0.0</alpha0>
<a0>0.0</a0>
<cla>4.752798721</cla>
<cda>0.6417112299</cda>
<cma>0.0.</cma>
Expand Down
Loading

0 comments on commit b195315

Please sign in to comment.