Skip to content

Commit

Permalink
Merge branch 'master' of github.com:jgoppert/aae497-f19
Browse files Browse the repository at this point in the history
  • Loading branch information
AlexanderJChapa committed Sep 23, 2019
2 parents f3b88c6 + 2ea51f5 commit 759bca0
Show file tree
Hide file tree
Showing 8 changed files with 465 additions and 771 deletions.
529 changes: 0 additions & 529 deletions lectures/4-Casadi-Transport.ipynb

This file was deleted.

74 changes: 74 additions & 0 deletions lectures/4-Rocket.ipynb
Original file line number Diff line number Diff line change
@@ -0,0 +1,74 @@
{
"cells": [
{
"cell_type": "code",
"execution_count": 1,
"metadata": {},
"outputs": [],
"source": [
"import casadi as ca\n",
"import numpy as np"
]
},
{
"cell_type": "code",
"execution_count": 2,
"metadata": {},
"outputs": [],
"source": [
"CL0 = 0.0\n",
"CLa = 2*np.pi\n",
"rho = 1.225\n",
"kclcd = 0.01\n",
"CD0 = 0.0\n",
"sf = 0.1 # area of fin\n",
"r = 0.1 # radius of body\n",
"sb = np.pi*r**2\n",
"lf = 1.0 # distance from cg to fin\n",
"\n",
"df = ca.SX.sym('df')\n",
"v = ca.SX.sym('v')\n",
"q = 0.5*rho*v**2\n",
"CL = CL0 + CLa*df\n",
"CD = CD0 + kclcd*CL**2\n",
"\n",
"Lf = CD*q*sf\n",
"Df = CD*q*sf\n",
"\n",
"CDb = 0.01\n",
"Db = CDb*q*sb\n",
"\n",
"\n",
"m_aero = lf*Lf"
]
},
{
"cell_type": "code",
"execution_count": null,
"metadata": {},
"outputs": [],
"source": []
}
],
"metadata": {
"kernelspec": {
"display_name": "Python 3",
"language": "python",
"name": "python3"
},
"language_info": {
"codemirror_mode": {
"name": "ipython",
"version": 3
},
"file_extension": ".py",
"mimetype": "text/x-python",
"name": "python",
"nbconvert_exporter": "python",
"pygments_lexer": "ipython3",
"version": "3.7.3"
}
},
"nbformat": 4,
"nbformat_minor": 4
}
Binary file added lectures/tilt_rotor.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
211 changes: 190 additions & 21 deletions ros/src/f16/models/rocket/rocket.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,13 @@

<link name='body'>
<inertial>
<pose>0 0 0 0 0 0</pose>
<pose>0 0 1.5 0 0 0</pose>
<mass>0.15</mass>
<inertia>
<ixx>1.0</ixx>
<iyy>1.0</iyy>
<izz>1.0</izz>
</inertia>
</inertial>
<collision name='collision'>
<geometry>
Expand All @@ -28,7 +34,34 @@
</visual>
</link>

<plugin name="body" filename="libLiftDragPlugin.so">
<a0>0.0</a0>
<cla>0.0</cla>
<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>
<cma_stall>0</cma_stall>
<cp>0 0 1.5</cp>
<area>0.03</area>
<air_density>1.2041</air_density>
<forward>0 0 1</forward>
<upward>0 1 0</upward>
<link_name>body</link_name>
</plugin>

<link name='nose_cone'>
<inertial>
<pose>0 0 2.9 0 0 0</pose>
<mass>0.01</mass>
<inertia>
<ixx>0.01</ixx>
<iyy>0.01</iyy>
<izz>0.01</izz>
</inertia>
</inertial>

<visual name='visual'>
<cast_shadows>0</cast_shadows>
<geometry>
Expand All @@ -45,11 +78,21 @@
</link>

<joint name='nose_cone' type='fixed'>
<pose>0 0 2.8 0 0 0</pose>
<child>nose_cone</child>
<parent>body</parent>
</joint>

<link name='fin1'>
<inertial>
<pose>0.2 0 0.2 0 0 0</pose>
<mass>0.01</mass>
<inertia>
<ixx>0.01</ixx>
<iyy>0.01</iyy>
<izz>0.01</izz>
</inertia>
</inertial>
<visual name='visual'>
<cast_shadows>0</cast_shadows>
<geometry>
Expand All @@ -68,18 +111,46 @@
<joint name='fin1' type='revolute'>
<child>fin1</child>
<parent>body</parent>
<pose>0 0 0 0 0 0</pose>
<pose>0 0 0.2 0 0 0</pose>
<axis>
<xyz>0 1 0</xyz>
<xyz>1 0 0</xyz>
<limit>
<lower>-1</lower>
<upper>1</upper>
<lower>0</lower>
<upper>0</upper>
</limit>
</axis>
</joint>

<!--<plugin name="fin1" filename="libLiftDragPlugin.so">-->
<!--<a0>0.0</a0>-->
<!--<cla>4.752798721</cla>-->
<!--<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>-->
<!--<cma_stall>0</cma_stall>-->
<!--<cp>0 0 0</cp>-->
<!--<area>0.1</area>-->
<!--<air_density>1.2041</air_density>-->
<!--<forward>0 0 1</forward>-->
<!--<upward>0 1 0</upward>-->
<!--<link_name>body</link_name>-->
<!--<control_joint_name>fin1</control_joint_name>-->
<!--<control_joint_rad_to_cl>-4.0</control_joint_rad_to_cl>-->
<!--</plugin>-->

