@garret also of note, the timeout happens only when I launch the instance of gazebo to display vtol. When I launch the default reccomended gazebo for iris, even with all the additional modules, timeout errors do not occur.
I am using this command:
docker run --rm -it --net=host --privileged -e DISPLAY=$DISPLAY -v /dev/input:/dev/input:rw -v /tmp/.X11-unix:/tmp/.X11-unix:ro --device=/dev/ttyUSB0:/dev/ttyUSB0 -v $(pwd)/run_gazebo_local_copy.bash:/usr/workspace/voxl2_hitl_gazebo/run_gazebo.bash -v $(pwd)/standard_vtol_hitl_local_copy.sdf:/usr/workspace/voxl2_hitl_gazebo/models/standard_vtol_hitl/standard_vtol_hitl.sdf voxl-gazebo-docker ./run_gazebo.bashMy custom files are:
"run_gazebo_local_copy.bash": #!/bin/bash # # Run gazebo in support of voxl2 hitl # # setup Gazebo env and update package path export GAZEBO_PLUGIN_PATH=$GAZEBO_PLUGIN_PATH:$(pwd) export GAZEBO_MODEL_PATH=$GAZEBO_MODEL_PATH:$(pwd)/models export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:$(pwd)/build echo -e "GAZEBO_PLUGIN_PATH $GAZEBO_PLUGIN_PATH" echo -e "GAZEBO_MODEL_PATH $GAZEBO_MODEL_PATH" echo -e "LD_LIBRARY_PATH $LD_LIBRARY_PATH" # gazebo worlds/hitl_iris_vio.world -> modified by Nikita Shakhraichuk to launch vtol model in the gazebo gazebo worlds/hitl_standard_vtol.world "standard_vtol_hitl.sdf": <?xml version="1.0"?> <sdf version='1.5'> <model name='standard_vtol_hitl'> <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>5</mass> <inertia> <ixx>0.477708333333</ixx> <ixy>0</ixy> <ixz>0</ixz> <iyy>0.341666666667</iyy> <iyz>0</iyz> <izz>0.811041666667</izz> </inertia> </inertial> <collision name='base_link_collision'> <pose>0 0 -0.07 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://standard_vtol/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 0.35 0.01 0 0 0</pose> <geometry> <box> <size>0.74 0.03 0.03</size> </box> </geometry> <material> <script> <name>Gazebo/DarkGrey</name> <uri>__default__</uri> </script> </material> </visual> <visual name='right_motor_column'> <pose>0 -0.35 0.01 0 0 0</pose> <geometry> <box> <size>0.74 0.03 0.03</size> </box> </geometry> <material> <script> <name>Gazebo/DarkGrey</name> <uri>__default__</uri> </script> </material> </visual> <visual name='m0'> <pose>-0.35 0.35 0.045 0 0 0</pose> <geometry> <cylinder> <length>0.035</length> <radius>0.02</radius> </cylinder> </geometry> <material> <script> <name>Gazebo/DarkGrey</name> <uri>__default__</uri> </script> </material> </visual> <visual name='m1'> <pose>-0.35 -0.35 0.045 0 0 0</pose> <geometry> <cylinder> <length>0.035</length> <radius>0.02</radius> </cylinder> </geometry> <material> <script> <name>Gazebo/DarkGrey</name> <uri>__default__</uri> </script> </material> </visual> <visual name='m2'> <pose>0.35 -0.35 0.045 0 0 0</pose> <geometry> <cylinder> <length>0.035</length> <radius>0.02</radius> </cylinder> </geometry> <material> <script> <name>Gazebo/DarkGrey</name> <uri>__default__</uri> </script> </material> </visual> <visual name='m3'> <pose>0.35 0.35 0.045 0 0 0</pose> <geometry> <cylinder> <length>0.035</length> <radius>0.02</radius> </cylinder> </geometry> <material> <script> <name>Gazebo/DarkGrey</name> <uri>__default__</uri> </script> </material> </visual> <gravity>1</gravity> <velocity_decay/> <self_collide>0</self_collide> </link> <link name='standard_vtol_hitl/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='standard_vtol_hitl/imu_joint' type='revolute'> <child>standard_vtol_hitl/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> <link name='rotor_0'> <pose>0.35 -0.35 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://standard_vtol/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.35 0.35 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_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://standard_vtol/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_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.35 0.35 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_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://standard_vtol/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>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.35 -0.35 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_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://standard_vtol/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_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> <link name='rotor_puller'> <pose>-0.22 0 0.0 0 1.57 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.04 0 0 0</pose> <geometry> <cylinder> <length>0.005</length> <radius>0.06</radius> </cylinder> </geometry> <surface> <contact> <ode/> </contact> <friction> <ode/> </friction> </surface> </collision> <visual name='rotor_puller_visual'> <pose>0 0 -0.04 0 0 0</pose> <geometry> <mesh> <scale>0.8 0.8 0.8</scale> <uri>model://standard_vtol/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_puller_joint' type='revolute'> <child>rotor_puller</child> <parent>base_link</parent> <axis> <xyz>1 0 0</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://standard_vtol/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://standard_vtol/meshes/x8_elevon_right.dae</uri> </mesh> </geometry> <material> <script> <name>Gazebo/Blue</name> <uri>__default__</uri> </script> </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> </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='elevator_joint' 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>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> <include> <uri>model://gps</uri> <pose>0 0 0 0 0 0</pose> <name>gps0</name> </include> <joint name='gps0_joint' type='fixed'> <child>gps0::link</child> <parent>base_link</parent> </joint> <plugin name="left_wing_lift" 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.50</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>-1.0</control_joint_rad_to_cl> <robotNamespace></robotNamespace> <windSubTopic>world_wind</windSubTopic> </plugin> <plugin name="right_wing_lift" 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.50</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>-1.0</control_joint_rad_to_cl> <robotNamespace></robotNamespace> <windSubTopic>world_wind</windSubTopic> </plugin> <plugin name="elevator_lift" filename="libLiftDragPlugin.so"> <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> elevator_joint </control_joint_name> <control_joint_rad_to_cl>-12.0</control_joint_rad_to_cl> <robotNamespace></robotNamespace> <windSubTopic>world_wind</windSubTopic> </plugin> <plugin name="rudder_lift" 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='front_right_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>1500</maxRotVelocity> <motorConstant>2e-05</motorConstant> <momentConstant>0.06</momentConstant> <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic> <motorNumber>0</motorNumber> <rotorDragCoefficient>0.000106428</rotorDragCoefficient> <rollingMomentCoefficient>1e-06</rollingMomentCoefficient> <motorSpeedPubTopic>/motor_speed/0</motorSpeedPubTopic> <rotorVelocitySlowdownSim>20</rotorVelocitySlowdownSim> </plugin> <plugin name='back_left_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>1500</maxRotVelocity> <motorConstant>2e-05</motorConstant> <momentConstant>0.06</momentConstant> <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic> <motorNumber>1</motorNumber> <rotorDragCoefficient>0.000106428</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>1500</maxRotVelocity> <motorConstant>2e-05</motorConstant> <momentConstant>0.06</momentConstant> <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic> <motorNumber>2</motorNumber> <rotorDragCoefficient>0.000106428</rotorDragCoefficient> <rollingMomentCoefficient>1e-06</rollingMomentCoefficient> <motorSpeedPubTopic>/motor_speed/2</motorSpeedPubTopic> <rotorVelocitySlowdownSim>20</rotorVelocitySlowdownSim> </plugin> <plugin name='back_right_motor_model' filename='libgazebo_motor_model.so'> <robotNamespace></robotNamespace> <jointName>rotor_3_joint</jointName> <linkName>rotor_3</linkName> <turningDirection>cw</turningDirection> <timeConstantUp>0.0125</timeConstantUp> <timeConstantDown>0.025</timeConstantDown> <maxRotVelocity>1500</maxRotVelocity> <motorConstant>2e-05</motorConstant> <momentConstant>0.06</momentConstant> <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic> <motorNumber>3</motorNumber> <rotorDragCoefficient>0.000106428</rotorDragCoefficient> <rollingMomentCoefficient>1e-06</rollingMomentCoefficient> <motorSpeedPubTopic>/motor_speed/3</motorSpeedPubTopic> <rotorVelocitySlowdownSim>20</rotorVelocitySlowdownSim> </plugin> <plugin name='puller_motor_model' filename='libgazebo_motor_model.so'> <robotNamespace></robotNamespace> <jointName>rotor_puller_joint</jointName> <linkName>rotor_puller</linkName> <turningDirection>cw</turningDirection> <timeConstantUp>0.0125</timeConstantUp> <timeConstantDown>0.025</timeConstantDown> <maxRotVelocity>3500</maxRotVelocity> <motorConstant>8.54858e-06</motorConstant> <momentConstant>0.01</momentConstant> <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic> <motorNumber>4</motorNumber> <rotorDragCoefficient>0.000106428</rotorDragCoefficient> <rollingMomentCoefficient>1e-06</rollingMomentCoefficient> <motorSpeedPubTopic>/motor_speed/4</motorSpeedPubTopic> <rotorVelocitySlowdownSim>20</rotorVelocitySlowdownSim> </plugin> <plugin name='gazebo_imu_plugin' filename='libgazebo_imu_plugin.so'> <robotNamespace></robotNamespace> <linkName>standard_vtol_hitl/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>500</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>250</pubRate> <baroTopic>/baro</baroTopic> </plugin> <plugin name='mavlink_interface' filename='libgazebo_mavlink_interface.so'> <robotNamespace/> <imuSubTopic>/imu</imuSubTopic> <magSubTopic>/mag</magSubTopic> <gpsSubTopic>/gps0</gpsSubTopic> <baroSubTopic>/baro</baroSubTopic> <mavlink_addr>INADDR_ANY</mavlink_addr> <mavlink_udp_port>14560</mavlink_udp_port> <mavlink_tcp_port>4560</mavlink_tcp_port> <serialEnabled>1</serialEnabled> <serialDevice>/dev/ttyUSB0</serialDevice> <baudRate>2000000</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>1</hil_mode> <hil_state_level>0</hil_state_level> <send_vision_estimation>0</send_vision_estimation> <send_odometry>1</send_odometry> <enable_lockstep>0</enable_lockstep> <use_tcp>1</use_tcp> <motorSpeedCommandPubTopic>/gazebo/command/motor_speed</motorSpeedCommandPubTopic> <control_channels> <channel name="rotor0"> <input_index>0</input_index> <input_offset>0</input_offset> <input_scaling>1500</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="rotor1"> <input_index>1</input_index> <input_offset>0</input_offset> <input_scaling>1500</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="rotor2"> <input_index>2</input_index> <input_offset>0</input_offset> <input_scaling>1500</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="rotor3"> <input_index>3</input_index> <input_offset>0</input_offset> <input_scaling>1500</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_3_joint</joint_name> </channel> <channel name="rotor4"> <input_index>4</input_index> <input_offset>0</input_offset> <input_scaling>5500</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_puller_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> <channel name="right_elevon"> <input_index>6</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="elevator"> <input_index>7</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>elevator_joint</joint_name> </channel> </control_channels> </plugin> <static>0</static> </model> </sdf>