반응형

새 모델은 어떻게 만들지..?

그냥 이 글을 따라가보자. [2]

 


모델 만들기

1. PX4의 Gazebo model directory 에 sdf 파일을 추가한다.

(Root/Tools/simulation/gz/models/**)

 

구성파일 만들기

2. airframe configuration file 만들기

펌웨어게 프레임 구성을 추가하려면..

2.1. init.d/airframes 폴더에 새로운 구성 파일을 만든다.

  • 짧게 묘사하는 파일 이름을 만들고 파일 이름 앞에 안 쓰는 autostart ID를 추가한다.(예를 들면, 1033092_superfast_vtol)
  • 파일에 구성 매개변수와 앱을 추가한다.

2.2 새 프레임 구성파일의 이름을 CMakeLists.txt 의 기체 타입과 관련 있는 섹션에 추가한다.

2.3 Build and upload the software.

 

3. 기체 프레임 구성파일에 Gazebo용 기본 매개변수를 정의한다.

PX4_SIMULATOR=${PX4_SIMULATOR:=gz}
PX4_GZ_WORLD=${PX4_GZ_WORLD:=default}
PX4_SIM_MODEL=${PX4_SIM_MODEL:=<MODEL_NAME>}

PX4_SIMULATOR:=gz

해당 기체 프레임으로 Gazebo를 기본 시뮬레이터로 설정

PX4_GZ_WORLD:=default

해당 기체 프레임의 기본 world 를 설정

PX4_SIM_MODEL:=<MODEL_NAME>

Gazebo model directory (Root/Tools/simulation/gz/models/**) 에 Gazebo 모델을 설정

 

 

Make a sample model refering from Standard VTOL [1]

After this post, I'll make a model like XIAKE800

'cause I already made an parameter file at this post, It will be a good reference.

 

Loadmap

  • Make an Airframe Configuration.
    • Add an Airframe Configuration
    • Add the name of the new frame configuration file to the CMakeLists.txt on init.d (For real vehicle)
    • Add the name of the new frame configuration file to the CMakeLists.txt on init.d-posix (For simulation vehicle)
  • Make a Gazebo Model
    • Collect aircraft properties (inertia, motor/prop, control surfaces)
    • Modify sdf file.
    • Add the name of the new moel to the CMake file (sitl_targets_gazebo-classic.cmake)

 


Make a XIAKE800

From Tiltrotor model (quad-plane, front twin-tilt rotor), make Xiake800 Gazebo model.

(It placed at /PX4-Autopilot/Tools/simulation/gazebo-classic/sitl_gazebo-classic/models/tiltrotor)

Model tree is shown below :

  • model : tiltrotor
    • links : base_link
    • joints
    • sensors (Airspeed sensor, IMU, GPS...)
    • Links and Joints (for geometry. motor, rotor, wing, control surfaces)
    • Plugins
      • LiftDrag (Aerodynamics)
      • gazebo_motor_model (Rotor model)
      • groundtruth
      • magnetometer
      • barometer
      • mavlink_interface

Link-Joint tree is shown below :

  • base_link
    • motor_0_joint - motor_0_link (tilting joint)
      • rotor_0_joint - rotor_0_link (tilting rotor)
    • motor_2_joint - motor_2_link (tilting joint)
      • rotor_2_joint - rotor_2_link (tilting rotor)
    • rotor_1_joint - rotor_1_link (fixed rotor)
    • rotor_3_joint - rotor_3_link (fixed rotor)
    • left_elevon_joint - left_elevon_link
    • right_elevon_joint - right_elevon_link

Note. that model describes rudder, but it don't be allowed to be controlled on mavlink_interface.

At airframe folder, tiltrotor airframe configuration is placed.

: 1042_gazebo-classic_tiltrotor

더보기
. ${R}etc/init.d/rc.vtol_defaults

param set-default MAV_TYPE 21

param set-default CA_AIRFRAME 3

param set-default CA_ROTOR_COUNT 4
param set-default CA_ROTOR0_PX 0.1515
param set-default CA_ROTOR0_PY 0.245
param set-default CA_ROTOR0_KM 0.05
param set-default CA_ROTOR1_PX -0.1515
param set-default CA_ROTOR1_PY -0.1875
param set-default CA_ROTOR1_KM 0.05
param set-default CA_ROTOR2_PX 0.1515
param set-default CA_ROTOR2_PY -0.245
param set-default CA_ROTOR2_KM -0.05
param set-default CA_ROTOR3_PX -0.1515
param set-default CA_ROTOR3_PY 0.1875
param set-default CA_ROTOR3_KM -0.05

param set-default CA_ROTOR0_TILT 1
param set-default CA_ROTOR2_TILT 2
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_CS_COUNT 3
param set-default CA_SV_TL_COUNT 2

param set-default PWM_MAIN_FUNC1 101
param set-default PWM_MAIN_FUNC2 102
param set-default PWM_MAIN_FUNC3 103
param set-default PWM_MAIN_FUNC4 104
param set-default PWM_MAIN_FUNC5 204
param set-default PWM_MAIN_FUNC6 205
param set-default PWM_MAIN_FUNC7 201
param set-default PWM_MAIN_FUNC8 202
param set-default PWM_MAIN_FUNC9 203

param set-default NPFG_PERIOD 12
param set-default FW_PR_FF 0.2
param set-default FW_PR_P 0.9
param set-default FW_PSP_OFF 2
param set-default FW_P_LIM_MIN -15
param set-default FW_RR_FF 0.1
param set-default FW_RR_P 0.3
param set-default FW_THR_TRIM 0.38
param set-default FW_THR_MAX 0.6
param set-default FW_THR_MIN 0.05
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 MC_AIRMODE 1
param set-default MC_YAWRATE_P 0.3
param set-default MC_YAWRATE_I 0.3

param set-default MPC_XY_VEL_P_ACC 3
param set-default MPC_XY_VEL_I_ACC 4
param set-default MPC_XY_VEL_D_ACC 0.1

param set-default MIS_TAKEOFF_ALT 10

param set-default VT_FWD_THRUST_EN 4
param set-default VT_FWD_THRUST_SC 0.6
param set-default VT_TILT_TRANS 0.6
param set-default VT_TYPE 1

 

For real world, tiltrotor airframe configuration is placed at this airframe folder

: 13030_generic_vtol_quad_tiltrotor

 

On QGC, you can see Control Allocation Status.

 

From this post, motor configuration and order would be modified.

PWM Channel Actuator Allocated Name Direction Disarm us
PWM1 TR: Tail Rotor Motor1 (M1) CCW  
PWM2 RR : Right Rotor Motor2 (M2) CCW  
PWM3 LE : Left Elevon Servo1 (S1) Reversed 1500
PWM4 LT : Left Tilting Servo3 (T1) Reversed 2000
PWM5 (TT : Tail Tilting) Disable (Servo5, T3)    
PWM6 RE : Right Elevon Servo2 (S2)   1500
PWM7 RT : Right Tilting Servo4 (T2)   1000
PWM8 LR : Left Rotor Motor3 (M3) CW  

I define geometry. Frame convention follows [Forward X, Right Y, Upsize Z]. Negative value is bold for readability.

link position input index motor
number
maxRotVelocity
input_scaling
link/plugin name
rotor_0 [-0.40,+0.00,+0.07] 0 0 2300 back_motor_model
motor_1 [+0.35,-0.35,+0.02] 6   - motor_1_tilt
rotor_1 [+0.35,-0.35,+0.07] 1 1 1800 front_right_motor_model
motor_2 [+0.35,+0.35,+0.02] 3   - motor_2_tilt
rotor_2 [+0.35,+0.35,+0.07] 7 2 1800 front_left_motor_model
left_elevon default 2   - left_elevon
right_elevon default 5   - right_elevon
motor_0 [-0.40,+0.00,+0.07] 4 - - motor_0_tilt

Link-Joint tree is shown below :

  • base_link
    • rotor_0_joint - rotor_0_link (fixed rotor)
    • motor_1_joint - motor_1_link (tilting joint)
      • rotor_1_joint - rotor_1_link (tilting rotor)
    • motor_2_joint - motor_2_link (tilting joint)
      • rotor_2_joint - rotor_2_link (tilting rotor)
    • left_elevon_joint - left_elevon_link
    • right_elevon_joint - right_elevon_link

 

Model file is below :

Note. This model has a big problem. It works well on multi-rotor mode. but, transition and fixed-wing mode don't work.

xiake1k.sdf.jinja
0.03MB

더보기
<!-- DO NOT EDIT: Generated from standard_vtol.sdf.jinja -->
<sdf version='1.5'>
  <model name='xiake1k'>
    <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>3</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.01 0 -0.08 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://xiake1k/meshes/x8_wing.dae</uri>
          </mesh>
        </geometry>
        <material>
          <script>
            <name>Gazebo/DarkGrey</name>
            <uri>__default__</uri>
          </script>
        </material>
      </visual>
      <visual name='left_motor_column'>
        <pose>0.20 0.35 0.01 0 0 0</pose>
        <geometry>
          <box>
            <size>0.40 0.03 0.03</size>
          </box>
        </geometry>
        <material>
          <script>
            <name>Gazebo/SkyBlue</name>
            <uri>__default__</uri>
          </script>
        </material>
      </visual>
      <visual name='right_motor_column'>
        <pose>0.20 -0.35 0.01 0 0 0</pose>
        <geometry>
          <box>
            <size>0.40 0.03 0.03</size>
          </box>
        </geometry>
        <material>
          <script>
            <name>Gazebo/SkyBlue</name>
            <uri>__default__</uri>
          </script>
        </material>
      </visual>
      <gravity>1</gravity>
      <velocity_decay/>
      <self_collide>0</self_collide>
    </link>
    <link name='xiake1k/imu_link'>
      <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>
    </link>
    <joint name='xiake1k/imu_joint' type='revolute'>
      <child>xiake1k/imu_link</child>
      <parent>base_link</parent>
      <axis>
        <xyz>1 0 0</xyz>
        <limit>
          <lower>0</lower>
          <upper>0</upper>
          <effort>0</effort>
          <velocity>0</velocity>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
        <use_parent_model_frame>1</use_parent_model_frame>
      </axis>
    </joint>
    <include>
      <uri>model://airspeed</uri>
      <pose>0 0 0 0 0 0</pose>
      <name>airspeed</name>
    </include>
    <joint name='airspeed_joint' type='fixed'>
      <child>airspeed::link</child>
      <parent>base_link</parent>
    </joint>
    <include>
      <uri>model://gps</uri>
      <pose>0 0 0 0 0 0</pose>
      <name>gps</name>
    </include>
    <joint name='gps_joint' type='fixed'>
      <child>gps::link</child>
      <parent>base_link</parent>
    </joint>

    <link name='motor_2'>
      <pose>0.35 +0.35 0.02 0 0 0</pose>
      <inertial>
        <pose>0 0 0 0 0 0</pose>
        <mass>0.05</mass>
        <inertia>
          <ixx>0.0166704</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.0166704</iyy>
          <iyz>0</iyz>
          <izz>0.0167604</izz>
        </inertia>
      </inertial>
      <collision name='motor_2_collision'>
        <pose>0 0 0 0 0 0</pose>
        <geometry>
          <cylinder>
            <length>0.035</length>
            <radius>0.02</radius>
          </cylinder>
        </geometry>
        <surface>
          <contact>
            <ode/>
          </contact>
          <friction>
            <ode/>
          </friction>
        </surface>
      </collision>
      <visual name='motor_2_visual'>
        <pose>0 0 0 0 0 0</pose>
        <geometry>
          <cylinder>
            <length>0.035</length>
            <radius>0.02</radius>
          </cylinder>
        </geometry>
        <material>
          <script>
            <name>Gazebo/Red</name>
            <uri>__default__</uri>
          </script>
        </material>
      </visual>
      <gravity>1</gravity>
      <velocity_decay/>
      <self_collide>0</self_collide>
    </link>
    <joint name='motor_2_joint' type='revolute'>
      <child>motor_2</child>
      <parent>base_link</parent>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1.570795</lower>
          <upper>+1.570795</upper>
        </limit>
        <dynamics>
          <friction>1.0</friction>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
        <use_parent_model_frame>1</use_parent_model_frame>
      </axis>
    </joint>
    <link name='rotor_2'>
      <pose>0.35 +0.35 0.10 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://xiake1k/meshes/iris_prop_ccw.dae</uri>
          </mesh>
        </geometry>
        <material>
          <script>
            <name>Gazebo/Blue</name>
            <uri>__default__</uri>
          </script>
        </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>motor_2</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>
        <use_parent_model_frame>1</use_parent_model_frame>
      </axis>
    </joint>

    <link name='rotor_0'>
      <pose>-0.40 0.0 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://xiake1k/meshes/iris_prop_ccw.dae</uri>
          </mesh>
        </geometry>
        <material>
          <script>
            <name>Gazebo/Orange</name>
            <uri>__default__</uri>
          </script>
        </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>
        <use_parent_model_frame>1</use_parent_model_frame>
      </axis>
    </joint>

    <link name='motor_1'>
      <pose>0.35 -0.35 0.02 0 0 0</pose>
      <inertial>
        <pose>0 0 0 0 0 0</pose>
        <mass>0.05</mass>
        <inertia>
          <ixx>0.0166704</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.0166704</iyy>
          <iyz>0</iyz>
          <izz>0.0167604</izz>
        </inertia>
      </inertial>
      <collision name='motor_1_collision'>
        <pose>0 0 0 0 0 0</pose>
        <geometry>
          <cylinder>
            <length>0.035</length>
            <radius>0.02</radius>
          </cylinder>
        </geometry>
        <surface>
          <contact>
            <ode/>
          </contact>
          <friction>
            <ode/>
          </friction>
        </surface>
      </collision>
      <visual name='motor_1_visual'>
        <pose>0 0 0 0 0 0</pose>
        <geometry>
          <cylinder>
            <length>0.035</length>
            <radius>0.02</radius>
          </cylinder>
        </geometry>
        <material>
          <script>
            <name>Gazebo/Red</name>
            <uri>__default__</uri>
          </script>
        </material>
      </visual>
      <gravity>1</gravity>
      <velocity_decay/>
      <self_collide>0</self_collide>
    </link>
    <joint name='motor_1_joint' type='revolute'>
      <child>motor_1</child>
      <parent>base_link</parent>
      <axis>
        <xyz>0 -1 0</xyz>
        <limit>
        <!-- 1.570795 : 180 deg-->
          <lower>-1.570795</lower>
          <upper>+1.570795</upper>
        </limit>
        <dynamics>
          <friction>1.0</friction>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
        <use_parent_model_frame>1</use_parent_model_frame>
      </axis>
    </joint>
    <link name='rotor_1'>
      <pose>0.35 -0.35 0.10 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://xiake1k/meshes/iris_prop_ccw.dae</uri>
          </mesh>
        </geometry>
        <material>
          <script>
            <name>Gazebo/Orange</name>
            <uri>__default__</uri>
          </script>
        </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>motor_1</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>
        <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.105 0.004 -0.034 1.5707963268 0 3.1415926536</pose>
        <geometry>
          <mesh>
            <scale>0.001 0.001 0.001</scale>
            <uri>model://xiake1k/meshes/x8_elevon_left.dae</uri>
          </mesh>
        </geometry>
        <material>
          <script>
            <name>Gazebo/Blue</name>
            <uri>__default__</uri>
          </script>
        </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://xiake1k/meshes/x8_elevon_right.dae</uri>
          </mesh>
        </geometry>
        <material>
          <script>
            <name>Gazebo/Blue</name>
            <uri>__default__</uri>
          </script>
        </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>
    </link>
    <joint name='left_elevon_joint'         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>
          <!-- -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='right_elevon_joint'        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>
          <!-- -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>1 0 0</xyz>
        <limit>
          <!-- -30/+30 deg. -->
          <lower>-0.01</lower>
          <upper>0.01</upper>
        </limit>
        <dynamics>
          <damping>1.000</damping>
        </dynamics>
      </axis>
      <physics>
        <ode>
          <implicit_spring_damper>1</implicit_spring_damper>
        </ode>
      </physics>
    </joint>

    <plugin name="left_wing"                filename="libLiftDragPlugin.so">
      <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.5</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_elevon_joint
      </control_joint_name>
      <control_joint_rad_to_cl>-2.0</control_joint_rad_to_cl>
      <robotNamespace></robotNamespace>
      <windSubTopic>world_wind</windSubTopic>
    </plugin>
    <plugin name="right_wing"               filename="libLiftDragPlugin.so">
      <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.5</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_elevon_joint
      </control_joint_name>
      <control_joint_rad_to_cl>-2.0</control_joint_rad_to_cl>
      <robotNamespace></robotNamespace>
      <windSubTopic>world_wind</windSubTopic>
    </plugin>
    <plugin name="rudder" filename="libLiftDragPlugin.so">
      <a0>0.0</a0>
      <cla>4.752798721</cla>
      <cda>0.6417112299</cda>
      <cma>0.0</cma>
      <alpha_stall>0.3391428111</alpha_stall>
      <cla_stall>-3.85</cla_stall>
      <cda_stall>-0.9233984055</cda_stall>
      <cma_stall>0</cma_stall>
      <cp>-0.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>
      <robotNamespace></robotNamespace>
      <windSubTopic>world_wind</windSubTopic>
    </plugin>

    <plugin name='back_motor_model'         filename='libgazebo_motor_model.so'>
      <robotNamespace></robotNamespace>
      <jointName>rotor_0_joint</jointName>
      <linkName>rotor_0</linkName>
      <turningDirection>ccw</turningDirection>
      <timeConstantUp>0.0125</timeConstantUp>
      <timeConstantDown>0.025</timeConstantDown>
      <maxRotVelocity>2300</maxRotVelocity>
      <motorConstant>2e-05</motorConstant>
      <momentConstant>0.06</momentConstant>
      <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
      <motorNumber>0</motorNumber>
      <rotorDragCoefficient>0.0000806428</rotorDragCoefficient>
      <rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
      <motorSpeedPubTopic>/motor_speed/0</motorSpeedPubTopic>
      <rotorVelocitySlowdownSim>20</rotorVelocitySlowdownSim>
    </plugin>
    <plugin name='front_right_motor_model'  filename='libgazebo_motor_model.so'>
      <robotNamespace></robotNamespace>
      <jointName>rotor_1_joint</jointName>
      <linkName>rotor_1</linkName>
      <turningDirection>ccw</turningDirection>
      <timeConstantUp>0.0125</timeConstantUp>
      <timeConstantDown>0.025</timeConstantDown>
      <maxRotVelocity>1800</maxRotVelocity>
      <motorConstant>2e-05</motorConstant>
      <momentConstant>0.06</momentConstant>
      <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
      <motorNumber>1</motorNumber>
      <rotorDragCoefficient>0.0000806428</rotorDragCoefficient>
      <rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
      <motorSpeedPubTopic>/motor_speed/1</motorSpeedPubTopic>
      <rotorVelocitySlowdownSim>20</rotorVelocitySlowdownSim>
    </plugin>
    <plugin name='front_left_motor_model'   filename='libgazebo_motor_model.so'>
      <robotNamespace></robotNamespace>
      <jointName>rotor_2_joint</jointName>
      <linkName>rotor_2</linkName>
      <turningDirection>cw</turningDirection>
      <timeConstantUp>0.0125</timeConstantUp>
      <timeConstantDown>0.025</timeConstantDown>
      <maxRotVelocity>1800</maxRotVelocity>
      <motorConstant>2e-05</motorConstant>
      <momentConstant>0.06</momentConstant>
      <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
      <motorNumber>7</motorNumber>
      <rotorDragCoefficient>0.0000806428</rotorDragCoefficient>
      <rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
      <motorSpeedPubTopic>/motor_speed/7</motorSpeedPubTopic>
      <rotorVelocitySlowdownSim>20</rotorVelocitySlowdownSim>
    </plugin>

    <plugin name='gazebo_imu_plugin'        filename='libgazebo_imu_plugin.so'>
      <robotNamespace></robotNamespace>
      <linkName>xiake1k/imu_link</linkName>
      <imuTopic>/imu</imuTopic>
      <gyroscopeNoiseDensity>0.0003394</gyroscopeNoiseDensity>
      <gyroscopeRandomWalk>3.8785e-05</gyroscopeRandomWalk>
      <gyroscopeBiasCorrelationTime>1000.0</gyroscopeBiasCorrelationTime>
      <gyroscopeTurnOnBiasSigma>0.0087</gyroscopeTurnOnBiasSigma>
      <accelerometerNoiseDensity>0.004</accelerometerNoiseDensity>
      <accelerometerRandomWalk>0.006</accelerometerRandomWalk>
      <accelerometerBiasCorrelationTime>300.0</accelerometerBiasCorrelationTime>
      <accelerometerTurnOnBiasSigma>0.196</accelerometerTurnOnBiasSigma>
    </plugin>
    <plugin name='groundtruth_plugin'       filename='libgazebo_groundtruth_plugin.so'>
      <robotNamespace/>
    </plugin>
    <plugin name='magnetometer_plugin'      filename='libgazebo_magnetometer_plugin.so'>
      <robotNamespace/>
      <pubRate>100</pubRate>
      <noiseDensity>0.0004</noiseDensity>
      <randomWalk>6.4e-06</randomWalk>
      <biasCorrelationTime>600</biasCorrelationTime>
      <magTopic>/mag</magTopic>
    </plugin>
    <plugin name='barometer_plugin'         filename='libgazebo_barometer_plugin.so'>
      <robotNamespace/>
      <pubRate>50</pubRate>
      <baroTopic>/baro</baroTopic>
    </plugin>
    <plugin name='mavlink_interface'        filename='libgazebo_mavlink_interface.so'>
      <robotNamespace></robotNamespace>
      <imuSubTopic>/imu</imuSubTopic>
      <magSubTopic>/mag</magSubTopic>
      <baroSubTopic>/baro</baroSubTopic>
      <mavlink_addr>INADDR_ANY</mavlink_addr>
      <mavlink_tcp_port>{{ mavlink_tcp_port }}</mavlink_tcp_port>
      <mavlink_udp_port>{{ mavlink_udp_port }}</mavlink_udp_port>
      <serialEnabled>false</serialEnabled>
      <serialDevice>/dev/ttyACM0</serialDevice>
      <baudRate>921600</baudRate>
      <qgc_addr>INADDR_ANY</qgc_addr>
      <qgc_udp_port>14550</qgc_udp_port>
      <sdk_addr>INADDR_ANY</sdk_addr>
      <sdk_udp_port>14540</sdk_udp_port>
      <hil_mode>false</hil_mode>
      <hil_state_level>false</hil_state_level>
      <enable_lockstep>true</enable_lockstep>
      <use_tcp>true</use_tcp>
      <motorSpeedCommandPubTopic>/gazebo/command/motor_speed</motorSpeedCommandPubTopic>
      <control_channels>
        <channel name="rotor_0">
          <input_index>0</input_index>
          <input_offset>0</input_offset>
          <input_scaling>2300</input_scaling>
          <zero_position_disarmed>0</zero_position_disarmed>
          <zero_position_armed>0</zero_position_armed>
          <joint_control_type>velocity</joint_control_type>
          <joint_name>rotor_0_joint</joint_name>
        </channel>
        <channel name="rotor_1">
          <input_index>1</input_index>
          <input_offset>0</input_offset>
          <input_scaling>1800</input_scaling>
          <zero_position_disarmed>0</zero_position_disarmed>
          <zero_position_armed>0</zero_position_armed>
          <joint_control_type>velocity</joint_control_type>
          <joint_name>rotor_1_joint</joint_name>
        </channel>
        <channel name="rotor_2">
          <input_index>7</input_index>
          <input_offset>0</input_offset>
          <input_scaling>1800</input_scaling>
          <zero_position_disarmed>0</zero_position_disarmed>
          <zero_position_armed>0</zero_position_armed>
          <joint_control_type>velocity</joint_control_type>
          <joint_name>rotor_2_joint</joint_name>
        </channel>
        <channel name="motor_1_tilt">
          <input_index>3</input_index>
          <!-- 0.174533 / 10 deg -->
          <!-- 0.261799 / 15 deg -->
          <!-- 0.523598 / 30 deg -->
          <!-- 0.785398 / 45 deg -->
          <!-- 0.872222 / 50 deg -->
          <!-- 1.046666 / 60 deg -->
          <!-- 1.570795 / 90 deg -->
          <!-- 1.832594 / 105 deg -->
          <!-- input = (u + offset) * scale + pos_arm -->
          <input_offset>-1</input_offset>
          <input_scaling>1.570795</input_scaling>
          <zero_position_armed>0</zero_position_armed>
          <zero_position_disarmed>0</zero_position_disarmed>
          <joint_control_type>position</joint_control_type>
          <joint_name>motor_1_joint</joint_name>
           <joint_control_pid>
            <p>100</p>
            <i>0</i>
            <d>0</d>
            <iMax>0.0</iMax>
            <iMin>0.0</iMin>
            <cmdMax>2</cmdMax>
            <cmdMin>-2</cmdMin>
            <errMax>0.2</errMax>
          </joint_control_pid>
        </channel>
        <channel name="motor_2_tilt">
          <input_index>6</input_index>
          <!-- 0.785398 -->
          <input_offset>1</input_offset>
          <input_scaling>1.570795</input_scaling>
          <zero_position_armed>0</zero_position_armed>
          <zero_position_disarmed>0</zero_position_disarmed>
          <joint_control_type>position</joint_control_type>
          <joint_name>motor_2_joint</joint_name>
           <joint_control_pid>
            <p>100</p>
            <i>0</i>
            <d>0</d>
            <iMax>0.0</iMax>
            <iMin>0.0</iMin>
            <cmdMax>2</cmdMax>
            <cmdMin>-2</cmdMin>
            <errMax>0.2</errMax>
          </joint_control_pid>
        </channel>
        <channel name="right_elevon">
          <input_index>2</input_index>
          <input_offset>0</input_offset>
          <input_scaling>1</input_scaling>
          <zero_position_disarmed>0</zero_position_disarmed>
          <zero_position_armed>0</zero_position_armed>
          <joint_control_type>position_kinematic</joint_control_type>
          <joint_name>right_elevon_joint</joint_name>
        </channel>
        <channel name="left_elevon">
          <input_index>5</input_index>
          <input_offset>0</input_offset>
          <input_scaling>1</input_scaling>
          <zero_position_disarmed>0</zero_position_disarmed>
          <zero_position_armed>0</zero_position_armed>
          <joint_control_type>position_kinematic</joint_control_type>
          <joint_name>left_elevon_joint</joint_name>
        </channel>
      </control_channels>
    </plugin>
    <static>0</static>
  </model>
</sdf>

 

Make a parameter configure file

 

xiake1k.params
0.04MB

 

멀티로터 비행 되는 영상이다.

XIAKE800을 만든 모델은 아니고, tiltrotor라고 있는 모델을 tri-copter로 바꿨다.

 

고정익 비행은 어떻게 되는거야..

나중에 해야지..

 

 


Reference

[1] https://docs.px4.io/main/en/sim_gazebo_gz/gazebo_vehicles.html#standard-vtol

[2] "Adding New Worlds and Models," https://docs.px4.io/main/en/sim_gazebo_gz/#adding-new-worlds-and-models

[3] "How to add a Configuration to Firmware," https://docs.px4.io/main/en/dev_airframes/adding_a_new_frame.html#how-to-add-a-configuration-to-firmware

 

** EOF **

728x90

+ Recent posts