mirror of
https://github.com/PotentiaRobotics/engine-software.git
synced 2025-04-26 14:39:49 -04:00
Add lower legs and feet
This commit is contained in:
parent
667395bfa2
commit
8535d1b1d3
simulation/worlds
|
@ -1,9 +1,9 @@
|
|||
Webots Project File version R2021a
|
||||
perspectives: 000000ff00000000fd00000003000000000000000000000000fc0100000002fc00000000ffffffff0000000000fffffffc0200000001fb00000012005300630065006e0065005400720065006501000000000000039f0000000000000000fb0000001a0044006f00630075006d0065006e0074006100740069006f006e0000000000ffffffff0000006900ffffff000000010000023a000003ccfc0200000002fb0000001400540065007800740045006400690074006f00720100000016000001830000008900fffffffb0000001a0043006f006e0073006f006c00650041006c006c0041006c006c010000019b000002470000003900ffffff0000000300000780000001e8fc0100000001fb0000000e0043006f006e0073006f006c00650100000000000007400000000000000000000004fc000003cc00000004000000040000000100000008fc00000000
|
||||
perspectives: 000000ff00000000fd00000003000000000000000000000000fc0100000002fc00000000ffffffff0000000000fffffffc0200000001fb00000012005300630065006e0065005400720065006501000000000000039f0000000000000000fb0000001a0044006f00630075006d0065006e0074006100740069006f006e0000000000ffffffff0000006900ffffff000000010000023a000003b6fc0200000002fb0000001400540065007800740045006400690074006f0072010000001a000002e30000008700fffffffb0000001a0043006f006e0073006f006c00650041006c006c0041006c006c01000002ff000000d10000003900ffffff0000000300000780000001e8fc0100000001fb0000000e0043006f006e0073006f006c0065010000000000000740000000000000000000000544000003b600000004000000040000000100000008fc00000000
|
||||
simulationViewPerspectives: 000000ff00000001000000020000016c000003d60100000002010000000101
|
||||
sceneTreePerspectives: 000000ff0000000100000002000000c0000000fa0100000002010000000201
|
||||
maximizedDockId: -1
|
||||
centralWidgetVisible: 1
|
||||
orthographicViewHeight: 1
|
||||
textFiles: 0 "controllers/olympian/standingBalance.py"
|
||||
textFiles: 0 "controllers/olympian/standingBalance.py" "controllers/olympian/olympian.py"
|
||||
consoles: Console:All:All
|
||||
|
|
|
@ -3,8 +3,8 @@ WorldInfo {
|
|||
coordinateSystem "NUE"
|
||||
}
|
||||
Viewpoint {
|
||||
orientation 0.1667677765231006 -0.9859728993943109 0.006778670483028679 0.08240461746309974
|
||||
position -0.03424025306816622 1.0119404189473493 3.799122587140713
|
||||
orientation -0.7235554390697962 0.681894820378785 0.10717733217942502 0.30559167713300855
|
||||
position 0.708189244094154 1.579061816199336 3.4903595614267746
|
||||
}
|
||||
TexturedBackground {
|
||||
}
|
||||
|
@ -14,7 +14,7 @@ RectangleArena {
|
|||
floorSize 5 5
|
||||
}
|
||||
Robot {
|
||||
translation 0 0.03 0
|
||||
translation 0 -0.12 0
|
||||
children [
|
||||
DEF Body Transform {
|
||||
translation 0 1.05 0
|
||||
|
@ -30,16 +30,34 @@ Robot {
|
|||
}
|
||||
]
|
||||
}
|
||||
HingeJoint {
|
||||
jointParameters HingeJointParameters {
|
||||
anchor 0.185 0.79 0
|
||||
BallJoint {
|
||||
jointParameters BallJointParameters {
|
||||
anchor 0.185 0.85 0
|
||||
}
|
||||
jointParameters2 JointParameters {
|
||||
axis 1 0 0
|
||||
}
|
||||
jointParameters3 JointParameters {
|
||||
}
|
||||
device [
|
||||
RotationalMotor {
|
||||
name "left_hip_pitch"
|
||||
}
|
||||
]
|
||||
device2 [
|
||||
RotationalMotor {
|
||||
name "left_hip_yaw"
|
||||
minPosition -1.5707963267948966
|
||||
maxPosition 1.5707963267948966
|
||||
}
|
||||
]
|
||||
device3 [
|
||||
RotationalMotor {
|
||||
name "left_hip_roll"
|
||||
}
|
||||
]
|
||||
endPoint Solid {
|
||||
translation 0.185 0.79 0
|
||||
translation 0.185 0.85 0
|
||||
rotation -1 0 0 1.8916846600245166e-06
|
||||
children [
|
||||
DEF upperLeftLeg Shape {
|
||||
|
@ -48,26 +66,119 @@ Robot {
|
|||
metalness 0
|
||||
}
|
||||
geometry Capsule {
|
||||
height 0.45
|
||||
height 0.3
|
||||
radius 0.075
|
||||
}
|
||||
}
|
||||
HingeJoint {
|
||||
jointParameters HingeJointParameters {
|
||||
anchor 0 -0.45 0
|
||||
}
|
||||
device [
|
||||
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 [
|
||||
RotationalMotor {
|
||||
name "left_foot_pitch"
|
||||
maxTorque 100
|
||||
}
|
||||
]
|
||||
device2 [
|
||||
RotationalMotor {
|
||||
name "left_foot_yaw"
|
||||
minPosition -1.5707963267948966
|
||||
maxPosition 1.5707963267948966
|
||||
}
|
||||
]
|
||||
device3 [
|
||||
RotationalMotor {
|
||||
name "left_foot_roll"
|
||||
maxTorque 100
|
||||
}
|
||||
]
|
||||
endPoint Solid {
|
||||
translation 0 -0.25 0
|
||||
children [
|
||||
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 {
|
||||
}
|
||||
}
|
||||
}
|
||||
]
|
||||
boundingObject USE left_shin
|
||||
physics Physics {
|
||||
}
|
||||
}
|
||||
}
|
||||
]
|
||||
boundingObject USE upperLeftLeg
|
||||
physics Physics {
|
||||
}
|
||||
}
|
||||
}
|
||||
HingeJoint {
|
||||
jointParameters HingeJointParameters {
|
||||
anchor -0.185 0.79 0
|
||||
BallJoint {
|
||||
jointParameters BallJointParameters {
|
||||
anchor -0.185 0.85 0
|
||||
}
|
||||
jointParameters2 JointParameters {
|
||||
axis 1 0 0
|
||||
}
|
||||
jointParameters3 JointParameters {
|
||||
}
|
||||
device [
|
||||
RotationalMotor {
|
||||
name "right_hip_pitch"
|
||||
}
|
||||
]
|
||||
device2 [
|
||||
RotationalMotor {
|
||||
name "right_hip_yaw"
|
||||
minPosition -1.5707963267948966
|
||||
maxPosition 1.5707963267948966
|
||||
}
|
||||
]
|
||||
device3 [
|
||||
RotationalMotor {
|
||||
name "right_hip_roll"
|
||||
}
|
||||
]
|
||||
endPoint Solid {
|
||||
translation -0.185 0.79 0
|
||||
translation -0.185 0.85 0
|
||||
rotation 1 0 0 0
|
||||
children [
|
||||
DEF upperRightLeg Shape {
|
||||
|
@ -76,10 +187,94 @@ Robot {
|
|||
metalness 0
|
||||
}
|
||||
geometry Capsule {
|
||||
height 0.45
|
||||
height 0.3
|
||||
radius 0.075
|
||||
}
|
||||
}
|
||||
HingeJoint {
|
||||
jointParameters HingeJointParameters {
|
||||
anchor 0 -0.45 0
|
||||
}
|
||||
device [
|
||||
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.25 0
|
||||
}
|
||||
jointParameters2 JointParameters {
|
||||
}
|
||||
jointParameters3 JointParameters {
|
||||
axis 1 0 0
|
||||
}
|
||||
device [
|
||||
RotationalMotor {
|
||||
name "right_foot_pitch"
|
||||
maxTorque 100
|
||||
}
|
||||
]
|
||||
device2 [
|
||||
RotationalMotor {
|
||||
name "right_foot_yaw"
|
||||
minPosition -1.5707963267948966
|
||||
maxPosition 1.5707963267948966
|
||||
}
|
||||
]
|
||||
device3 [
|
||||
RotationalMotor {
|
||||
name "right_foot_roll"
|
||||
maxTorque 100
|
||||
}
|
||||
]
|
||||
endPoint Solid {
|
||||
translation 0 -0.25 0
|
||||
children [
|
||||
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 {
|
||||
}
|
||||
}
|
||||
}
|
||||
]
|
||||
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 "upperRightLegMotor"
|
||||
boundingObject USE upperRightLeg
|
||||
|
|
Loading…
Reference in New Issue
Block a user