Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Pr liftdrag coefficients #690

Merged
merged 10 commits into from
Jan 25, 2021
31 changes: 18 additions & 13 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
/// \brief angle of attack when airfoil stalls, relative to alpha0
protected: double alphaStall;

/// \brief Cl-alpha rate after stall
Expand All @@ -84,9 +84,6 @@ 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 @@ -104,16 +101,19 @@ namespace gazebo
/// \brief effective planeform surface area
protected: double area;

/// \brief angle of sweep
protected: double sweep;

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

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

/// \brief Cm at zero lift (zero-lift moment coefficient)
protected: double cm_alpha0;

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

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

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

/// \brief how much to change CL per radian of control surface joint
/// value.
protected: double controlJointRadToCL;
/// \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 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">-->
<!--<a0>{{rtr_a0}}</a0>-->
<!--<alpha0>{{rtr_a0}}</alpha0>-->
<!--<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">-->
<!--<a0>{{rtr_a0}}</a0>-->
<!--<alpha0>{{rtr_a0}}</alpha0>-->
<!--<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">
<a0>0</a0>
<alpha0>0</alpha0>
<cla>0</cla>
<cda>1.114</cda> <!-- Such that Cd = 1.75 at alpha = 90deg (= upright parachute) -->
<cma>0</cma>
Expand Down
96 changes: 56 additions & 40 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_elevon">
<link name="left_aileron">
<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_elevon_visual'>
<visual name='left_aileron_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_elevon">
<link name="right_aileron">
<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_elevon_visual'>
<visual name='right_aileron_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_elevon_joint' type='revolute'>
<joint name='left_aileron_joint' type='revolute'>
<parent>base_link</parent>
<child>left_elevon</child>
<child>left_aileron</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_elevon_joint' type='revolute'>
<joint name='right_aileron_joint' type='revolute'>
<parent>base_link</parent>
<child>right_elevon</child>
<child>right_aileron</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,11 +496,13 @@
<child>gps::link</child>
<parent>base_link</parent>
</joint>
<plugin name="left_wing" filename="libLiftDragPlugin.so">
<a0>0.05984281113</a0>
<plugin name="left_wing_liftdrag" filename="libLiftDragPlugin.so">
<alpha0>-0.009519322</alpha0>
<cd_alpha0>0.003</cd_alpha0>
<cm_alpha0>0.002072715</cm_alpha0>
<cla>4.752798721</cla>
<cda>0.6417112299</cda>
<cma>0.0</cma>
<cda>0.35</cda>
<cma>0.02</cma>
<alpha_stall>0.3391428111</alpha_stall>
<cla_stall>-3.85</cla_stall>
<cda_stall>-0.9233984055</cda_stall>
Expand All @@ -512,17 +514,21 @@
<upward>0 0 1</upward>
<link_name>base_link</link_name>
<control_joint_name>
left_elevon_joint
left_aileron_joint
</control_joint_name>
<control_joint_rad_to_cl>-0.5</control_joint_rad_to_cl>
<cl_delta>-0.5</cl_delta>
<cd_delta>0.05</cd_delta>
<cm_delta>0.005</cm_delta>
<robotNamespace></robotNamespace>
<windSubTopic>world_wind</windSubTopic>
</plugin>
<plugin name="right_wing" filename="libLiftDragPlugin.so">
<a0>0.05984281113</a0>
<plugin name="right_wing_liftdrag" filename="libLiftDragPlugin.so">
<alpha0>-0.009519322</alpha0>
<cd_alpha0>0.003</cd_alpha0>
<cm_alpha0>0.002072715</cm_alpha0>
<cla>4.752798721</cla>
<cda>0.6417112299</cda>
<cma>0.0</cma>
<cda>0.35</cda>
<cma>0.02</cma>
<alpha_stall>0.3391428111</alpha_stall>
<cla_stall>-3.85</cla_stall>
<cda_stall>-0.9233984055</cda_stall>
Expand All @@ -534,17 +540,21 @@
<upward>0 0 1</upward>
<link_name>base_link</link_name>
<control_joint_name>
right_elevon_joint
right_aileron_joint
</control_joint_name>
<control_joint_rad_to_cl>-0.5</control_joint_rad_to_cl>
<cl_delta>-0.5</cl_delta>
<cd_delta>0.05</cd_delta>
<cm_delta>0.005</cm_delta>
<robotNamespace></robotNamespace>
<windSubTopic>world_wind</windSubTopic>
</plugin>
<plugin name="left_flap" filename="libLiftDragPlugin.so">
<a0>0.05984281113</a0>
<plugin name="left_flap_liftdrag" filename="libLiftDragPlugin.so">
<alpha0>-0.009519322</alpha0>
<cd_alpha0>0.003</cd_alpha0>
<cm_alpha0>0.002072715</cm_alpha0>
<cla>4.752798721</cla>
<cda>0.6417112299</cda>
<cma>0.0</cma>
<cda>0.35</cda>
<cma>0.02</cma>
<alpha_stall>0.3391428111</alpha_stall>
<cla_stall>-3.85</cla_stall>
<cda_stall>-0.9233984055</cda_stall>
Expand All @@ -558,15 +568,19 @@
<control_joint_name>
left_flap_joint
</control_joint_name>
<control_joint_rad_to_cl>-0.5</control_joint_rad_to_cl>
<cl_delta>-0.5</cl_delta>
<cd_delta>0.05</cd_delta>
<cm_delta>0.005</cm_delta>
<robotNamespace></robotNamespace>
<windSubTopic>world_wind</windSubTopic>
</plugin>
<plugin name="right_flap" filename="libLiftDragPlugin.so">
<a0>0.05984281113</a0>
<plugin name="right_flap_liftdrag" filename="libLiftDragPlugin.so">
<alpha0>-0.009519322</alpha0>
<cd_alpha0>0.003</cd_alpha0>
<cm_alpha0>0.002072715</cm_alpha0>
<cla>4.752798721</cla>
<cda>0.6417112299</cda>
<cma>0.0</cma>
<cda>0.35</cda>
<cma>0.02</cma>
<alpha_stall>0.3391428111</alpha_stall>
<cla_stall>-3.85</cla_stall>
<cda_stall>-0.9233984055</cda_stall>
Expand All @@ -580,12 +594,14 @@
<control_joint_name>
right_flap_joint
</control_joint_name>
<control_joint_rad_to_cl>-0.5</control_joint_rad_to_cl>
<cl_delta>-0.5</cl_delta>
<cd_delta>0.05</cd_delta>
<cm_delta>0.005</cm_delta>
<robotNamespace></robotNamespace>
<windSubTopic>world_wind</windSubTopic>
</plugin>
<plugin name="elevator" filename="libLiftDragPlugin.so">
<a0>-0.2</a0>
<plugin name="elevator_liftdrag" filename="libLiftDragPlugin.so">
<alpha0>-0.2</alpha0>
<cla>4.752798721</cla>
<cda>0.6417112299</cda>
<cma>0.0</cma>
Expand All @@ -602,12 +618,12 @@
<control_joint_name>
elevator_joint
</control_joint_name>
<control_joint_rad_to_cl>-4.0</control_joint_rad_to_cl>
<cl_delta>-4.0</cl_delta>
<robotNamespace></robotNamespace>
<windSubTopic>world_wind</windSubTopic>
</plugin>
<plugin name="rudder" filename="libLiftDragPlugin.so">
<a0>0.0</a0>
<plugin name="rudder_liftdrag" filename="libLiftDragPlugin.so">
<alpha0>0.0</alpha0>
<cla>4.752798721</cla>
<cda>0.6417112299</cda>
<cma>0.0</cma>
Expand All @@ -624,7 +640,7 @@
<control_joint_name>
rudder_joint
</control_joint_name>
<control_joint_rad_to_cl>4.0</control_joint_rad_to_cl>
<cl_delta>4.0</cl_delta>
<robotNamespace></robotNamespace>
<windSubTopic>world_wind</windSubTopic>
</plugin>
Expand Down Expand Up @@ -719,23 +735,23 @@
<joint_control_type>velocity</joint_control_type>
<joint_name>rotor_puller_joint</joint_name>
</channel>
<channel name="left_elevon">
<channel name="left_aileron">
<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_elevon_joint</joint_name>
<joint_name>left_aileron_joint</joint_name>
</channel>
<channel name="right_elevon">
<channel name="right_aileron">
<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_elevon_joint</joint_name>
<joint_name>right_aileron_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">
<a0>0.05984281113</a0>
<alpha0>0.05984281113</alpha0>
<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>
<control_joint_rad_to_cl>-1.0</control_joint_rad_to_cl>
<cl_delta>-1.0</cl_delta>
<robotNamespace></robotNamespace>
<windSubTopic>world_wind</windSubTopic>
</plugin>
<plugin name="right_wing_lift" filename="libLiftDragPlugin.so">
<a0>0.05984281113</a0>
<alpha0>0.05984281113</alpha0>
<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>
<control_joint_rad_to_cl>-1.0</control_joint_rad_to_cl>
<cl_delta>-1.0</cl_delta>
<robotNamespace></robotNamespace>
<windSubTopic>world_wind</windSubTopic>
</plugin>
<plugin name="elevator_lift" filename="libLiftDragPlugin.so">
<a0>-0.2</a0>
<alpha0>-0.2</alpha0>
<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>
<control_joint_rad_to_cl>-12.0</control_joint_rad_to_cl>
<cl_delta>-12.0</cl_delta>
<robotNamespace></robotNamespace>
<windSubTopic>world_wind</windSubTopic>
</plugin>
<plugin name="rudder_lift" filename="libLiftDragPlugin.so">
<a0>0.0</a0>
<alpha0>0.0</alpha0>
<cla>4.752798721</cla>
<cda>0.6417112299</cda>
<cma>0.0.</cma>
Expand Down
Loading