ardupilot/libraries/SITL/examples/Webots/worlds/webots_tricopter.wbt

Ignoring revisions in .git-blame-ignore-revs. Click here to bypass and see the normal blame view.

301 lines
6.9 KiB
Plaintext
Raw Permalink Normal View History

2021-08-15 10:17:24 -03:00
#VRML_SIM R2021b utf8
2019-09-15 16:53:56 -03:00
WorldInfo {
2021-08-15 10:17:24 -03:00
gravity 9.80665
2019-09-15 16:53:56 -03:00
physics "sitl_physics_env"
basicTimeStep 1
2021-08-15 10:17:24 -03:00
FPS 15
optimalThreadCount 4
coordinateSystem "NUE"
2019-09-15 16:53:56 -03:00
randomSeed 52
}
2021-08-15 10:17:24 -03:00
Viewpoint {
2021-11-14 11:49:25 -04:00
orientation 0.6321101793339116 0.7585904605856989 0.15804187511804393 5.646432505192663
position -5.214083564314484 4.660863205046186 6.918610542541648
2021-08-15 10:17:24 -03:00
follow "tricopter"
}
2019-09-15 16:53:56 -03:00
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)"
}
Background {
skyColor [
0.15 0.5 1
]
}
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 [
Receiver {
name "receiver_main"
type "serial"
channel 1
bufferSize 32
}
2019-09-15 16:53:56 -03:00
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 {
2021-11-14 11:49:25 -04:00
translation -4.884985544693083e-15 -4.102262941092767e-12 1.8091922030330322e-13
rotation 3.896036368440465e-10 1 -7.369610254815084e-10 1.5707963071795863
2019-09-15 16:53:56 -03:00
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
2021-08-15 10:17:24 -03:00
radius 0.1
2019-09-15 16:53:56 -03:00
}
}
]
}
slowHelix Solid {
2021-08-15 10:17:24 -03:00
rotation 0 1 0 1.1667874781290464
2019-09-15 16:53:56 -03:00
children [
Shape {
appearance Appearance {
material Material {
2021-08-15 10:17:24 -03:00
diffuseColor 0.45098 0.823529 0.0862745
2019-09-15 16:53:56 -03:00
}
}
geometry Cylinder {
height 0.002
2021-08-15 10:17:24 -03:00
radius 0.1
2019-09-15 16:53:56 -03:00
}
}
]
}
}
]
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
2021-08-15 10:17:24 -03:00
radius 0.1
2019-09-15 16:53:56 -03:00
}
}
]
}
slowHelix Solid {
2021-08-15 10:17:24 -03:00
rotation 0 1 0 1.1667874781290464
2019-09-15 16:53:56 -03:00
children [
Shape {
appearance Appearance {
material Material {
2021-08-15 10:17:24 -03:00
diffuseColor 0.960784 0.47451 0
2019-09-15 16:53:56 -03:00
}
}
geometry Cylinder {
height 0.002
2021-08-15 10:17:24 -03:00
radius 0.1
2019-09-15 16:53:56 -03:00
}
}
]
}
}
]
}
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
2021-08-15 10:17:24 -03:00
radius 0.1
2019-09-15 16:53:56 -03:00
}
}
]
}
slowHelix Solid {
2021-08-15 10:17:24 -03:00
rotation 0 1 0 1.1667874781290464
2019-09-15 16:53:56 -03:00
children [
Shape {
appearance Appearance {
material Material {
2021-08-15 10:17:24 -03:00
diffuseColor 0.960784 0.47451 0
2019-09-15 16:53:56 -03:00
}
}
geometry Cylinder {
height 0.002
2021-08-15 10:17:24 -03:00
radius 0.1
2019-09-15 16:53:56 -03:00
}
}
]
}
}
]
}
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 1
2019-09-15 16:53:56 -03:00
}
}
]
name "tricopter"
physics Physics {
mass 0.001
}
controller "ardupilot_SITL_TRICOPTER"
2021-08-15 10:17:24 -03:00
controllerArgs [
"-p"
"5599"
"-df"
"0.01"
]
customData "1"
2019-09-15 16:53:56 -03:00
}
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)"
2021-08-15 10:17:24 -03:00
frontTexture [
"https://ardupilot.org/application/files/6315/7552/1962/ArduPilot-Motto.png"
]
2019-09-15 16:53:56 -03:00
}