Standalone px4 stable (#22467)

simulation gazebo: move the gazebo models to submodule, allow for operation with external gazebo instance, independent of startup order. Allows drag an drop of models from gazebo fuel.

* rolled back updates

Signed-off-by: frederik <frederik@auterion.com>

* fixing empy

Signed-off-by: frederik <frederik@auterion.com>

* Update GZBridge.cpp to lower drop position 

Dropping from 1m leads to movement in the rc_cessna. Dropping from 0.5m leads to no movement.

* Update STANDALONE env variable.

* Update STANDALONE env_variable on GZBridge

* Update src/modules/simulation/gz_bridge/GZBridge.cpp

Co-authored-by: Daniel Agar <daniel@agar.ca>

* test removal of x500

Signed-off-by: frederik <frederik.anilmarkus@gmail.com>

* removed all models and reworked logic

Signed-off-by: frederik <frederik.anilmarkus@gmail.com>

* remove model path in set_sdf_filename

Signed-off-by: frederik <frederik.anilmarkus@gmail.com>

* filter resource path for world sdf

Signed-off-by: frederik <frederik.anilmarkus@gmail.com>

* updated structure to keep old make px4_sitl

Signed-off-by: frederik <frederik.anilmarkus@gmail.com>

* remove gz tools

Signed-off-by: frederik <frederik.anilmarkus@gmail.com>

* import gz as submodule and reverse rc simulator logic

Signed-off-by: frederik <frederik.anilmarkus@gmail.com>

* [gz-sim]: source GZ_SIM_RESOURCE_PATH only if PX4 starts gz server

Signed-off-by: Beniamino Pozzan <beniamino.pozzan@gmail.com>

* Typo fix

---------

Signed-off-by: frederik <frederik@auterion.com>
Signed-off-by: frederik <frederik.anilmarkus@gmail.com>
Signed-off-by: Beniamino Pozzan <beniamino.pozzan@gmail.com>
Co-authored-by: Daniel Agar <daniel@agar.ca>
Co-authored-by: Beniamino Pozzan <beniamino.pozzan@gmail.com>
This commit is contained in:
Frederik Markus 2023-12-18 09:43:20 +01:00 committed by GitHub
parent 6ffc5a9eae
commit 65e53286b6
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
66 changed files with 101 additions and 11603 deletions

3
.gitmodules vendored
View File

@ -76,3 +76,6 @@
path = src/lib/heatshrink/heatshrink
url = https://github.com/PX4/heatshrink.git
branch = px4
[submodule "Tools/simulation/gz"]
path = Tools/simulation/gz
url = https://github.com/PX4/PX4-gazebo-models.git

View File

@ -51,44 +51,50 @@ elif [ "$PX4_SIMULATOR" = "gz" ] || [ "$(param show -q SIM_GZ_EN)" = "1" ]; then
param set SIM_GZ_HOME_ALT ${PX4_HOME_LON}
fi
# source generated gz_env.sh for GZ_SIM_RESOURCE_PATH
if [ -f ./gz_env.sh ]; then
. ./gz_env.sh
# Only start up Gazebo if PX4_GZ_STANDALONE is not set.
if [ -z "${PX4_GZ_STANDALONE}" ]; then
elif [ -f ../gz_env.sh ]; then
. ../gz_env.sh
fi
# "gz sim" only avaiilable in Garden and later
GZ_SIM_VERSIONS=$(gz sim --versions 2>&1)
if [ $? -eq 0 ] && [ "${GZ_SIM_VERSIONS}" != "" ]
then
# "gz sim" from Garden on
gz_command="gz"
gz_sub_command="sim"
else
echo "ERROR [init] Gazebo gz please install gz-garden"
exit 1
fi
# look for running ${gz_command} gazebo world
gz_world=$( ${gz_command} topic -l | grep -m 1 -e "^/world/.*/clock" | sed 's/\/world\///g; s/\/clock//g' )
# shellcheck disable=SC2153
if [ -z "${gz_world}" ] && [ -n "${PX4_GZ_WORLDS}" ] && [ -n "${PX4_GZ_WORLD}" ]; then
echo "INFO [init] starting gazebo with world: ${PX4_GZ_WORLDS}/${PX4_GZ_WORLD}.sdf"
${gz_command} ${gz_sub_command} --verbose=1 -r -s "${PX4_GZ_WORLDS}/${PX4_GZ_WORLD}.sdf" &
if [ -z "${HEADLESS}" ]; then
# HEADLESS not set, starting gui
${gz_command} ${gz_sub_command} -g &
# "gz sim" only available in Garden and later
GZ_SIM_VERSIONS=$(gz sim --versions 2>&1)
if [ $? -eq 0 ] && [ "${GZ_SIM_VERSIONS}" != "" ]
then
# "gz sim" from Garden on
gz_command="gz"
gz_sub_command="sim"
else
echo "ERROR [init] Gazebo gz please install gz-garden"
exit 1
fi
# look for running ${gz_command} gazebo world
gz_world=$( ${gz_command} topic -l | grep -m 1 -e "^/world/.*/clock" | sed 's/\/world\///g; s/\/clock//g' )
# shellcheck disable=SC2153
if [ -z "${gz_world}" ] && [ -n "${PX4_GZ_WORLD}" ]; then
# source generated gz_env.sh for GZ_SIM_RESOURCE_PATH
if [ -f ./gz_env.sh ]; then
. ./gz_env.sh
elif [ -f ../gz_env.sh ]; then
. ../gz_env.sh
fi
echo "INFO [init] starting gazebo with world: ${PX4_GZ_WORLDS}/${PX4_GZ_WORLD}.sdf"
${gz_command} ${gz_sub_command} --verbose=1 -r -s "${PX4_GZ_WORLDS}/${PX4_GZ_WORLD}.sdf" &
if [ -z "${HEADLESS}" ]; then
# HEADLESS not set, starting gui
${gz_command} ${gz_sub_command} -g &
fi
else
echo "INFO [init] gazebo already running world: ${gz_world}"
PX4_GZ_WORLD=${gz_world}
fi
else
echo "INFO [init] gazebo already running world: ${gz_world}"
PX4_GZ_WORLD=${gz_world}
echo "INFO [init] Standalone PX4 launch, waiting for Gazebo"
fi
# start gz_bridge

1
Tools/simulation/gz Submodule

@ -0,0 +1 @@
Subproject commit c00a63597548f2eae9909a80ea07c1aeca13bbd2

View File

@ -1,14 +0,0 @@
<?xml version="1.0"?>
<model>
<name>Advanced Plane</name>
<version>1.0</version>
<sdf version='1.5'>model.sdf</sdf>
<author>
<name>Karthik Srivatsan</name>
</author>
<description>
This is a model of a standard plane, which uses the advanced liftdrag plugin.
</description>
</model>

View File

@ -1,578 +0,0 @@
<?xml version="1.0"?>
<sdf version='1.5'>
<model name='plane'>
<pose>0 0 0.246 0 0 0</pose>
<link name='base_link'>
<pose>0 0 0 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>1</mass>
<inertia>
<ixx>0.197563</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.1458929</iyy>
<iyz>0</iyz>
<izz>0.1477</izz>
</inertia>
</inertial>
<collision name='base_link_collision'>
<pose>0 0 -0.07 0 0 0</pose>
<geometry>
<box>
<size>0.47 0.47 0.11</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<max_vel>10</max_vel>
<min_depth>0.01</min_depth>
</ode>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='base_link_visual'>
<pose>0.07 0 -0.08 0 0 0</pose>
<geometry>
<mesh>
<scale>0.1 0.1 0.1</scale>
<uri>https://fuel.gazebosim.org/1.0/PX4/models/Advanced%20Plane/tip/files/meshes/body.dae</uri>
</mesh>
</geometry>
<material>
<ambient>.175 .175 .175 1.0</ambient>
<diffuse>.175 .175 .175 1.0</diffuse>
</material>
</visual>
<gravity>1</gravity>
<velocity_decay/>
<self_collide>0</self_collide>
<sensor name="imu_sensor" type="imu">
<always_on>1</always_on>
<update_rate>250</update_rate>
</sensor>
<sensor name="air_pressure_sensor" type="air_pressure">
<always_on>1</always_on>
<update_rate>50</update_rate>
<air_pressure>
<pressure>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.01</stddev>
</noise>
</pressure>
</air_pressure>
</sensor>
</link>
<link name='rotor_puller'>
<pose>0.3 0 0.0 0 1.57 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.005</mass>
<inertia>
<ixx>9.75e-07</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.000166704</iyy>
<iyz>0</iyz>
<izz>0.000167604</izz>
</inertia>
</inertial>
<collision name='rotor_puller_collision'>
<pose>0.0 0 0.0 0 0 0</pose>
<geometry>
<cylinder>
<length>0.005</length>
<radius>0.1</radius>
</cylinder>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='rotor_puller_visual'>
<pose>0 0 -0.09 0 0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>https://fuel.gazebosim.org/1.0/PX4/models/Advanced%20Plane/tip/files/meshes/iris_prop_ccw.dae</uri>
</mesh>
</geometry>
<material>
<ambient>.175 .175 .175 1.0</ambient>
<diffuse>.175 .175 .175 1.0</diffuse>
</material>
</visual>
<gravity>1</gravity>
<velocity_decay/>
<self_collide>0</self_collide>
</link>
<joint name='rotor_puller_joint' type='revolute'>
<child>rotor_puller</child>
<parent>base_link</parent>
<axis>
<xyz>1 0 0</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
<link name="left_elevon">
<inertial>
<mass>0.00000001</mass>
<inertia>
<ixx>0.000001</ixx>
<ixy>0.0</ixy>
<iyy>0.000001</iyy>
<ixz>0.0</ixz>
<iyz>0.0</iyz>
<izz>0.000001</izz>
</inertia>
<pose>0 0.3 0 0.00 0 0.0</pose>
</inertial>
<visual name='left_elevon_visual'>
<pose>0.07 0.0 -0.08 0.00 0 0.0</pose>
<geometry>
<mesh>
<scale>0.1 0.1 0.1</scale>
<uri>https://fuel.gazebosim.org/1.0/PX4/models/Advanced%20Plane/tip/files/meshes/left_aileron.dae</uri>
</mesh>
</geometry>
<material>
<ambient>1 0 0 1.0</ambient>
<diffuse>1 0 0 1.0</diffuse>
</material>
</visual>
</link>
<link name="right_elevon">
<inertial>
<mass>0.00000001</mass>
<inertia>
<ixx>0.000001</ixx>
<ixy>0.0</ixy>
<iyy>0.000001</iyy>
<ixz>0.0</ixz>
<iyz>0.0</iyz>
<izz>0.000001</izz>
</inertia>
<pose>0 -0.3 0 0.00 0 0.0</pose>
</inertial>
<visual name='right_elevon_visual'>
<pose>0.07 0.0 -0.08 0.00 0 0.0</pose>
<geometry>
<mesh>
<scale>0.1 0.1 0.1</scale>
<uri>https://fuel.gazebosim.org/1.0/PX4/models/Advanced%20Plane/tip/files/meshes/right_aileron.dae</uri>
</mesh>
</geometry>
<material>
<ambient>1 0 0 1.0</ambient>
<diffuse>1 0 0 1.0</diffuse>
</material>
</visual>
</link>
<link name="left_flap">
<inertial>
<mass>0.00000001</mass>
<inertia>
<ixx>0.000001</ixx>
<ixy>0.0</ixy>
<iyy>0.000001</iyy>
<ixz>0.0</ixz>
<iyz>0.0</iyz>
<izz>0.000001</izz>
</inertia>
<pose>0 0.15 0 0.00 0 0.0</pose>
</inertial>
<visual name='left_flap_visual'>
<pose>0.07 0.0 -0.08 0.00 0 0.0</pose>
<geometry>
<mesh>
<scale>0.1 0.1 0.1</scale>
<uri>https://fuel.gazebosim.org/1.0/PX4/models/Advanced%20Plane/tip/files/meshes/left_flap.dae</uri>
</mesh>
</geometry>
<material>
<ambient>1 0 0 1.0</ambient>
<diffuse>1 0 0 1.0</diffuse>
</material>
</visual>
</link>
<link name="right_flap">
<inertial>
<mass>0.00000001</mass>
<inertia>
<ixx>0.000001</ixx>
<ixy>0.0</ixy>
<iyy>0.000001</iyy>
<ixz>0.0</ixz>
<iyz>0.0</iyz>
<izz>0.000001</izz>
</inertia>
<pose>0 -0.15 0 0.00 0 0.0</pose>
</inertial>
<visual name='right_flap_visual'>
<pose>0.07 0.0 -0.08 0.00 0 0.0</pose>
<geometry>
<mesh>
<scale>0.1 0.1 0.1</scale>
<uri>https://fuel.gazebosim.org/1.0/PX4/models/Advanced%20Plane/tip/files/meshes/right_flap.dae</uri>
</mesh>
</geometry>
<material>
<ambient>1 0 0 1.0</ambient>
<diffuse>1 0 0 1.0</diffuse>
</material>
</visual>
</link>
<link name="elevator">
<inertial>
<mass>0.00000001</mass>
<inertia>
<ixx>0.000001</ixx>
<ixy>0.0</ixy>
<iyy>0.000001</iyy>
<ixz>0.0</ixz>
<iyz>0.0</iyz>
<izz>0.000001</izz>
</inertia>
<pose> -0.5 0 0 0.00 0 0.0</pose>
</inertial>
<visual name='elevator_visual'>
<pose>0.07 0.0 -0.08 0.00 0 0.0</pose>
<geometry>
<mesh>
<scale>0.1 0.1 0.1</scale>
<uri>https://fuel.gazebosim.org/1.0/PX4/models/Advanced%20Plane/tip/files/meshes/elevators.dae</uri>
</mesh>
</geometry>
<material>
<ambient>1 0 0 1.0</ambient>
<diffuse>1 0 0 1.0</diffuse>
</material>
</visual>
</link>
<link name="rudder">
<inertial>
<mass>0.00000001</mass>
<inertia>
<ixx>0.000001</ixx>
<ixy>0.0</ixy>
<iyy>0.000001</iyy>
<ixz>0.0</ixz>
<iyz>0.0</iyz>
<izz>0.000001</izz>
</inertia>
<pose>-0.5 0 0.05 0 0 0 </pose>
</inertial>
<visual name='rudder_visual'>
<pose>0.07 0.0 -0.08 0.00 0 0.0</pose>
<geometry>
<mesh>
<scale>0.1 0.1 0.1</scale>
<uri>https://fuel.gazebosim.org/1.0/PX4/models/Advanced%20Plane/tip/files/meshes/rudder.dae</uri>
</mesh>
</geometry>
<material>
<ambient>1 0 0 1.0</ambient>
<diffuse>1 0 0 1.0</diffuse>
</material>
</visual>
</link>
<joint name='servo_0' type='revolute'>
<parent>base_link</parent>
<child>left_elevon</child>
<pose>-0.07 0.4 0.08 0.00 0 0.0</pose>
<axis>
<xyz>0 1 0</xyz>
<limit>
<!-- -30/+30 deg. -->
<lower>-0.53</lower>
<upper>0.53</upper>
</limit>
<dynamics>
<damping>1.000</damping>
</dynamics>
</axis>
<physics>
<ode>
<implicit_spring_damper>1</implicit_spring_damper>
</ode>
</physics>
</joint>
<plugin
filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController">
<joint_name>servo_0</joint_name>
<sub_topic>servo_0</sub_topic>
<p_gain>10</p_gain>
<i_gain>0</i_gain>
<d_gain>0</d_gain>
</plugin>
<joint name='servo_1' type='revolute'>
<parent>base_link</parent>
<child>right_elevon</child>
<pose>-0.07 -0.4 0.08 0.00 0 0.0</pose>
<axis>
<xyz>0 1 0</xyz>
<limit>
<!-- -30/+30 deg. -->
<lower>-0.53</lower>
<upper>0.53</upper>
</limit>
<dynamics>
<damping>1.000</damping>
</dynamics>
</axis>
<physics>
<ode>
<implicit_spring_damper>1</implicit_spring_damper>
</ode>
</physics>
</joint>
<plugin
filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController">
<joint_name>servo_1</joint_name>
<sub_topic>servo_1</sub_topic>
<p_gain>10</p_gain>
<i_gain>0</i_gain>
<d_gain>0</d_gain>
</plugin>
<joint name='servo_4' type='revolute'>
<parent>base_link</parent>
<child>left_flap</child>
<pose>-0.07 0.2 0.08 0.00 0 0.0</pose>
<axis>
<xyz>0 1 0</xyz>
<limit>
<!-- -30/+30 deg. -->
<lower>-0.53</lower>
<upper>0.53</upper>
</limit>
<dynamics>
<damping>1.000</damping>
</dynamics>
</axis>
<physics>
<ode>
<implicit_spring_damper>1</implicit_spring_damper>
</ode>
</physics>
</joint>
<plugin
filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController">
<joint_name>servo_4</joint_name>
<sub_topic>servo_4</sub_topic>
<p_gain>10</p_gain>
<i_gain>0</i_gain>
<d_gain>0</d_gain>
</plugin>
<joint name='servo_5' type='revolute'>
<parent>base_link</parent>
<child>right_flap</child>
<pose>-0.07 -0.2 0.08 0.00 0 0.0</pose>
<axis>
<xyz>0 1 0</xyz>
<limit>
<!-- -30/+30 deg. -->
<lower>-0.53</lower>
<upper>0.53</upper>
</limit>
<dynamics>
<damping>1.000</damping>
</dynamics>
</axis>
<physics>
<ode>
<implicit_spring_damper>1</implicit_spring_damper>
</ode>
</physics>
</joint>
<plugin
filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController">
<joint_name>servo_5</joint_name>
<sub_topic>servo_5</sub_topic>
<p_gain>10</p_gain>
<i_gain>0</i_gain>
<d_gain>0</d_gain>
</plugin>
<joint name='servo_2' type='revolute'>
<parent>base_link</parent>
<child>elevator</child>
<pose> -0.5 0 0 0 0 0</pose>
<axis>
<xyz>0 1 0</xyz>
<limit>
<!-- -30/+30 deg. -->
<lower>-0.53</lower>
<upper>0.53</upper>
</limit>
<dynamics>
<damping>1.000</damping>
</dynamics>
</axis>
<physics>
<ode>
<implicit_spring_damper>1</implicit_spring_damper>
</ode>
</physics>
</joint>
<plugin
filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController">
<joint_name>servo_2</joint_name>
<sub_topic>servo_2</sub_topic>
<p_gain>10</p_gain>
<i_gain>0</i_gain>
<d_gain>0</d_gain>
</plugin>
<joint name='servo_3' type='revolute'>
<parent>base_link</parent>
<child>rudder</child>
<pose>-0.5 0 0.05 0.00 0 0.0</pose>
<axis>
<xyz>0 0 1</xyz>
<limit>
<!-- -30/+30 deg. -->
<lower>-0.53</lower>
<upper>0.53</upper>
</limit>
<dynamics>
<damping>1.000</damping>
</dynamics>
</axis>
<physics>
<ode>
<implicit_spring_damper>1</implicit_spring_damper>
</ode>
</physics>
</joint>
<plugin
filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController">
<joint_name>servo_3</joint_name>
<sub_topic>servo_3</sub_topic>
<p_gain>10</p_gain>
<i_gain>0</i_gain>
<d_gain>0</d_gain>
</plugin>
<plugin filename="gz-sim-advanced-lift-drag-system" name="gz::sim::systems::AdvancedLiftDrag">
<a0>0.0</a0>
<CL0>0.15188</CL0>
<AR>6.5</AR>
<eff>0.97</eff>
<CLa>5.015</CLa>
<CD0>0.029</CD0>
<Cem0>0.075</Cem0>
<Cema>-0.463966</Cema>
<CYb>-0.258244</CYb>
<Cellb>-0.039250</Cellb>
<Cenb>0.100826</Cenb>
<CDp>0.0</CDp>
<CYp>0.065861</CYp>
<CLp>0.0</CLp>
<Cellp>-0.487407</Cellp>
<Cemp>0.0</Cemp>
<Cenp>-0.040416</Cenp>
<CDq>0.055166</CDq>
<CYq>0.0</CYq>
<CLq>7.971792</CLq>
<Cellq>0.0</Cellq>
<Cemq>-12.140140</Cemq>
<Cenq>0.0</Cenq>
<CDr>0.0</CDr>
<CYr>0.230299</CYr>
<CLr>0.0</CLr>
<Cellr>0.078165</Cellr>
<Cemr>0.0</Cemr>
<Cenr>-0.089947</Cenr>
<alpha_stall>0.3391428111</alpha_stall>
<CLa_stall>-3.85</CLa_stall>
<CDa_stall>-0.9233984055</CDa_stall>
<Cema_stall>0</Cema_stall>
<cp>-0.12 0.0 0.0</cp>
<area>0.34</area>
<mac>0.22</mac>
<air_density>1.2041</air_density>
<forward>1 0 0</forward>
<upward>0 0 1</upward>
<link_name>base_link</link_name>
<num_ctrl_surfaces>4</num_ctrl_surfaces>
<control_surface>
<name>servo_0</name>
<index>0</index>
<direction>1</direction>
<CD_ctrl>-0.000059</CD_ctrl>
<CY_ctrl>0.000171</CY_ctrl>
<CL_ctrl>-0.011940</CL_ctrl>
<Cell_ctrl>-0.003331</Cell_ctrl>
<Cem_ctrl>0.001498</Cem_ctrl>
<Cen_ctrl>-0.000057</Cen_ctrl>
</control_surface>
<control_surface>
<name>servo_1</name>
<direction>1</direction>
<index>1</index>
<CD_ctrl>-0.000059</CD_ctrl>
<CY_ctrl>-0.000171</CY_ctrl>
<CL_ctrl>-0.011940</CL_ctrl>
<Cell_ctrl>0.003331</Cell_ctrl>
<Cem_ctrl>0.001498</Cem_ctrl>
<Cen_ctrl>0.000057</Cen_ctrl>
</control_surface>
<control_surface>
<name>servo_2</name>
<direction>-1</direction>
<index>2</index>
<CD_ctrl>0.000274</CD_ctrl>
<CY_ctrl>0</CY_ctrl>
<CL_ctrl>0.010696</CL_ctrl>
<Cell_ctrl>0.0</Cell_ctrl>
<Cem_ctrl>-0.025798</Cem_ctrl>
<Cen_ctrl>0.0</Cen_ctrl>
</control_surface>
<control_surface>
<name>servo_3</name>
<direction>1</direction>
<index>3</index>
<CD_ctrl>0.0</CD_ctrl>
<CY_ctrl>-0.003913</CY_ctrl>
<CL_ctrl>0.0</CL_ctrl>
<Cell_ctrl>-0.000257</Cell_ctrl>
<Cem_ctrl>0.0</Cem_ctrl>
<Cen_ctrl>0.001613</Cen_ctrl>
</control_surface>
</plugin>
<plugin filename="gz-sim-multicopter-motor-model-system" name="gz::sim::systems::MulticopterMotorModel">
<jointName>rotor_puller_joint</jointName>
<linkName>rotor_puller</linkName>
<turningDirection>cw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>3500</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.01</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>0</motorNumber>
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
</model>
</sdf>

View File

@ -1,15 +0,0 @@
<?xml version="1.0"?>
<model>
<name>Omnicopter</name>
<version>1.0</version>
<sdf version='1.9'>model.sdf</sdf>
<author>
<name>Jaeyoung Lim</name>
<email>jalim@ethz.ch</email>
</author>
<description>
Omnicopter model for over actuated system
</description>
</model>

View File

@ -1,8 +0,0 @@
<?xml version="1.0" encoding="UTF-8"?>
<sdf version='1.9'>
<include>
<name>omnicopter</name>
<pose>0 0 0.2 0 0 0</pose>
<uri>https://fuel.gazebosim.org/1.0/PX4/models/Omnicopter</uri>
</include>
</sdf>

View File

@ -1,15 +0,0 @@
<?xml version="1.0"?>
<model>
<name>PX4 Vision</name>
<version>1.0</version>
<sdf version='1.9'>model.sdf</sdf>
<author>
<name>Jaeyoung Lim</name>
<email>jaeyoung@auterion.com</email>
</author>
<description>
This is a model of the Holybro PX4 Vision
</description>
</model>

View File

@ -1,10 +0,0 @@
<?xml version="1.0" encoding="UTF-8"?>
<sdf version='1.9'>
<model name='px4vision'>
<include>
<uri>
https://fuel.gazebosim.org/1.0/PX4/models/PX4 Vision
</uri>
</include>
</model>
</sdf>

File diff suppressed because one or more lines are too long

View File

@ -1,165 +0,0 @@
<?xml version="1.0" encoding="UTF-8" standalone="no" ?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<authoring_tool>SketchUp 15.3.331</authoring_tool>
</contributor>
<created>2015-05-26T23:41:25Z</created>
<modified>2015-05-26T23:41:25Z</modified>
<unit meter="0.0254" name="inch" />
<up_axis>Z_UP</up_axis>
</asset>
<library_visual_scenes>
<visual_scene id="ID1">
<node name="SketchUp">
<node id="ID2" name="instance_0">
<matrix>0.001745328 -0.9999985 0 70.84882 0.9999985 0.001745328 0 -0.03157813 -0 0 1 -19.50896 0 0 0 1</matrix>
<instance_node url="#ID3" />
</node>
</node>
</visual_scene>
</library_visual_scenes>
<library_nodes>
<node id="ID3" name="ske2A3">
<node id="ID4" name="group_0">
<matrix>1.963935 -3.469447e-018 0 1.237124 3.469447e-018 1.963935 0 258.791 0 0 1.963935 40.4385 0 0 0 1</matrix>
<instance_geometry url="#ID5">
<bind_material>
<technique_common>
<instance_material symbol="Material2" target="#ID6">
<bind_vertex_input semantic="UVSET0" input_semantic="TEXCOORD" input_set="0" />
</instance_material>
<instance_material symbol="Material3" target="#ID11">
<bind_vertex_input semantic="UVSET0" input_semantic="TEXCOORD" input_set="0" />
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="ID15" name="group_1">
<matrix>1.963935 -4.336809e-018 0 -68.35112 4.336809e-018 1.963935 0 258.791 0 0 1.963935 40.4385 0 0 0 1</matrix>
<instance_geometry url="#ID16">
<bind_material>
<technique_common>
<instance_material symbol="Material2" target="#ID6">
<bind_vertex_input semantic="UVSET0" input_semantic="TEXCOORD" input_set="0" />
</instance_material>
<instance_material symbol="Material3" target="#ID11">
<bind_vertex_input semantic="UVSET0" input_semantic="TEXCOORD" input_set="0" />
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
</node>
</library_nodes>
<library_geometries>
<geometry id="ID5">
<mesh>
<source id="ID8">
<float_array id="ID13" count="126">29.29134 15.47244 1.496063 -2.220446e-016 15.47244 0.2362205 29.29134 15.47244 0.1574803 29.29134 15.47244 0.1574803 -2.220446e-016 15.47244 0.2362205 29.29134 15.47244 1.496063 0.07874016 15.55118 1.574803 -2.220446e-016 15.47244 0.2362205 29.29134 15.47244 1.496063 29.29134 15.47244 1.496063 -2.220446e-016 15.47244 0.2362205 0.07874016 15.55118 1.574803 29.29134 15.47244 0.1574803 -2.220446e-016 15.47244 0.2362205 0.2362205 17.71654 0.2362205 0.2362205 17.71654 0.2362205 -2.220446e-016 15.47244 0.2362205 29.29134 15.47244 0.1574803 0.2362205 17.71654 0.2362205 -2.220446e-016 15.47244 0.2362205 0.07874016 15.55118 1.574803 0.07874016 15.55118 1.574803 -2.220446e-016 15.47244 0.2362205 0.2362205 17.71654 0.2362205 29.29134 15.47244 1.496063 0.2362205 17.71654 1.574803 0.07874016 15.55118 1.574803 0.07874016 15.55118 1.574803 0.2362205 17.71654 1.574803 29.29134 15.47244 1.496063 29.33071 23.14961 1.220472 29.33071 23.14961 1.220472 0.2362205 17.71654 1.574803 0.2362205 17.71654 1.574803 3.779528 26.81102 1.220472 3.779528 26.81102 1.220472 3.779528 26.81102 1.220472 3.779528 26.81102 1.220472 3.779528 26.81102 1.220472 3.779528 26.81102 1.220472 29.33071 23.14961 1.220472 29.33071 23.14961 1.220472</float_array>
<technique_common>
<accessor count="42" source="#ID13" stride="3">
<param name="X" type="float" />
<param name="Y" type="float" />
<param name="Z" type="float" />
</accessor>
</technique_common>
</source>
<source id="ID9">
<float_array id="ID14" count="126">8.832897e-019 -1 0 8.832897e-019 -1 0 8.832897e-019 -1 0 -8.832897e-019 1 -0 -8.832897e-019 1 -0 -8.832897e-019 1 -0 -0.002532054 -0.9982624 0.05887026 -0.002532054 -0.9982624 0.05887026 -0.002532054 -0.9982624 0.05887026 0.002532054 0.9982624 -0.05887026 0.002532054 0.9982624 -0.05887026 0.002532054 0.9982624 -0.05887026 0.007390569 0.1304752 -0.991424 -0.002688162 0.0002829644 -0.9999963 0.004389455 0.04876336 -0.9988007 -0.004389455 -0.04876336 0.9988007 0.002688162 -0.0002829644 0.9999963 -0.007390569 -0.1304752 0.991424 -0.9752032 0.2211027 0.009609949 -0.9931459 0.1045417 0.05227084 -0.9949927 0.093762 0.03461586 0.9949927 -0.093762 -0.03461586 0.9931459 -0.1045417 -0.05227084 0.9752032 -0.2211027 -0.009609949 0.005110827 0.03434514 0.999397 0.003976796 0.01640632 0.9998575 0.00269488 -0.0001959912 0.9999963 -0.00269488 0.0001959912 -0.9999963 -0.003976796 -0.01640632 -0.9998575 -0.005110827 -0.03434514 -0.999397 0.009196932 0.1303557 -0.9914246 -0.009196932 -0.1303557 0.9914246 -0.9758321 0.2185214 -5.056631e-018 0.9758321 -0.2185214 5.056631e-018 0.00548519 0.03663055 0.9993138 -0.00548519 -0.03663055 -0.9993138 0.0146102 0.1019572 -0.9946815 -0.0146102 -0.1019572 0.9946815 -0.9317774 0.3630302 0 0.9317774 -0.3630302 -0 0.00513686 0.03584755 0.9993441 -0.00513686 -0.03584755 -0.9993441</float_array>
<technique_common>
<accessor count="42" source="#ID14" stride="3">
<param name="X" type="float" />
<param name="Y" type="float" />
<param name="Z" type="float" />
</accessor>
</technique_common>
</source>
<vertices id="ID10">
<input semantic="POSITION" source="#ID8" />
<input semantic="NORMAL" source="#ID9" />
</vertices>
<triangles count="13" material="Material2">
<input offset="0" semantic="VERTEX" source="#ID10" />
<p>0 1 2 6 7 8 6 7 8 12 13 14 18 19 20 0 1 2 24 25 26 30 12 14 18 20 32 24 34 25 30 14 36 38 18 32 40 34 24</p>
</triangles>
<triangles count="13" material="Material3">
<input offset="0" semantic="VERTEX" source="#ID10" />
<p>3 4 5 9 10 11 9 10 11 15 16 17 21 22 23 3 4 5 27 28 29 15 17 31 33 21 23 28 35 29 37 15 31 33 23 39 29 35 41</p>
</triangles>
</mesh>
</geometry>
<geometry id="ID16">
<mesh>
<source id="ID17">
<float_array id="ID20" count="144">34.13386 15.47244 0.2362205 4.80315 15.47244 0.1574803 33.89764 17.6378 0.2362205 33.89764 17.6378 0.2362205 4.80315 15.47244 0.1574803 34.13386 15.47244 0.2362205 30.31496 26.73228 1.220472 30.31496 26.73228 1.220472 33.89764 17.6378 1.574803 34.13386 15.47244 0.2362205 33.89764 17.6378 0.2362205 33.89764 17.6378 0.2362205 34.13386 15.47244 0.2362205 33.89764 17.6378 1.574803 34.05512 15.55118 1.574803 4.80315 15.47244 0.1574803 34.13386 15.47244 0.2362205 34.13386 15.47244 0.2362205 4.80315 15.47244 0.1574803 34.05512 15.55118 1.574803 34.05512 15.55118 1.574803 4.80315 15.47244 0.1574803 34.13386 15.47244 0.2362205 34.13386 15.47244 0.2362205 4.80315 15.47244 0.1574803 34.05512 15.55118 1.574803 30.31496 26.73228 1.220472 30.31496 26.73228 1.220472 4.88189 23.22835 1.220472 4.88189 23.22835 1.220472 34.05512 15.55118 1.574803 34.05512 15.55118 1.574803 34.05512 15.55118 1.574803 4.80315 15.47244 1.496063 4.80315 15.47244 0.1574803 4.80315 15.47244 0.1574803 4.80315 15.47244 1.496063 34.05512 15.55118 1.574803 33.89764 17.6378 1.574803 30.31496 26.73228 1.220472 4.88189 23.22835 1.220472 4.88189 23.22835 1.220472 30.31496 26.73228 1.220472 33.89764 17.6378 1.574803 34.05512 15.55118 1.574803 4.80315 15.47244 1.496063 4.80315 15.47244 1.496063 34.05512 15.55118 1.574803</float_array>
<technique_common>
<accessor count="48" source="#ID20" stride="3">
<param name="X" type="float" />
<param name="Y" type="float" />
<param name="Z" type="float" />
</accessor>
</technique_common>
</source>
<source id="ID18">
<float_array id="ID21" count="144">0.002684554 0.0002928604 -0.9999964 -0.01473734 0.12288 -0.9923121 -0.000787119 0.04689963 -0.9988993 0.000787119 -0.04689963 0.9988993 0.01473734 -0.12288 0.9923121 -0.002684554 -0.0002928604 0.9999964 -0.007277174 0.110315 -0.99387 0.007277174 -0.110315 0.99387 0.9725871 0.2323356 0.009718386 0.9955834 0.08736469 0.03436596 0.9719196 0.2353134 -1.202976e-016 -0.9719196 -0.2353134 1.202976e-016 -0.9955834 -0.08736469 -0.03436596 -0.9725871 -0.2323356 -0.009718386 -0.0001576182 -0.9982749 0.05871278 -0.0001576182 -0.9982749 0.05871278 -0.0001576182 -0.9982749 0.05871278 0.0001576182 0.9982749 -0.05871278 0.0001576182 0.9982749 -0.05871278 0.0001576182 0.9982749 -0.05871278 -0.0001576182 -0.9982749 0.05871278 -0.0001576182 -0.9982749 0.05871278 -0.0001576182 -0.9982749 0.05871278 0.0001576182 0.9982749 -0.05871278 0.0001576182 0.9982749 -0.05871278 0.0001576182 0.9982749 -0.05871278 0.9304084 0.3665245 -2.676506e-016 -0.9304084 -0.3665245 2.676506e-016 -0.01872985 0.1359493 -0.9905387 0.01872985 -0.1359493 0.9905387 0.9957011 0.07514725 0.05415023 -0.9957011 -0.07514725 -0.05415023 0.00269178 -0.9999964 0 0.00269178 -0.9999964 0 0.00269178 -0.9999964 0 -0.00269178 0.9999964 -0 -0.00269178 0.9999964 -0 -0.00269178 0.9999964 -0 -0.003787425 0.01626622 0.9998605 -0.005087832 0.03692966 0.9993049 -0.005301222 0.03582462 0.999344 0.005301222 -0.03582462 -0.999344 0.005087832 -0.03692966 -0.9993049 0.003787425 -0.01626622 -0.9998605 -0.002691234 -0.000203112 0.9999964 -0.005229389 0.03392175 0.9994108 0.005229389 -0.03392175 -0.9994108 0.002691234 0.000203112 -0.9999964</float_array>
<technique_common>
<accessor count="48" source="#ID21" stride="3">
<param name="X" type="float" />
<param name="Y" type="float" />
<param name="Z" type="float" />
</accessor>
</technique_common>
</source>
<vertices id="ID19">
<input semantic="POSITION" source="#ID17" />
<input semantic="NORMAL" source="#ID18" />
</vertices>
<triangles count="13" material="Material2">
<input offset="0" semantic="VERTEX" source="#ID19" />
<p>0 1 2 2 1 6 8 9 10 14 15 16 20 21 22 26 8 10 6 1 28 8 30 9 32 33 34 32 33 34 38 39 40 44 38 45 38 40 45</p>
</triangles>
<triangles count="13" material="Material3">
<input offset="0" semantic="VERTEX" source="#ID19" />
<p>3 4 5 7 4 3 11 12 13 17 18 19 23 24 25 11 13 27 29 4 7 12 31 13 35 36 37 35 36 37 41 42 43 46 43 47 46 41 43</p>
</triangles>
</mesh>
</geometry>
</library_geometries>
<library_materials>
<material id="ID6" name="Color_003">
<instance_effect url="#ID7" />
</material>
<material id="ID11" name="__White_">
<instance_effect url="#ID12" />
</material>
</library_materials>
<library_effects>
<effect id="ID7">
<profile_COMMON>
<technique sid="COMMON">
<lambert>
<diffuse>
<color>0.6666667 0.6666667 0.6666667 1</color>
</diffuse>
</lambert>
</technique>
</profile_COMMON>
</effect>
<effect id="ID12">
<profile_COMMON>
<technique sid="COMMON">
<lambert>
<diffuse>
<color>1 1 1 1</color>
</diffuse>
</lambert>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<scene>
<instance_visual_scene url="#ID1" />
</scene>
</COLLADA>

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

View File

@ -1,114 +0,0 @@
<?xml version="1.0" encoding="UTF-8" standalone="no" ?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<authoring_tool>SketchUp 15.3.331</authoring_tool>
</contributor>
<created>2015-05-26T23:42:29Z</created>
<modified>2015-05-26T23:42:29Z</modified>
<unit meter="0.0254" name="inch" />
<up_axis>Z_UP</up_axis>
</asset>
<library_visual_scenes>
<visual_scene id="ID1">
<node name="SketchUp">
<node id="ID2" name="instance_0">
<matrix>0.001745328 -0.9999985 0 70.84882 0.9999985 0.001745328 0 -0.03157813 -0 0 1 -19.50896 0 0 0 1</matrix>
<instance_node url="#ID3" />
</node>
</node>
</visual_scene>
</library_visual_scenes>
<library_nodes>
<node id="ID3" name="ske2A3">
<node id="ID4" name="group_0">
<matrix>1.963935 -1.149254e-016 0 -217.1153 1.149254e-016 1.963935 0 16.85582 0 0 1.963935 19.40739 0 0 0 1</matrix>
<instance_geometry url="#ID5">
<bind_material>
<technique_common>
<instance_material symbol="Material2" target="#ID6">
<bind_vertex_input semantic="UVSET0" input_semantic="TEXCOORD" input_set="0" />
</instance_material>
<instance_material symbol="Material3" target="#ID11">
<bind_vertex_input semantic="UVSET0" input_semantic="TEXCOORD" input_set="0" />
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
</node>
</library_nodes>
<library_geometries>
<geometry id="ID5">
<mesh>
<source id="ID8">
<float_array id="ID13" count="120">173.5827 65.35433 28.34646 173.5433 59.72441 29.01575 162.197 60.69059 28.48352 162.197 60.69059 28.48352 173.5433 59.72441 29.01575 173.5827 65.35433 28.34646 162.1654 66.5748 27.75591 162.1654 66.5748 27.75591 182.126 64.29134 28.77953 182.126 64.29134 28.77953 173.5827 65.35433 28.34646 162.1654 66.5748 27.75591 173.5433 59.76378 30.43307 173.5433 59.76378 30.43307 162.1654 66.5748 27.75591 173.5827 65.35433 28.34646 182.1654 58.62205 31.06299 182.126 64.29134 28.77953 182.126 64.29134 28.77953 182.1654 58.62205 31.06299 182.1654 58.62205 29.44882 182.1654 58.62205 29.44882 162.1654 60.7874 29.93396 162.1654 60.7874 29.93396 191.0236 57.48031 31.22047 191.0236 57.48031 31.22047 191.063 63.07087 29.29134 191.063 63.07087 29.29134 191.063 63.07087 29.29134 191.063 63.07087 29.29134 191.0236 57.48031 29.96063 191.0236 57.48031 29.96063 207.0079 55.62992 31.77165 207.0079 55.62992 31.77165 207.0472 60.90551 30.11811 207.0472 60.90551 30.11811 207.0472 60.90551 30.11811 207.0472 60.90551 30.11811 207.0079 55.62992 30.55118 207.0079 55.62992 30.55118</float_array>
<technique_common>
<accessor count="40" source="#ID13" stride="3">
<param name="X" type="float" />
<param name="Y" type="float" />
<param name="Z" type="float" />
</accessor>
</technique_common>
</source>
<source id="ID9">
<float_array id="ID14" count="120">0.03634531 -0.1188937 -0.9922416 0.03587327 -0.1179703 -0.9923689 0.03771441 -0.121225 -0.9919083 -0.03771441 0.121225 0.9919083 -0.03587327 0.1179703 0.9923689 -0.03634531 0.1188937 0.9922416 0.0382097 -0.1224293 -0.9917414 -0.0382097 0.1224293 0.9917414 0.03775177 -0.1171551 -0.9923958 -0.03775177 0.1171551 0.9923958 -0.01224891 0.3540955 0.9351291 -0.00989876 0.3514344 0.9361602 -0.01674714 0.3501002 0.9365625 0.01674714 -0.3501002 -0.9365625 0.00989876 -0.3514344 -0.9361602 0.01224891 -0.3540955 -0.9351291 0.01322657 0.3694758 0.9291462 0.006999627 0.365608 0.9307426 -0.006999627 -0.365608 -0.9307426 -0.01322657 -0.3694758 -0.9291462 0.03836032 -0.1173106 -0.9923541 -0.03836032 0.1173106 0.9923541 -0.009366748 0.3522106 0.9358739 0.009366748 -0.3522106 -0.9358739 0.005662451 0.3347006 0.9423075 -0.005662451 -0.3347006 -0.9423075 0.03866059 -0.1186285 -0.9921858 -0.03866059 0.1186285 0.9921858 -0.004253652 0.3235305 0.9462082 0.004253652 -0.3235305 -0.9462082 0.03750441 -0.1151827 -0.9926361 -0.03750441 0.1151827 0.9926361 -0.005596535 0.305409 0.9522048 0.005596535 -0.305409 -0.9522048 0.02892951 -0.08956398 -0.9955608 -0.02892951 0.08956398 0.9955608 -0.008830529 0.2991342 0.9541702 0.008830529 -0.2991342 -0.9541702 0.02731657 -0.08198631 -0.996259 -0.02731657 0.08198631 0.996259</float_array>
<technique_common>
<accessor count="40" source="#ID14" stride="3">
<param name="X" type="float" />
<param name="Y" type="float" />
<param name="Z" type="float" />
</accessor>
</technique_common>
</source>
<vertices id="ID10">
<input semantic="POSITION" source="#ID8" />
<input semantic="NORMAL" source="#ID9" />
</vertices>
<triangles count="16" material="Material2">
<input offset="0" semantic="VERTEX" source="#ID10" />
<p>0 1 2 0 2 6 8 1 0 10 11 12 16 17 10 20 1 8 12 11 22 16 10 12 24 17 16 26 20 8 28 17 24 26 30 20 32 28 24 34 30 26 36 28 32 34 38 30</p>
</triangles>
<triangles count="16" material="Material3">
<input offset="0" semantic="VERTEX" source="#ID10" />
<p>3 4 5 7 3 5 5 4 9 13 14 15 15 18 19 9 4 21 23 14 13 13 15 19 19 18 25 9 21 27 25 18 29 21 31 27 25 29 33 27 31 35 33 29 37 31 39 35</p>
</triangles>
</mesh>
</geometry>
</library_geometries>
<library_materials>
<material id="ID6" name="__White_">
<instance_effect url="#ID7" />
</material>
<material id="ID11" name="__Gray_">
<instance_effect url="#ID12" />
</material>
</library_materials>
<library_effects>
<effect id="ID7">
<profile_COMMON>
<technique sid="COMMON">
<lambert>
<diffuse>
<color>1 1 1 1</color>
</diffuse>
</lambert>
</technique>
</profile_COMMON>
</effect>
<effect id="ID12">
<profile_COMMON>
<technique sid="COMMON">
<lambert>
<diffuse>
<color>0.5019608 0.5019608 0.5019608 1</color>
</diffuse>
</lambert>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<scene>
<instance_visual_scene url="#ID1" />
</scene>
</COLLADA>

View File

@ -1,114 +0,0 @@
<?xml version="1.0" encoding="UTF-8" standalone="no" ?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<authoring_tool>SketchUp 15.3.331</authoring_tool>
</contributor>
<created>2015-05-26T23:42:19Z</created>
<modified>2015-05-26T23:42:19Z</modified>
<unit meter="0.0254" name="inch" />
<up_axis>Z_UP</up_axis>
</asset>
<library_visual_scenes>
<visual_scene id="ID1">
<node name="SketchUp">
<node id="ID2" name="instance_0">
<matrix>0.001745328 -0.9999985 0 70.84882 0.9999985 0.001745328 0 -0.03157813 -0 0 1 -19.50896 0 0 0 1</matrix>
<instance_node url="#ID3" />
</node>
</node>
</visual_scene>
</library_visual_scenes>
<library_nodes>
<node id="ID3" name="ske2A3">
<node id="ID4" name="group_0">
<matrix>1.963935 -1.144917e-016 0 -217.1153 1.144917e-016 1.963935 0 16.85582 0 0 1.963935 19.40739 0 0 0 1</matrix>
<instance_geometry url="#ID5">
<bind_material>
<technique_common>
<instance_material symbol="Material2" target="#ID6">
<bind_vertex_input semantic="UVSET0" input_semantic="TEXCOORD" input_set="0" />
</instance_material>
<instance_material symbol="Material3" target="#ID11">
<bind_vertex_input semantic="UVSET0" input_semantic="TEXCOORD" input_set="0" />
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
</node>
</library_nodes>
<library_geometries>
<geometry id="ID5">
<mesh>
<source id="ID8">
<float_array id="ID13" count="96">137.2835 66.92913 26.77165 121.9291 59.25197 27.79528 121.9291 66.92913 26.25984 121.9291 66.92913 26.25984 121.9291 59.25197 27.79528 137.2835 66.92913 26.77165 137.2835 59.25197 29.96063 137.2835 66.92913 26.77165 121.9291 66.92913 26.25984 121.9291 66.92913 26.25984 137.2835 66.92913 26.77165 137.2835 59.25197 29.96063 137.2835 59.25197 27.79528 137.2835 59.25197 27.79528 121.9291 59.25197 29.33071 121.9291 59.25197 29.33071 152.3228 59.25197 30.23622 152.3228 59.25197 30.23622 152.3622 66.92913 27.44094 152.3622 66.92913 27.44094 152.3622 66.92913 27.44094 152.3622 66.92913 27.44094 152.3228 59.25197 28.4252 152.3228 59.25197 28.4252 162.1654 59.25197 30.51181 162.1654 59.25197 30.51181 162.1654 66.5748 27.75591 162.1654 66.5748 27.75591 162.1654 66.5748 27.75591 162.1654 66.5748 27.75591 162.2047 59.25197 28.66142 162.2047 59.25197 28.66142</float_array>
<technique_common>
<accessor count="32" source="#ID13" stride="3">
<param name="X" type="float" />
<param name="Y" type="float" />
<param name="Z" type="float" />
</accessor>
</technique_common>
</source>
<source id="ID9">
<float_array id="ID14" count="96">0.02682621 -0.1417739 -0.9895355 0.02297159 -0.1771324 -0.9839189 0.03266858 -0.1960115 -0.9800573 -0.03266858 0.1960115 0.9800573 -0.02297159 0.1771324 0.9839189 -0.02682621 0.1417739 0.9895355 -0.02493687 0.3815814 0.9239988 -0.02780814 0.3770153 0.9257895 -0.03575652 0.3750234 0.9263255 0.03575652 -0.3750234 -0.9263255 0.02780814 -0.3770153 -0.9257895 0.02493687 -0.3815814 -0.9239988 0.02165175 -0.1314105 -0.9910916 -0.02165175 0.1314105 0.9910916 -0.03806375 0.3711215 0.9278038 0.03806375 -0.3711215 -0.9278038 -0.03001613 0.3487806 0.9367236 0.03001613 -0.3487806 -0.9367236 0.03483823 -0.1279932 -0.991163 -0.03483823 0.1279932 0.991163 -0.03222275 0.344211 0.9383392 0.03222275 -0.344211 -0.9383392 0.03366092 -0.1263005 -0.9914208 -0.03366092 0.1263005 0.9914208 -0.02130276 0.3477379 0.9373497 0.02130276 -0.3477379 -0.9373497 0.02520877 -0.1245398 -0.9918943 -0.02520877 0.1245398 0.9918943 -0.01733589 0.3521731 0.9357743 0.01733589 -0.3521731 -0.9357743 0.02371739 -0.1225611 -0.9921775 -0.02371739 0.1225611 0.9921775</float_array>
<technique_common>
<accessor count="32" source="#ID14" stride="3">
<param name="X" type="float" />
<param name="Y" type="float" />
<param name="Z" type="float" />
</accessor>
</technique_common>
</source>
<vertices id="ID10">
<input semantic="POSITION" source="#ID8" />
<input semantic="NORMAL" source="#ID9" />
</vertices>
<triangles count="12" material="Material2">
<input offset="0" semantic="VERTEX" source="#ID10" />
<p>0 1 2 6 7 8 12 1 0 6 8 14 16 7 6 18 12 0 20 7 16 18 22 12 24 20 16 26 22 18 24 28 20 30 22 26</p>
</triangles>
<triangles count="12" material="Material3">
<input offset="0" semantic="VERTEX" source="#ID10" />
<p>3 4 5 9 10 11 5 4 13 15 9 11 11 10 17 5 13 19 17 10 21 13 23 19 17 21 25 19 23 27 21 29 25 27 23 31</p>
</triangles>
</mesh>
</geometry>
</library_geometries>
<library_materials>
<material id="ID6" name="__White_">
<instance_effect url="#ID7" />
</material>
<material id="ID11" name="__Gray_">
<instance_effect url="#ID12" />
</material>
</library_materials>
<library_effects>
<effect id="ID7">
<profile_COMMON>
<technique sid="COMMON">
<lambert>
<diffuse>
<color>1 1 1 1</color>
</diffuse>
</lambert>
</technique>
</profile_COMMON>
</effect>
<effect id="ID12">
<profile_COMMON>
<technique sid="COMMON">
<lambert>
<diffuse>
<color>0.5019608 0.5019608 0.5019608 1</color>
</diffuse>
</lambert>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<scene>
<instance_visual_scene url="#ID1" />
</scene>
</COLLADA>

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

View File

@ -1,114 +0,0 @@
<?xml version="1.0" encoding="UTF-8" standalone="no" ?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<authoring_tool>SketchUp 15.3.331</authoring_tool>
</contributor>
<created>2015-05-26T23:41:47Z</created>
<modified>2015-05-26T23:41:47Z</modified>
<unit meter="0.0254" name="inch" />
<up_axis>Z_UP</up_axis>
</asset>
<library_visual_scenes>
<visual_scene id="ID1">
<node name="SketchUp">
<node id="ID2" name="instance_0">
<matrix>0.001745328 -0.9999985 0 70.84882 0.9999985 0.001745328 0 -0.03157813 -0 0 1 -19.50896 0 0 0 1</matrix>
<instance_node url="#ID3" />
</node>
</node>
</visual_scene>
</library_visual_scenes>
<library_nodes>
<node id="ID3" name="ske2A3">
<node id="ID4" name="group_0">
<matrix>1.963935 -1.140581e-016 0 -217.1153 1.140581e-016 1.963935 0 16.85582 0 0 1.963935 19.40739 0 0 0 1</matrix>
<instance_geometry url="#ID5">
<bind_material>
<technique_common>
<instance_material symbol="Material2" target="#ID6">
<bind_vertex_input semantic="UVSET0" input_semantic="TEXCOORD" input_set="0" />
</instance_material>
<instance_material symbol="Material3" target="#ID11">
<bind_vertex_input semantic="UVSET0" input_semantic="TEXCOORD" input_set="0" />
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
</node>
</library_nodes>
<library_geometries>
<geometry id="ID5">
<mesh>
<source id="ID8">
<float_array id="ID13" count="120">58.93701 66.5748 27.75591 47.55906 59.6063 29.13386 47.59843 65.15748 28.30709 47.59843 65.15748 28.30709 47.55906 59.6063 29.13386 58.93701 66.5748 27.75591 39.33071 58.62205 29.56693 39.33071 58.62205 29.56693 58.97638 60.95635 29.96063 58.93701 66.5748 27.75591 47.59843 65.15748 28.30709 47.59843 65.15748 28.30709 58.93701 66.5748 27.75591 58.97638 60.95635 29.96063 58.97638 60.7874 28.50244 58.97638 60.7874 28.50244 39.29134 64.13386 28.74016 39.29134 64.13386 28.74016 47.59843 59.64567 30.43307 47.59843 59.64567 30.43307 30.11811 57.59843 29.96063 30.11811 57.59843 29.96063 39.29134 64.13386 28.74016 39.29134 64.13386 28.74016 30.07874 63.0315 29.25197 30.07874 63.0315 29.25197 39.33071 58.62205 30.7874 39.33071 58.62205 30.7874 14.13386 55.62992 30.55118 14.13386 55.62992 30.55118 30.07874 63.0315 29.25197 30.07874 63.0315 29.25197 14.05512 60.94488 30.07874 14.05512 60.94488 30.07874 30.11811 57.59843 31.1811 30.11811 57.59843 31.1811 14.05512 60.94488 30.07874 14.05512 60.94488 30.07874 14.13386 55.62992 31.77165 14.13386 55.62992 31.77165</float_array>
<technique_common>
<accessor count="40" source="#ID13" stride="3">
<param name="X" type="float" />
<param name="Y" type="float" />
<param name="Z" type="float" />
</accessor>
</technique_common>
</source>
<source id="ID9">
<float_array id="ID14" count="120">-0.03804767 -0.1336973 -0.9902916 -0.03393509 -0.1443297 -0.9889476 -0.03164446 -0.1472782 -0.9885888 0.03164446 0.1472782 0.9885888 0.03393509 0.1443297 0.9889476 0.03804767 0.1336973 0.9902916 -0.0294332 -0.1482161 -0.9885169 0.0294332 0.1482161 0.9885169 -0.001092279 0.3636841 0.9315217 -0.000409118 0.3652875 0.9308947 0.0008682838 0.3607536 0.9326607 -0.0008682838 -0.3607536 -0.9326607 0.000409118 -0.3652875 -0.9308947 0.001092279 -0.3636841 -0.9315217 -0.04154783 -0.1281008 -0.9908905 0.04154783 0.1281008 0.9908905 -0.03197393 -0.1454677 -0.9888462 0.03197393 0.1454677 0.9888462 -0.0004293308 0.3574471 0.9339333 0.0004293308 -0.3574471 -0.9339333 -0.0272016 -0.1325668 -0.9908007 0.0272016 0.1325668 0.9908007 0.004716089 0.3506517 0.9364941 -0.004716089 -0.3506517 -0.9364941 -0.03271636 -0.125567 -0.9915455 0.03271636 0.125567 0.9915455 0.002870077 0.3456667 0.938353 -0.002870077 -0.3456667 -0.938353 -0.03566361 -0.09775055 -0.9945717 0.03566361 0.09775055 0.9945717 0.00538455 0.3372325 0.941406 -0.00538455 -0.3372325 -0.941406 -0.03975437 -0.08905412 -0.9952331 0.03975437 0.08905412 0.9952331 0.003353341 0.3312469 0.9435382 -0.003353341 -0.3312469 -0.9435382 -0.0006590497 0.3100183 0.9507304 0.0006590497 -0.3100183 -0.9507304 -0.002169095 0.3034651 0.9528401 0.002169095 -0.3034651 -0.9528401</float_array>
<technique_common>
<accessor count="40" source="#ID14" stride="3">
<param name="X" type="float" />
<param name="Y" type="float" />
<param name="Z" type="float" />
</accessor>
</technique_common>
</source>
<vertices id="ID10">
<input semantic="POSITION" source="#ID8" />
<input semantic="NORMAL" source="#ID9" />
</vertices>
<triangles count="16" material="Material2">
<input offset="0" semantic="VERTEX" source="#ID10" />
<p>0 1 2 2 1 6 8 9 10 14 1 0 2 6 16 8 10 18 6 20 16 18 10 22 16 20 24 18 22 26 20 28 24 26 22 30 24 28 32 26 30 34 34 30 36 34 36 38</p>
</triangles>
<triangles count="16" material="Material3">
<input offset="0" semantic="VERTEX" source="#ID10" />
<p>3 4 5 7 4 3 11 12 13 5 4 15 17 7 3 19 11 13 17 21 7 23 11 19 25 21 17 27 23 19 25 29 21 31 23 27 33 29 25 35 31 27 37 31 35 39 37 35</p>
</triangles>
</mesh>
</geometry>
</library_geometries>
<library_materials>
<material id="ID6" name="__White_">
<instance_effect url="#ID7" />
</material>
<material id="ID11" name="__Gray_">
<instance_effect url="#ID12" />
</material>
</library_materials>
<library_effects>
<effect id="ID7">
<profile_COMMON>
<technique sid="COMMON">
<lambert>
<diffuse>
<color>1 1 1 1</color>
</diffuse>
</lambert>
</technique>
</profile_COMMON>
</effect>
<effect id="ID12">
<profile_COMMON>
<technique sid="COMMON">
<lambert>
<diffuse>
<color>0.5019608 0.5019608 0.5019608 1</color>
</diffuse>
</lambert>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<scene>
<instance_visual_scene url="#ID1" />
</scene>
</COLLADA>

View File

@ -1,161 +0,0 @@
<?xml version="1.0" encoding="UTF-8" standalone="no" ?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<authoring_tool>SketchUp 15.3.331</authoring_tool>
</contributor>
<created>2015-05-26T23:42:08Z</created>
<modified>2015-05-26T23:42:08Z</modified>
<unit meter="0.0254" name="inch" />
<up_axis>Z_UP</up_axis>
</asset>
<library_visual_scenes>
<visual_scene id="ID1">
<node name="SketchUp">
<node id="ID2" name="instance_0">
<matrix>0.001745328 -0.9999985 0 70.84882 0.9999985 0.001745328 0 -0.03157813 -0 0 1 -19.50896 0 0 0 1</matrix>
<instance_node url="#ID3" />
</node>
</node>
</visual_scene>
</library_visual_scenes>
<library_nodes>
<node id="ID3" name="ske2A3">
<node id="ID4" name="group_0">
<matrix>1.963935 -1.140581e-016 0 -217.1153 1.140581e-016 1.963935 0 16.85582 0 0 1.963935 19.40739 0 0 0 1</matrix>
<instance_geometry url="#ID5">
<bind_material>
<technique_common>
<instance_material symbol="Material2" target="#ID6">
<bind_vertex_input semantic="UVSET0" input_semantic="TEXCOORD" input_set="0" />
</instance_material>
<instance_material symbol="Material3" target="#ID11">
<bind_vertex_input semantic="UVSET0" input_semantic="TEXCOORD" input_set="0" />
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
<instance_geometry url="#ID15">
<bind_material>
<technique_common>
<instance_material symbol="Material2" target="#ID16">
<bind_vertex_input semantic="UVSET0" input_semantic="TEXCOORD" input_set="0" />
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
</node>
</library_nodes>
<library_geometries>
<geometry id="ID5">
<mesh>
<source id="ID8">
<float_array id="ID13" count="102">99.2126 66.9685 26.29921 83.85827 66.92913 26.81102 99.2126 59.25197 29.33071 99.2126 59.25197 29.33071 83.85827 66.92913 26.81102 99.2126 66.9685 26.29921 83.85827 59.25197 29.96063 83.85827 59.25197 29.96063 99.2126 66.9685 26.29921 83.85827 59.25197 27.79528 83.85827 66.92913 26.81102 83.85827 66.92913 26.81102 83.85827 59.25197 27.79528 99.2126 66.9685 26.29921 68.77953 66.92913 27.44094 68.77953 66.92913 27.44094 68.8189 59.25197 28.4252 68.77953 66.92913 27.44094 76.33858 59.25197 28.11024 76.33858 59.25197 28.11024 68.8189 59.25197 28.4252 68.77953 66.92913 27.44094 99.2126 59.25197 27.79528 99.2126 59.25197 27.79528 68.8189 59.25197 30.23622 68.8189 59.25197 30.23622 58.97638 59.25197 28.70079 58.97638 59.25197 28.70079 58.93701 66.5748 27.75591 58.93701 66.5748 27.75591 58.93701 66.5748 27.75591 58.93701 66.5748 27.75591 58.97638 59.25197 30.62992 58.97638 59.25197 30.62992</float_array>
<technique_common>
<accessor count="34" source="#ID13" stride="3">
<param name="X" type="float" />
<param name="Y" type="float" />
<param name="Z" type="float" />
</accessor>
</technique_common>
</source>
<source id="ID9">
<float_array id="ID14" count="102">0.03007387 0.365487 0.9303305 0.03702604 0.3770976 0.9254331 0.03254441 0.3698361 0.9285269 -0.03254441 -0.3698361 -0.9285269 -0.03702604 -0.3770976 -0.9254331 -0.03007387 -0.365487 -0.9303305 0.0348804 0.3734313 0.9270018 -0.0348804 -0.3734313 -0.9270018 -0.009746117 -0.1715996 -0.9851186 -0.03218648 -0.1366818 -0.990092 -0.03707021 -0.127129 -0.9911932 0.03707021 0.127129 0.9911932 0.03218648 0.1366818 0.990092 0.009746117 0.1715996 0.9851186 0.02096268 0.3482456 0.9371689 -0.02096268 -0.3482456 -0.9371689 -0.03461144 -0.1272104 -0.9912717 -0.03455417 -0.1273749 -0.9912526 -0.04145418 -0.1271596 -0.9910156 0.04145418 0.1271596 0.9910156 0.03461144 0.1272104 0.9912717 0.03455417 0.1273749 0.9912526 6.679878e-018 -0.1903334 -0.9817195 -6.679878e-018 0.1903334 0.9817195 0.02167083 0.3471584 0.9375561 -0.02167083 -0.3471584 -0.9375561 -0.02738866 -0.1277233 -0.9914316 0.02738866 0.1277233 0.9914316 0.02865303 0.3551468 0.9343713 -0.02865303 -0.3551468 -0.9343713 -0.02711419 -0.1280677 -0.9913947 0.02711419 0.1280677 0.9913947 0.03720642 0.365263 0.9301605 -0.03720642 -0.365263 -0.9301605</float_array>
<technique_common>
<accessor count="34" source="#ID14" stride="3">
<param name="X" type="float" />
<param name="Y" type="float" />
<param name="Z" type="float" />
</accessor>
</technique_common>
</source>
<vertices id="ID10">
<input semantic="POSITION" source="#ID8" />
<input semantic="NORMAL" source="#ID9" />
</vertices>
<triangles count="13" material="Material2">
<input offset="0" semantic="VERTEX" source="#ID10" />
<p>0 1 2 2 1 6 8 9 10 1 14 6 10 16 17 16 10 18 18 10 9 8 22 9 6 14 24 16 26 17 24 14 28 17 26 30 24 28 32</p>
</triangles>
<triangles count="13" material="Material3">
<input offset="0" semantic="VERTEX" source="#ID10" />
<p>3 4 5 7 4 3 11 12 13 7 15 4 12 11 19 19 11 20 21 20 11 12 23 13 25 15 7 21 27 20 29 15 25 31 27 21 33 29 25</p>
</triangles>
</mesh>
</geometry>
<geometry id="ID15">
<mesh>
<source id="ID18">
<float_array id="ID20" count="9">58.97638 60.7874 28.50244 58.93701 66.5748 27.75591 58.97638 60.95635 29.96063</float_array>
<technique_common>
<accessor count="3" source="#ID20" stride="3">
<param name="X" type="float" />
<param name="Y" type="float" />
<param name="Z" type="float" />
</accessor>
</technique_common>
</source>
<vertices id="ID19">
<input semantic="POSITION" source="#ID18" />
</vertices>
<lines count="2" material="Material2">
<input offset="0" semantic="VERTEX" source="#ID19" />
<p>1 0 2 1</p>
</lines>
</mesh>
</geometry>
</library_geometries>
<library_materials>
<material id="ID6" name="__White_">
<instance_effect url="#ID7" />
</material>
<material id="ID11" name="__Gray_">
<instance_effect url="#ID12" />
</material>
<material id="ID16" name="edge_color477979255">
<instance_effect url="#ID17" />
</material>
</library_materials>
<library_effects>
<effect id="ID7">
<profile_COMMON>
<technique sid="COMMON">
<lambert>
<diffuse>
<color>1 1 1 1</color>
</diffuse>
</lambert>
</technique>
</profile_COMMON>
</effect>
<effect id="ID12">
<profile_COMMON>
<technique sid="COMMON">
<lambert>
<diffuse>
<color>0.5019608 0.5019608 0.5019608 1</color>
</diffuse>
</lambert>
</technique>
</profile_COMMON>
</effect>
<effect id="ID17">
<profile_COMMON>
<technique sid="COMMON">
<constant>
<transparent opaque="A_ONE">
<color>0.1843137 0.3098039 0.3098039 1</color>
</transparent>
<transparency>
<float>1</float>
</transparency>
</constant>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<scene>
<instance_visual_scene url="#ID1" />
</scene>
</COLLADA>

File diff suppressed because one or more lines are too long

View File

@ -1,15 +0,0 @@
<?xml version="1.0"?>
<model>
<name>rc_cessna</name>
<version>1.0</version>
<sdf version='1.9'>model.sdf</sdf>
<author>
<name>Benjamin Perseghetti</name>
<email>bperseghetti@rudislabs.com</email>
</author>
<description>
This is a model of an RC Cessna 182.
</description>
</model>

View File

@ -1,824 +0,0 @@
<?xml version="1.0"?>
<sdf version='1.9'>
<model name='rc_cessna'>
<pose>0 0 0.246 0 0 0</pose>
<link name='base_link'>
<pose>0 0 0 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>1.5</mass>
<inertia>
<ixx>0.197563</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.1458929</iyy>
<iyz>0</iyz>
<izz>0.1477</izz>
</inertia>
</inertial>
<collision name='fuselodge_collision'>
<pose>-.14 0 0 0 0 0</pose>
<geometry>
<box>
<size>0.65 .08 0.10</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<max_vel>10</max_vel>
<min_depth>0.01</min_depth>
</ode>
</contact>
</surface>
</collision>
<collision name='wings_collision'>
<pose>-0.01 0 0.07 0 0 0</pose>
<geometry>
<box>
<size>0.1 1.0 0.01</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<max_vel>10</max_vel>
<min_depth>0.01</min_depth>
</ode>
</contact>
</surface>
</collision>
<!-- <visual name='fuselodge_collision_visual'>
<pose>-.14 0 0 0 0 0</pose>
<geometry>
<box>
<size>0.65 .08 0.1</size>
</box>
</geometry>
</visual>
<visual name='wings_collision_visual'>
<pose>-0.01 0 0.07 0 0 0</pose>
<geometry>
<box>
<size>0.1 1.0 0.01</size>
</box>
</geometry>
</visual> -->
<visual name='base_link_visual'>
<pose>0.07 0 -0.08 0 0 0</pose>
<geometry>
<mesh>
<scale>0.1 0.1 0.1</scale>
<uri>model://rc_cessna/meshes/body.dae</uri>
</mesh>
</geometry>
<material>
<ambient>.175 .175 .175 1.0</ambient>
<diffuse>.175 .175 .175 1.0</diffuse>
</material>
</visual>
<gravity>1</gravity>
<velocity_decay/>
<self_collide>0</self_collide>
<sensor name="imu_sensor" type="imu">
<always_on>1</always_on>
<update_rate>250</update_rate>
</sensor>
<sensor name="air_pressure_sensor" type="air_pressure">
<always_on>1</always_on>
<update_rate>50</update_rate>
<air_pressure>
<pressure>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.01</stddev>
</noise>
</pressure>
</air_pressure>
</sensor>
</link>
<link name="airspeed">
<pose>0 0 0 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.015</mass>
<inertia>
<ixx>1e-05</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1e-05</iyy>
<iyz>0</iyz>
<izz>1e-05</izz>
</inertia>
</inertial>
<visual name="airspeed_visual">
<geometry>
<cylinder>
<radius>0.01</radius>
<length>0.1</length>
</cylinder>
</geometry>
<material>
<ambient>0 0 0 1.0</ambient>
<diffuse>0 0 0 1.0</diffuse>
</material>
</visual>
<!-- <sensor name="air_speed" type="air_speed">
<always_on>1</always_on>
<update_rate>5.0</update_rate>
<enable_metrics>false</enable_metrics>
<air_speed>
<airspeed>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.01</stddev>
</noise>
</airspeed>
</air_speed>
</sensor> -->
</link>
<joint name='airspeed_joint' type='fixed'>
<child>airspeed</child>
<parent>base_link</parent>
</joint>
<link name='rotor_puller'>
<pose>0.22 0 0.0 0 1.57079632679 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.005</mass>
<inertia>
<ixx>9.75e-07</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.000166704</iyy>
<iyz>0</iyz>
<izz>0.000167604</izz>
</inertia>
</inertial>
<collision name='rotor_puller_collision'>
<pose>0 0 0 0 -1.57079632679 0</pose>
<geometry>
<box>
<size>0.005 0.22 0.02</size>
</box>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<!-- <visual name='rotor_puller_collision_visual'>
<pose>0 0 0 0 -1.57079632679 0</pose>
<geometry>
<box>
<size>0.005 0.22 0.02</size>
</box>
</geometry>
</visual> -->
<visual name='rotor_puller_visual'>
<pose>0 0 0 0 0 -1.57079632679</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://rc_cessna/meshes/iris_prop_ccw.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0 0 1 1.0</ambient>
<diffuse>0 0 1 1.0</diffuse>
</material>
</visual>
<gravity>1</gravity>
<velocity_decay/>
<self_collide>0</self_collide>
</link>
<joint name='rotor_puller_joint' type='revolute'>
<child>rotor_puller</child>
<parent>base_link</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name="left_elevon">
<inertial>
<mass>0.00000001</mass>
<inertia>
<ixx>0.000001</ixx>
<ixy>0.0</ixy>
<iyy>0.000001</iyy>
<ixz>0.0</ixz>
<iyz>0.0</iyz>
<izz>0.000001</izz>
</inertia>
<pose>0 0.3 0 0.00 0 0.0</pose>
</inertial>
<visual name='left_elevon_visual'>
<pose>0.07 0.0 -0.08 0.00 0 0.0</pose>
<geometry>
<mesh>
<scale>0.1 0.1 0.1</scale>
<uri>model://rc_cessna/meshes/left_aileron.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0 0 1 1.0</ambient>
<diffuse>0 0 1 1.0</diffuse>
</material>
</visual>
</link>
<link name="LeftWheel">
<pose relative_to="LeftWheelJoint">0 0 0 0 0 0</pose>
<inertial>
<mass>.05</mass>
<inertia>
<ixx>0.00003331</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.0000204</iyy>
<iyz>0</iyz>
<izz>0.0000204</izz>
</inertia>
</inertial>
<gravity>true</gravity>
<velocity_decay/>
<visual name="LeftWheelVisual">
<pose>0 0 0 -1.57079632679 0 0</pose>
<geometry>
<cylinder>
<length>0.01</length>
<radius>0.03</radius>
</cylinder>
</geometry>
</visual>
<collision name="LeftWheelCollision">
<pose>0 0 0 -1.57079632679 0 0</pose>
<geometry>
<cylinder>
<length>0.01</length>
<radius>0.03</radius>
</cylinder>
</geometry>
<surface>
<friction>
<ode>
<mu>1.0</mu>
<mu2>0.5</mu2>
<fdir1>0 0 1</fdir1>
</ode>
</friction>
</surface>
</collision>
</link>
<link name="RightWheel">
<pose relative_to="RightWheelJoint">0 0 0 0 0 0</pose>
<inertial>
<mass>.05</mass>
<inertia>
<ixx>0.00003331</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.0000204</iyy>
<iyz>0</iyz>
<izz>0.0000204</izz>
</inertia>
</inertial>
<gravity>true</gravity>
<velocity_decay/>
<visual name="RightWheelVisual">
<pose>0 0 0 -1.57079632679 0 0</pose>
<geometry>
<cylinder>
<length>0.01</length>
<radius>0.03</radius>
</cylinder>
</geometry>
</visual>
<collision name="RightWheelCollision">
<pose>0 0 0 -1.57079632679 0 0</pose>
<geometry>
<cylinder>
<length>0.01</length>
<radius>0.03</radius>
</cylinder>
</geometry>
<surface>
<friction>
<ode>
<mu>1.0</mu>
<mu2>0.5</mu2>
<fdir1>0 0 1</fdir1>
</ode>
</friction>
</surface>
</collision>
</link>
<link name="CenterWheel">
<pose relative_to="CenterWheelJoint">0 0 0 0 0 0</pose>
<inertial>
<mass>.05</mass>
<inertia>
<ixx>0.00003331</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.0000204</iyy>
<iyz>0</iyz>
<izz>0.0000204</izz>
</inertia>
</inertial>
<gravity>true</gravity>
<velocity_decay/>
<visual name="CenterWheelVisual">
<pose>0 0 0 -1.57079632679 0 0</pose>
<geometry>
<cylinder>
<length>0.01</length>
<radius>0.025</radius>
</cylinder>
</geometry>
</visual>
<collision name="CenterWheelCollision">
<pose>0 0 0 -1.57079632679 0 0</pose>
<geometry>
<cylinder>
<length>0.01</length>
<radius>0.025</radius>
</cylinder>
</geometry>
<surface>
<friction>
<ode>
<mu>1.0</mu>
<mu2>0.5</mu2>
<fdir1>0 0 1</fdir1>
</ode>
</friction>
</surface>
</collision>
</link>
<link name="right_elevon">
<inertial>
<mass>0.00000001</mass>
<inertia>
<ixx>0.000001</ixx>
<ixy>0.0</ixy>
<iyy>0.000001</iyy>
<ixz>0.0</ixz>
<iyz>0.0</iyz>
<izz>0.000001</izz>
</inertia>
<pose>0 -0.3 0 0.00 0 0.0</pose>
</inertial>
<visual name='right_elevon_visual'>
<pose>0.07 0.0 -0.08 0.00 0 0.0</pose>
<geometry>
<mesh>
<scale>0.1 0.1 0.1</scale>
<uri>model://rc_cessna/meshes/right_aileron.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0 0 1 1.0</ambient>
<diffuse>0 0 1 1.0</diffuse>
</material>
</visual>
</link>
<link name="left_flap">
<inertial>
<mass>0.00000001</mass>
<inertia>
<ixx>0.000001</ixx>
<ixy>0.0</ixy>
<iyy>0.000001</iyy>
<ixz>0.0</ixz>
<iyz>0.0</iyz>
<izz>0.000001</izz>
</inertia>
<pose>0 0.15 0 0.00 0 0.0</pose>
</inertial>
<visual name='left_flap_visual'>
<pose>0.07 0.0 -0.08 0.00 0 0.0</pose>
<geometry>
<mesh>
<scale>0.1 0.1 0.1</scale>
<uri>model://rc_cessna/meshes/left_flap.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0 0 1 1.0</ambient>
<diffuse>0 0 1 1.0</diffuse>
</material>
</visual>
</link>
<link name="right_flap">
<inertial>
<mass>0.00000001</mass>
<inertia>
<ixx>0.000001</ixx>
<ixy>0.0</ixy>
<iyy>0.000001</iyy>
<ixz>0.0</ixz>
<iyz>0.0</iyz>
<izz>0.000001</izz>
</inertia>
<pose>0 -0.15 0 0.00 0 0.0</pose>
</inertial>
<visual name='right_flap_visual'>
<pose>0.07 0.0 -0.08 0.00 0 0.0</pose>
<geometry>
<mesh>
<scale>0.1 0.1 0.1</scale>
<uri>model://rc_cessna/meshes/right_flap.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0 0 1 1.0</ambient>
<diffuse>0 0 1 1.0</diffuse>
</material>
</visual>
</link>
<link name="elevator">
<inertial>
<mass>0.00000001</mass>
<inertia>
<ixx>0.000001</ixx>
<ixy>0.0</ixy>
<iyy>0.000001</iyy>
<ixz>0.0</ixz>
<iyz>0.0</iyz>
<izz>0.000001</izz>
</inertia>
<pose> -0.5 0 0 0.00 0 0.0</pose>
</inertial>
<visual name='elevator_visual'>
<pose>0.07 0.0 -0.08 0.00 0 0.0</pose>
<geometry>
<mesh>
<scale>0.1 0.1 0.1</scale>
<uri>model://rc_cessna/meshes/elevators.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0 0 1 1.0</ambient>
<diffuse>0 0 1 1.0</diffuse>
</material>
</visual>
</link>
<link name="rudder">
<inertial>
<mass>0.00000001</mass>
<inertia>
<ixx>0.000001</ixx>
<ixy>0.0</ixy>
<iyy>0.000001</iyy>
<ixz>0.0</ixz>
<iyz>0.0</iyz>
<izz>0.000001</izz>
</inertia>
<pose>-0.5 0 0.05 0 0 0 </pose>
</inertial>
<visual name='rudder_visual'>
<pose>0.07 0.0 -0.08 0.00 0 0.0</pose>
<geometry>
<mesh>
<scale>0.1 0.1 0.1</scale>
<uri>model://rc_cessna/meshes/rudder.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0 0 1 1.0</ambient>
<diffuse>0 0 1 1.0</diffuse>
</material>
</visual>
</link>
<joint name='servo_0' type='revolute'>
<parent>base_link</parent>
<child>left_elevon</child>
<pose>-0.07 0.4 0.08 0.00 0 0.0</pose>
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-0.53</lower>
<upper>0.53</upper>
</limit>
<dynamics>
<damping>1.000</damping>
</dynamics>
</axis>
<physics>
<ode>
<implicit_spring_damper>1</implicit_spring_damper>
</ode>
</physics>
</joint>
<joint name='servo_1' type='revolute'>
<parent>base_link</parent>
<child>right_elevon</child>
<pose>-0.07 -0.4 0.08 0.00 0 0.0</pose>
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-0.53</lower>
<upper>0.53</upper>
</limit>
<dynamics>
<damping>1.000</damping>
</dynamics>
</axis>
<physics>
<ode>
<implicit_spring_damper>1</implicit_spring_damper>
</ode>
</physics>
</joint>
<joint name='left_flap_joint' type='revolute'>
<parent>base_link</parent>
<child>left_flap</child>
<pose>-0.07 0.2 0.08 0.00 0 0.0</pose>
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-0.53</lower>
<upper>0.53</upper>
</limit>
<dynamics>
<damping>1.000</damping>
</dynamics>
</axis>
<physics>
<ode>
<implicit_spring_damper>1</implicit_spring_damper>
</ode>
</physics>
</joint>
<joint name='right_flap_joint' type='revolute'>
<parent>base_link</parent>
<child>right_flap</child>
<pose>-0.07 -0.2 0.08 0.00 0 0.0</pose>
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-0.53</lower>
<upper>0.53</upper>
</limit>
<dynamics>
<damping>1.000</damping>
</dynamics>
</axis>
<physics>
<ode>
<implicit_spring_damper>1</implicit_spring_damper>
</ode>
</physics>
</joint>
<joint name='servo_2' type='revolute'>
<parent>base_link</parent>
<child>elevator</child>
<pose> -0.5 0 0 0 0 0</pose>
<axis>
<xyz>0 1 0</xyz>
<limit>
<!-- -30/+30 deg. -->
<lower>-0.53</lower>
<upper>0.53</upper>
</limit>
<dynamics>
<damping>1.000</damping>
</dynamics>
</axis>
<physics>
<ode>
<implicit_spring_damper>1</implicit_spring_damper>
</ode>
</physics>
</joint>
<joint name='rudder_joint' type='revolute'>
<parent>base_link</parent>
<child>rudder</child>
<pose>-0.5 0 0.05 0.00 0 0.0</pose>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-0.53</lower>
<upper>0.53</upper>
</limit>
<dynamics>
<damping>1.000</damping>
</dynamics>
</axis>
<physics>
<ode>
<implicit_spring_damper>1</implicit_spring_damper>
</ode>
</physics>
</joint>
<joint name="LeftWheelJoint" type="revolute">
<parent>base_link</parent>
<child>LeftWheel</child>
<pose relative_to="base_link">-.035 .13 -0.12 0 0 0</pose>
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-1.79769e+308</lower>
<upper>1.79769e+308</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<joint name="RightWheelJoint" type="revolute">
<parent>base_link</parent>
<child>RightWheel</child>
<pose relative_to="base_link">-.035 -.13 -0.12 0 0 0</pose>
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-1.79769e+308</lower>
<upper>1.79769e+308</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<joint name="CenterWheelJoint" type="revolute">
<parent>base_link</parent>
<child>CenterWheel</child>
<pose relative_to="base_link">.135 0 -0.12 0 0 0</pose>
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-1.79769e+308</lower>
<upper>1.79769e+308</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<plugin filename="gz-sim-lift-drag-system" name="gz::sim::systems::LiftDrag">
<a0>0.05984281113</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.05 0.45 0.05</cp>
<area>0.6</area>
<air_density>1.2041</air_density>
<forward>1 0 0</forward>
<upward>0 0 1</upward>
<link_name>base_link</link_name>
<control_joint_name>servo_0</control_joint_name>
<control_joint_rad_to_cl>-0.3</control_joint_rad_to_cl>
</plugin>
<plugin
filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController">
<joint_name>servo_0</joint_name>
<sub_topic>servo_0</sub_topic>
<p_gain>10.0</p_gain>
</plugin>
<plugin filename="gz-sim-lift-drag-system" name="gz::sim::systems::LiftDrag">
<a0>0.05984281113</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.05 -0.45 0.05</cp>
<area>0.6</area>
<air_density>1.2041</air_density>
<forward>1 0 0</forward>
<upward>0 0 1</upward>
<link_name>base_link</link_name>
<control_joint_name>servo_1</control_joint_name>
<control_joint_rad_to_cl>-0.3</control_joint_rad_to_cl>
</plugin>
<plugin
filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController">
<joint_name>servo_1</joint_name>
<sub_topic>servo_1</sub_topic>
<p_gain>10.0</p_gain>
</plugin>
<plugin filename="gz-sim-lift-drag-system" name="gz::sim::systems::LiftDrag">
<a0>0.05984281113</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.05 0.15 0.05</cp>
<area>0.6</area>
<air_density>1.2041</air_density>
<forward>1 0 0</forward>
<upward>0 0 1</upward>
<link_name>base_link</link_name>
<control_joint_name>left_flap_joint</control_joint_name>
<control_joint_rad_to_cl>-0.1</control_joint_rad_to_cl>
</plugin>
<plugin filename="gz-sim-lift-drag-system" name="gz::sim::systems::LiftDrag">
<a0>0.05984281113</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.05 -0.15 0.05</cp>
<area>0.6</area>
<air_density>1.2041</air_density>
<forward>1 0 0</forward>
<upward>0 0 1</upward>
<link_name>base_link</link_name>
<control_joint_name>right_flap_joint</control_joint_name>
<control_joint_rad_to_cl>-0.1</control_joint_rad_to_cl>
</plugin>
<plugin filename="gz-sim-lift-drag-system" name="gz::sim::systems::LiftDrag">
<a0>-0.2</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.5 0 0</cp>
<area>0.01</area>
<air_density>1.2041</air_density>
<forward>1 0 0</forward>
<upward>0 0 1</upward>
<link_name>base_link</link_name>
<control_joint_name>servo_2</control_joint_name>
<control_joint_rad_to_cl>-4.0</control_joint_rad_to_cl>
</plugin>
<plugin
filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController">
<joint_name>servo_2</joint_name>
<sub_topic>servo_2</sub_topic>
<p_gain>10.0</p_gain>
</plugin>
<plugin filename="gz-sim-lift-drag-system" name="gz::sim::systems::LiftDrag">
<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.5 0 0.05</cp>
<area>0.02</area>
<air_density>1.2041</air_density>
<forward>1 0 0</forward>
<upward>0 1 0</upward>
<link_name>base_link</link_name>
<control_joint_name>rudder_joint</control_joint_name>
<control_joint_rad_to_cl>0.8</control_joint_rad_to_cl>
</plugin>
<plugin
filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController">
<joint_name>rudder_joint</joint_name>
<sub_topic>servo_3</sub_topic>
<p_gain>10.0</p_gain>
</plugin>
<plugin filename="gz-sim-multicopter-motor-model-system" name="gz::sim::systems::MulticopterMotorModel">
<jointName>rotor_puller_joint</jointName>
<linkName>rotor_puller</linkName>
<turningDirection>ccw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1000</maxRotVelocity>
<motorConstant>2.44858e-05</motorConstant>
<momentConstant>0.016</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>0</motorNumber>
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<static>0</static>
</model>
</sdf>

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

View File

@ -1,15 +0,0 @@
<?xml version="1.0"?>
<model>
<name>Standard VTOL</name>
<version>1.0</version>
<sdf version='1.10'>model.sdf</sdf>
<author>
<name>Roman Bapst</name>
<email>roman@px4.io</email>
</author>
<description>
This is a model of a standard VTOL quad plane.
</description>
</model>

View File

@ -1,755 +0,0 @@
<?xml version="1.0"?>
<!-- DO NOT EDIT: Generated from standard_vtol.sdf.jinja -->
<sdf version='1.10'>
<model name='standard_vtol'>
<pose>0 0 0.246 0 0 0</pose>
<link name='base_link'>
<pose>0 0 0 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>5</mass>
<inertia>
<ixx>0.477708333333</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.341666666667</iyy>
<iyz>0</iyz>
<izz>0.811041666667</izz>
</inertia>
</inertial>
<collision name='base_link_collision'>
<pose>0 0 -0.07 0 0 0</pose>
<geometry>
<box>
<size>0.55 2.144 0.05</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<kp>100000</kp>
<kd>1.0</kd>
<max_vel>0.1</max_vel>
<min_depth>0.001</min_depth>
</ode>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='base_link_visual'>
<pose>0.53 -1.072 -0.1 1.5707963268 0 3.1415926536</pose>
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://standard_vtol/meshes/x8_wing.dae</uri>
</mesh>
</geometry>
<material>
<ambient>.175 .175 .175 1.0</ambient>
<diffuse>.175 .175 .175 1.0</diffuse>
</material>
</visual>
<visual name='left_motor_column'>
<pose>0 0.35 0.01 0 0 0</pose>
<geometry>
<box>
<size>0.74 0.03 0.03</size>
</box>
</geometry>
<material>
<ambient>.175 .175 .175 1.0</ambient>
<diffuse>.175 .175 .175 1.0</diffuse>
</material>
</visual>
<visual name='right_motor_column'>
<pose>0 -0.35 0.01 0 0 0</pose>
<geometry>
<box>
<size>0.74 0.03 0.03</size>
</box>
</geometry>
<material>
<ambient>.175 .175 .175 1.0</ambient>
<diffuse>.175 .175 .175 1.0</diffuse>
</material>
</visual>
<visual name='m0'>
<pose>-0.35 0.35 0.045 0 0 0</pose>
<geometry>
<cylinder>
<length>0.035</length>
<radius>0.02</radius>
</cylinder>
</geometry>
<material>
<ambient>.175 .175 .175 1.0</ambient>
<diffuse>.175 .175 .175 1.0</diffuse>
</material>
</visual>
<visual name='m1'>
<pose>-0.35 -0.35 0.045 0 0 0</pose>
<geometry>
<cylinder>
<length>0.035</length>
<radius>0.02</radius>
</cylinder>
</geometry>
<material>
<ambient>.175 .175 .175 1.0</ambient>
<diffuse>.175 .175 .175 1.0</diffuse>
</material>
</visual>
<visual name='m2'>
<pose>0.35 -0.35 0.045 0 0 0</pose>
<geometry>
<cylinder>
<length>0.035</length>
<radius>0.02</radius>
</cylinder>
</geometry>
<material>
<ambient>.175 .175 .175 1.0</ambient>
<diffuse>.175 .175 .175 1.0</diffuse>
</material>
</visual>
<visual name='m3'>
<pose>0.35 0.35 0.045 0 0 0</pose>
<geometry>
<cylinder>
<length>0.035</length>
<radius>0.02</radius>
</cylinder>
</geometry>
<material>
<ambient>.175 .175 .175 1.0</ambient>
<diffuse>.175 .175 .175 1.0</diffuse>
</material>
</visual>
<gravity>1</gravity>
<velocity_decay/>
<self_collide>0</self_collide>
<sensor name="imu_sensor" type="imu">
<always_on>1</always_on>
<update_rate>250</update_rate>
</sensor>
<sensor name="air_pressure_sensor" type="air_pressure">
<always_on>1</always_on>
<update_rate>50</update_rate>
<air_pressure>
<pressure>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.01</stddev>
</noise>
</pressure>
</air_pressure>
</sensor>
</link>
<link name='rotor_0'>
<pose>0.35 -0.35 0.07 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.005</mass>
<inertia>
<ixx>9.75e-07</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.000166704</iyy>
<iyz>0</iyz>
<izz>0.000167604</izz>
</inertia>
</inertial>
<collision name='rotor_0_collision'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<cylinder>
<length>0.005</length>
<radius>0.1</radius>
</cylinder>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='rotor_0_visual'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://standard_vtol/meshes/iris_prop_ccw.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0 0 1 1.0</ambient>
<diffuse>0 0 1 1.0</diffuse>
</material>
</visual>
<gravity>1</gravity>
<velocity_decay/>
<self_collide>0</self_collide>
</link>
<joint name='rotor_0_joint' type='revolute'>
<child>rotor_0</child>
<parent>base_link</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name='rotor_1'>
<pose>-0.35 0.35 0.07 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.005</mass>
<inertia>
<ixx>9.75e-07</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.000166704</iyy>
<iyz>0</iyz>
<izz>0.000167604</izz>
</inertia>
</inertial>
<collision name='rotor_1_collision'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<cylinder>
<length>0.005</length>
<radius>0.1</radius>
</cylinder>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='rotor_1_visual'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://standard_vtol/meshes/iris_prop_ccw.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0 0 1 1.0</ambient>
<diffuse>0 0 1 1.0</diffuse>
</material>
</visual>
<gravity>1</gravity>
<velocity_decay/>
<self_collide>0</self_collide>
</link>
<joint name='rotor_1_joint' type='revolute'>
<child>rotor_1</child>
<parent>base_link</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name='rotor_2'>
<pose>0.35 0.35 0.07 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.005</mass>
<inertia>
<ixx>9.75e-07</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.000166704</iyy>
<iyz>0</iyz>
<izz>0.000167604</izz>
</inertia>
</inertial>
<collision name='rotor_2_collision'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<cylinder>
<length>0.005</length>
<radius>0.1</radius>
</cylinder>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='rotor_2_visual'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://standard_vtol/meshes/iris_prop_ccw.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0 0 1 1.0</ambient>
<diffuse>0 0 1 1.0</diffuse>
</material>
</visual>
<gravity>1</gravity>
<velocity_decay/>
<self_collide>0</self_collide>
</link>
<joint name='rotor_2_joint' type='revolute'>
<child>rotor_2</child>
<parent>base_link</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name='rotor_3'>
<pose>-0.35 -0.35 0.07 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.005</mass>
<inertia>
<ixx>9.75e-07</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.000166704</iyy>
<iyz>0</iyz>
<izz>0.000167604</izz>
</inertia>
</inertial>
<collision name='rotor_3_collision'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<cylinder>
<length>0.005</length>
<radius>0.1</radius>
</cylinder>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='rotor_3_visual'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://standard_vtol/meshes/iris_prop_ccw.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0 0 1 1.0</ambient>
<diffuse>0 0 1 1.0</diffuse>
</material>
</visual>
<gravity>1</gravity>
<velocity_decay/>
<self_collide>0</self_collide>
</link>
<joint name='rotor_3_joint' type='revolute'>
<child>rotor_3</child>
<parent>base_link</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name='rotor_puller'>
<pose>-0.22 0 0.0 0 1.57 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.005</mass>
<inertia>
<ixx>9.75e-07</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.000166704</iyy>
<iyz>0</iyz>
<izz>0.000167604</izz>
</inertia>
</inertial>
<collision name='rotor_puller_collision'>
<pose>0.0 0 -0.04 0 0 0</pose>
<geometry>
<cylinder>
<length>0.005</length>
<radius>0.06</radius>
</cylinder>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='rotor_puller_visual'>
<pose>0 0 -0.04 0 0 0</pose>
<geometry>
<mesh>
<scale>0.8 0.8 0.8</scale>
<uri>model://standard_vtol/meshes/iris_prop_ccw.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0 0 1 1.0</ambient>
<diffuse>0 0 1 1.0</diffuse>
</material>
</visual>
<gravity>1</gravity>
<velocity_decay/>
<self_collide>0</self_collide>
</link>
<joint name='rotor_puller_joint' type='revolute'>
<pose>0.0 0 0.0 0 -1.57 0</pose>
<child>rotor_puller</child>
<parent>base_link</parent>
<axis>
<xyz>1 0 0</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name="left_elevon">
<inertial>
<mass>0.00000001</mass>
<inertia>
<ixx>0.000001</ixx>
<ixy>0.0</ixy>
<iyy>0.000001</iyy>
<ixz>0.0</ixz>
<iyz>0.0</iyz>
<izz>0.000001</izz>
</inertia>
<pose>0 0.3 0 0.00 0 0.0</pose>
</inertial>
<visual name='left_elevon_visual'>
<pose>-0.105 0.004 -0.034 1.5707963268 0 3.1415926536</pose>
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://standard_vtol/meshes/x8_elevon_left.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0 0 1 1.0</ambient>
<diffuse>0 0 1 1.0</diffuse>
</material>
</visual>
</link>
<link name="right_elevon">
<inertial>
<mass>0.00000001</mass>
<inertia>
<ixx>0.000001</ixx>
<ixy>0.0</ixy>
<iyy>0.000001</iyy>
<ixz>0.0</ixz>
<iyz>0.0</iyz>
<izz>0.000001</izz>
</inertia>
<pose>0 -0.6 0 0.00 0 0.0</pose>
</inertial>
<visual name='right_elevon_visual'>
<pose>0.281 -1.032 -0.034 1.5707963268 0 3.1415926536</pose>
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://standard_vtol/meshes/x8_elevon_right.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0 0 1 1.0</ambient>
<diffuse>0 0 1 1.0</diffuse>
</material>
</visual>
</link>
<link name="elevator">
<inertial>
<mass>0.00000001</mass>
<inertia>
<ixx>0.000001</ixx>
<ixy>0.0</ixy>
<iyy>0.000001</iyy>
<ixz>0.0</ixz>
<iyz>0.0</iyz>
<izz>0.000001</izz>
</inertia>
<pose> -0.5 0 0 0.00 0 0.0</pose>
</inertial>
</link>
<joint name='servo_0' type='revolute'>
<parent>base_link</parent>
<child>left_elevon</child>
<pose>-0.18 0.6 -0.005 0 0 0.265</pose>
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-0.53</lower>
<upper>0.53</upper>
</limit>
<dynamics>
<damping>1.000</damping>
</dynamics>
</axis>
<physics>
<ode>
<implicit_spring_damper>1</implicit_spring_damper>
</ode>
</physics>
</joint>
<joint name='servo_1' type='revolute'>
<parent>base_link</parent>
<child>right_elevon</child>
<pose>-0.18 -0.6 -0.005 0 0 -0.265</pose>
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-0.53</lower>
<upper>0.53</upper>
</limit>
<dynamics>
<damping>1.000</damping>
</dynamics>
</axis>
<physics>
<ode>
<implicit_spring_damper>1</implicit_spring_damper>
</ode>
</physics>
</joint>
<joint name='servo_2' type='revolute'>
<parent>base_link</parent>
<child>elevator</child>
<pose> -0.5 0 0 0 0 0</pose>
<axis>
<xyz>0 1 0</xyz>
<limit>
<!-- -30/+30 deg. -->
<lower>-0.53</lower>
<upper>0.53</upper>
</limit>
<dynamics>
<damping>1.000</damping>
</dynamics>
</axis>
<physics>
<ode>
<implicit_spring_damper>1</implicit_spring_damper>
</ode>
</physics>
</joint>
<plugin filename="gz-sim-lift-drag-system" name="gz::sim::systems::LiftDrag">
<a0>0.05984281113</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.05 0.3 0.05</cp>
<area>0.50</area>
<air_density>1.2041</air_density>
<forward>1 0 0</forward>
<upward>0 0 1</upward>
<link_name>base_link</link_name>
<control_joint_name>servo_0</control_joint_name>
<control_joint_rad_to_cl>-1.0</control_joint_rad_to_cl>
</plugin>
<plugin
filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController">
<joint_name>servo_0</joint_name>
<sub_topic>servo_0</sub_topic>
</plugin>
<plugin filename="gz-sim-lift-drag-system" name="gz::sim::systems::LiftDrag">
<a0>0.05984281113</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.05 -0.3 0.05</cp>
<area>0.50</area>
<air_density>1.2041</air_density>
<forward>1 0 0</forward>
<upward>0 0 1</upward>
<link_name>base_link</link_name>
<control_joint_name>servo_1</control_joint_name>
<control_joint_rad_to_cl>-1.0</control_joint_rad_to_cl>
</plugin>
<plugin
filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController">
<joint_name>servo_1</joint_name>
<sub_topic>servo_1</sub_topic>
</plugin>
<plugin filename="gz-sim-lift-drag-system" name="gz::sim::systems::LiftDrag">
<a0>-0.2</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.5 0 0</cp>
<area>0.01</area>
<air_density>1.2041</air_density>
<forward>1 0 0</forward>
<upward>0 0 1</upward>
<link_name>base_link</link_name>
<control_joint_name>servo_2</control_joint_name>
<control_joint_name>servo_2</control_joint_name>
<control_joint_rad_to_cl>-12.0</control_joint_rad_to_cl>
</plugin>
<plugin
filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController">
<joint_name>servo_2</joint_name>
<sub_topic>servo_2</sub_topic>
</plugin>
<plugin filename="gz-sim-multicopter-motor-model-system" name="gz::sim::systems::MulticopterMotorModel">
<jointName>rotor_0_joint</jointName>
<linkName>rotor_0</linkName>
<turningDirection>ccw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1500</maxRotVelocity>
<motorConstant>2e-05</motorConstant>
<momentConstant>0.06</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>0</motorNumber>
<rotorDragCoefficient>0.000106428</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<rotorVelocitySlowdownSim>20</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<plugin filename="gz-sim-multicopter-motor-model-system" name="gz::sim::systems::MulticopterMotorModel">
<jointName>rotor_1_joint</jointName>
<linkName>rotor_1</linkName>
<turningDirection>ccw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1500</maxRotVelocity>
<motorConstant>2e-05</motorConstant>
<momentConstant>0.06</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>1</motorNumber>
<rotorDragCoefficient>0.000106428</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<rotorVelocitySlowdownSim>20</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<plugin
filename="gz-sim-multicopter-motor-model-system"
name="gz::sim::systems::MulticopterMotorModel">
<jointName>rotor_2_joint</jointName>
<linkName>rotor_2</linkName>
<turningDirection>cw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1500</maxRotVelocity>
<motorConstant>2e-05</motorConstant>
<momentConstant>0.06</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>2</motorNumber>
<rotorDragCoefficient>0.000106428</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<rotorVelocitySlowdownSim>20</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<plugin
filename="gz-sim-multicopter-motor-model-system"
name="gz::sim::systems::MulticopterMotorModel">
<jointName>rotor_3_joint</jointName>
<linkName>rotor_3</linkName>
<turningDirection>cw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1500</maxRotVelocity>
<motorConstant>2e-05</motorConstant>
<momentConstant>0.06</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>3</motorNumber>
<rotorDragCoefficient>0.000106428</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<rotorVelocitySlowdownSim>20</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<plugin
filename="gz-sim-multicopter-motor-model-system"
name="gz::sim::systems::MulticopterMotorModel">
<jointName>rotor_puller_joint</jointName>
<linkName>rotor_puller</linkName>
<turningDirection>cw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>3500</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.01</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>4</motorNumber>
<rotorDragCoefficient>0.000106428</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<rotorVelocitySlowdownSim>20</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<static>0</static>
</model>
</sdf>

Binary file not shown.

Before

Width:  |  Height:  |  Size: 1.5 MiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 25 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 26 KiB

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

Binary file not shown.

Before

Width:  |  Height:  |  Size: 1.5 MiB

File diff suppressed because one or more lines are too long

View File

@ -1,11 +0,0 @@
<?xml version="1.0"?>
<model>
<name>x500</name>
<version>1.0</version>
<sdf version="1.9">model.sdf</sdf>
<author>
<name>Benjamin Perseghetti</name>
<email>bperseghetti@rudislabs.com</email>
</author>
<description>Model of the NXP HoverGames Drone development kit (KIT-HGDRONEK66). The PX4 software compatible kit provides mechanical, RC remote and other components needed to evaluate the RDDRONE-FMUK66 reference design. The FMU includes 100Base-T1 Automotive Ethernet, dual CAN transceivers, as well as SE050 secure element, and works with add on boards NavQPlus, MR-T1ETH8, MR-T1ADAPT, and CAN-nodes such as UCANS32K1SIC. Kit may be used with, and contains the components needed for the HoverGames.com coding challenges.</description>
</model>

View File

@ -1,588 +0,0 @@
<?xml version="1.0" encoding="UTF-8"?>
<sdf version='1.9'>
<model name='x500'>
<pose>0 0 .24 0 0 0</pose>
<self_collide>false</self_collide>
<static>false</static>
<link name="base_link">
<inertial>
<mass>2.0</mass>
<inertia>
<ixx>0.02166666666666667</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.02166666666666667</iyy>
<iyz>0</iyz>
<izz>0.04000000000000001</izz>
</inertia>
</inertial>
<gravity>true</gravity>
<velocity_decay/>
<visual name="base_link_visual">
<pose>0 0 .025 0 0 3.141592654</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://x500/meshes/NXP-HGD-CF.dae</uri>
</mesh>
</geometry>
</visual>
<visual name="5010_motor_base_0">
<pose>0.174 0.174 .032 0 0 -.45</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://x500/meshes/5010Base.dae</uri>
</mesh>
</geometry>
</visual>
<visual name="5010_motor_base_1">
<pose>-0.174 0.174 .032 0 0 -.45</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://x500/meshes/5010Base.dae</uri>
</mesh>
</geometry>
</visual>
<visual name="5010_motor_base_2">
<pose>0.174 -0.174 .032 0 0 -.45</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://x500/meshes/5010Base.dae</uri>
</mesh>
</geometry>
</visual>
<visual name="5010_motor_base_3">
<pose>-0.174 -0.174 .032 0 0 -.45</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://x500/meshes/5010Base.dae</uri>
</mesh>
</geometry>
</visual>
<visual name="NXP_FMUK66_FRONT">
<pose>0.047 .001 .043 1 0 1.57</pose>
<cast_shadows>false</cast_shadows>
<geometry>
<plane>
<normal>0 0 1</normal>
<size>.013 .007</size>
</plane>
</geometry>
<material>
<diffuse>1.0 1.0 1.0</diffuse>
<specular>1.0 1.0 1.0</specular>
<pbr>
<metal>
<albedo_map>model://x500/materials/textures/nxp.png</albedo_map>
</metal>
</pbr>
</material>
</visual>
<visual name="NXP_FMUK66_TOP">
<pose>-0.023 0 .0515 0 0 -1.57</pose>
<cast_shadows>false</cast_shadows>
<geometry>
<plane>
<normal>0 0 1</normal>
<size>.013 .007</size>
</plane>
</geometry>
<material>
<diffuse>1.0 1.0 1.0</diffuse>
<specular>1.0 1.0 1.0</specular>
<pbr>
<metal>
<albedo_map>model://x500/materials/textures/nxp.png</albedo_map>
</metal>
</pbr>
</material>
</visual>
<visual name="RDDRONE_FMUK66_TOP">
<pose>-.03 0 .0515 0 0 -1.57</pose>
<cast_shadows>false</cast_shadows>
<geometry>
<plane>
<normal>0 0 1</normal>
<size>.032 .0034</size>
</plane>
</geometry>
<material>
<diffuse>1.0 1.0 1.0</diffuse>
<specular>1.0 1.0 1.0</specular>
<pbr>
<metal>
<albedo_map>model://x500/materials/textures/rd.png</albedo_map>
</metal>
</pbr>
</material>
</visual>
<collision name="base_link_collision_0">
<pose>0 0 .007 0 0 0</pose>
<geometry>
<box>
<size>0.35355339059327373 0.35355339059327373 0.05</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<min_depth>0.001</min_depth>
<max_vel>0</max_vel>
</ode>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<collision name="base_link_collision_1">
<pose>0 -0.098 -.123 -0.35 0 0</pose>
<geometry>
<box>
<size>0.015 0.015 0.21</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<min_depth>0.001</min_depth>
<max_vel>0</max_vel>
</ode>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<collision name="base_link_collision_2">
<pose>0 0.098 -.123 0.35 0 0</pose>
<geometry>
<box>
<size>0.015 0.015 0.21</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<min_depth>0.001</min_depth>
<max_vel>0</max_vel>
</ode>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<collision name="base_link_collision_3">
<pose>0 -0.132 -.2195 0 0 0</pose>
<geometry>
<box>
<size>0.25 0.015 0.015</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<min_depth>0.001</min_depth>
<max_vel>0</max_vel>
</ode>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<collision name="base_link_collision_4">
<pose>0 0.132 -.2195 0 0 0</pose>
<geometry>
<box>
<size>0.25 0.015 0.015</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<min_depth>0.001</min_depth>
<max_vel>0</max_vel>
</ode>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<sensor name="air_pressure_sensor" type="air_pressure">
<always_on>1</always_on>
<update_rate>50</update_rate>
<air_pressure>
<pressure>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.01</stddev>
</noise>
</pressure>
</air_pressure>
</sensor>
<sensor name="imu_sensor" type="imu">
<always_on>1</always_on>
<update_rate>250</update_rate>
</sensor>
</link>
<link name="rotor_0">
<gravity>true</gravity>
<self_collide>false</self_collide>
<velocity_decay/>
<pose>0.174 -0.174 0.06 0 0 0</pose>
<inertial>
<mass>0.016076923076923075</mass>
<inertia>
<ixx>3.8464910483993325e-07</ixx>
<iyy>2.6115851691700804e-05</iyy>
<izz>2.649858234714004e-05</izz>
</inertia>
</inertial>
<visual name="rotor_0_visual">
<pose>-0.022 -0.14638461538461536 -0.016 0 0 0</pose>
<geometry>
<mesh>
<scale>0.8461538461538461 0.8461538461538461 0.8461538461538461</scale>
<uri>model://x500/meshes/1345_prop_ccw.stl</uri>
</mesh>
</geometry>
<material>
<script>
<name>Gazebo/DarkGrey</name>
<uri>file://media/materials/scripts/gazebo.material</uri>
</script>
</material>
</visual>
<visual name="rotor_0_visual_motor_bell">
<pose>0 0 -.032 0 0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://x500/meshes/5010Bell.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="rotor_0_collision">
<pose>0 0 0 0 0 0 </pose>
<geometry>
<box>
<size>0.2792307692307692 0.016923076923076923 0.0008461538461538462</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<min_depth>0.001</min_depth>
<max_vel>0</max_vel>
</ode>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
</link>
<joint name="rotor_0_joint" type="revolute">
<parent>base_link</parent>
<child>rotor_0</child>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name="rotor_1">
<gravity>true</gravity>
<self_collide>false</self_collide>
<velocity_decay/>
<pose>-0.174 0.174 0.06 0 0 0</pose>
<inertial>
<mass>0.016076923076923075</mass>
<inertia>
<ixx>3.8464910483993325e-07</ixx>
<iyy>2.6115851691700804e-05</iyy>
<izz>2.649858234714004e-05</izz>
</inertia>
</inertial>
<visual name="rotor_1_visual">
<pose>-0.022 -0.14638461538461536 -0.016 0 0 0</pose>
<geometry>
<mesh>
<scale>0.8461538461538461 0.8461538461538461 0.8461538461538461</scale>
<uri>model://x500/meshes/1345_prop_ccw.stl</uri>
</mesh>
</geometry>
<material>
<script>
<name>Gazebo/DarkGrey</name>
<uri>file://media/materials/scripts/gazebo.material</uri>
</script>
</material>
</visual>
<visual name="rotor_1_visual_motor_top">
<pose>0 0 -.032 0 0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://x500/meshes/5010Bell.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="rotor_1_collision">
<pose>0 0 0 0 0 0 </pose>
<geometry>
<box>
<size>0.2792307692307692 0.016923076923076923 0.0008461538461538462</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<min_depth>0.001</min_depth>
<max_vel>0</max_vel>
</ode>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
</link>
<joint name="rotor_1_joint" type="revolute">
<parent>base_link</parent>
<child>rotor_1</child>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name="rotor_2">
<gravity>true</gravity>
<self_collide>false</self_collide>
<velocity_decay/>
<pose>0.174 0.174 0.06 0 0 0</pose>
<inertial>
<mass>0.016076923076923075</mass>
<inertia>
<ixx>3.8464910483993325e-07</ixx>
<iyy>2.6115851691700804e-05</iyy>
<izz>2.649858234714004e-05</izz>
</inertia>
</inertial>
<visual name="rotor_2_visual">
<pose>-0.022 -0.14638461538461536 -0.016 0 0 0</pose>
<geometry>
<mesh>
<scale>0.8461538461538461 0.8461538461538461 0.8461538461538461</scale>
<uri>model://x500/meshes/1345_prop_cw.stl</uri>
</mesh>
</geometry>
<material>
<script>
<name>Gazebo/DarkGrey</name>
<uri>file://media/materials/scripts/gazebo.material</uri>
</script>
</material>
</visual>
<visual name="rotor_2_visual_motor_top">
<pose>0 0 -.032 0 0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://x500/meshes/5010Bell.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="rotor_2_collision">
<pose>0 0 0 0 0 0 </pose>
<geometry>
<box>
<size>0.2792307692307692 0.016923076923076923 0.0008461538461538462</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<min_depth>0.001</min_depth>
<max_vel>0</max_vel>
</ode>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
</link>
<joint name="rotor_2_joint" type="revolute">
<parent>base_link</parent>
<child>rotor_2</child>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name="rotor_3">
<gravity>true</gravity>
<self_collide>false</self_collide>
<velocity_decay/>
<pose>-0.174 -0.174 0.06 0 0 0</pose>
<inertial>
<mass>0.016076923076923075</mass>
<inertia>
<ixx>3.8464910483993325e-07</ixx>
<iyy>2.6115851691700804e-05</iyy>
<izz>2.649858234714004e-05</izz>
</inertia>
</inertial>
<visual name="rotor_3_visual">
<pose>-0.022 -0.14638461538461536 -0.016 0 0 0</pose>
<geometry>
<mesh>
<scale>0.8461538461538461 0.8461538461538461 0.8461538461538461</scale>
<uri>model://x500/meshes/1345_prop_cw.stl</uri>
</mesh>
</geometry>
<material>
<script>
<name>Gazebo/DarkGrey</name>
<uri>file://media/materials/scripts/gazebo.material</uri>
</script>
</material>
</visual>
<visual name="rotor_3_visual_motor_top">
<pose>0 0 -.032 0 0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://x500/meshes/5010Bell.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="rotor_3_collision">
<pose>0 0 0 0 0 0 </pose>
<geometry>
<box>
<size>0.2792307692307692 0.016923076923076923 0.0008461538461538462</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<min_depth>0.001</min_depth>
<max_vel>0</max_vel>
</ode>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
</link>
<joint name="rotor_3_joint" type="revolute">
<parent>base_link</parent>
<child>rotor_3</child>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<plugin filename="gz-sim-multicopter-motor-model-system" name="gz::sim::systems::MulticopterMotorModel">
<jointName>rotor_0_joint</jointName>
<linkName>rotor_0</linkName>
<turningDirection>ccw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1000.0</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.016</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>0</motorNumber>
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<plugin filename="gz-sim-multicopter-motor-model-system" name="gz::sim::systems::MulticopterMotorModel">
<jointName>rotor_1_joint</jointName>
<linkName>rotor_1</linkName>
<turningDirection>ccw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1000.0</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.016</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>1</motorNumber>
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<plugin filename="gz-sim-multicopter-motor-model-system" name="gz::sim::systems::MulticopterMotorModel">
<jointName>rotor_2_joint</jointName>
<linkName>rotor_2</linkName>
<turningDirection>cw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1000.0</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.016</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>2</motorNumber>
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<plugin filename="gz-sim-multicopter-motor-model-system" name="gz::sim::systems::MulticopterMotorModel">
<jointName>rotor_3_joint</jointName>
<linkName>rotor_3</linkName>
<turningDirection>cw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1000.0</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.016</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>3</motorNumber>
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
</model>
</sdf>

Binary file not shown.

Before

Width:  |  Height:  |  Size: 32 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 51 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 28 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 27 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 23 KiB

View File

@ -1,11 +0,0 @@
<?xml version="1.0"?>
<model>
<name>x500-Depth</name>
<version>1.0</version>
<sdf version="1.9">model.sdf</sdf>
<author>
<name>Benjamin Perseghetti</name>
<email>bperseghetti@rudislabs.com</email>
</author>
<description>Model of the NXP HoverGames Drone development kit (KIT-HGDRONEK66). The PX4 software compatible kit provides mechanical, RC remote and other components needed to evaluate the RDDRONE-FMUK66 reference design. The FMU includes 100Base-T1 Automotive Ethernet, dual CAN transceivers, as well as SE050 secure element, and works with add on boards NavQPlus, MR-T1ETH8, MR-T1ADAPT, and CAN-nodes such as UCANS32K1SIC. Kit may be used with, and contains the components needed for the HoverGames.com coding challenges.</description>
</model>

View File

@ -1,17 +0,0 @@
<?xml version="1.0" encoding="UTF-8"?>
<sdf version='1.9'>
<model name='x500-Depth'>
<include merge='true'>
<uri>x500</uri>
</include>
<include merge='true'>
<uri>https://fuel.gazebosim.org/1.0/RudisLaboratories/models/OakD-Lite</uri>
<pose>.12 .03 .242 0 0 0</pose>
</include>
<joint name="CameraJoint" type="fixed">
<parent>base_link</parent>
<child>OakD-Lite/base_link</child>
<pose relative_to="base_link">.12 .03 .242 0 0 0</pose>
</joint>
</model>
</sdf>

Binary file not shown.

Before

Width:  |  Height:  |  Size: 32 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 50 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 27 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 27 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 23 KiB

View File

@ -1,11 +0,0 @@
<?xml version="1.0"?>
<model>
<name>x500-vision</name>
<version>1.0</version>
<sdf version="1.9">model.sdf</sdf>
<author>
<name>Jaeyoung Lim</name>
<email>jalim@ethz.ch</email>
</author>
<description>Model of the X500 with a odometry/external vision input.</description>
</model>

View File

@ -1,13 +0,0 @@
<?xml version="1.0" encoding="UTF-8"?>
<sdf version='1.9'>
<model name='x500-vision'>
<include merge='true'>
<uri>x500</uri>
</include>
<plugin
filename="gz-sim-odometry-publisher-system"
name="gz::sim::systems::OdometryPublisher">
<dimensions>3</dimensions>
</plugin>
</model>
</sdf>

View File

@ -1,149 +0,0 @@
## Purpose
The idea of this tool is to automate the writing of the Advanced Lift Drag plugin by automatizing the coefficient generation and requiring minimal user calculations.
## Setup
In order to run this tool, it is necessary to follow these steps:
1. Download AVL 3.36 from <https://web.mit.edu/drela/Public/web/avl/>. The file for AVL version 3.36 can be found about halfway down the page.
2. After downloading, extract AVL and move it to the home directory using:
```shell
sudo tar -xf avl3.36.tgz
mv ./Avl /home/
```
Follow the README.md found in Avl to finish the setup process for AVL (requires to set up plotlib and eispack libraries). I recommend using the gfortran compile option. This might require you to install gfortran. This can be done by running:
```shell
sudo apt update
sudo apt install gfortran
```
When running the Makefile for AVL, you might encounter an Error 1 message stating that there is a directory missing. This does not prevent AVL from working for our purposes. Once the process described in the AVL README is completed, AVL is ready to be used. No further set up is required on the side of the AVL or the tool.
If you want to move the location of the AVL directory, this can simply be done by passing the `--avl_path` flag to the `input_avl.py` file, using the desired directory location for the flag (don't forget to place a "/" behind the last part of the path). Running this will automatically also adjust the paths where necessary.
## Run
To run the tool all that is needed is to modify the `input.yml` to the plane that you desire and then run `python input_avl.py <your_custom_yaml_file>.yml` Note that you require to have the yaml and argparse packages in your python environment to run this. An example template has been provided in the form of the `input.yml` that implements a standard plane with two ailerons, an elevator and a rudder. This example template can be run using: `python input_avl.py --yaml_file input.yml`.
Once the script has been executed, the generated .avl, .sdf and a plot of the proposed control surfaces can be found in <your-planes-name> directory. The sdf file is the generated Advanced Lift Drag Plugin that can be copied and pasted straight into a model.sdf file, which can then be run in Gazebo.
## Functionality
The tool first asks the user for a range of vehicle specific parameters that are needed in order to specify the geometry and physical properties of the plane. The user has the choice to define a completely custom model, or alternatively select a predefined model template (such as a Cessna or a VTOL), which has a known number of control surfaces, and then provide only some physical properties, without having to define the entire model themselves. The input_avl.py file takes the provided parameter and creates an .avl file from this that can be read by AVL (the program). This happens in the process.sh file. The necessary output generated by AVL will be saved in two files: custom_vehicle_body_axis_derivatives.txt and custom_vehicle_stability_derivatives.txt. These two files contain the parameters that are required in order to populate the Advanced Lift Drag Plugin. Finally, avl_out_parse.py reads the generated .txt files and accordingly assigns parameters to the correct element in sdf. Once this is done, it is only a question of copy and pasting the generated Advanced Lift Drag plugin (found as <custom_plane>.sdf into the desired model.sdf file. )
## Usability
The current implementation provides a minimal working example. More accurate measurements can be made by adjusting the chosen number of vortices along span and chord according to desired preferences. A good starting point for this can be found here: <https://www.redalyc.org/pdf/6735/673571173005.pdf>. Furthermore, one can also more accurately model a vehicle by using a larger number of sections. In the current .yml file, only a left and right edge are defined for each surface yielding exactly one section, but the code supports expanding this to any number of desired sections.
## IMPORTANT POINTS TO NOTE
- A control surface in AVL is always defined from left to right. This means you need to first provide the left edge of a surface and then the right edge. If you do this the opposite way around, a surface will essentially be defined upside down.
- The tool is designed to only support at most two control surfaces of any type on any one vehicle. Having more surfaces than that can lead to faulty behavior.
- Another important point is that these scripts make use of the match, case syntax, which was only introduced in Python in version 3.10.
- The primary reference resource for AVL can be found at <https://web.mit.edu/drela/Public/web/avl/AVL_User_Primer.pdf>. This document was written by the creators of AVL and contains all the variables that could be required in defining the control surfaces.
- AVL cannot predict stall values. As such these need to be calculated/estimated another way. In the current implementation, default stall values have been taken from PX4's Advanced Plane. These should naturally be changed for new/different models.
## Parameter Assignment
Below is a comprehensive list on how the parameters are assigned at output and what files in AVL they are taken from. I am by no means an AVL expert, so please verify that these are actually the correct parameters required by the Advanced Lift Drag Plugin. For an explanation of what the parameters do, please see take a look at the Advanced Lift Drag Plugin.
(name-in-AVL) -> (name-in-plugin)
From the stability derivatives log file, the following advanced lift drag plugin parameters are taken:
Alpha -> alpha The angle of attack
Cmtot -> Cem0 Pitching moment coefficient at zero angle of attack
CLtot -> CL0 Lift Coefficient at zero angle of attack
CDtot -> CD0 Drag coefficient at zero angle of attack
CLa -> CLa dCL/da (slope of CL-alpha curve)
CYa -> CYa dCy/da (sideforce slope wrt alpha)
Cla -> Cella dCl/da (roll moment slope wrt alpha)
Cma -> Cema dCm/da (pitching moment slope wrt alpha - before stall)
Cna -> Cena dCn/da (yaw moment slope wrt alpha)
CLb -> CLb dCL/dbeta (lift coefficient slope wrt beta)
CYb -> CYb dCY/dbeta (side force slope wrt beta)
Clb -> Cellb dCl/dbeta (roll moment slope wrt beta)
Cmb -> Cemb dCm/dbeta (pitching moment slope wrt beta)
Cnb -> Cenb dCn/dbeta (yaw moment slope wrt beta)
From the body axis derivatives log file, the following advanced lift drag plugin parameters are taken:
e -> eff Wing efficiency (Oswald efficiency factor for a 3D wing)
CXp -> CDp dCD/dp (drag coefficient slope wrt roll rate)
CYp -> CYp dCY/dp (sideforce slope wrt roll rate)
CZp -> CLp dCL/dp (lift coefficient slope wrt roll rate)
Clp -> Cellp dCl/dp (roll moment slope wrt roll rate)
Cmp -> Cemp dCm/dp (pitching moment slope wrt roll rate)
Cmp -> Cenp dCn/dp (yaw moment slope wrt roll rate)
CXq -> CDq dCD/dq (drag coefficient slope wrt pitching rate)
CYq -> CYq dCY/dq (side force slope wrt pitching rate)
CZq -> CLq dCL/dq (lift coefficient slope wrt pitching rate)
Clq -> Cellq dCl/dq (roll moment slope wrt pitching rate)
Cmq -> Cemq dCm/dq (pitching moment slope wrt pitching rate)
Cnq -> Cenq dCn/dq (yaw moment slope wrt pitching rate)
CXr -> CDr dCD/dr (drag coefficient slope wrt yaw rate)
CYr -> CYr dCY/dr (side force slope wrt yaw rate)
CZr -> CLr dCL/dr (lift coefficient slope wrt yaw rate)
Clr -> Cellr dCl/dr (roll moment slope wrt yaw rate)
Cmr -> Cemr dCm/dr (pitching moment slope wrt yaw rate)
Cnr -> Cenr dCn/dr (yaw moment slope wrt yaw rate)
Furthermore, every control surface also has six own parameters, which are also derived from this log file. {i} below ranges from 1 to the number of unique control surface types in the model.
CXd{i} -> CD_ctrl Effect of the control surface's deflection on drag
CYd{i} -> CY_ctrl Effect of the control surface's deflection on side force
CZd{i} -> CL_ctrl Effect of the control surface's deflection on lift
Cld{i} -> Cell_ctrl Effect of the control surface's deflection on roll moment
Cmd{i} -> Cem_ctrl Effect of the control surface's deflection on pitching moment
Cnd{i} -> Cen_ctrl Effect of the control surface's deflection on yaw moment
## Future Work
The tool, while self-contained, could be expanded into multiple directions.
1. Currently hinge positions and gains are set at default levels, and these could, if desired be further customized for more control.
2. More vehicles could be added to provide default templates that require less input. At the moment, only "custom" works completely.
3. Fuselage modelling could be included to further improve the accuracy of calculated coefficients.
4. At the moment only NACA airfoils are provided as a way to generate cambered surfaces. An alternative to this would be to use custom airfoil files.

View File

@ -1,342 +0,0 @@
#!/usr/bin/env
import argparse
import shutil
import fileinput
import subprocess
import os
from typing import TextIO
"""
Get the desired coefficient from the AVL output files by looking through the file line by line and picking it out when encountered.
Args:
file (TextIO): The file from which the desired coefficient should be read.
token (str): The coefficient which to look for.
Return:
value (str): The value associated with the desired coefficient.
"""
def get_coef(file: TextIO,token: str) -> str:
linesplit = []
for line in file:
if f' {token} ' in line:
linesplit = line.split()
break
index = 0
for i,v in enumerate(linesplit):
if v == token:
index = i
value = linesplit[index+2]
return value
"""
Write all gathered, model-wide coefficients to the sdf file.
Args:
file (TextIO): The file to which the desired coefficient should be written.
token_str (str): The coefficients for which the associated value should be written.
token (str): The value which should be placed in the avl.
Return:
None.
"""
def write_coef(file: TextIO, token_str: str, token: str):
old_line = f'<{token_str}></{token_str}>'
new_line = f'<{token_str}>{token}</{token_str}>'
with fileinput.FileInput(file, inplace=True) as output_file:
for line in output_file:
print(line.replace(old_line, new_line), end='')
"""
Write all gathered, control surface specific parameters to the sdf file.
Args:
file (TextIO): The file to which the desired coefficients should be written.
ctrl_surface_vec (list): A vector that contains all 6 necessary coefficient values for the control surface in question.
index (str): The model-wide index number of the control surface in question.
direction (str): The direction in which the control surface can be actuated.
Return:
None.
"""
def ctrl_surface_coef(file: TextIO,ctrl_surface_vec: list,index: str, direction: str):
extracted_text = ''
with open("./templates/control_surface.sdf",'r') as open_file:
for line in open_file:
extracted_text += line
open_file.close()
# Insert necessary coefficient values, index and direction in correct sdf location.
extracted_text = extracted_text.replace("<name></name>",f'<name>servo_{index}</name>')
extracted_text = extracted_text.replace("<index></index>",f'<index>{index}</index>')
extracted_text = extracted_text.replace("<direction></direction>",f'<directon>{direction}</direction>')
extracted_text = extracted_text.replace("<CD_ctrl></CD_ctrl>",f'<CD_ctrl>{ctrl_surface_vec[0]}</CD_ctrl>')
extracted_text = extracted_text.replace("<CY_ctrl></CY_ctrl>",f'<CY_ctrl>{ctrl_surface_vec[1]}</CY_ctrl>')
extracted_text = extracted_text.replace("<CL_ctrl></CL_ctrl>",f'<CL_ctrl>{ctrl_surface_vec[2]}</CL_ctrl>')
extracted_text = extracted_text.replace("<Cell_ctrl></Cell_ctrl>",f'<Cell_ctrl>{ctrl_surface_vec[3]}</Cell_ctrl>')
extracted_text = extracted_text.replace("<Cem_ctrl></Cem_ctrl>",f'<Cem_ctrl>{ctrl_surface_vec[4]}</Cem_ctrl>')
extracted_text = extracted_text.replace("<Cen_ctrl></Cen_ctrl>",f'<Cen_ctrl>{ctrl_surface_vec[5]}</Cen_ctrl>')
# Create model specific template
with open(file,'a') as plugin_file:
plugin_file.write(extracted_text + "\n")
plugin_file.close()
"""
Read out the necessary log files to gather the desired parameters and write them to the sdf plugin file.
Arguments provided here are passed in the input_avl.py file.
Args:
file_name (TextIO): The file to which the desired coefficients should be written.
vehicle_type (str): The type of vehicle in use.
AR (str): The calculated aspect ratio.
mac (str): The calculated mean aerodynamic chord.
ref_pt_x (str): The x coordinate of the reference point, at which forces and moments are applied.
ref_pt_y (str): The y coordinate of the reference point, at which forces and moments are applied.
ref_pt_z (str): The z coordinate of the reference point, at which forces and moments are applied.
num_ctrl_surfaces (str): The number of control surfaces that the model uses.
area (str): The wing surface area.
ctrl_surface_order (list): A list containing the types of control surfaces, in theorder in which
they have been defined in the .avl file.
avl_path (str): A string containing the directory where the AVL directory should be moved to.
Return:
None.
"""
def main(file_name: TextIO, vehicle_type: str, AR: str, mac: str, ref_pt_x: str, ref_pt_y: str, ref_pt_z: str, num_ctrl_surfaces: str, area: str, ctrl_surface_order: list, avl_path:str):
# Set current path for user
curr_path = subprocess.run(['pwd'], stdout=subprocess.PIPE, stderr=subprocess.PIPE, text=True)
if curr_path.returncode == 0:
# Save the output in a variable
savedir = curr_path.stdout.strip()
else:
raise LookupError("Invalid path to directory. Check both the avl_automation directory and the Avl directory are positioned correctly.")
# Set the file directory path from where the AVL output logs can be read.
filedir = f'{avl_path}Avl/runs/'
# Read out all necessary parameters from the stability and body axis derivatives files.
with open(f'{filedir}custom_vehicle_stability_derivatives.txt','r+') as stability_file:
original_position = stability_file.tell()
# As plane is modelled at 0 degree AoA, the total coefficients should(?) correspond to the
# 0 degree coefficients required by the plugin.
alpha = get_coef(stability_file,"Alpha")
Cem0 = get_coef(stability_file,"Cmtot")
CL0 = get_coef(stability_file,"CLtot")
CD0 = get_coef(stability_file,"CDtot")
CLa = get_coef(stability_file,"CLa")
CYa = get_coef(stability_file,"CYa")
Cella = get_coef(stability_file,"Cla")
Cema = get_coef(stability_file,"Cma")
Cena = get_coef(stability_file,"Cna")
stability_file.seek(original_position)
CLb = get_coef(stability_file,"CLb")
CYb = get_coef(stability_file,"CYb")
Cellb = get_coef(stability_file,"Clb")
Cemb = get_coef(stability_file,"Cmb")
Cenb = get_coef(stability_file,"Cnb")
stability_file.close()
with open(f'{filedir}custom_vehicle_body_axis_derivatives.txt') as bodyax_file:
original_position = bodyax_file.tell()
eff = get_coef(bodyax_file,"e")
bodyax_file.seek(original_position)
CDp = get_coef(bodyax_file,"CXp")
CYp = get_coef(bodyax_file,"CYp")
CLp = get_coef(bodyax_file,"CZp")
Cellp = get_coef(bodyax_file,"Clp")
Cemp = get_coef(bodyax_file,"Cmp")
Cenp = get_coef(bodyax_file,"Cnp")
bodyax_file.seek(original_position)
CDq = get_coef(bodyax_file,"CXq")
CYq = get_coef(bodyax_file,"CYq")
CLq = get_coef(bodyax_file,"CZq")
Cellq = get_coef(bodyax_file,"Clq")
Cemq = get_coef(bodyax_file,"Cmq")
Cenq = get_coef(bodyax_file,"Cnq")
bodyax_file.seek(original_position)
CDr = get_coef(bodyax_file,"CXr")
CYr = get_coef(bodyax_file,"CYr")
CLr = get_coef(bodyax_file,"CZr")
Cellr = get_coef(bodyax_file,"Clr")
Cemr = get_coef(bodyax_file,"Cmr")
Cenr = get_coef(bodyax_file,"Cnr")
bodyax_file.close()
plane_type = vehicle_type
ctrl_surface_mat = []
# Maybe in the future you want more types of set aircraft. Thus us a case differentiator.
match plane_type:
case "custom":
ctrl_surface_vec = []
with open(f'{filedir}custom_vehicle_body_axis_derivatives.txt') as bodyax_file:
original_position = bodyax_file.tell()
for i in range(1,(len(set(ctrl_surface_order)))+1):
ctrl_surface_vec = []
ctrl_surface_vec.append(get_coef(bodyax_file,f'CXd{i}'))
ctrl_surface_vec.append(get_coef(bodyax_file,f'CYd{i}'))
ctrl_surface_vec.append(get_coef(bodyax_file,f'CZd{i}'))
ctrl_surface_vec.append(get_coef(bodyax_file,f'Cld{i}'))
ctrl_surface_vec.append(get_coef(bodyax_file,f'Cmd{i}'))
ctrl_surface_vec.append(get_coef(bodyax_file,f'Cnd{i}'))
bodyax_file.seek(original_position)
ctrl_surface_mat.append(ctrl_surface_vec)
# SPECIFY STALL PARAMETERS BASED ON AIRCRAFT TYPE (IF PROVIDED)
if not os.path.exists(f'{savedir}/{file_name}'):
os.makedirs(f'{savedir}/{file_name}')
file_name = f'{savedir}/{file_name}/{file_name}.sdf'
shutil.copy(f'{savedir}/templates/advanced_lift_drag_template.sdf',file_name)
# Get argument coefficients taken directly from the input file.
write_coef(file_name,"a0",alpha)
write_coef(file_name,"CL0",CL0)
write_coef(file_name,"CD0",CD0)
write_coef(file_name,"Cem0",Cem0)
write_coef(file_name,"AR",AR)
write_coef(file_name,"area",area)
write_coef(file_name,"mac",mac)
write_coef(file_name,"air_density",1.2041) # TODO: Provide custom air density option
write_coef(file_name,"forward","1 0 0")
write_coef(file_name,"upward","0 0 1")
write_coef(file_name,"link_name","base_link")
write_coef(file_name,"cp",f'{ref_pt_x} {ref_pt_y} {ref_pt_z}')
write_coef(file_name,"num_ctrl_surfaces",num_ctrl_surfaces)
write_coef(file_name,"CLa",CLa)
write_coef(file_name,"CYa",CYa)
write_coef(file_name,"Cella",Cella)
write_coef(file_name,"Cema",Cema)
write_coef(file_name,"Cena",Cena)
write_coef(file_name,"CLb",CLb)
write_coef(file_name,"CYb",CYb)
write_coef(file_name,"Cellb",Cellb)
write_coef(file_name,"Cemb",Cemb)
write_coef(file_name,"Cenb",Cenb)
write_coef(file_name,"CDp",CDp)
write_coef(file_name,"CYp",CYp)
write_coef(file_name,"CLp",CLp)
write_coef(file_name,"Cellp",Cellp)
write_coef(file_name,"Cemp",Cemp)
write_coef(file_name,"Cenp",Cenp)
write_coef(file_name,"CDq",CDq)
write_coef(file_name,"CYq",CYq)
write_coef(file_name,"CLq",CLq)
write_coef(file_name,"Cellq",Cellq)
write_coef(file_name,"Cemq",Cemq)
write_coef(file_name,"Cenq",Cenq)
write_coef(file_name,"CDr",CDr)
write_coef(file_name,"CYr",CYr)
write_coef(file_name,"CLr",CLr)
write_coef(file_name,"Cellr",Cellr)
write_coef(file_name,"Cemr",Cemr)
write_coef(file_name,"Cenr",Cenr)
write_coef(file_name,"eff",eff)
# TODO: Improve this for custom stall values
# Note: Currently these stall values are simply taken from advanced_plane presets.
write_coef(file_name,"alpha_stall","0.3391428111")
write_coef(file_name,"CLa_stall","-3.85")
write_coef(file_name,"CDa_stall","-0.9233984055")
write_coef(file_name,"Cema_stall","0")
# Check whether a particular type of control surface has been seen before. If it has,
# then the current control surface is the (right) counterpart.
# ASSUMPTION: There is the assumption that an vehicle will only ever have two of any
# particular type of control surface. (left and right). If this is not the case, the negation
# below will likely not work correctly.
type_seen = list()
# Dictionary containing the directions that each type of control surface can move.
ctrl_direction = {"aileron": 1,"elevator": -1,"rudder": 1}
# More set types in the future?
match plane_type:
case "custom":
for i, ctrl_surface in enumerate(ctrl_surface_order):
# Check whether a particular type of control surface has been seen before. If it has,
# then the current control surface is the (right) counterpart. Depending on the exact
# nature of the encountered type you then need to negate the correct parameters.
if ctrl_surface in type_seen:
# Work out what the corresponding index for the first encounter of the ctrl surface is.
seen_index = type_seen.index(ctrl_surface)
if ctrl_surface == 'aileron':
#Change for right wing aileron by flipping sign
ctrl_surface_mat[seen_index][3] = -float(ctrl_surface_mat[0][3])
ctrl_surface_mat[seen_index][5] = -float(ctrl_surface_mat[0][5])
# Split Elevators are assumed to never run differentially. Feel free to add a
# condition if your plane does require differential elevator action.
else:
# If a ctrl surface has not been encountered add it to the type_seen list and
# set the index to the length of the list - 1 as this corresponds to the newest
# unseen element in ctrl_surface_mat .
type_seen.append(ctrl_surface)
seen_index = len(type_seen) - 1
ctrl_surface_coef(file_name,ctrl_surface_mat[seen_index],i,ctrl_direction[ctrl_surface])
# close the sdf file with plugin
with open(file_name,'a') as plugin_file:
plugin_file.write("</plugin>")
plugin_file.close()
if __name__ == '__main__':
parser = argparse.ArgumentParser()
parser.add_argument("file_name", help="The file to which the desired coefficients should be written.")
parser.add_argument("vehicle_type", help="The type of vehicle in use.")
parser.add_argument("AR", help="The calculated aspect ratio.")
parser.add_argument("mac", help="The calculated mean aerodynamic chord.")
parser.add_argument("ref_pt_x", help="The x coordinate of the reference point, at which forces and moments are applied.")
parser.add_argument("ref_pt_y", help="The y coordinate of the reference point, at which forces and moments are applied.")
parser.add_argument("ref_pt_z", help="The z coordinate of the reference point, at which forces and moments are applied.")
parser.add_argument("num_ctrl_surfaces", help="The number of control surfaces that the model uses.")
parser.add_argument("area", help= "The wing surface area.")
parser.add_argument("ctrl_surface_order", help=" A list containing the types of control surfaces, in theorder in which \
they have been defined in the .avl file.")
parser.add_argument("avl_path",help="A string containing the directory where the AVL directory should be moved to.")
args = parser.parse_args()
main(args.file_name,args.vehicle_type,args.AR,args.mac,args.ref_pt_x,args.ref_pt_y,
args.ref_pt_z,args.num_ctrl_surfaces,args.area,args.ctrl_surface_order,args.avl_path)

View File

@ -1,10 +0,0 @@
oper
x
n custom_plane
st custom_vehicle_stability_derivatives.txt
sb custom_vehicle_body_axis_derivatives.txt
g
h
quit

View File

@ -1,142 +0,0 @@
# Enter a name for your vehicle
vehicle_name: plane_example_2
# Enter the type of airframe you would like to use:
frame_type: custom
# First define some model-wide parameters for custom models:
reference_area: 12
wing_span: 15
# Provide a reference point at which the forces and moments generated will act.
reference_point:
X: 0
Y: 0
Z: 0
#Provide information on each of the Control Surfaces
num_ctrl_surfaces: 4
control_surfaces:
- name: right_wing
type: aileron
nchord: 1
cspace: 1
nspan: 16
sspace: -2
angle: 4
translation:
X: 0
Y: 0
Z: 0
naca: 2412
sections:
- name: section_1
position:
X: -0.25
Y: 0
Z: 0
chord: 1
ainc: 0
nspan: 8
sspace: 1
- name: section_2
position:
X: -0.175
Y: 5
Z: 0.5
chord: 0.7
ainc: 0
nspan: 0
sspace: 0
- name: left_wing
type: aileron
nchord: 1
cspace: 1
nspan: 16
sspace: -2
angle: 4
translation:
X: 0
Y: 0
Z: 0
naca: 2412
sections:
- name: section_1
position:
X: -0.175
Y: -5
Z: 0.5
chord: 0.7
ainc: 0
nspan: 0
sspace: 0
- name: section_2
position:
X: -0.25
Y: 0
Z: 0
chord: 1
ainc: 0
nspan: 8
sspace: 1
- name: elevator
type: elevator
nchord: 1
cspace: 1
nspan: 7
sspace: -2
translation:
X: 6
Y: 0
Z: 0.5
sections:
- name: section_1
position:
X: -0.1
Y: 0
Z: 0
chord: 0.4
ainc: 0
nspan: 7
sspace: -1.25
- name: section_2
position:
X: -0.075
Y: 2
Z: 0
chord: 0.3
ainc: 0
nspan: 0
sspace: 0
- name: fin
type: rudder
nchord: 1
cspace: 1
nspan: 10
sspace: 1
translation:
X: 6
Y: 0
Z: 0.5
sections:
- name: section_1
position:
X: -0.1
Y: 0
Z: 0
chord: 0.4
ainc: 0
nspan: 7
sspace: -1.25
- name: section_2
position:
X: -0.075
Y: 0
Z: 1
chord: 0.3
ainc: 0
nspan: 0
sspace: 0

View File

@ -1,314 +0,0 @@
#!/usr/bin/env
import argparse
import avl_out_parse
import os
import yaml
import subprocess
import shutil
"""
Write individual airfoil section definitions to the .avl file.
Sections are defined through a 3D point in space and assigned properties such as chord, angle of incidence etc.
AVL then links them up to the other sections of a particular surface. You can define any number of sections for
a particular surface, but there always have to be at least two (a left and right edge).
Args:
plane_name (str): The name of the vehicle.
x (str): The x coordinate of the section.
y (str): The y coordinate of the section.
z (str): The z coordinate of the section.
chord (str): Chord in this section of the surface. Trailing edge is at x + chord, y, z.
ainc (str): Angle of incidence for this section. Taken as a rotation (RH rule) about the surface's
spanwise axis projected onto the Y-Z plane.
nspan (str): Number of spanwise vortices in until the next section.
sspan (str): Controls the spanwise spacing of the vortices.
naca_number (str): The chosen NACA number that will define the cambered properties of this section
of the surface. For help picking an airfoil go to: http://airfoiltools.com/airfoil/naca4digit.
ctrl_surface_type: The selected type of control surface. This should be consistent along the entirety of
the surface. (Question: Flap and Aileron along the same airfoil?)
Return:
None.
"""
def write_section(plane_name: str,x: str,y: str,z: str,chord: str,ainc: str,nspan: str,sspace: str,naca_number: str,ctrl_surf_type: str):
with open(f'{plane_name}.avl','a') as avl_file:
avl_file.write("SECTION \n")
avl_file.write("!Xle Yle Zle Chord Ainc Nspanwise Sspace \n")
avl_file.write(f'{x} {y} {z} {chord} {ainc} {nspan} {sspace} \n')
if naca_number != "0000":
avl_file.write("NACA \n")
avl_file.write(f'{naca_number} \n')
avl_file.close()
match ctrl_surf_type:
case 'aileron':
#TODO provide custom options for gain and hinge positions
with open(f'{plane_name}.avl','a') as avl_file:
avl_file.write("CONTROL \n")
avl_file.write("aileron 1.0 0.0 0.0 0.0 0.0 -1 \n")
avl_file.close()
case 'elevator':
with open(f'{plane_name}.avl','a') as avl_file:
avl_file.write("CONTROL \n")
avl_file.write("elevator 1.0 0.0 0.0 0.0 0.0 1 \n")
avl_file.close()
case 'rudder':
with open(f'{plane_name}.avl','a') as avl_file:
avl_file.write("CONTROL \n")
avl_file.write("rudder 1.0 0.0 0.0 0.0 0.0 1 \n")
avl_file.close()
"""
Read the provided yaml file and generate the corresponding .avl file that can be read into AVL.
Also calls AVL and the avl_out_parse.py file that generates the sdf plugin.
Args:
yaml_file: Path to the input yaml file
avl_path: Set the avl_path to provide a desired directory for where Avl should be located.
Return:
None
"""
def main():
user = os.environ.get('USER')
# This will find Avl on a users machine.
for root, dirs, _ in os.walk(f'/home/{user}/'):
if "Avl" in dirs:
target_directory_path = os.path.join(root, "Avl")
break
parent_directory_path = os.path.dirname(target_directory_path)
filedir = f'{parent_directory_path}/'
print(filedir)
parser = argparse.ArgumentParser()
parser.add_argument("--yaml_file", help="Path to input yaml file.")
parser.add_argument("--avl_path", default=filedir, help="Provide an absolute AVL path. If this argument is passed, AVL will be moved there and the files will adjust their paths accordingly.")
inputs = parser.parse_args()
# If the user passes the avl_path argument then move Avl to that location:
if inputs.avl_path != filedir:
#Check if the directory is already there
if os.path.exists(f'{inputs.avl_path}/Avl') and os.path.isdir(f'{inputs.avl_path}/Avl'):
print("Avl is already at desired location")
else:
shutil.move(f'{filedir}Avl',inputs.avl_path)
# Adjust paths to AVL in process.sh
print("Adjusting paths")
with open("./process.sh", "r") as file:
all_lines = file.readlines()
file.close()
it = 0
for line in all_lines:
if "cp $DIR_PATH/$CUSTOM_MODEL.avl" in line:
new_line = f'cp $DIR_PATH/$CUSTOM_MODEL.avl {inputs.avl_path}Avl/runs\n'
all_lines[it] = new_line
if "/Avl/runs/plot.ps $DIR_PATH/" in line:
new_line =f'mv {inputs.avl_path}Avl/runs/plot.ps $DIR_PATH/\n'
all_lines[it] = new_line
if "cd" in line and "/Avl/runs" in line:
new_line = f'cd {inputs.avl_path}Avl/runs\n'
all_lines[it] = new_line
it += 1
with open("./process.sh", "w") as file:
file.writelines(all_lines)
file.close()
with open(inputs.yaml_file,'r') as yaml_file:
yaml_data = yaml.safe_load(yaml_file)
airframes = ['cessna','standard_vtol','custom']
plane_name = yaml_data['vehicle_name']
frame_type = yaml_data['frame_type']
if not frame_type in airframes:
raise ValueError("\nThis is not a valid airframe, please choose a valid airframe. \n")
# Parameters that need to be provided:
# General
# - Reference Area (Sref)
# - Wing span (Bref) (wing span squared / area = aspect ratio which is a required parameter for the sdf file)
# - Reference point (X,Y,Zref) point at which moments and forces are calculated
#Control Surface specific
# - type (select from options; aileron,elevator,rudder)
# - nchord
# - cspace
# - nspanwise
# - sspace
# - x,y,z 1. (section)
# - chord 1. (section)
# - ainc 1. (section)
# - Nspan 1. (optional for section)
# - sspace 1. (optional for section)
# - x,y,z 2. (section)
# - chord 2. (section)
# - ainc 2. (section)
# - Nspan 2. (optional for section)
# - sspace 2. (optional for section)
# TODO: Find out if elevons are defined
ctrl_surface_types = ['aileron','elevator','rudder']
# - Reference Chord (Cref) (= area/wing span)
delineation = '!***************************************'
sec_demark = '#--------------------------------------------------'
num_ctrl_surfaces = 0
ctrl_surface_order = []
area = 0
span = 0
ref_pt_x = None
ref_pt_y = None
ref_pt_z = None
# Future work: Provide some pre-worked frames for a Cessna and standard VTOL if there is a need for it
match frame_type:
case "custom":
# These parameters are consistent across all models.
# At the moment we do not use any symmetry axis for mirroring.
with open(f'{plane_name}.avl','w') as avl_file:
avl_file.write(f'{delineation} \n')
avl_file.write(f'!{plane_name} input dataset \n')
avl_file.write(f'{delineation} \n')
avl_file.write(f'{plane_name} \n')
avl_file.write('!Mach \n0.0 \n')
avl_file.write('!IYsym IZsym Zsym \n')
avl_file.write('0 0 0 \n')
avl_file.close()
# First define some model-specific parameters for custom models
area = yaml_data["reference_area"]
span = yaml_data["wing_span"]
ref_pt_x = yaml_data["reference_point"]["X"]
ref_pt_y = yaml_data["reference_point"]["Y"]
ref_pt_z = yaml_data["reference_point"]["Z"]
if(span != 0 and area != 0):
ref_chord = float(area)/float(span)
else:
raise ValueError("Invalid reference chord value. Check area and wing span values.")
# Write the gathered model-wide parameters into the .avl file
with open(f'{plane_name}.avl','a') as avl_file:
avl_file.write('!Sref Cref Bref \n')
avl_file.write(f'{area} {str(ref_chord)} {span} \n')
avl_file.write('!Xref Yref Zref \n')
avl_file.write(f'{ref_pt_x} {ref_pt_y} {ref_pt_z} \n')
avl_file.close()
num_ctrl_surfaces = yaml_data["num_ctrl_surfaces"]
for i, control_surface in enumerate(yaml_data["control_surfaces"]):
# Wings always need to be defined from left to right
ctrl_surf_name = control_surface['name']
ctrl_surf_type = control_surface['type']
if ctrl_surf_type not in ctrl_surface_types:
raise ValueError(f'The selected type is invalid. Available types are: {ctrl_surface_types}')
# The order of control surfaces becomes important in the output parsing
# to correctly assign derivatives to particular surfaces.
ctrl_surface_order.append(ctrl_surf_type)
nchord = control_surface["nchord"]
cspace = control_surface["cspace"]
nspanwise = control_surface["nspan"]
sspace = control_surface["sspace"]
# TODO: Add more control surface types that also require Angles.
if ctrl_surf_type.lower() == 'aileron':
angle = control_surface["angle"]
#Translation of control surface, will move the whole surface to specified position
tx = control_surface["translation"]["X"]
ty = control_surface["translation"]["Y"]
tz = control_surface["translation"]["Z"]
# Write common part of this surface to .avl file
with open(f'{plane_name}.avl','a') as avl_file:
avl_file.write(sec_demark)
avl_file.write("\nSURFACE \n")
avl_file.write(f'{ctrl_surf_name} \n')
avl_file.write("!Nchordwise Cspace Nspanwise Sspace \n")
avl_file.write(f'{nchord} {cspace} {nspanwise} {sspace} \n')
# If we have a elevator, we can duplicate the defined control surface along the y-axis of the model
# as both sides are generally modelled and controlled as one in simulation. Adjust for split elevators if desired.
if ctrl_surf_type.lower() == 'elevator':
avl_file.write("\nYDUPLICATE\n")
avl_file.write("0.0\n\n")
# Elevators and Rudders do not require an angle of incidence.
if ctrl_surf_type.lower() == 'aileron':
avl_file.write("ANGLE \n")
avl_file.write(f'{angle} \n')
# Translate the surface to a particular position in space.
avl_file.write("TRANSLATE \n")
avl_file.write(f'{tx} {ty} {tz} \n')
avl_file.close()
# Define NACA airfoil shape.
# For help picking an airfoil go to: http://airfoiltools.com/airfoil/naca4digit
# NOTE: AVL can only use 4-digit NACA codes.
if ctrl_surf_type.lower() == "aileron":
naca_number = control_surface["naca"]
else:
# Provide a default NACA number for unused airfoils
naca_number = '0000'
# Iterating over each defined section for the control surface. There need to be at least
# two in order to define a left and right edge, but there is no upper limit.
# CRITICAL: ALWAYS DEFINE YOUR SECTION FROM LEFT TO RIGHT
for j, section in enumerate(control_surface["sections"]):
print(f'Defining {j}. section of {i+1}. control surface \n')
y = section["position"]["Y"]
z = section["position"]["Z"]
x = section["position"]["X"]
chord = section["chord"]
ainc = section["ainc"]
nspan = section["nspan"]
write_section(plane_name,x,y,z,chord,ainc,nspan,sspace,naca_number,ctrl_surf_type)
print(f'\nPARAMETER DEFINITION FOR {i+1}. CONTROL SURFACE COMPLETED \n')
# Calculation of Aspect Ratio (AR) and Mean Aerodynamic Chord (mac)
AR = str((float(span)*float(span))/float(area))
mac = str((2/3)*(float(area)/float(span)))
# Call shell script that will pass the generated .avl file to AVL
os.system(f'./process.sh {plane_name}')
# Call main function of avl parse script to parse the generated AVL files.
avl_out_parse.main(plane_name,frame_type,AR,mac,ref_pt_x,ref_pt_y,ref_pt_z,num_ctrl_surfaces,area,ctrl_surface_order,inputs.avl_path)
# Finally move all generated files to a new directory and show the generated geometry image:
result = subprocess.run(['pwd'], stdout=subprocess.PIPE, stderr=subprocess.PIPE, text=True)
if result.returncode == 0:
# Save the output in a variable
current_path = result.stdout.strip()
# Run image plot from avl_automation directory.
os.system(f'mv ./{plane_name}.* ./{plane_name}' )
os.system(f'evince {current_path}/{plane_name}/{plane_name}.ps')
if __name__ == '__main__':
main()

View File

@ -1,27 +0,0 @@
#!/bin/bash
CUSTOM_MODEL=$1
DIR_PATH=$(pwd)
cp $DIR_PATH/$CUSTOM_MODEL.avl /home/$USER/Avl/runs/
cd
cd /home/$USER/Avl/runs
old_stability_derivatives="custom_vehicle_stability_derivatives.txt"
old_body_ax_derivatives="custom_vehicle_body_axis_derivatives.txt"
if [ -e "$old_stability_derivatives" ]; then
# Delete old stability derivative file
rm "$old_stability_derivatives"
fi
if [ -e "$old_body_ax_derivatives" ]; then
# Delete old body_axis derivative file
rm "$old_body_ax_derivatives"
fi
#avl_steps.txt can be used to run commands on the AVL commandline.
../bin/avl $CUSTOM_MODEL.avl < $DIR_PATH/avl_steps.txt
echo "\n"
#After completion move the plot to avl_automation directory
mv /home/$USER/Avl/runs/plot.ps $DIR_PATH/
mv $DIR_PATH/plot.ps $DIR_PATH/$CUSTOM_MODEL.ps

View File

@ -1,43 +0,0 @@
<plugin filename="gz-sim-advanced-lift-drag-system" name="gz::sim::systems::AdvancedLiftDrag">
<a0></a0>
<CL0></CL0>
<AR></AR>
<eff></eff>
<CLa></CLa>
<CD0></CD0>
<Cem0></Cem0>
<Cema></Cema>
<CYb></CYb>
<Cellb></Cellb>
<Cenb></Cenb>
<CDp></CDp>
<CYp></CYp>
<CLp></CLp>
<Cellp></Cellp>
<Cemp></Cemp>
<Cenp></Cenp>
<CDq></CDq>
<CYq></CYq>
<CLq></CLq>
<Cellq></Cellq>
<Cemq></Cemq>
<Cenq></Cenq>
<CDr></CDr>
<CYr></CYr>
<CLr></CLr>
<Cellr></Cellr>
<Cemr></Cemr>
<Cenr></Cenr>
<alpha_stall></alpha_stall>
<CLa_stall></CLa_stall>
<CDa_stall></CDa_stall>
<Cema_stall></Cema_stall>
<cp></cp>
<area></area>
<mac></mac>
<air_density></air_density>
<forward></forward>
<upward></upward>
<link_name></link_name>
<num_ctrl_surfaces></num_ctrl_surfaces>

View File

@ -1,11 +0,0 @@
<control_surface>
<name></name>
<index></index>
<direction></direction>
<CD_ctrl></CD_ctrl>
<CY_ctrl></CY_ctrl>
<CL_ctrl></CL_ctrl>
<Cell_ctrl></Cell_ctrl>
<Cem_ctrl></Cem_ctrl>
<Cen_ctrl></Cen_ctrl>
</control_surface>

View File

@ -1,148 +0,0 @@
<sdf version='1.9'>
<world name='default'>
<physics type="ode">
<max_step_size>0.004</max_step_size>
<real_time_factor>1.0</real_time_factor>
<real_time_update_rate>250</real_time_update_rate>
</physics>
<plugin name='gz::sim::systems::Physics' filename='gz-sim-physics-system'/>
<plugin name='gz::sim::systems::UserCommands' filename='gz-sim-user-commands-system'/>
<plugin name='gz::sim::systems::SceneBroadcaster' filename='gz-sim-scene-broadcaster-system'/>
<plugin name='gz::sim::systems::Contact' filename='gz-sim-contact-system'/>
<plugin name='gz::sim::systems::Imu' filename='gz-sim-imu-system'/>
<plugin name='gz::sim::systems::AirPressure' filename='gz-sim-air-pressure-system'/>
<plugin name='gz::sim::systems::ApplyLinkWrench' filename='gz-sim-apply-link-wrench-system'/>
<plugin name='gz::sim::systems::Sensors' filename='gz-sim-sensors-system'>
<render_engine>ogre2</render_engine>
</plugin>
<gui fullscreen='false'>
<plugin name='3D View' filename='GzScene3D'>
<gz-gui>
<title>3D View</title>
<property type='bool' key='showTitleBar'>0</property>
<property type='string' key='state'>docked</property>
</gz-gui>
<engine>ogre2</engine>
<scene>scene</scene>
<ambient_light>0.5984631152222222 0.5984631152222222 0.5984631152222222</ambient_light>
<background_color>0.8984631152222222 0.8984631152222222 0.8984631152222222</background_color>
<camera_pose>-6 0 6 0 0.5 0</camera_pose>
</plugin>
<plugin name='World control' filename='WorldControl'>
<gz-gui>
<title>World control</title>
<property type='bool' key='showTitleBar'>0</property>
<property type='bool' key='resizable'>0</property>
<property type='double' key='height'>72</property>
<property type='double' key='width'>121</property>
<property type='double' key='z'>1</property>
<property type='string' key='state'>floating</property>
<anchors target='3D View'>
<line own='left' target='left'/>
<line own='bottom' target='bottom'/>
</anchors>
</gz-gui>
<play_pause>1</play_pause>
<step>1</step>
<start_paused>1</start_paused>
</plugin>
<plugin name='World stats' filename='WorldStats'>
<gz-gui>
<title>World stats</title>
<property type='bool' key='showTitleBar'>0</property>
<property type='bool' key='resizable'>0</property>
<property type='double' key='height'>110</property>
<property type='double' key='width'>290</property>
<property type='double' key='z'>1</property>
<property type='string' key='state'>floating</property>
<anchors target='3D View'>
<line own='right' target='right'/>
<line own='bottom' target='bottom'/>
</anchors>
</gz-gui>
<sim_time>1</sim_time>
<real_time>1</real_time>
<real_time_factor>1</real_time_factor>
<iterations>1</iterations>
</plugin>
<plugin name='Entity tree' filename='EntityTree'/>
</gui>
<gravity>0 0 -9.8</gravity>
<magnetic_field>6e-06 2.3e-05 -4.2e-05</magnetic_field>
<atmosphere type='adiabatic'/>
<scene>
<grid>false</grid>
<ambient>0.4 0.4 0.4 1</ambient>
<background>0.7 0.7 0.7 1</background>
<shadows>true</shadows>
</scene>
<model name='ground_plane'>
<static>true</static>
<link name='link'>
<collision name='collision'>
<geometry>
<plane>
<normal>0 0 1</normal>
<size>1 1</size>
</plane>
</geometry>
<surface>
<friction>
<ode/>
</friction>
<bounce/>
<contact/>
</surface>
</collision>
<visual name='visual'>
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
<pose>0 0 0 0 -0 0</pose>
<inertial>
<pose>0 0 0 0 -0 0</pose>
<mass>1</mass>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
</inertial>
<enable_wind>false</enable_wind>
</link>
<pose>0 0 0 0 -0 0</pose>
<self_collide>false</self_collide>
</model>
<light name='sunUTC' type='directional'>
<pose>0 0 500 0 -0 0</pose>
<cast_shadows>true</cast_shadows>
<intensity>1</intensity>
<direction>0.001 0.625 -0.78</direction>
<diffuse>0.904 0.904 0.904 1</diffuse>
<specular>0.271 0.271 0.271 1</specular>
<attenuation>
<range>2000</range>
<linear>0</linear>
<constant>1</constant>
<quadratic>0</quadratic>
</attenuation>
<spot>
<inner_angle>0</inner_angle>
<outer_angle>0</outer_angle>
<falloff>0</falloff>
</spot>
</light>
</world>
</sdf>

View File

@ -1,151 +0,0 @@
<sdf version='1.9'>
<world name='windy'>
<physics type="ode">
<max_step_size>0.004</max_step_size>
<real_time_factor>1.0</real_time_factor>
<real_time_update_rate>250</real_time_update_rate>
</physics>
<plugin name='gz::sim::systems::Physics' filename='gz-sim-physics-system'/>
<plugin name='gz::sim::systems::UserCommands' filename='gz-sim-user-commands-system'/>
<plugin name='gz::sim::systems::SceneBroadcaster' filename='gz-sim-scene-broadcaster-system'/>
<plugin name='gz::sim::systems::Contact' filename='gz-sim-contact-system'/>
<plugin name='gz::sim::systems::Imu' filename='gz-sim-imu-system'/>
<plugin name='gz::sim::systems::AirPressure' filename='gz-sim-air-pressure-system'/>
<plugin name='gz::sim::systems::ApplyLinkWrench' filename='gz-sim-apply-link-wrench-system'/>
<plugin name='gz::sim::systems::Sensors' filename='gz-sim-sensors-system'>
<render_engine>ogre2</render_engine>
</plugin>
<gui fullscreen='false'>
<plugin name='3D View' filename='GzScene3D'>
<gz-gui>
<title>3D View</title>
<property type='bool' key='showTitleBar'>0</property>
<property type='string' key='state'>docked</property>
</gz-gui>
<engine>ogre2</engine>
<scene>scene</scene>
<ambient_light>0.5984631152222222 0.5984631152222222 0.5984631152222222</ambient_light>
<background_color>0.8984631152222222 0.8984631152222222 0.8984631152222222</background_color>
<camera_pose>-6 0 6 0 0.5 0</camera_pose>
</plugin>
<plugin name='World control' filename='WorldControl'>
<gz-gui>
<title>World control</title>
<property type='bool' key='showTitleBar'>0</property>
<property type='bool' key='resizable'>0</property>
<property type='double' key='height'>72</property>
<property type='double' key='width'>121</property>
<property type='double' key='z'>1</property>
<property type='string' key='state'>floating</property>
<anchors target='3D View'>
<line own='left' target='left'/>
<line own='bottom' target='bottom'/>
</anchors>
</gz-gui>
<play_pause>1</play_pause>
<step>1</step>
<start_paused>1</start_paused>
</plugin>
<plugin name='World stats' filename='WorldStats'>
<gz-gui>
<title>World stats</title>
<property type='bool' key='showTitleBar'>0</property>
<property type='bool' key='resizable'>0</property>
<property type='double' key='height'>110</property>
<property type='double' key='width'>290</property>
<property type='double' key='z'>1</property>
<property type='string' key='state'>floating</property>
<anchors target='3D View'>
<line own='right' target='right'/>
<line own='bottom' target='bottom'/>
</anchors>
</gz-gui>
<sim_time>1</sim_time>
<real_time>1</real_time>
<real_time_factor>1</real_time_factor>
<iterations>1</iterations>
</plugin>
<plugin name='Entity tree' filename='EntityTree'/>
</gui>
<gravity>0 0 -9.8</gravity>
<magnetic_field>6e-06 2.3e-05 -4.2e-05</magnetic_field>
<atmosphere type='adiabatic'/>
<scene>
<grid>false</grid>
<ambient>0.4 0.4 0.4 1</ambient>
<background>0.7 0.7 0.7 1</background>
<shadows>true</shadows>
</scene>
<model name='ground_plane'>
<static>true</static>
<link name='link'>
<collision name='collision'>
<geometry>
<plane>
<normal>0 0 1</normal>
<size>1 1</size>
</plane>
</geometry>
<surface>
<friction>
<ode/>
</friction>
<bounce/>
<contact/>
</surface>
</collision>
<visual name='visual'>
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
<pose>0 0 0 0 -0 0</pose>
<inertial>
<pose>0 0 0 0 -0 0</pose>
<mass>1</mass>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
</inertial>
<enable_wind>true</enable_wind>
</link>
<pose>0 0 0 0 -0 0</pose>
<self_collide>false</self_collide>
</model>
<light name='sunUTC' type='directional'>
<pose>0 0 500 0 -0 0</pose>
<cast_shadows>true</cast_shadows>
<intensity>1</intensity>
<direction>0.001 0.625 -0.78</direction>
<diffuse>0.904 0.904 0.904 1</diffuse>
<specular>0.271 0.271 0.271 1</specular>
<attenuation>
<range>2000</range>
<linear>0</linear>
<constant>1</constant>
<quadratic>0</quadratic>
</attenuation>
<spot>
<inner_angle>0</inner_angle>
<outer_angle>0</outer_angle>
<falloff>0</falloff>
</spot>
</light>
<wind>
<linear_velocity>10 10 10</linear_velocity>
</wind>
</world>
</sdf>

View File

@ -72,14 +72,24 @@ if(gz-transport_FOUND)
module.yaml
)
file(GLOB gz_models
LIST_DIRECTORIES true
RELATIVE ${PX4_SOURCE_DIR}/Tools/simulation/gz/models
${PX4_SOURCE_DIR}/Tools/simulation/gz/models/*
px4_add_git_submodule(TARGET git_gz PATH "${PX4_SOURCE_DIR}/Tools/simulation/gz")
include(ExternalProject)
ExternalProject_Add(gz
SOURCE_DIR ${PX4_SOURCE_DIR}/Tools/simulation/gz
CMAKE_ARGS -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX}
BINARY_DIR ${PX4_BINARY_DIR}/build_gz
INSTALL_COMMAND ""
DEPENDS git_gz
USES_TERMINAL_CONFIGURE true
USES_TERMINAL_BUILD true
EXCLUDE_FROM_ALL true
BUILD_ALWAYS 1
)
file(GLOB gz_worlds
${PX4_SOURCE_DIR}/Tools/simulation/gz/worlds/*.sdf
set(gz_worlds
default
windy
baylands
)
# find corresponding airframes
@ -100,56 +110,20 @@ if(gz-transport_FOUND)
set(model_only)
string(REGEX REPLACE ".*_gz_" "" model_only ${gz_airframe})
if(EXISTS "${PX4_SOURCE_DIR}/Tools/simulation/gz/models/${model_only}")
if((EXISTS "${PX4_SOURCE_DIR}/Tools/simulation/gz/models/${model_only}/model.sdf"))
#message(STATUS "Ignition SDF file found for ${model_only}")
else()
message(WARNING "Ignition no SDF file found for ${model_only}")
endif()
else()
message(WARNING "model directory ${PX4_SOURCE_DIR}/Tools/simulation/gz/models/${model_only} not found")
endif()
endforeach()
foreach(model ${gz_models})
# match model to airframe
set(airframe_model_only)
set(airframe_sys_autostart)
set(gz_airframe_found)
foreach(gz_airframe IN LISTS gz_airframes)
string(REGEX REPLACE ".*_gz_" "" airframe_model_only ${gz_airframe})
string(REGEX REPLACE "_gz_.*" "" airframe_sys_autostart ${gz_airframe})
if(model STREQUAL ${airframe_model_only})
set(gz_airframe_found ${gz_airframe})
break()
endif()
endforeach()
if(gz_airframe_found)
#message(STATUS "gz model: ${model} (${airframe_model_only}), airframe: ${gz_airframe_found}, SYS_AUTOSTART: ${airframe_sys_autostart}")
else()
message(WARNING "gz missing model: ${model} (${airframe_model_only}), airframe: ${gz_airframe_found}, SYS_AUTOSTART: ${airframe_sys_autostart}")
endif()
foreach(world ${gz_worlds})
get_filename_component("world_name" ${world} NAME_WE)
if(world_name STREQUAL "default")
add_custom_target(gz_${model}
COMMAND ${CMAKE_COMMAND} -E env PX4_SIM_MODEL=gz_${model} $<TARGET_FILE:px4>
add_custom_target(gz_${model_only}
COMMAND ${CMAKE_COMMAND} -E env PX4_SIM_MODEL=gz_${model_only} $<TARGET_FILE:px4>
WORKING_DIRECTORY ${SITL_WORKING_DIR}
USES_TERMINAL
DEPENDS px4
)
else()
add_custom_target(gz_${model}_${world_name}
COMMAND ${CMAKE_COMMAND} -E env PX4_SIM_MODEL=gz_${model} PX4_GZ_WORLD=${world_name} $<TARGET_FILE:px4>
add_custom_target(gz_${model_only}_${world_name}
COMMAND ${CMAKE_COMMAND} -E env PX4_SIM_MODEL=gz_${model_only} PX4_GZ_WORLD=${world_name} $<TARGET_FILE:px4>
WORKING_DIRECTORY ${SITL_WORKING_DIR}
USES_TERMINAL
DEPENDS px4
@ -157,7 +131,6 @@ if(gz-transport_FOUND)
endif()
endforeach()
endforeach()
# PX4_GZ_MODELS, PX4_GZ_WORLDS, GZ_SIM_RESOURCE_PATH
configure_file(gz_env.sh.in ${PX4_BINARY_DIR}/rootfs/gz_env.sh)

View File

@ -98,7 +98,7 @@ int GZBridge::init()
// If model position z is less equal than 0, move above floor to prevent floor glitching
if (model_pose_v[2] <= 0.0) {
PX4_INFO("Model position z is less or equal 0.0, moving upwards");
model_pose_v[2] = 1.0;
model_pose_v[2] = 0.5;
}
gz::msgs::Pose *p = req.mutable_pose();
@ -122,15 +122,44 @@ int GZBridge::init()
bool result;
std::string create_service = "/world/" + _world_name + "/create";
if (_node.Request(create_service, req, 1000, rep, result)) {
if (!rep.data() || !result) {
PX4_ERR("EntityFactory service call failed");
bool gz_called = false;
// Check if PX4_GZ_STANDALONE has been set.
char *standalone_val = std::getenv("PX4_GZ_STANDALONE");
if ((standalone_val != nullptr) && (std::strcmp(standalone_val, "1") == 0)) {
// Check if Gazebo has been called and if not attempt to reconnect.
while (gz_called == false) {
if (_node.Request(create_service, req, 1000, rep, result)) {
if (!rep.data() || !result) {
PX4_ERR("EntityFactory service call failed");
return PX4_ERROR;
} else {
gz_called = true;
}
}
// If Gazebo has not been called, wait 2 seconds and try again.
else {
PX4_WARN("Service call timed out as Gazebo has not been detected.");
system_usleep(2000000);
}
}
}
// If PX4_GZ_STANDALONE has been set, you can try to connect but GZ_SIM_RESOURCE_PATH needs to be set correctly to work.
else {
if (_node.Request(create_service, req, 1000, rep, result)) {
if (!rep.data() || !result) {
PX4_ERR("EntityFactory service call failed.");
return PX4_ERROR;
}
} else {
PX4_ERR("Service call timed out. Check GZ_SIM_RESOURCE_PATH is set correctly.");
return PX4_ERROR;
}
} else {
PX4_ERR("Service call timed out");
return PX4_ERROR;
}
}