#VRML_SIM R2021a utf8
WorldInfo {
  gravity 0.2
  basicTimeStep 16
  coordinateSystem "NUE"
}
Viewpoint {
  orientation -0.6002466325295073 0.7753295528057134 0.19638753698511255 0.7477472527006542
  position 0.844819390262747 2.391065676253801 3.2173738573028166
}
TexturedBackground {
}
TexturedBackgroundLight {
}
RectangleArena {
  floorSize 5 5
}
Robot {
  translation -1 0 0
  children [
    Gyro {
      translation 0 1.05 0
      name "pelvis_gyro"
    }
    Accelerometer {
      translation 0 1.05 0
      name "pelvis_accelerometer"
    }
    DEF Body Transform {
      translation 0 1.05 0
      children [
        DEF pelvis Shape {
          appearance PBRAppearance {
            roughness 1
            metalness 0
          }
          geometry Box {
            size 0.2 0.2 0.25
          }
        }
      ]
    }
    BallJoint {
      jointParameters BallJointParameters {
        anchor 0.185 1.15 0
      }
      jointParameters2 JointParameters {
        axis 1 0 0
      }
      jointParameters3 JointParameters {
      }
      device [
        PositionSensor {
          name "left_hip_pitch_position_sensor"
        }
        RotationalMotor {
          name "left_hip_pitch"
        }
      ]
      device2 [
        PositionSensor {
          name "left_hip_yaw_position_sensor"
        }
        RotationalMotor {
          name "left_hip_yaw"
          minPosition -1.5707963267948966
          maxPosition 1.5707963267948966
        }
      ]
      device3 [
        PositionSensor {
          name "left_hip_roll_position_sensor"
        }
        RotationalMotor {
          name "left_hip_roll"
        }
      ]
      endPoint Solid {
        translation 0.185 0.85 0
        rotation -1 0 0 1.8916846600245166e-06
        children [
          DEF left_thigh Shape {
            appearance PBRAppearance {
              roughness 1
              metalness 0
            }
            geometry Capsule {
              height 0.3
              radius 0.075
            }
          }
          HingeJoint {
            jointParameters HingeJointParameters {
              anchor 0 -0.225 0
            }
            device [
              PositionSensor {
                name "left_knee_pitch_position_sensor"
              }
              RotationalMotor {
                name "left_knee_pitch"
              }
            ]
            endPoint Solid {
              translation 0 -0.45 0
              rotation 1 0 0 0
              children [
                DEF left_shin Shape {
                  appearance PBRAppearance {
                    roughness 1
                    metalness 0
                  }
                  geometry Capsule {
                    height 0.3
                    radius 0.075
                  }
                }
                BallJoint {
                  jointParameters BallJointParameters {
                    anchor 0 -0.25 0
                  }
                  jointParameters2 JointParameters {
                  }
                  jointParameters3 JointParameters {
                    axis 1 0 0
                  }
                  device [
                    PositionSensor {
                      name "left_ankle_yaw_position_sensor"
                    }
                    RotationalMotor {
                      name "left_ankle_yaw"
                      maxTorque 10000
                    }
                  ]
                  device2 [
                    PositionSensor {
                      name "left_ankle_roll_position_sensor"
                    }
                    RotationalMotor {
                      name "left_ankle_roll"
                      minPosition -1.5707963267948966
                      maxPosition 1.5707963267948966
                    }
                  ]
                  device3 [
                    PositionSensor {
                      name "left_ankle_pitch_position_sensor"
                    }
                    RotationalMotor {
                      name "left_ankle_pitch"
                      maxTorque 10000
                    }
                  ]
                  endPoint Solid {
                    translation 0 -0.25 0
                    children [
                      TouchSensor {
                        children [
                          Solid {
                            translation 0 -0.05 0
                            children [
                              DEF left_foot_force_sensor_shape Shape {
                                appearance PBRAppearance {
                                  baseColor 0 0 0
                                  roughness 1
                                  metalness 0
                                }
                                geometry Box {
                                  size 0.2 0.05 0.4
                                }
                              }
                            ]
                            boundingObject USE left_foot_force_sensor_shape
                            physics Physics {
                              density -1
                              mass 4.000000000000001
                              centerOfMass [
                                0 0 0
                              ]
                              inertiaMatrix [
                                0.054166666666666696 0.0666666666666667 0.014166666666666675
                                0 0 0
                              ]
                            }
                          }
                        ]
                        name "left_foot_force_sensor"
                        boundingObject USE left_foot_force_sensor_shape
                        physics Physics {
                          density -1
                          mass 4.000000000000001
                          centerOfMass [
                            0 0 0
                          ]
                          inertiaMatrix [
                            0.054166666666666696 0.0666666666666667 0.014166666666666675
                            0 0 0
                          ]
                        }
                        type "force"
                      }
                      DEF left_foot Shape {
                        appearance PBRAppearance {
                          roughness 1
                          metalness 0
                        }
                        geometry Box {
                          size 0.2 0.05 0.4
                        }
                      }
                    ]
                    boundingObject USE left_foot
                    physics Physics {
                      density -1
                      mass 4.000000000000001
                      centerOfMass [
                        0 0 0
                      ]
                      inertiaMatrix [
                        0.054166666666666696 0.0666666666666667 0.014166666666666675
                        0 0 0
                      ]
                    }
                  }
                }
              ]
              boundingObject USE left_shin
              physics Physics {
                density -1
                mass 7.068583470577034
                centerOfMass [
                  0 0 0
                ]
                inertiaMatrix [
                  0.10586308213356384 0.018886371460448012 0.10586308213356384
                  0 0 0
                ]
              }
            }
          }
        ]
        boundingObject USE left_thigh
        physics Physics {
          density -1
          mass 7.068583470577034
          centerOfMass [
            0 0 0
          ]
          inertiaMatrix [
            0.10586308213356384 0.018886371460448012 0.10586308213356384
            0 0 0
          ]
        }
      }
    }
    BallJoint {
      jointParameters BallJointParameters {
        anchor -0.185 1.15 0
      }
      jointParameters2 JointParameters {
        axis 1 0 0
      }
      jointParameters3 JointParameters {
      }
      device [
        PositionSensor {
          name "right_hip_pitch_position_sensor"
        }
        RotationalMotor {
          name "right_hip_pitch"
        }
      ]
      device2 [
        PositionSensor {
          name "right_hip_yaw_position_sensor"
        }
        RotationalMotor {
          name "right_hip_yaw"
          minPosition -1.5707963267948966
          maxPosition 1.5707963267948966
        }
      ]
      device3 [
        PositionSensor {
          name "right_hip_roll_position_sensor"
        }
        RotationalMotor {
          name "right_hip_roll"
        }
      ]
      endPoint Solid {
        translation -0.185 0.85 0
        rotation 1 0 0 0
        children [
          DEF right_thigh Shape {
            appearance PBRAppearance {
              roughness 1
              metalness 0
            }
            geometry Capsule {
              height 0.3
              radius 0.075
            }
          }
          HingeJoint {
            jointParameters HingeJointParameters {
              anchor 0 -0.225 0
            }
            device [
              PositionSensor {
                name "right_knee_pitch_position_sensor"
              }
              RotationalMotor {
                name "right_knee_pitch"
              }
            ]
            endPoint Solid {
              translation 0 -0.45 0
              rotation 1 0 0 0
              children [
                DEF right_shin Shape {
                  appearance PBRAppearance {
                    roughness 1
                    metalness 0
                  }
                  geometry Capsule {
                    height 0.3
                    radius 0.075
                  }
                }
                BallJoint {
                  jointParameters BallJointParameters {
                    anchor 0 -0.225 0
                  }
                  jointParameters2 JointParameters {
                  }
                  jointParameters3 JointParameters {
                    axis 1 0 0
                  }
                  device [
                    PositionSensor {
                      name "right_ankle_yaw_position_sensor"
                    }
                    RotationalMotor {
                      name "right_ankle_yaw"
                      maxTorque 10000
                    }
                  ]
                  device2 [
                    PositionSensor {
                      name "right_ankle_roll_position_sensor"
                    }
                    RotationalMotor {
                      name "right_ankle_roll"
                      minPosition -1.5707963267948966
                      maxPosition 1.5707963267948966
                    }
                  ]
                  device3 [
                    PositionSensor {
                      name "right_ankle_pitch_position_sensor"
                    }
                    RotationalMotor {
                      name "right_ankle_pitch"
                      maxTorque 10000
                    }
                  ]
                  endPoint Solid {
                    translation 0 -0.25 0
                    children [
                      TouchSensor {
                        translation 0 -0.05 0
                        children [
                          Solid {
                            children [
                              DEF right_foot_force_sensor_shape Shape {
                                appearance PBRAppearance {
                                  baseColor 0 0 0
                                  roughness 1
                                  metalness 0
                                }
                                geometry Box {
                                  size 0.2 0.05 0.4
                                }
                              }
                            ]
                            boundingObject USE right_foot_force_sensor_shape
                            physics Physics {
                              density -1
                              mass 4.000000000000001
                              centerOfMass [
                                0 0 0
                              ]
                              inertiaMatrix [
                                0.054166666666666696 0.0666666666666667 0.014166666666666675
                                0 0 0
                              ]
                            }
                          }
                        ]
                        name "right_foot_force_sensor"
                        boundingObject USE right_foot_force_sensor_shape
                        physics Physics {
                          density -1
                          mass 4.000000000000001
                          centerOfMass [
                            0 0 0
                          ]
                          inertiaMatrix [
                            0.054166666666666696 0.0666666666666667 0.014166666666666675
                            0 0 0
                          ]
                        }
                        type "force-3d"
                      }
                      DEF right_foot Shape {
                        appearance PBRAppearance {
                          roughness 1
                          metalness 0
                        }
                        geometry Box {
                          size 0.2 0.05 0.4
                        }
                      }
                    ]
                    boundingObject USE right_foot
                    physics Physics {
                      density -1
                      mass 4.000000000000001
                      centerOfMass [
                        0 0 0
                      ]
                      inertiaMatrix [
                        0.054166666666666696 0.0666666666666667 0.014166666666666675
                        0 0 0
                      ]
                    }
                  }
                }
              ]
              boundingObject USE right_shin
              physics Physics {
                density -1
                mass 7.068583470577034
                centerOfMass [
                  0 0 0
                ]
                inertiaMatrix [
                  0.10586308213356384 0.018886371460448012 0.10586308213356384
                  0 0 0
                ]
              }
            }
          }
        ]
        name "right_thigh_motor"
        boundingObject USE right_thigh
        physics Physics {
          density -1
          mass 7.068583470577034
          centerOfMass [
            0 0 0
          ]
          inertiaMatrix [
            0.10586308213356384 0.018886371460448012 0.10586308213356384
            0 0 0
          ]
        }
      }
    }
    BallJoint {
      jointParameters BallJointParameters {
        anchor 0 1.15 0
      }
      jointParameters2 JointParameters {
        axis 1 0 0
      }
      jointParameters3 JointParameters {
      }
      device [
        PositionSensor {
          name "torso_pitch_position_sensor"
        }
        RotationalMotor {
          name "torso_pitch"
          maxVelocity 100000
        }
      ]
      device2 [
        PositionSensor {
          name "torso_yaw_position_sensor"
        }
        RotationalMotor {
          name "torso_yaw"
          minPosition -1.5707963267948966
          maxPosition 1.5707963267948966
        }
      ]
      device3 [
        PositionSensor {
          name "torso_roll_position_sensor"
        }
        RotationalMotor {
          name "torso_roll"
        }
      ]
      endPoint Solid {
        translation 0 1.51 0
        rotation 1 0 0 0
        children [
          Gyro {
            name "torso_gyro"
          }
          Accelerometer {
            name "torso_accelerometer"
          }
          DEF torso Shape {
            appearance PBRAppearance {
              roughness 1
              metalness 0
            }
            geometry Box {
              size 0.5 0.7 0.25
            }
          }
          BallJoint {
            jointParameters BallJointParameters {
              anchor -0.33 0.25 0
            }
            jointParameters2 JointParameters {
            }
            jointParameters3 JointParameters {
              axis 1 0 0
            }
            device [
              PositionSensor {
                name "right_shoulder_roll_position_sensor"
              }
              RotationalMotor {
                name "right_shoulder_roll"
              }
            ]
            device2 [
              PositionSensor {
                name "right_shoulder_yaw_position_sensor"
              }
              RotationalMotor {
                name "right_shoulder_yaw"
                minPosition -1.5707963267948966
                maxPosition 1.5707963267948966
              }
            ]
            device3 [
              PositionSensor {
                name "right_shoulder_pitch_position_sensor"
              }
              RotationalMotor {
                name "right_shoulder_pitch"
              }
            ]
            endPoint Solid {
              translation -0.330806 0.1 -2.28548e-05
              rotation 0.0008954593566532848 0.9999525246665688 -0.009702915309103947 0.12741759639284905
              children [
                HingeJoint {
                  jointParameters HingeJointParameters {
                    anchor 0 -0.2125 0
                  }
                  device [
                    PositionSensor {
                      name "right_elbow_pitch_position_sensor"
                    }
                    RotationalMotor {
                      name "right_elbow_pitch"
                    }
                  ]
                  endPoint Solid {
                    translation 0 -0.42499999999726895 -1.5235950555825944e-06
                    rotation 1 0 0 3.5849604925388305e-06
                    children [
                      DEF right_lower_arm Shape {
                        appearance PBRAppearance {
                          roughness 1
                          metalness 0
                        }
                        geometry Capsule {
                          height 0.25
                          radius 0.075
                        }
                      }
                    ]
                    boundingObject USE right_lower_arm
                    physics Physics {
                      density -1
                      mass 6.185010536754905
                      centerOfMass [
                        0 0 0
                      ]
                      inertiaMatrix [
                        0.07323531077523626 0.016401322584073275 0.07323531077523626
                        0 0 0
                      ]
                    }
                  }
                }
                DEF right_upper_arm Shape {
                  appearance PBRAppearance {
                    roughness 1
                    metalness 0
                  }
                  geometry Capsule {
                    height 0.3
                    radius 0.075
                  }
                }
              ]
              boundingObject USE right_upper_arm
              physics Physics {
                density -1
                mass 7.068583470577034
                centerOfMass [
                  0 0 0
                ]
                inertiaMatrix [
                  0.10586308213356384 0.018886371460448012 0.10586308213356384
                  0 0 0
                ]
              }
            }
          }
          BallJoint {
            jointParameters BallJointParameters {
              anchor 0 0.48 0
            }
            jointParameters2 JointParameters {
              axis 1 0 0
            }
            jointParameters3 JointParameters {
            }
            device [
              PositionSensor {
                name "neck_pitch_position_sensor"
              }
              RotationalMotor {
                name "neck_pitch"
              }
            ]
            device2 [
              PositionSensor {
                name "neck_yaw_position_sensor"
              }
              RotationalMotor {
                name "neck_yaw"
                minPosition -1.5707963267948966
                maxPosition 1.5707963267948966
              }
            ]
            device3 [
              PositionSensor {
                name "neck_roll_position_sensor"
              }
              RotationalMotor {
                name "neck_roll"
              }
            ]
            endPoint Solid {
              translation 1.56889e-10 0.48 0.000487964
              rotation 0.9999999999997564 -6.209227482014029e-07 -3.186911752856171e-07 5.228680744087191
              children [
                DEF head Shape {
                  appearance PBRAppearance {
                    roughness 1
                    metalness 0
                  }
                  geometry Sphere {
                    radius 0.125
                  }
                }
              ]
              name "solid(2)"
              boundingObject USE head
              physics Physics {
                density -1
                mass 8.18123086872342
                centerOfMass [
                  0 0 0
                ]
                inertiaMatrix [
                  0.05113269292952138 0.05113269292952138 0.05113269292952138
                  0 0 0
                ]
              }
            }
          }
          BallJoint {
            jointParameters BallJointParameters {
              anchor 0.33 0.25 0
            }
            jointParameters2 JointParameters {
            }
            jointParameters3 JointParameters {
              axis 1 0 0
            }
            device [
              PositionSensor {
                name "left_shoulder_roll_position_sensor"
              }
              RotationalMotor {
                name "left_shoulder_roll"
              }
            ]
            device2 [
              PositionSensor {
                name "left_shoulder_yaw_position_sensor"
              }
              RotationalMotor {
                name "left_shoulder_yaw"
                minPosition -1.5707963267948966
                maxPosition 1.5707963267948966
              }
            ]
            device3 [
              PositionSensor {
                name "left_shoulder_pitch_position_sensor"
              }
              RotationalMotor {
                name "left_shoulder_pitch"
              }
            ]
            endPoint Solid {
              translation 0.33 0.1 0
              children [
                HingeJoint {
                  jointParameters HingeJointParameters {
                    anchor 0 -0.2125 0
                  }
                  device [
                    PositionSensor {
                      name "left_elbow_pitch_position_sensor"
                    }
                    RotationalMotor {
                      name "left_elbow_pitch"
                    }
                  ]
                  endPoint Solid {
                    translation 0 -0.42499999999726895 -1.5235950555825944e-06
                    rotation 0.9999999999999999 0 0 3.5849604925388305e-06
                    children [
                      DEF left_lower_arm Shape {
                        appearance PBRAppearance {
                          roughness 1
                          metalness 0
                        }
                        geometry Capsule {
                          height 0.25
                          radius 0.075
                        }
                      }
                    ]
                    boundingObject USE left_lower_arm
                    physics Physics {
                      density -1
                      mass 6.185010536754905
                      centerOfMass [
                        0 0 0
                      ]
                      inertiaMatrix [
                        0.07323531077523626 0.016401322584073275 0.07323531077523626
                        0 0 0
                      ]
                    }
                  }
                }
                DEF left_upper_arm Shape {
                  appearance PBRAppearance {
                    roughness 1
                    metalness 0
                  }
                  geometry Capsule {
                    height 0.3
                    radius 0.075
                  }
                }
              ]
              name "solid(1)"
              boundingObject USE left_upper_arm
              physics Physics {
                density -1
                mass 7.068583470577034
                centerOfMass [
                  0 0 0
                ]
                inertiaMatrix [
                  0.10586308213356384 0.018886371460448012 0.10586308213356384
                  0 0 0
                ]
              }
            }
          }
        ]
        name "solid(2)"
        boundingObject USE torso
        physics Physics {
          density -1
          mass 87.5
          centerOfMass [
            0 0 0
          ]
          inertiaMatrix [
            4.028645833333333 2.2786458333333335 5.395833333333334
            0 0 0
          ]
        }
      }
    }
  ]
  boundingObject USE Body
  physics Physics {
    density -1
    mass 10.000000000000002
    centerOfMass [
      0 1.05 0
    ]
    inertiaMatrix [
      11.11041666666667 0.08541666666666668 11.091666666666669
      0 0 0
    ]
  }
  controller "olympian"
  selfCollision TRUE
}