Commit 055c18e6 authored by srees's avatar srees Committed by Stephen Rees
Browse files

Add f450 specific files

parent 02e77e73
<sdf version='1.5'>
<model name='f450'>
<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.0347563</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.0458929</iyy>
<iyz>0</iyz>
<izz>0.0977</izz>
</inertia>
</inertial>
<collision name='base_link_collision'>
<pose>0 0 0 0 -0 0</pose>
<geometry>
<box>
<size>0.318 0.318 0.12</size>
</box>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='base_link_visual'>
<pose>0 0 0 0 -0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://rotors_description/meshes/f450.dae</uri>
</mesh>
</geometry>
<material>
<script>
<name>Gazebo/LightGrey</name>
<uri>__default__</uri>
</script>
</material>
</visual>
<gravity>1</gravity>
<velocity_decay/>
<self_collide>0</self_collide>
</link>
<link name='f450/robot_camera'>
<pose>0.12 0 0.06 0 0 0</pose>
<inertial>
<pose>0 0 0 0 -0 0</pose>
<mass>0.015</mass>
<inertia>
<ixx>1e-06</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1e-06</iyy>
<iyz>0</iyz>
<izz>1e-06</izz>
</inertia>
</inertial>
<visual name="visual">
<geometry>
<box>
<size>0.001 0.001 0.001</size>
</box>
</geometry>
</visual>
<sensor name='camera' type='camera'>
<always_on>true</always_on>
<update_rate>30</update_rate>
<camera>
<horizontal_fov>1</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
</camera>
<plugin name="camera_plugin" filename="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<imageTopicName>image_raw_front</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<updateRate>10.0</updateRate>
<cameraName>uav_camera</cameraName>
<frameName>f450/robot_camera</frameName>
<CxPrime>320.5</CxPrime>
<Cx>320.5</Cx>
<Cy>240.5</Cy>
<hackBaseline>0</hackBaseline>
<focalLength>10</focalLength>
<distortionK1>0.0</distortionK1>
<distortionK2>0.0</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionT1>0.0</distortionT1>
<distortionT2>0.0</distortionT2>
</plugin>
</sensor>
</link>
<link name='f450/robot_camera_down'>
<pose>-0.12 0 0.01 0 1.57079 0</pose>
<inertial>
<pose>0 0 0 0 -0 0</pose>
<mass>0.015</mass>
<inertia>
<ixx>1e-06</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1e-06</iyy>
<iyz>0</iyz>
<izz>1e-06</izz>
</inertia>
</inertial>
<visual name="visual">
<geometry>
<box>
<size>0.001 0.001 0.001</size>
</box>
</geometry>
</visual>
<sensor name='camera' type='camera'>
<always_on>true</always_on>
<update_rate>30</update_rate>
<camera>
<horizontal_fov>1</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
</camera>
<plugin name="camera_plugin" filename="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<imageTopicName>image_raw_down</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<updateRate>10.0</updateRate>
<cameraName>uav_camera</cameraName>
<frameName>f450/robot_camera_down</frameName>
<CxPrime>320.5</CxPrime>
<Cx>320.5</Cx>
<Cy>240.5</Cy>
<hackBaseline>0</hackBaseline>
<focalLength>1</focalLength>
<distortionK1>0.0</distortionK1>
<distortionK2>0.0</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionT1>0.0</distortionT1>
<distortionT2>0.0</distortionT2>
</plugin>
</sensor>
</link>
<joint name='f450/front_cam_joint' type='revolute'>
<child>f450/robot_camera</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>
<joint name='f450/down_cam_joint' type='revolute'>
<child>f450/robot_camera_down</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>
<link name='iris/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='iris/imu_joint' type='revolute'>
<child>iris/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>
<link name='rotor_0'>
<pose>0.159 -0.159 0.11 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://rotors_description/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_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='rotor_1'>
<pose>-0.159 0.159 0.11 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://rotors_description/meshes/iris_prop_ccw.dae</uri>
</mesh>
</geometry>
<material>
<script>
<name>Gazebo/DarkGrey</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>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='rotor_2'>
<pose>0.159 0.159 0.11 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://rotors_description/meshes/iris_prop_cw.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>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='rotor_3'>
<pose>-0.159 -0.159 0.11 0 -0 0</pose>
<inertial>
<pose>0 0 0 0 -0 0</pose>
<mass>0.005</mass>
<inertia>
<ixx>9.75e-07</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.000166704</iyy>
<iyz>0</iyz>
<izz>0.000167604</izz>
</inertia>
</inertial>
<collision name='rotor_3_collision'>
<pose>0 0 0 0 -0 0</pose>
<geometry>
<cylinder>
<length>0.005</length>
<radius>0.1</radius>
</cylinder>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='rotor_3_visual'>
<pose>0 0 0 0 -0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://rotors_description/meshes/iris_prop_cw.dae</uri>
</mesh>
</geometry>
<material>
<script>
<name>Gazebo/DarkGrey</name>
<uri>__default__</uri>
</script>
</material>
</visual>
<gravity>1</gravity>
<velocity_decay/>
<self_collide>0</self_collide>
</link>
<joint name='rotor_3_joint' type='revolute'>
<child>rotor_3</child>
<parent>base_link</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
<plugin name='rosbag' filename='librotors_gazebo_multirotor_base_plugin.so'>
<robotNamespace>iris</robotNamespace>
<linkName>base_link</linkName>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
</plugin>
<plugin name='front_right_motor_model' filename='librotors_gazebo_motor_model.so'>
<robotNamespace>iris</robotNamespace>
<jointName>rotor_0_joint</jointName>
<linkName>rotor_0</linkName>
<turningDirection>ccw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>2000</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.16</momentConstant>
<commandSubTopic>gazebo/command/motor_speed</commandSubTopic>
<motorNumber>0</motorNumber>
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<motorSpeedPubTopic>motor_speed/0</motorSpeedPubTopic>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
</plugin>
<plugin name='back_left_motor_model' filename='librotors_gazebo_motor_model.so'>
<robotNamespace>iris</robotNamespace>
<jointName>rotor_1_joint</jointName>
<linkName>rotor_1</linkName>
<turningDirection>ccw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>2000</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.16</momentConstant>
<commandSubTopic>gazebo/command/motor_speed</commandSubTopic>
<motorNumber>1</motorNumber>
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<motorSpeedPubTopic>motor_speed/1</motorSpeedPubTopic>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
</plugin>
<plugin name='front_left_motor_model' filename='librotors_gazebo_motor_model.so'>
<robotNamespace>iris</robotNamespace>
<jointName>rotor_2_joint</jointName>
<linkName>rotor_2</linkName>
<turningDirection>cw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>2000</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.16</momentConstant>
<commandSubTopic>gazebo/command/motor_speed</commandSubTopic>
<motorNumber>2</motorNumber>
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<motorSpeedPubTopic>motor_speed/2</motorSpeedPubTopic>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
</plugin>
<plugin name='back_right_motor_model' filename='librotors_gazebo_motor_model.so'>
<robotNamespace>iris</robotNamespace>
<jointName>rotor_3_joint</jointName>
<linkName>rotor_3</linkName>
<turningDirection>cw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>2000</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.16</momentConstant>
<commandSubTopic>gazebo/command/motor_speed</commandSubTopic>
<motorNumber>3</motorNumber>
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<motorSpeedPubTopic>motor_speed/3</motorSpeedPubTopic>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
</plugin>
<plugin name='mavlink_interface' filename='librotors_gazebo_mavlink_interface.so'>
<robotNamespace>iris</robotNamespace>
<imuSubTopic>imu</imuSubTopic>
<motorSpeedCommandPubTopic>gazebo/command/motor_speed</motorSpeedCommandPubTopic>
</plugin>
<static>0</static>
<plugin name='rotors_gazebo_imu_plugin' filename='librotors_gazebo_imu_plugin.so'>
<robotNamespace>iris</robotNamespace>
<linkName>iris/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>
</model>
</sdf>
<?xml version="1.0"?>
<model>
<name>UPenn F450</name>
<version>1.0</version>
<sdf version='1.4'>f450.sdf</sdf>
<author>
<name>Jnaneshwar Das and Anurag Makineni</name>
<email>jnaneshwar.das@gmail.com</email>
</author>
<description>
This is a model of the DJI f450 Quadrotor with onboard Intel NUC and MatrixVision Bluefox camera, top and down. The original model has been created by Anurag Makineni and Jnaneshwar Das.
</description>
</model>
This diff is collapsed.
<?xml version="1.0" ?>
<sdf version="1.5">
<world name="default">
<!-- A global light source -->
<include>
<uri>model://sun</uri>
</include>
<!-- A ground plane -->
<include>
<uri>model://ground_plane</uri>
</include>
<include>
<uri>model://f450</uri>
</include>
</world>
</sdf>
Markdown is supported
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment