oscillation_ctrl/models/spiri/model.sdf

634 lines
21 KiB
XML

<?xml version="1.0" ?>
<sdf version='1.6'>
<model name='spiri'>
<link name='base'>
<pose frame=''>0 0 0 0 -0 -0</pose>
<inertial>
<pose frame=''>0 0.00268 -0.000742 0 -0 0</pose>
<mass>1.437</mass>
<inertia>
<ixx>0.1152</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.1152</iyy>
<iyz>0</iyz>
<izz>0.218</izz>
<!-- <ixx>0.003252814</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.003252814</iyy>
<iyz>0</iyz>
<izz>0.032498525</izz> -->
</inertia><!-- x= 0.032498525 y=0.003252814 z=0.031612672 -->
</inertial>
<collision name='base_collision'>
<pose frame=''>0 0 -0.02103 0 -0 0</pose>
<geometry>
<box>
<size>0.21355 0.132 0.04206</size>
</box>
</geometry>
</collision>
<visual name='base_visual'>
<pose frame=''>0 0 0 0 -0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://spiri/meshes/spiri_base_bottom.dae</uri>
</mesh>
</geometry>
</visual>
<collision name='base_top_collision_1'>
<pose frame=''>0 0 0.03025 0 -0 0</pose>
<geometry>
<box>
<size>0.21355 0.132 0.0605</size>
</box>
</geometry>
</collision>
<visual name='base_top_visual_1'>
<pose frame=''>0 0 0 0 -0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://spiri/meshes/spiri_base_top.dae</uri>
</mesh>
</geometry>
</visual>
<collision name='base_fixed_joint_lump__shank_LF_collision_2'>
<pose frame=''>0.112711 0.112711 -0.001 0 -0 0.785398</pose>
<geometry>
<box>
<size>0.2 0.014 0.11</size>
</box>
</geometry>
</collision>
<visual name='base_fixed_joint_lump__shank_LF_visual_2'>
<pose frame=''>0.042 0.042 -0.001 0 -0 0.785398</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://spiri/meshes/spiri_shank.dae</uri>
</mesh>
</geometry>
</visual>
<collision name='base_fixed_joint_lump__shank_LH_collision_3'>
<pose frame=''>-0.112711 0.112711 -0.001 0 -0 2.35619</pose>
<geometry>
<box>
<size>0.2 0.014 0.11</size>
</box>
</geometry>
</collision>
<visual name='base_fixed_joint_lump__shank_LH_visual_3'>
<pose frame=''>-0.042 0.042 -0.001 0 -0 2.35619</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://spiri/meshes/spiri_shank.dae</uri>
</mesh>
</geometry>
</visual>
<collision name='base_fixed_joint_lump__shank_RF_collision_4'>
<pose frame=''>0.112711 -0.112711 -0.001 0 0 -0.785398</pose>
<geometry>
<box>
<size>0.2 0.014 0.11</size>
</box>
</geometry>
</collision>
<visual name='base_fixed_joint_lump__shank_RF_visual_4'>
<pose frame=''>0.042 -0.042 -0.001 0 0 -0.785398</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://spiri/meshes/spiri_shank.dae</uri>
</mesh>
</geometry>
</visual>
<collision name='base_fixed_joint_lump__shank_RH_collision_5'>
<pose frame=''>-0.112711 -0.112711 -0.001 0 0 -2.35619</pose>
<geometry>
<box>
<size>0.2 0.014 0.11</size>
</box>
</geometry>
</collision>
<visual name='base_fixed_joint_lump__shank_RH_visual_5'>
<pose frame=''>-0.042 -0.042 -0.001 0 0 -2.35619</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://spiri/meshes/spiri_shank.dae</uri>
</mesh>
</geometry>
</visual>
</link>
<link name='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='imu_joint' type='revolute'>
<child>imu_link</child>
<parent>base</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>
<link name='propeller_LF'>
<pose frame=''>0.165037 0.165037 0.042 0 -0 0.785398</pose>
<inertial>
<pose frame=''>0 0 0 0 -0 0</pose>
<mass>0.01</mass>
<inertia>
<ixx>0.0005299083</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.0005235333</iyy>
<iyz>0</iyz>
<izz>0.000011775</izz>
</inertia>
</inertial>
<collision name='propeller_LF_collision'>
<pose frame=''>0 0 0.009 0 -0 0</pose>
<geometry>
<box>
<size>0.033 0.25 0.018</size>
</box>
</geometry>
</collision>
<visual name='propeller_LF_visual'>
<pose frame=''>0 0 0 0 -0 0.785398</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://spiri/meshes/spiri_propeller.dae</uri>
</mesh>
</geometry>
</visual>
</link>
<joint name='shank_LF_to_propeller_LF' type='revolute'>
<child>propeller_LF</child>
<parent>base</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='propeller_LH'>
<pose frame=''>-0.165037 0.165037 0.042 0 -0 2.35619</pose>
<inertial>
<pose frame=''>0 0 0 0 -0 0</pose>
<mass>0.01</mass>
<inertia>
<ixx>0.0005299083</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.0005235333</iyy>
<iyz>0</iyz>
<izz>0.000011775</izz>
</inertia>
</inertial>
<collision name='propeller_LH_collision'>
<pose frame=''>0 0 0.009 0 -0 0</pose>
<geometry>
<box>
<size>0.033 0.25 0.018</size>
</box>
</geometry>
</collision>
<visual name='propeller_LH_visual'>
<pose frame=''>0 0 0 0 -0 0.785398</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://spiri/meshes/spiri_propeller.dae</uri>
</mesh>
</geometry>
</visual>
</link>
<joint name='shank_LH_to_propeller_LH' type='revolute'>
<child>propeller_LH</child>
<parent>base</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='propeller_RF'>
<pose frame=''>0.165037 -0.165037 0.042 0 0 -0.785398</pose>
<inertial>
<pose frame=''>0 0 0 0 -0 0</pose>
<mass>0.01</mass>
<inertia>
<ixx>0.0005299083</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.0005235333</iyy>
<iyz>0</iyz>
<izz>0.000011775</izz>
</inertia>
</inertial>
<collision name='propeller_RF_collision'>
<pose frame=''>0 0 0.009 0 -0 0</pose>
<geometry>
<box>
<size>0.033 0.25 0.018</size>
</box>
</geometry>
</collision>
<visual name='propeller_RF_visual'>
<pose frame=''>0 0 0 0 -0 0.785398</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://spiri/meshes/spiri_propeller.dae</uri>
</mesh>
</geometry>
</visual>
</link>
<joint name='shank_RF_to_propeller_RF' type='revolute'>
<child>propeller_RF</child>
<parent>base</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='propeller_RH'>
<pose frame=''>-0.165037 -0.165037 0.042 0 0 -2.35619</pose>
<inertial>
<pose frame=''>0 0 0 0 -0 0</pose>
<mass>0.01</mass>
<inertia>
<ixx>0.0005299083</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.0005235333</iyy>
<iyz>0</iyz>
<izz>0.000011775</izz>
</inertia>
</inertial>
<collision name='propeller_RH_collision'>
<pose frame=''>0 0 0.009 0 -0 0</pose>
<geometry>
<box>
<size>0.033 0.25 0.018</size>
</box>
</geometry>
</collision>
<visual name='propeller_RH_visual'>
<pose frame=''>0 0 0 0 -0 0.785398</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://spiri/meshes/spiri_propeller.dae</uri>
</mesh>
</geometry>
</visual>
</link>
<joint name='shank_RH_to_propeller_RH' type='revolute'>
<child>propeller_RH</child>
<parent>base</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>
<model name='gps0'>
<link name='link'>
<pose>0 0 0 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.01</mass>
<inertia>
<ixx>2.1733e-06</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>2.1733e-06</iyy>
<iyz>0</iyz>
<izz>1.8e-07</izz>
</inertia>
</inertial>
<visual name='visual'>
<geometry>
<cylinder>
<radius>0.01</radius>
<length>0.002</length>
</cylinder>
</geometry>
<material>
<script>
<name>Gazebo/Black</name>
<uri>__default__</uri>
</script>
</material>
</visual>
<sensor name='gps' type='gps'>
<pose>0 0 0 0 0 0</pose>
<plugin name='gps_plugin' filename='libgazebo_gps_plugin.so'>
<robotNamespace/>
<gpsNoise>1</gpsNoise>
<gpsXYRandomWalk>2.0</gpsXYRandomWalk>
<gpsZRandomWalk>4.0</gpsZRandomWalk>
<gpsXYNoiseDensity>0.0002</gpsXYNoiseDensity>
<gpsZNoiseDensity>0.0004</gpsZNoiseDensity>
<gpsVXYNoiseDensity>0.2</gpsVXYNoiseDensity>
<gpsVZNoiseDensity>0.4</gpsVZNoiseDensity>
</plugin>
</sensor>
</link>
</model>
<joint name='gps0_joint' type='fixed'>
<parent>base</parent>
<child>gps0::link</child>
</joint>
<plugin name='rosbag' filename='libgazebo_multirotor_base_plugin.so'>
<robotNamespace/>
<linkName>base</linkName>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
</plugin>
<plugin name='front_right_motor_model' filename='libgazebo_motor_model.so'>
<robotNamespace/>
<jointName>shank_RF_to_propeller_RF</jointName>
<linkName>propeller_RF</linkName>
<turningDirection>ccw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1100</maxRotVelocity>
<motorConstant>5.84e-06</motorConstant>
<momentConstant>0.06</momentConstant>
<commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
<motorNumber>0</motorNumber>
<rotorDragCoefficient>0.000175</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<motorSpeedPubTopic>/motor_speed/0</motorSpeedPubTopic>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
</plugin>
<plugin name='back_left_motor_model' filename='libgazebo_motor_model.so'>
<robotNamespace/>
<jointName>shank_LH_to_propeller_LH</jointName>
<linkName>propeller_LH</linkName>
<turningDirection>ccw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1100</maxRotVelocity>
<motorConstant>5.84e-06</motorConstant>
<momentConstant>0.06</momentConstant>
<commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
<motorNumber>1</motorNumber>
<rotorDragCoefficient>0.000175</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<motorSpeedPubTopic>/motor_speed/1</motorSpeedPubTopic>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
</plugin>
<plugin name='front_left_motor_model' filename='libgazebo_motor_model.so'>
<robotNamespace/>
<jointName>shank_LF_to_propeller_LF</jointName>
<linkName>propeller_LF</linkName>
<turningDirection>cw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1100</maxRotVelocity>
<motorConstant>5.84e-06</motorConstant>
<momentConstant>0.06</momentConstant>
<commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
<motorNumber>2</motorNumber>
<rotorDragCoefficient>0.000175</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<motorSpeedPubTopic>/motor_speed/2</motorSpeedPubTopic>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
</plugin>
<plugin name='back_right_motor_model' filename='libgazebo_motor_model.so'>
<robotNamespace/>
<jointName>shank_RH_to_propeller_RH</jointName>
<linkName>propeller_RH</linkName>
<turningDirection>cw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1100</maxRotVelocity>
<motorConstant>5.84e-06</motorConstant>
<momentConstant>0.06</momentConstant>
<commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
<motorNumber>3</motorNumber>
<rotorDragCoefficient>0.000175</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<motorSpeedPubTopic>/motor_speed/3</motorSpeedPubTopic>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
</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>
<baroDriftPaPerSec>0</baroDriftPaPerSec>
</plugin>
<plugin name='mavlink_interface' filename='libgazebo_mavlink_interface.so'>
<robotNamespace/>
<imuSubTopic>/imu</imuSubTopic>
<magSubTopic>/mag</magSubTopic>
<baroSubTopic>/baro</baroSubTopic>
<mavlink_addr>INADDR_ANY</mavlink_addr>
<mavlink_tcp_port>4560</mavlink_tcp_port>
<mavlink_udp_port>14560</mavlink_udp_port>
<serialEnabled>0</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>0</hil_mode>
<hil_state_level>0</hil_state_level>
<send_vision_estimation>0</send_vision_estimation>
<send_odometry>1</send_odometry>
<enable_lockstep>1</enable_lockstep>
<use_tcp>1</use_tcp> <!--This needs to be set to 1-->
<motorSpeedCommandPubTopic>/gazebo/command/motor_speed</motorSpeedCommandPubTopic>
<control_channels>
<channel name='rotor1'>
<input_index>0</input_index>
<input_offset>0</input_offset>
<input_scaling>1000</input_scaling>
<zero_position_disarmed>0</zero_position_disarmed>
<zero_position_armed>100</zero_position_armed>
<joint_control_type>velocity</joint_control_type>
</channel>
<channel name='rotor2'>
<input_index>1</input_index>
<input_offset>0</input_offset>
<input_scaling>1000</input_scaling>
<zero_position_disarmed>0</zero_position_disarmed>
<zero_position_armed>100</zero_position_armed>
<joint_control_type>velocity</joint_control_type>
</channel>
<channel name='rotor3'>
<input_index>2</input_index>
<input_offset>0</input_offset>
<input_scaling>1000</input_scaling>
<zero_position_disarmed>0</zero_position_disarmed>
<zero_position_armed>100</zero_position_armed>
<joint_control_type>velocity</joint_control_type>
</channel>
<channel name='rotor4'>
<input_index>3</input_index>
<input_offset>0</input_offset>
<input_scaling>1000</input_scaling>
<zero_position_disarmed>0</zero_position_disarmed>
<zero_position_armed>100</zero_position_armed>
<joint_control_type>velocity</joint_control_type>
</channel>
<channel name='rotor5'>
<input_index>4</input_index>
<input_offset>1</input_offset>
<input_scaling>324.6</input_scaling>
<zero_position_disarmed>0</zero_position_disarmed>
<zero_position_armed>0</zero_position_armed>
<joint_control_type>velocity</joint_control_type>
<joint_control_pid>
<p>0.1</p>
<i>0</i>
<d>0</d>
<iMax>0.0</iMax>
<iMin>0.0</iMin>
<cmdMax>2</cmdMax>
<cmdMin>-2</cmdMin>
</joint_control_pid>
<joint_name>zephyr_delta_wing::propeller_joint</joint_name>
</channel>
<channel name='rotor6'>
<input_index>5</input_index>
<input_offset>0</input_offset>
<input_scaling>0.524</input_scaling>
<zero_position_disarmed>0</zero_position_disarmed>
<zero_position_armed>0</zero_position_armed>
<joint_control_type>position</joint_control_type>
<joint_name>zephyr_delta_wing::flap_left_joint</joint_name>
<joint_control_pid>
<p>10.0</p>
<i>0</i>
<d>0</d>
<iMax>0</iMax>
<iMin>0</iMin>
<cmdMax>20</cmdMax>
<cmdMin>-20</cmdMin>
</joint_control_pid>
</channel>
<channel name='rotor7'>
<input_index>6</input_index>
<input_offset>0</input_offset>
<input_scaling>0.524</input_scaling>
<zero_position_disarmed>0</zero_position_disarmed>
<zero_position_armed>0</zero_position_armed>
<joint_control_type>position</joint_control_type>
<joint_name>zephyr_delta_wing::flap_right_joint</joint_name>
<joint_control_pid>
<p>10.0</p>
<i>0</i>
<d>0</d>
<iMax>0</iMax>
<iMin>0</iMin>
<cmdMax>20</cmdMax>
<cmdMin>-20</cmdMin>
</joint_control_pid>
</channel>
<channel name='rotor8'>
<input_index>7</input_index>
<input_offset>0</input_offset>
<input_scaling>0.524</input_scaling>
<zero_position_disarmed>0</zero_position_disarmed>
<zero_position_armed>0</zero_position_armed>
<joint_control_type>position</joint_control_type>
</channel>
</control_channels>
</plugin>
<plugin name='rotors_gazebo_imu_plugin' filename='libgazebo_imu_plugin.so'>
<robotNamespace/>
<linkName>imu_link</linkName>
<imuTopic>/imu</imuTopic>
<gyroscopeNoiseDensity>0.00018665</gyroscopeNoiseDensity>
<gyroscopeRandomWalk>3.8785e-05</gyroscopeRandomWalk>
<gyroscopeBiasCorrelationTime>1000.0</gyroscopeBiasCorrelationTime>
<gyroscopeTurnOnBiasSigma>0.0087</gyroscopeTurnOnBiasSigma>
<accelerometerNoiseDensity>0.00186</accelerometerNoiseDensity>
<accelerometerRandomWalk>0.006</accelerometerRandomWalk>
<accelerometerBiasCorrelationTime>300.0</accelerometerBiasCorrelationTime>
<accelerometerTurnOnBiasSigma>0.196</accelerometerTurnOnBiasSigma>
</plugin>
</model>
</sdf>