#VRML_SIM R2019b utf8 WorldInfo { gravity 0 -9.80665 0 physics "sitl_physics_env" basicTimeStep 2 FPS 25 optimalThreadCount 4 randomSeed 52 } DogHouse { translation 34.82 0.76 -24.56 name "dog house(1)" } DogHouse { translation 161.819 0.75 -152.174 name "dog house(2)" } DogHouse { translation 185.42 0.77 48.97 name "dog house(5)" } Viewpoint { orientation 0.9997750421775041 -0.014997750480821456 -0.01499775048082146 4.712163997257285 position 0.17712971811531414 14.83048200793912 -1.4201693307676047 follow "tricopter" } Background { skyColor [ 0.15 0.5 1 ] cubemap Cubemap { } } Solid { translation 36.93 0.77 -37.93 children [ HouseWithGarage { } ] } Solid { translation 192.76999999999998 0 64.98 rotation 0 1 0 -1.5707963071795863 children [ HouseWithGarage { } ] name "solid(1)" } DEF DEF_VEHICLE Robot { translation -8.233889875751989e-05 0.666500515499142 -1.3598750857814472 rotation 0.00514799893982893 0.9999767940663002 0.004461999081102697 0.261804 children [ Compass { name "compass1" } Camera { translation 0 0.25 0 name "camera1" } Transform { translation -0.34 0 0 rotation 0 1 0 1.5707959999999999 children [ HingeJoint { jointParameters HingeJointParameters { position -9.388038782122357e-12 axis 0 0 1 } device [ RotationalMotor { name "servo_tail" maxVelocity 50000 maxTorque 1000 } ] endPoint Solid { translation -4.884982810326628e-15 -4.1022629410960365e-12 1.8091922030330322e-13 rotation 2.3470124341273664e-11 1 -3.708275057969111e-10 1.5707963071795863 children [ Propeller { shaftAxis 0 1 0 thrustConstants 11.44 0 torqueConstants 1e-05 0 device RotationalMotor { name "motor3" controlPID 10.001 0 0 maxVelocity 1000 } fastHelix Solid { children [ Shape { appearance Appearance { material Material { diffuseColor 1 0 0.1 } } geometry Cylinder { height 0.002 radius 0.02 } } ] } slowHelix Solid { rotation 0 1 0 2.238367478129037 children [ Shape { appearance Appearance { material Material { diffuseColor 0 1 0.09999999999999999 } } geometry Cylinder { height 0.002 radius 0.02 } } ] } } ] name "solid(1)" boundingObject Box { size 0.01 0.01 0.01 } physics Physics { mass 0.001 } } } ] } Transform { translation 0.17 0 0.3 children [ Propeller { shaftAxis 0 -1 0 thrustConstants -11.443 0 torqueConstants 1e-05 0 device RotationalMotor { name "motor1" controlPID 10.001 0 0 maxVelocity 1000 } fastHelix Solid { children [ Shape { appearance Appearance { material Material { diffuseColor 1 0 0.1 } } geometry Cylinder { height 0.002 radius 0.02 } } ] } slowHelix Solid { rotation 0 1 0 0.012993 children [ Shape { appearance Appearance { material Material { diffuseColor 1 0 0.1 } } geometry Cylinder { height 0.002 radius 0.02 } } ] } } ] } Transform { translation 0.16 0 -0.3 children [ Propeller { shaftAxis 0 1 0 thrustConstants 11.443 0 torqueConstants 1e-05 0 device RotationalMotor { name "motor2" controlPID 10.001 0 0 maxVelocity 1000 } fastHelix Solid { children [ Shape { appearance Appearance { material Material { diffuseColor 1 0 0.1 } } geometry Cylinder { height 0.002 radius 0.02 } } ] } slowHelix Solid { rotation 0 1 0 0.012993 children [ Shape { appearance Appearance { material Material { diffuseColor 1 0 0.1 } } geometry Cylinder { height 0.002 radius 0.02 } } ] } } ] } Emitter { rotation 0 1 0 -1.5707963071795863 name "emitter_plugin" } InertialUnit { name "inertial_unit" } Gyro { name "gyro1" } Accelerometer { name "accelerometer1" } GPS { name "gps1" } Solid { children [ Shape { appearance Appearance { material Material { } } geometry Box { size 0.1 0.1 0.1 } } ] boundingObject Box { size 0.1 0.1 0.1 } physics Physics { mass 0.6 } } ] name "tricopter" physics Physics { mass 0.001 } controller "ardupilot_SITL_TRICOPTER" supervisor TRUE } DirectionalLight { direction 0 -1 0 } UnevenTerrain { size 500 1 500 } HouseWithGarage { translation 174.25 1.88 -157.5 rotation 0 1 0 -1.5707963071795863 } AdvertisingBoard { translation 0 2.35 -5.71 } AdvertisingBoard { translation 84.03999999999999 2.35 -5.81 rotation 0 1 0 -1.5707963071795863 name "advertising board(1)" }