mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-15 04:07:35 +08:00
82dce9353c
Signed-off-by: Beniamino Pozzan <beniamino.pozzan@phd.unipd.it>
825 lines
24 KiB
XML
825 lines
24 KiB
XML
<?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>cw</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>
|