forked from Archive/PX4-Autopilot
Port of Advanced Plane from Gazebo Classic to Gazebo (#22167)
* started tiltrotor port * added advanced plane and changed some parameters on the tiltrotor * added advanced plane * removed tiltrotor for clean push * removed standard vtol old model file * removing the standard vtol changes from this PR, since it is not part of the advanced plane * removed advanced plane meshes as they are already found in the rc_cessna * updating and improving airframe parameters * updated mesh paths Signed-off-by: frederik <frederik@auterion.com> --------- Signed-off-by: frederik <frederik@auterion.com> Co-authored-by: frederik <frederik@auterion.com>
This commit is contained in:
parent
22ee90b7d7
commit
39fbfd8e0c
|
@ -0,0 +1,82 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# @name Advanced Plane SITL
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.fw_defaults
|
||||
|
||||
PX4_SIMULATOR=${PX4_SIMULATOR:=gz}
|
||||
PX4_GZ_WORLD=${PX4_GZ_WORLD:=default}
|
||||
PX4_SIM_MODEL=${PX4_SIM_MODEL:=advanced_plane}
|
||||
|
||||
param set-default SIM_GZ_EN 1
|
||||
|
||||
param set-default SENS_EN_GPSSIM 1
|
||||
param set-default SENS_EN_MAGSIM 1
|
||||
param set-default SENS_EN_ARSPDSIM 1
|
||||
|
||||
param set-default FW_LND_ANG 8
|
||||
param set-default NPFG_PERIOD 12
|
||||
|
||||
param set-default FW_MAN_P_MAX 30
|
||||
param set-default FW_PR_P 0.9
|
||||
param set-default FW_PR_FF 0.5
|
||||
param set-default FW_PR_I 0.5
|
||||
|
||||
param set-default FW_PSP_OFF 2
|
||||
param set-default FW_P_LIM_MAX 32
|
||||
param set-default FW_P_LIM_MIN -15
|
||||
|
||||
param set-default FW_RR_FF 0.5
|
||||
param set-default FW_RR_P 0.3
|
||||
param set-default FW_RR_I 0.5
|
||||
|
||||
param set-default FW_YR_FF 0.5
|
||||
param set-default FW_YR_P 0.6
|
||||
param set-default FW_YR_I 0.5
|
||||
|
||||
param set-default FW_SPOILERS_LND 0.4
|
||||
|
||||
param set-default FW_THR_MIN 0.05
|
||||
param set-default FW_THR_TRIM 0.25
|
||||
|
||||
param set-default FW_T_CLMB_MAX 8
|
||||
param set-default FW_T_SINK_MAX 2.7
|
||||
param set-default FW_T_SINK_MIN 2.2
|
||||
|
||||
param set-default FW_W_EN 1
|
||||
|
||||
param set-default MIS_TAKEOFF_ALT 30
|
||||
|
||||
param set-default NAV_ACC_RAD 15
|
||||
param set-default NAV_DLL_ACT 2
|
||||
|
||||
param set-default RWTO_TKOFF 1
|
||||
|
||||
param set-default CA_AIRFRAME 1
|
||||
|
||||
param set-default CA_ROTOR_COUNT 1
|
||||
param set-default CA_ROTOR0_PX 0.3
|
||||
|
||||
param set-default CA_SV_CS_COUNT 6
|
||||
param set-default CA_SV_CS0_TRQ_R -0.5
|
||||
param set-default CA_SV_CS0_TYPE 1
|
||||
param set-default CA_SV_CS1_TRQ_R 0.5
|
||||
param set-default CA_SV_CS1_TYPE 2
|
||||
param set-default CA_SV_CS2_TRQ_P 1.0
|
||||
param set-default CA_SV_CS2_TYPE 3
|
||||
param set-default CA_SV_CS3_TRQ_Y 1.0
|
||||
param set-default CA_SV_CS3_TYPE 4
|
||||
param set-default CA_SV_CS4_TYPE 9
|
||||
param set-default CA_SV_CS5_TYPE 10
|
||||
|
||||
param set-default SIM_GZ_EC_FUNC1 101
|
||||
param set-default SIM_GZ_EC_MIN1 10
|
||||
param set-default SIM_GZ_EC_MAX1 1600
|
||||
|
||||
param set-default SIM_GZ_SV_FUNC1 201
|
||||
param set-default SIM_GZ_SV_FUNC2 202
|
||||
param set-default SIM_GZ_SV_FUNC3 203
|
||||
param set-default SIM_GZ_SV_FUNC4 204
|
||||
param set-default SIM_GZ_SV_FUNC5 205
|
||||
param set-default SIM_GZ_SV_FUNC6 206
|
|
@ -79,6 +79,7 @@ px4_add_romfs_files(
|
|||
4004_gz_standard_vtol
|
||||
4005_gz_x500_vision
|
||||
4006_gz_px4vision
|
||||
4008_gz_advanced_plane
|
||||
|
||||
6011_gazebo-classic_typhoon_h480
|
||||
6011_gazebo-classic_typhoon_h480.post
|
||||
|
|
|
@ -0,0 +1,14 @@
|
|||
<?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>
|
|
@ -0,0 +1,578 @@
|
|||
<?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/frede791/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/frede791/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/frede791/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/frede791/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/frede791/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/frede791/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/frede791/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/frede791/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>
|
Loading…
Reference in New Issue