<link name='fin2'>
<pose>0 0 0 0 0 1.57</pose>
<inertial>
<pose>0.2 0 0.2 0 0 0</pose>
<mass>0.01</mass>
<inertia>
<ixx>0.01</ixx>
<iyy>0.01</iyy>
<izz>0.01</izz>
</inertia>
</inertial>
<visual name='visual'>
<cast_shadows>0</cast_shadows>
<geometry>
Expand All @@ -98,18 +169,46 @@
<joint name='fin2' type='revolute'>
<child>fin2</child>
<parent>body</parent>
<pose>0 0 0 0 0 0</pose>
<pose>0 0 0.2 0 0 0</pose>
<axis>
<xyz>1 0 0</xyz>
<limit>
<lower>-1</lower>
<upper>1</upper>
<lower>0</lower>
<upper>0</upper>
</limit>
</axis>
</joint>

<!--<plugin name="fin2" filename="libLiftDragPlugin.so">-->
<!--<a0>0.0</a0>-->
<!--<cla>4.752798721</cla>-->
<!--<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>-->
<!--<cma_stall>0</cma_stall>-->
<!--<cp>0 0 0</cp>-->
<!--<area>0.1</area>-->
<!--<air_density>1.2041</air_density>-->
<!--<forward>0 0 1</forward>-->
<!--<upward>1 0 0</upward>-->
<!--<link_name>body</link_name>-->
<!--<control_joint_name>fin2</control_joint_name>-->
<!--<control_joint_rad_to_cl>-4.0</control_joint_rad_to_cl>-->
<!--</plugin>-->

<link name='fin3'>
<pose>0 0 0 0 0 3.14</pose>
<inertial>
<pose>0.2 0 0.2 0 0 0</pose>
<mass>0.01</mass>
<inertia>
<ixx>0.01</ixx>
<iyy>0.01</iyy>
<izz>0.01</izz>
</inertia>
</inertial>
<visual name='visual'>
<cast_shadows>0</cast_shadows>
<geometry>
Expand All @@ -128,18 +227,46 @@
<joint name='fin3' type='revolute'>
<child>fin3</child>
<parent>body</parent>
<pose>0 0 0 0 0 0</pose>
<pose>0 0 0.2 0 0 0</pose>
<axis>
<xyz>1 0 0</xyz>
<limit>
<lower>-1</lower>
<upper>1</upper>
<lower>0</lower>
<upper>0</upper>
</limit>
</axis>
</joint>

<!--<plugin name="fin3" filename="libLiftDragPlugin.so">-->
<!--<a0>0.0</a0>-->
<!--<cla>4.752798721</cla>-->
<!--<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>-->
<!--<cma_stall>0</cma_stall>-->
<!--<cp>0 0 0</cp>-->
<!--<area>0.1</area>-->
<!--<air_density>1.2041</air_density>-->
<!--<forward>0 0 1</forward>-->
<!--<upward>0 1 0</upward>-->
<!--<link_name>body</link_name>-->
<!--<control_joint_name>fin3</control_joint_name>-->
<!--<control_joint_rad_to_cl>-4.0</control_joint_rad_to_cl>-->
<!--</plugin>-->

<link name='fin4'>
<pose>0 0 0 0 0 -1.57</pose>
<inertial>
<pose>0.2 0 0.2 0 0 0</pose>
<mass>0.01</mass>
<inertia>
<ixx>0.01</ixx>
<iyy>0.01</iyy>
<izz>0.01</izz>
</inertia>
</inertial>
<visual name='visual'>
<cast_shadows>0</cast_shadows>
<geometry>
Expand All @@ -158,23 +285,65 @@
<joint name='fin4' type='revolute'>
<child>fin4</child>
<parent>body</parent>
<pose>0 0 0 0 0 0</pose>
<pose>0 0 0.2 0 0 0</pose>
<axis>
<xyz>1 0 0</xyz>
<limit>
<lower>-1</lower>
<upper>1</upper>
<lower>0</lower>
<upper>0</upper>
</limit>
</axis>
</joint>

<plugin name="rocket_plugin" filename="libRocketPlugin.so">
<body>body</body>
<fin1>fin1</fin1>
<fin2>fin2</fin2>
<fin3>fin3</fin3>
<fin4>fin4</fin4>
</plugin>
<!--<plugin name="fin4" filename="libLiftDragPlugin.so">-->
<!--<a0>0.0</a0>-->
<!--<cla>4.752798721</cla>-->
<!--<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>-->
<!--<cma_stall>0</cma_stall>-->
<!--<cp>0 0 0</cp>-->
<!--<area>0.1</area>-->
<!--<air_density>1.2041</air_density>-->
<!--<forward>0 0 1</forward>-->
<!--<upward>1 0 0</upward>-->
<!--<link_name>body</link_name>-->
<!--<control_joint_name>fin4</control_joint_name>-->
<!--<control_joint_rad_to_cl>-4.0</control_joint_rad_to_cl>-->
<!--</plugin>-->

<link name='rocket_motor'>
<pose>0 0 0 0 0 0</pose>
<inertial>
<mass>0.8</mass>
</inertial>
<visual name='visual'>
<cast_shadows>0</cast_shadows>
<geometry>
<cylinder>
<radius>0.05</radius>
<length>0.3</length>
</cylinder>
</geometry>
<material>
<script>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
</link>

<joint name='rocket_motor' type='fixed'>
<pose>0 0 0 0 0 0</pose>
<child>rocket_motor</child>
<parent>body</parent>
</joint>

<plugin name="rocket_plugin" filename="libRocketPlugin.so">
<motor>rocket_motor</motor>
</plugin>

</model>
</sdf>
Expand Down
Loading

0 comments on commit 759bca0

Please sign in to comment.