<?xml version="1.0" ?> <sdf version="1.5"> <model name="f550_amazing"> <static>false</static> <pose>0 0 0.35 0 0 0</pose> <!-- ######################################## LOWER_PLATE # ######################################## --> <link name="base_link"> <gravity>true</gravity> <pose>0 0 0.0015 0 0 0</pose> <inertial> <pose frame=''>0.001005 0 -0.0090035 0 -0 0</pose> <mass>0.6</mass> <inertia> <ixx>0.011</ixx> <ixy>0</ixy> <ixz>0</ixz> <iyy>0.015</iyy> <iyz>0</iyz> <izz>0.021</izz> </inertia> </inertial> <visual name="base_link_visual"> <geometry> <mesh> <scale>0.001 0.001 0.001</scale> <uri>model://f550_amazing/meshes/Lower_plate_CG.STL</uri> </mesh> </geometry> <material> <script> <name>Gazebo/DarkGrey</name> <uri>file://media/materials/scripts/gazebo.material</uri> </script> </material> </visual> </link> <!-- ####################################### /LOWER_PLATE # ######################################## --> <!-- <joint name="fixed to ground" type="fixed"> <parent>world</parent> <child>base_link</child> </joint> --> <!-- ######################################## TOP_PLATE ############################################ --> <link name="Top_plate_link"> <gravity>true</gravity> <pose>0 0 0.0375 0 0 2.09439510239</pose> <inertial> <mass>0.1</mass> <inertia> <ixx>0.001</ixx> <ixy>0</ixy> <ixz>0</ixz> <iyy>0.001</iyy> <iyz>0</iyz> <izz>0.001</izz> </inertia> </inertial> <visual name="visual_Top_plate"> <geometry> <mesh> <scale>0.001 0.001 0.001</scale> <uri>model://f550_amazing/meshes/Top_plate_CG.STL</uri> </mesh> </geometry> <material> <script> <name>Gazebo/DarkGrey</name> <uri>file://media/materials/scripts/gazebo.material</uri> </script> </material> </visual> </link> <joint name='Lower_Top_joint' type='fixed'> <child>Top_plate_link</child> <parent>base_link</parent> </joint> <!-- ####################################### /TOP_PLATE ############################################ --> <!-- ########################################## CAMERA ########################################### --> <link name='camera_down_link'> <pose>0 0 0 0 1.57079 3.14159265359</pose> <inertial> <mass>0.001</mass> <inertia> <ixx>0.001</ixx> <ixy>0</ixy> <ixz>0</ixz> <iyy>0.001</iyy> <iyz>0</iyz> <izz>0.001</izz> </inertia> </inertial> <gravity>1</gravity> <self_collide>0</self_collide> <kinematic>0</kinematic> <visual name='visual_camera_down'> <pose>0 0 0 0 -1.57079 0</pose> <geometry> <mesh> <scale>0.001 0.001 0.001</scale> <uri>model://f550_amazing/meshes/oCam-1MGN-U_CG.stl</uri> </mesh> </geometry> <material> <script> <name>Gazebo/Grey</name> <uri>file://media/materials/scripts/gazebo.material</uri> </script> </material> </visual> <sensor name='camera' type='camera'> <always_on>1</always_on> <update_rate>30</update_rate> <camera name='__default__'> <horizontal_fov>1.13446</horizontal_fov> <image> <width>1280</width> <height>720</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>f550_amazing/robot_camera_down</frameName> <CxPrime>640.5</CxPrime> <Cx>640.5</Cx> <Cy>360.5</Cy> <hackBaseline>0</hackBaseline> <focalLength>1004.603218</focalLength> <distortionK1>0.0</distortionK1> <distortionK2>0.0</distortionK2> <distortionK3>0.0</distortionK3> <distortionT1>0.0</distortionT1> <distortionT2>0.0</distortionT2> <robotNamespace>/</robotNamespace> </plugin> </sensor> </link> <joint name='camera_down_joint' type='fixed'> <parent>base_link</parent> <child>camera_down_link</child> </joint> <!-- ########################################## /CAMERA ########################################## --> <!-- ########################################## IMU ############################################## --> <link name='imu_link'> <pose frame=''>0 0 0 0 0 3.1415927</pose> <inertial> <pose frame=''>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="visual_imu"> <pose frame=''>0 0 0 0 0 3.1415927</pose> <geometry> <box> <size>0.01 0.02 0.02</size> </box> </geometry> </visual> </link> <joint name='imu_joint' type='revolute'> <child>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> <!-- ######################################### /IMU ############################################## --> <!-- ############################################# ARM1 ############################################ --> <link name="Arm1_link"> <gravity>true</gravity> <pose>0 0.1874 0.009875004 0 0 1.57079632679</pose> <inertial> <mass>0.1</mass> <inertia> <ixx>0.001</ixx> <ixy>0</ixy> <ixz>0</ixz> <iyy>0.001</iyy> <iyz>0</iyz> <izz>0.001</izz> </inertia> </inertial> <!-- <collision name="collision_Arm1_box"> <pose>-0.02 0 0.009 0 0 0</pose> <geometry> <box> <size>0.175 0.034 0.037</size> </box> </geometry> </collision> <collision name="collision_Arm1_cyl"> <pose>0.09 0 0.02 0 0 0</pose> <geometry> <cylinder> <length>0.097</length> <radius>0.02</radius> </cylinder> </geometry> </collision> --> <visual name="visual_Arm1"> <geometry> <mesh> <scale>0.001 0.001 0.001</scale> <uri>model://f550_amazing/meshes/Arm_CG.STL</uri> </mesh> </geometry> <material> <script> <name>Gazebo/DarkGrey</name> <uri>file://media/materials/scripts/gazebo.material</uri> </script> </material> </visual> </link> <joint name='Lower_Arm1_joint' type='fixed'> <child>Arm1_link</child> <parent>base_link</parent> </joint> <!-- ############################################ /ARM1 ############################################ --> <!-- ############################################# ARM2 ############################################ --> <link name="Arm2_link"> <gravity>true</gravity> <pose>0.162293160669 0.0937 0.009875004 0 0 0.523598775598</pose> <inertial> <mass>0.1</mass> <inertia> <ixx>0.001</ixx> <ixy>0</ixy> <ixz>0</ixz> <iyy>0.001</iyy> <iyz>0</iyz> <izz>0.001</izz> </inertia> </inertial> <visual name="visual_Arm2"> <geometry> <mesh> <scale>0.001 0.001 0.001</scale> <uri>model://f550_amazing/meshes/Arm_CG.STL</uri> </mesh> </geometry> </visual> </link> <joint name='Lower_Arm2_joint' type='fixed'> <child>Arm2_link</child> <parent>base_link</parent> </joint> <!-- ############################################ /ARM2 ############################################ --> <!-- ############################################# ARM3 ############################################ --> <link name="Arm3_link"> <gravity>true</gravity> <pose>0.162293160669 -0.0937 0.009875004 0 0 -0.523598775598</pose> <inertial> <mass>0.1</mass> <inertia> <ixx>0.001</ixx> <ixy>0</ixy> <ixz>0</ixz> <iyy>0.001</iyy> <iyz>0</iyz> <izz>0.001</izz> </inertia> </inertial> <visual name="visual_Arm3"> <geometry> <mesh> <scale>0.001 0.001 0.001</scale> <uri>model://f550_amazing/meshes/Arm_CG.STL</uri> </mesh> </geometry> </visual> </link> <joint name='Lower_Arm3_joint' type='fixed'> <child>Arm3_link</child> <parent>base_link</parent> </joint> <!-- ############################################ /ARM3 ############################################ --> <!-- ############################################# ARM4 ############################################ --> <link name="Arm4_link"> <gravity>true</gravity> <pose>0 -0.1874 0.009875004 0 0 -1.57079632679</pose> <inertial> <mass>0.1</mass> <inertia> <ixx>0.001</ixx> <ixy>0</ixy> <ixz>0</ixz> <iyy>0.001</iyy> <iyz>0</iyz> <izz>0.001</izz> </inertia> </inertial> <visual name="visual_Arm4"> <geometry> <mesh> <scale>0.001 0.001 0.001</scale> <uri>model://f550_amazing/meshes/Arm_CG.STL</uri> </mesh> </geometry> <material> <script> <name>Gazebo/DarkGrey</name> <uri>file://media/materials/scripts/gazebo.material</uri> </script> </material> </visual> </link> <joint name='Lower_Arm4_joint' type='fixed'> <child>Arm4_link</child> <parent>base_link</parent> </joint> <!-- ############################################ /ARM4 ############################################ --> <!-- ############################################# ARM5 ############################################ --> <link name="Arm5_link"> <gravity>true</gravity> <pose>-0.162293160669 -0.0937 0.009875004 0 0 3.66519142919</pose> <inertial> <mass>0.1</mass> <inertia> <ixx>0.001</ixx> <ixy>0</ixy> <ixz>0</ixz> <iyy>0.001</iyy> <iyz>0</iyz> <izz>0.001</izz> </inertia> </inertial> <visual name="visual_Arm5"> <geometry> <mesh> <scale>0.001 0.001 0.001</scale> <uri>model://f550_amazing/meshes/Arm_CG.STL</uri> </mesh> </geometry> <material> <script> <name>Gazebo/DarkGrey</name> <uri>file://media/materials/scripts/gazebo.material</uri> </script> </material> </visual> </link> <joint name='Lower_Arm5_joint' type='fixed'> <child>Arm5_link</child> <parent>base_link</parent> </joint> <!-- ############################################ /ARM5 ############################################ --> <!-- ############################################# ARM6 ############################################ --> <link name="Arm6_link"> <gravity>true</gravity> <pose>-0.162293160669 0.0937 0.009875004 0 0 2.61799387799</pose> <inertial> <mass>0.1</mass> <inertia> <ixx>0.001</ixx> <ixy>0</ixy> <ixz>0</ixz> <iyy>0.001</iyy> <iyz>0</iyz> <izz>0.001</izz> </inertia> </inertial> <visual name="visual_Arm6"> <geometry> <mesh> <scale>0.001 0.001 0.001</scale> <uri>model://f550_amazing/meshes/Arm_CG.STL</uri> </mesh> </geometry> <material> <script> <name>Gazebo/DarkGrey</name> <uri>file://media/materials/scripts/gazebo.material</uri> </script> </material> </visual> </link> <joint name='Lower_Arm6_joint' type='fixed'> <child>Arm6_link</child> <parent>base_link</parent> </joint> <!-- ############################################ /ARM6 ############################################ --> <!-- ######################################### ROTOR0 ############################################ --> <link name='rotor_0'> <pose frame=''>-0.279726205 0.1615 0.07 0 0 2.09439510239</pose> <inertial> <mass>0.005</mass> <inertia> <ixx>9.75e-07</ixx> <ixy>0</ixy> <ixz>0</ixz> <iyy>0.000273104</iyy> <iyz>0</iyz> <izz>0.000274004</izz> </inertia> </inertial> <!-- <collision name='rotor_0_collision'> <geometry> <cylinder> <length>0.01</length> <radius>0.128</radius> </cylinder> </geometry> <surface> <contact> <ode/> </contact> <friction> <ode/> </friction> </surface> </collision> --> <visual name='rotor_0_visual'> <geometry> <mesh> <scale>0.001 0.001 0.001</scale> <uri>model://f550_amazing/meshes/prop_cw_CG.stl</uri> </mesh> </geometry> <material> <script> <name>Gazebo/DarkGrey</name> <uri>file://media/materials/scripts/gazebo.material</uri> </script> </material> </visual> </link> <joint name='rotor_0_joint' type='revolute'> <child>rotor_0</child> <parent>base_link</parent> <axis> <xyz>0.046 0.0827 1.8977</xyz> <limit> <lower>-1e+16</lower> <upper>1e+16</upper> <effort>10</effort> <velocity>-1</velocity> </limit> <dynamics> <damping>0.005</damping> </dynamics> <use_parent_model_frame>1</use_parent_model_frame> </axis> <physics> <ode> <implicit_spring_damper>1</implicit_spring_damper> </ode> </physics> </joint> <!-- ######################################## /ROTOR0 ############################################ --> <!-- ######################################### ROTOR1 ############################################ --> <link name='rotor_1'> <pose frame=''>0.279726205 -0.1615 0.07 0 0 -2.09439510239</pose> <inertial> <mass>0.005</mass> <inertia> <ixx>9.75e-07</ixx> <ixy>0</ixy> <ixz>0</ixz> <iyy>0.000273104</iyy> <iyz>0</iyz> <izz>0.000274004</izz> </inertia> </inertial> <visual name='rotor_1_visual'> <geometry> <mesh> <scale>0.001 0.001 0.001</scale> <uri>model://f550_amazing/meshes/prop_ccw_CG.stl</uri> </mesh> </geometry> </visual> </link> <joint name='rotor_1_joint' type='revolute'> <child>rotor_1</child> <parent>base_link</parent> <axis> <xyz>0.046 0.0827 1.8977</xyz> <limit> <lower>-1e+16</lower> <upper>1e+16</upper> <effort>10</effort> <velocity>-1</velocity> </limit> <dynamics> <damping>0.005</damping> </dynamics> <use_parent_model_frame>1</use_parent_model_frame> </axis> <physics> <ode> <implicit_spring_damper>1</implicit_spring_damper> </ode> </physics> </joint> <!-- ######################################## /ROTOR1 ############################################ --> <!-- ######################################### ROTOR2 ############################################ --> <link name='rotor_2'> <pose frame=''>-0.279726205 -0.1615 0.07 0 0 2.09439510239</pose> <inertial> <mass>0.005</mass> <inertia> <ixx>9.75e-07</ixx> <ixy>0</ixy> <ixz>0</ixz> <iyy>0.000273104</iyy> <iyz>0</iyz> <izz>0.000274004</izz> </inertia> </inertial> <visual name='rotor_2_visual'> <geometry> <mesh> <scale>0.001 0.001 0.001</scale> <uri>model://f550_amazing/meshes/prop_ccw_CG.stl</uri> </mesh> </geometry> </visual> </link> <joint name='rotor_2_joint' type='revolute'> <child>rotor_2</child> <parent>base_link</parent> <axis> <xyz>0.046 0.0827 1.8977</xyz> <limit> <lower>-1e+16</lower> <upper>1e+16</upper> <effort>10</effort> <velocity>-1</velocity> </limit> <dynamics> <damping>0.005</damping> </dynamics> <use_parent_model_frame>1</use_parent_model_frame> </axis> <physics> <ode> <implicit_spring_damper>1</implicit_spring_damper> </ode> </physics> </joint> <!-- ######################################## /ROTOR2 ############################################ --> <!-- ######################################### ROTOR3 ############################################ --> <link name='rotor_3'> <pose frame=''>0.279726205 0.1615 0.07 0 0 0</pose> <inertial> <mass>0.005</mass> <inertia> <ixx>9.75e-07</ixx> <ixy>0</ixy> <ixz>0</ixz> <iyy>0.000273104</iyy> <iyz>0</iyz> <izz>0.000274004</izz> </inertia> </inertial> <visual name='rotor_3_visual'> <geometry> <mesh> <scale>0.001 0.001 0.001</scale> <uri>model://f550_amazing/meshes/prop_cw_CG.stl</uri> </mesh> </geometry> <material> <script> <name>Gazebo/DarkGrey</name> <uri>file://media/materials/scripts/gazebo.material</uri> </script> </material> </visual> </link> <joint name='rotor_3_joint' type='revolute'> <child>rotor_3</child> <parent>base_link</parent> <axis> <xyz>0.046 0.0827 1.8977</xyz> <limit> <lower>-1e+16</lower> <upper>1e+16</upper> <effort>10</effort> <velocity>-1</velocity> </limit> <dynamics> <damping>0.005</damping> </dynamics> <use_parent_model_frame>1</use_parent_model_frame> </axis> <physics> <ode> <implicit_spring_damper>1</implicit_spring_damper> </ode> </physics> </joint> <!-- ######################################## /ROTOR3 ############################################ --> <!-- ######################################### ROTOR4 ############################################ --> <link name='rotor_4'> <pose frame=''>0 0.323 0.07 0 0 0</pose> <inertial> <mass>0.005</mass> <inertia> <ixx>9.75e-07</ixx> <ixy>0</ixy> <ixz>0</ixz> <iyy>0.000273104</iyy> <iyz>0</iyz> <izz>0.000274004</izz> </inertia> </inertial> <visual name='rotor_4_visual'> <geometry> <mesh> <scale>0.001 0.001 0.001</scale> <uri>model://f550_amazing/meshes/prop_ccw_CG.stl</uri> </mesh> </geometry> </visual> </link> <joint name='rotor_4_joint' type='revolute'> <child>rotor_4</child> <parent>base_link</parent> <axis> <xyz>0.046 0.0827 1.8977</xyz> <limit> <lower>-1e+16</lower> <upper>1e+16</upper> <effort>10</effort> <velocity>-1</velocity> </limit> <dynamics> <damping>0.005</damping> </dynamics> <use_parent_model_frame>1</use_parent_model_frame> </axis> <physics> <ode> <implicit_spring_damper>1</implicit_spring_damper> </ode> </physics> </joint> <!-- ######################################## /ROTOR4 ############################################ --> <!-- ######################################### ROTOR5 ############################################ --> <link name='rotor_5'> <pose frame=''>0 -0.323 0.07 0 0 -2.09439510239</pose> <inertial> <mass>0.005</mass> <inertia> <ixx>9.75e-07</ixx> <ixy>0</ixy> <ixz>0</ixz> <iyy>0.000273104</iyy> <iyz>0</iyz> <izz>0.000274004</izz> </inertia> </inertial> <visual name='rotor_5_visual'> <geometry> <mesh> <scale>0.001 0.001 0.001</scale> <uri>model://f550_amazing/meshes/prop_ccw_CG.stl</uri> </mesh> </geometry> <material> <script> <name>Gazebo/DarkGrey</name> <uri>file://media/materials/scripts/gazebo.material</uri> </script> </material> </visual> </link> <joint name='rotor_5_joint' type='revolute'> <child>rotor_5</child> <parent>base_link</parent> <axis> <xyz>0.046 0.0827 1.8977</xyz> <limit> <lower>-1e+16</lower> <upper>1e+16</upper> <effort>10</effort> <velocity>-1</velocity> </limit> <dynamics> <damping>0.005</damping> </dynamics> <use_parent_model_frame>1</use_parent_model_frame> </axis> <physics> <ode> <implicit_spring_damper>1</implicit_spring_damper> </ode> </physics> </joint> <!-- ######################################## /ROTOR5 ############################################ --> <!-- ######################################### grip1 ############################################### --> <link name="cylinder1"> <pose>0 -0.0967 0 0 0 0</pose> <inertial> <mass>0.01</mass> <inertia> <ixx>0.01</ixx> <ixy>0</ixy> <ixz>0</ixz> <iyy>0.01</iyy> <iyz>0</iyz> <izz>0.01</izz> </inertia> </inertial> <visual name="visual"> <geometry> <mesh> <scale>0.001 0.001 0.001</scale> <uri>model://f550_amazing/meshes/cylinder.stl</uri> </mesh> </geometry> </visual> </link> <joint name="base_link_cylinder1" type="fixed"> <child>cylinder1</child> <parent>base_link</parent> </joint> <link name="grip1"> <pose>0 -0.0967 -0.02 0 0 0</pose> <inertial> <mass>0.01</mass> <inertia> <ixx>0.01</ixx> <ixy>0</ixy> <ixz>0</ixz> <iyy>0.01</iyy> <iyz>0</iyz> <izz>0.01</izz> </inertia> </inertial> <collision name="collision"> <geometry> <mesh> <scale>0.001 0.001 0.001</scale> <uri>model://f550_amazing/meshes/grip_long.stl</uri> </mesh> </geometry> <surface> <contact> <ode> <min_depth>0.001</min_depth> </ode> </contact> <friction> <ode> <mu>50</mu> <mu2>50</mu2> </ode> </friction> </surface> </collision> <visual name="visual"> <geometry> <mesh> <scale>0.001 0.001 0.001</scale> <uri>model://f550_amazing/meshes/grip_long.stl</uri> </mesh> </geometry> </visual> </link> <joint name="cylinder_grip1" type="revolute"> <pose>0 0 0 0 0 0</pose> <child>grip1</child> <parent>cylinder1</parent> <axis> <xyz>1 0 0</xyz> <limit> <lower>0.001</lower> <upper>1.570</upper> <velocity>1</velocity> </limit> <dynamics> <damping>5</damping> <friction>0.5</friction> </dynamics> </axis> <physics> <ode> <implicit_spring_damper>1</implicit_spring_damper>' </ode> </physics> </joint> <!-- ######################################### /grip1 ############################################### --> <!-- ######################################### grip2 ############################################### --> <link name="cylinder2"> <pose>0.0837446656546 0.04835 0 0 0 2.09439510239</pose> <inertial> <mass>0.01</mass> <inertia> <ixx>0.01</ixx> <ixy>0</ixy> <ixz>0</ixz> <iyy>0.01</iyy> <iyz>0</iyz> <izz>0.01</izz> </inertia> </inertial> <visual name="visual"> <geometry> <mesh> <scale>0.001 0.001 0.001</scale> <uri>model://f550_amazing/meshes/cylinder.stl</uri> </mesh> </geometry> </visual> </link> <joint name="base_link_cylinder2" type="fixed"> <child>cylinder2</child> <parent>base_link</parent> </joint> <link name="grip2"> <pose>0.0837446656546 0.04835 -0.02 0 0 2.09439510239</pose> <inertial> <mass>0.01</mass> <inertia> <ixx>0.01</ixx> <ixy>0</ixy> <ixz>0</ixz> <iyy>0.01</iyy> <iyz>0</iyz> <izz>0.01</izz> </inertia> </inertial> <collision name="collision"> <geometry> <mesh> <scale>0.001 0.001 0.001</scale> <uri>model://f550_amazing/meshes/grip_long.stl</uri> </mesh> </geometry> <surface> <contact> <ode> <min_depth>0.001</min_depth> </ode> </contact> <friction> <ode> <mu>50</mu> <mu2>50</mu2> </ode> </friction> </surface> </collision> <visual name="visual"> <geometry> <mesh> <scale>0.001 0.001 0.001</scale> <uri>model://f550_amazing/meshes/grip_long.stl</uri> </mesh> </geometry> </visual> </link> <joint name="cylinder_grip2" type="revolute"> <pose>0 0 0 0 0 0</pose> <child>grip2</child> <parent>cylinder2</parent> <axis> <xyz>1 0 0</xyz> <limit> <lower>0.001</lower> <upper>1.570</upper> <velocity>1</velocity> </limit> <dynamics> <damping>5</damping> <friction>0.5</friction> </dynamics> </axis> <physics> <ode> <implicit_spring_damper>1</implicit_spring_damper>' </ode> </physics> </joint> <!-- ######################################### /grip2 ############################################### --> <!-- ######################################### grip3 ############################################### --> <link name="cylinder3"> <pose>0.0837446656546 -0.04835 0 0 0 1.0471975512</pose> <inertial> <mass>0.01</mass> <inertia> <ixx>0.01</ixx> <ixy>0</ixy> <ixz>0</ixz> <iyy>0.01</iyy> <iyz>0</iyz> <izz>0.01</izz> </inertia> </inertial> <visual name="visual"> <geometry> <mesh> <scale>0.001 0.001 0.001</scale> <uri>model://f550_amazing/meshes/cylinder.stl</uri> </mesh> </geometry> </visual> </link> <joint name="base_link_cylinder3" type="fixed"> <child>cylinder3</child> <parent>base_link</parent> </joint> <link name="grip3"> <pose>0.0837446656546 -0.04835 -0.02 0 0 1.0471975512</pose> <inertial> <mass>0.01</mass> <inertia> <ixx>0.01</ixx> <ixy>0</ixy> <ixz>0</ixz> <iyy>0.01</iyy> <iyz>0</iyz> <izz>0.01</izz> </inertia> </inertial> <collision name="collision"> <geometry> <mesh> <scale>0.001 0.001 0.001</scale> <uri>model://f550_amazing/meshes/grip.stl</uri> </mesh> </geometry> <surface> <contact> <ode> <min_depth>0.001</min_depth> </ode> </contact> <friction> <ode> <mu>50</mu> <mu2>50</mu2> </ode> </friction> </surface> </collision> <visual name="visual"> <geometry> <mesh> <scale>0.001 0.001 0.001</scale> <uri>model://f550_amazing/meshes/grip.stl</uri> </mesh> </geometry> </visual> </link> <joint name="cylinder_grip3" type="revolute"> <pose>0 0 0 0 0 0</pose> <child>grip3</child> <parent>cylinder3</parent> <axis> <xyz>1 0 0</xyz> <limit> <lower>0.001</lower> <upper>1.570</upper> <velocity>1</velocity> </limit> <dynamics> <damping>5</damping> <friction>0.5</friction> </dynamics> </axis> <physics> <ode> <implicit_spring_damper>1</implicit_spring_damper>' </ode> </physics> </joint> <!-- ######################################### /grip3 ############################################### --> <!-- ######################################### grip4 ############################################### --> <link name="cylinder4"> <pose>0 0.0967 0 0 0 0</pose> <inertial> <mass>0.01</mass> <inertia> <ixx>0.01</ixx> <ixy>0</ixy> <ixz>0</ixz> <iyy>0.01</iyy> <iyz>0</iyz> <izz>0.01</izz> </inertia> </inertial> <visual name="visual"> <geometry> <mesh> <scale>0.001 0.001 0.001</scale> <uri>model://f550_amazing/meshes/cylinder.stl</uri> </mesh> </geometry> </visual> </link> <joint name="base_link_cylinder4" type="fixed"> <child>cylinder4</child> <parent>base_link</parent> </joint> <link name="grip4"> <pose>0 0.0967 -0.02 0 0 3.14159265359</pose> <inertial> <mass>0.01</mass> <inertia> <ixx>0.01</ixx> <ixy>0</ixy> <ixz>0</ixz> <iyy>0.01</iyy> <iyz>0</iyz> <izz>0.01</izz> </inertia> </inertial> <collision name="collision"> <geometry> <mesh> <scale>0.001 0.001 0.001</scale> <uri>model://f550_amazing/meshes/grip.stl</uri> </mesh> </geometry> <surface> <contact> <ode> <min_depth>0.001</min_depth> </ode> </contact> <friction> <ode> <mu>50</mu> <mu2>50</mu2> </ode> </friction> </surface> </collision> <visual name="visual"> <geometry> <mesh> <scale>0.001 0.001 0.001</scale> <uri>model://f550_amazing/meshes/grip.stl</uri> </mesh> </geometry> </visual> </link> <joint name="cylinder_grip4" type="revolute"> <pose>0 0 0 0 0 0</pose> <child>grip4</child> <parent>cylinder4</parent> <axis> <xyz>1 0 0</xyz> <limit> <lower>0.001</lower> <upper>1.570</upper> <velocity>1</velocity> </limit> <dynamics> <damping>5</damping> <friction>0.5</friction> </dynamics> </axis> <physics> <ode> <implicit_spring_damper>1</implicit_spring_damper>' </ode> </physics> </joint> <!-- ######################################### /grip4 ############################################### --> <!-- ######################################### grip5 ############################################### --> <link name="cylinder5"> <pose>-0.0837446656546 0.04835 0 0 0 4.18879020479</pose> <inertial> <mass>0.01</mass> <inertia> <ixx>0.01</ixx> <ixy>0</ixy> <ixz>0</ixz> <iyy>0.01</iyy> <iyz>0</iyz> <izz>0.01</izz> </inertia> </inertial> <visual name="visual"> <geometry> <mesh> <scale>0.001 0.001 0.001</scale> <uri>model://f550_amazing/meshes/cylinder.stl</uri> </mesh> </geometry> </visual> </link> <joint name="base_link_cylinder5" type="fixed"> <child>cylinder5</child> <parent>base_link</parent> </joint> <link name="grip5"> <pose>-0.0837446656546 0.04835 -0.02 0 0 4.18879020479</pose> <inertial> <mass>0.01</mass> <inertia> <ixx>0.01</ixx> <ixy>0</ixy> <ixz>0</ixz> <iyy>0.01</iyy> <iyz>0</iyz> <izz>0.01</izz> </inertia> </inertial> <collision name="collision"> <geometry> <mesh> <scale>0.001 0.001 0.001</scale> <uri>model://f550_amazing/meshes/grip_long.stl</uri> </mesh> </geometry> <surface> <contact> <ode> <min_depth>0.001</min_depth> </ode> </contact> <friction> <ode> <mu>50</mu> <mu2>50</mu2> </ode> </friction> </surface> </collision> <visual name="visual"> <geometry> <mesh> <scale>0.001 0.001 0.001</scale> <uri>model://f550_amazing/meshes/grip_long.stl</uri> </mesh> </geometry> </visual> </link> <joint name="cylinder_grip5" type="revolute"> <pose>0 0 0 0 0 0</pose> <child>grip5</child> <parent>cylinder5</parent> <axis> <xyz>1 0 0</xyz> <limit> <lower>0.001</lower> <upper>1.570</upper> <velocity>1</velocity> </limit> <dynamics> <damping>5</damping> <friction>0.5</friction> </dynamics> </axis> <physics> <ode> <implicit_spring_damper>1</implicit_spring_damper>' </ode> </physics> </joint> <!-- ######################################### /grip5 ############################################### --> <!-- ######################################### grip6 ############################################### --> <link name="cylinder6"> <pose>-0.0837446656546 -0.04835 0 0 0 -1.0471975512</pose> <inertial> <mass>0.01</mass> <inertia> <ixx>0.01</ixx> <ixy>0</ixy> <ixz>0</ixz> <iyy>0.01</iyy> <iyz>0</iyz> <izz>0.01</izz> </inertia> </inertial> <visual name="visual"> <geometry> <mesh> <scale>0.001 0.001 0.001</scale> <uri>model://f550_amazing/meshes/cylinder.stl</uri> </mesh> </geometry> </visual> </link> <joint name="base_link_cylinder6" type="fixed"> <child>cylinder6</child> <parent>base_link</parent> </joint> <link name="grip6"> <pose>-0.0837446656546 -0.04835 -0.02 0 0 -1.0471975512</pose> <inertial> <mass>0.01</mass> <inertia> <ixx>0.01</ixx> <ixy>0</ixy> <ixz>0</ixz> <iyy>0.01</iyy> <iyz>0</iyz> <izz>0.01</izz> </inertia> </inertial> <collision name="collision"> <geometry> <mesh> <scale>0.001 0.001 0.001</scale> <uri>model://f550_amazing/meshes/grip.stl</uri> </mesh> </geometry> <surface> <contact> <ode> <min_depth>0.001</min_depth> </ode> </contact> <friction> <ode> <mu>50</mu> <mu2>50</mu2> </ode> </friction> </surface> </collision> <visual name="visual"> <geometry> <mesh> <scale>0.001 0.001 0.001</scale> <uri>model://f550_amazing/meshes/grip.stl</uri> </mesh> </geometry> </visual> </link> <joint name="cylinder_grip6" type="revolute"> <pose>0 0 0 0 0 0</pose> <child>grip6</child> <parent>cylinder6</parent> <axis> <xyz>1 0 0</xyz> <limit> <lower>0.001</lower> <upper>1.570</upper> <velocity>1</velocity> </limit> <dynamics> <damping>5</damping> <friction>0.5</friction> </dynamics> </axis> <physics> <ode> <implicit_spring_damper>1</implicit_spring_damper>' </ode> </physics> </joint> <!-- ######################################### /grip6 ############################################### --> <!-- ###################################### GRIPPER PLUGIN ########################################## --> <plugin name="hex_gripper_control" filename="libgripper_plugin.so" /> <!-- ###################################### /GRIPPER PLUGIN ######################################### --> <!-- ##################################### MOTOR PLUGINS ######################################### --> <plugin name='front_right_motor_model' filename='librotors_gazebo_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>1100</maxRotVelocity> <motorConstant>8.54858e-06</motorConstant> <momentConstant>0.06</momentConstant> <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic> <motorNumber>4</motorNumber> <rotorDragCoefficient>0.000806428</rotorDragCoefficient> <rollingMomentCoefficient>1e-06</rollingMomentCoefficient> <motorSpeedPubTopic>/motor_speed/4</motorSpeedPubTopic> <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim> </plugin> <plugin name='back_left_motor_model' filename='librotors_gazebo_motor_model.so'> <robotNamespace></robotNamespace> <jointName>rotor_1_joint</jointName> <linkName>rotor_1</linkName> <turningDirection>cw</turningDirection> <timeConstantUp>0.0125</timeConstantUp> <timeConstantDown>0.025</timeConstantDown> <maxRotVelocity>1100</maxRotVelocity> <motorConstant>8.54858e-06</motorConstant> <momentConstant>0.06</momentConstant> <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic> <motorNumber>5</motorNumber> <rotorDragCoefficient>0.000806428</rotorDragCoefficient> <rollingMomentCoefficient>1e-06</rollingMomentCoefficient> <motorSpeedPubTopic>/motor_speed/5</motorSpeedPubTopic> <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim> </plugin> <plugin name='front_left_motor_model' filename='librotors_gazebo_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>1100</maxRotVelocity> <motorConstant>8.54858e-06</motorConstant> <momentConstant>0.06</momentConstant> <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic> <motorNumber>2</motorNumber> <rotorDragCoefficient>0.000806428</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></robotNamespace> <jointName>rotor_3_joint</jointName> <linkName>rotor_3</linkName> <turningDirection>ccw</turningDirection> <timeConstantUp>0.0125</timeConstantUp> <timeConstantDown>0.025</timeConstantDown> <maxRotVelocity>1100</maxRotVelocity> <motorConstant>8.54858e-06</motorConstant> <momentConstant>0.06</momentConstant> <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic> <motorNumber>3</motorNumber> <rotorDragCoefficient>0.000806428</rotorDragCoefficient> <rollingMomentCoefficient>1e-06</rollingMomentCoefficient> <motorSpeedPubTopic>/motor_speed/3</motorSpeedPubTopic> <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim> </plugin> <plugin name='back_left_motor_model' filename='librotors_gazebo_motor_model.so'> <robotNamespace></robotNamespace> <jointName>rotor_4_joint</jointName> <linkName>rotor_4</linkName> <turningDirection>cw</turningDirection> <timeConstantUp>0.0125</timeConstantUp> <timeConstantDown>0.025</timeConstantDown> <maxRotVelocity>1100</maxRotVelocity> <motorConstant>8.54858e-06</motorConstant> <momentConstant>0.06</momentConstant> <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic> <motorNumber>0</motorNumber> <rotorDragCoefficient>0.000806428</rotorDragCoefficient> <rollingMomentCoefficient>1e-06</rollingMomentCoefficient> <motorSpeedPubTopic>/motor_speed/0</motorSpeedPubTopic> <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim> </plugin> <plugin name='front_left_motor_model' filename='librotors_gazebo_motor_model.so'> <robotNamespace></robotNamespace> <jointName>rotor_5_joint</jointName> <linkName>rotor_5</linkName> <turningDirection>ccw</turningDirection> <timeConstantUp>0.0125</timeConstantUp> <timeConstantDown>0.025</timeConstantDown> <maxRotVelocity>1100</maxRotVelocity> <motorConstant>8.54858e-06</motorConstant> <momentConstant>0.06</momentConstant> <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic> <motorNumber>1</motorNumber> <rotorDragCoefficient>0.000806428</rotorDragCoefficient> <rollingMomentCoefficient>1e-06</rollingMomentCoefficient> <motorSpeedPubTopic>/motor_speed/1</motorSpeedPubTopic> <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim> </plugin> <!-- #################################### /MOTOR PLUGINS ######################################### --> <!-- ################################### MAVLINK PLUGIN ########################################## --> <plugin name='mavlink_interface' filename='librotors_gazebo_mavlink_interface.so'> <robotNamespace></robotNamespace> <imuSubTopic>/imu</imuSubTopic> <motorSpeedCommandPubTopic>/gazebo/command/motor_speed</motorSpeedCommandPubTopic> <control_channels> <channel name="rotor0"> <input_index>0</input_index> <input_offset>1</input_offset> <input_scaling>450</input_scaling> <zero_position_disarmed>0</zero_position_disarmed> <zero_position_armed>100</zero_position_armed> <joint_control_type>velocity</joint_control_type> <joint_name>rotor_4_joint</joint_name> </channel> <channel name="rotor1"> <input_index>1</input_index> <input_offset>1</input_offset> <input_scaling>450</input_scaling> <zero_position_disarmed>0</zero_position_disarmed> <zero_position_armed>100</zero_position_armed> <joint_control_type>velocity</joint_control_type> <joint_name>rotor_5_joint</joint_name> </channel> <channel name="rotor2"> <input_index>2</input_index> <input_offset>1</input_offset> <input_scaling>450</input_scaling> <zero_position_disarmed>0</zero_position_disarmed> <zero_position_armed>100</zero_position_armed> <joint_control_type>velocity</joint_control_type> <joint_name>rotor_2_joint</joint_name> </channel> <channel name="rotor3"> <input_index>3</input_index> <input_offset>1</input_offset> <input_scaling>450</input_scaling> <zero_position_disarmed>0</zero_position_disarmed> <zero_position_armed>100</zero_position_armed> <joint_control_type>velocity</joint_control_type> <joint_name>rotor_3_joint</joint_name> </channel> <channel name="rotor4"> <input_index>4</input_index> <input_offset>1</input_offset> <input_scaling>450</input_scaling> <zero_position_disarmed>0</zero_position_disarmed> <zero_position_armed>100</zero_position_armed> <joint_control_type>velocity</joint_control_type> <joint_name>rotor_0_joint</joint_name> </channel> <channel name="rotor5"> <input_index>5</input_index> <input_offset>1</input_offset> <input_scaling>450</input_scaling> <zero_position_disarmed>0</zero_position_disarmed> <zero_position_armed>100</zero_position_armed> <joint_control_type>velocity</joint_control_type> <joint_name>rotor_1_joint</joint_name> </channel> <channel name="gimbal_roll"> <input_index>6</input_index> <input_offset>0</input_offset> <input_scaling>-3.1415</input_scaling> <zero_position_disarmed>0</zero_position_disarmed> <zero_position_armed>0</zero_position_armed> <joint_control_type>position_gztopic</joint_control_type> <gztopic>/gimbal_roll_cmd</gztopic> <joint_name>typhoon_h480::cgo3_camera_joint</joint_name> </channel> <channel name="gimbal_pitch"> <input_index>7</input_index> <input_offset>0</input_offset> <input_scaling>3.1415</input_scaling> <zero_position_disarmed>0</zero_position_disarmed> <zero_position_armed>0</zero_position_armed> <joint_control_type>position_gztopic</joint_control_type> <gztopic>/gimbal_pitch_cmd</gztopic> <joint_name>typhoon_h480::cgo3_camera_joint</joint_name> </channel> <channel name="gimbal_yaw"> <input_index>8</input_index> <input_offset>-0.5</input_offset> <input_scaling>-3.1415</input_scaling> <zero_position_disarmed>0</zero_position_disarmed> <zero_position_armed>0</zero_position_armed> <joint_control_type>position_gztopic</joint_control_type> <gztopic>/gimbal_yaw_cmd</gztopic> <joint_name>typhoon_h480::cgo3_vertical_arm_joint</joint_name> </channel> <channel name="left_leg"> <input_index>9</input_index> <input_offset>1</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</joint_control_type> <joint_control_pid> <p>50.0</p> <i>0</i> <d>0</d> <iMax>0</iMax> <iMin>0</iMin> <cmdMax>10</cmdMax> <cmdMin>-10</cmdMin> </joint_control_pid> <joint_name>left_leg_joint</joint_name> </channel> <channel name="right_leg"> <input_index>10</input_index> <input_offset>1</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</joint_control_type> <joint_control_pid> <p>50.0</p> <i>0</i> <d>0</d> <iMax>0</iMax> <iMin>0</iMin> <cmdMax>10</cmdMax> <cmdMin>-10</cmdMin> </joint_control_pid> <joint_name>right_leg_joint</joint_name> </channel> </control_channels> </plugin> <!-- ################################### /MAVLINK PLUGIN ######################################### --> <!-- ################################### IMU PLUGIN ############################################## --> <plugin name='rotors_gazebo_imu_plugin' filename='librotors_gazebo_imu_plugin.so'> <robotNamespace></robotNamespace> <linkName>imu_link</linkName> <imuTopic>/imu</imuTopic> <gyroscopeNoiseDensity>0</gyroscopeNoiseDensity> <gyroscopeRandomWalk>0</gyroscopeRandomWalk> <gyroscopeBiasCorrelationTime>1000.0</gyroscopeBiasCorrelationTime> <gyroscopeTurnOnBiasSigma>0</gyroscopeTurnOnBiasSigma> <accelerometerNoiseDensity>0</accelerometerNoiseDensity> <accelerometerRandomWalk>0</accelerometerRandomWalk> <accelerometerBiasCorrelationTime>300.0</accelerometerBiasCorrelationTime> <accelerometerTurnOnBiasSigma>0</accelerometerTurnOnBiasSigma> </plugin> <!-- ################################## /IMU PLUGIN ############################################## --> </model> </sdf>