Add files via upload

This commit is contained in:
Ram Vempati 2021-11-07 13:32:21 -05:00 committed by GitHub
commit 877de136c5
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
41 changed files with 5068 additions and 0 deletions

View File

@ -0,0 +1,21 @@
import math
from controller import Robot, Supervisor, Display
import time
supervisor = Supervisor()
global TIMESTEP
TIMESTEP = int(supervisor.getBasicTimeStep())
startTime = time.time()
robotNode = supervisor.getRoot()
children = robotNode.getField("children")
robot = children.getMFNode(5)
right_torso_roll = supervisor.getDevice("Rev13")
left_torso_roll = supervisor.getDevice("Rev21")
right_ankle_roll = supervisor.getDevice("Rev16")
left_ankle_roll = supervisor.getDevice("Rev24")
for i in range(0, 1000):
right_torso_roll.setPosition(-1 * i/1000)
left_torso_roll.setPosition(-1 * i/1000)
right_ankle_roll.setPosition(-1 * i/1000)
left_ankle_roll.setPosition(-1 * i/1000)
print(robot.getCenterOfMass())
supervisor.step(TIMESTEP)

View File

@ -0,0 +1,105 @@
import math
from controller import Robot, Supervisor, Display
import time
import ikpy
import ikpy.chain
import numpy as np
import ikpy.utils.plot as plot_utils
from ikpy.urdf.utils import get_urdf_tree
import matplotlib.pyplot as plt
supervisor = Supervisor()
global TIMESTEP
TIMESTEP = int(supervisor.getBasicTimeStep())
startTime = time.time()
robotNode = supervisor.getRoot()
children = robotNode.getField("children")
robot = children.getMFNode(5)
lThighPitch = supervisor.getDevice("Rev20")
lKneePitch = supervisor.getDevice("Rev23")
lArmRoll = supervisor.getDevice("Rev8")
right_shoulder_roll = supervisor.getDevice("Rev4")
left_shoulder_roll = supervisor.getDevice("Rev8")
right_arm_uzi = supervisor.getDevice("Rev3")
left_arm_uzi = supervisor.getDevice("Rev7")
torso_pitch = supervisor.getDevice("Rev1")
torso_roll = supervisor.getDevice("Rev2")
# torso_yaw = supervisor.getDevice("Rev")
right_torso_pitch = supervisor.getDevice("Rev12")
left_torso_pitch = supervisor.getDevice("Rev20")
right_torso_roll = supervisor.getDevice("Rev13")
left_torso_roll = supervisor.getDevice("Rev21")
right_knee_pitch = supervisor.getDevice("Rev15")
left_knee_pitch = supervisor.getDevice("Rev23")
right_ankle_pitch = supervisor.getDevice("Rev19")
left_ankle_pitch = supervisor.getDevice("Rev25")
right_ankle_roll = supervisor.getDevice("Rev16")
left_ankle_roll = supervisor.getDevice("Rev24")
print(lArmRoll.getAvailableTorque())
# lArmRoll.setAvailableTorque(10)
# lArmRoll.setTorque(-3)
print(lArmRoll.getAvailableTorque())
# lArmRoll.setPosition(-0.5*math.pi)
left_torso_pitch.setAvailableTorque(10)
right_torso_pitch.setAvailableTorque(10)
right_torso_pitch.setPosition(0.5)
# print(lThighPitch.getAvailableTorque())
# print(lKneePitch.getAvailableTorque())
# lThighPitch.setAvailableTorque(50)
# lKneePitch.setAvailableTorque(50)
# print(lThighPitch.getAvailableTorque())
# print(lKneePitch.getAvailableTorque())
# lThighPitch.setPosition(-0.2)
# lKneePitch.setPosition(-0.2)
# f = open("olympian.urdf", "w")
# f.write(supervisor.getUrdf())
# f.close()
# get_urdf_tree("olympian.urdf", root_element="base_link", out_image_path="./out/olympian")
# lLegChain = ikpy.chain.Chain.from_urdf_file("olympian.urdf" ,
# # active_links_mask=[False,True,False,True,True,False,False,False],
# base_elements=["base_link", "Rev20"]
# )
# fig, ax = plot_utils.init_3d_figure()
# lLegChain.plot(lLegChain.inverse_kinematics_frame(lLegChain.forward_kinematics([0] * 7)), ax)
# print(lLegChain)
# plt.show()
# device0 = supervisor.getDeviceByIndex(0)
# device0.setPosition(0.3)
# device6 = supervisor.getDeviceByIndex(6)
# device6.setPosition(0.3)
# device12 = supervisor.getDeviceByIndex(14)
# device12.setPosition(-0.3)
#TODO GET IKPY IN HERE AND LOOK AT UML DIAGRAM AND FIGURE OUT DEVICE NAMES

View File

@ -0,0 +1,212 @@
<?xml version="1.0"?>
<robot name="Olympian" xmlns:xacro="http://ros.org/wiki/xacro">
<link name="base_link">
</link>
<joint name="Rev20" type="revolute">
<parent link="base_link"/>
<child link="Leg_Pitch_v5_2"/>
<axis xyz="1 0 0"/>
<limit effort="10000" velocity="10"/>
<origin xyz="0.2 0.812 0.1" rpy="0 0 0"/>
</joint>
<link name="Leg_Pitch_v5_2">
</link>
<joint name="Rev21" type="revolute">
<parent link="Leg_Pitch_v5_2"/>
<child link="Leg_Roll_v4_2"/>
<axis xyz="0 0 -1"/>
<limit effort="10000" velocity="10"/>
<origin xyz="0.05 0 -0.075" rpy="0 0 0"/>
</joint>
<link name="Leg_Roll_v4_2">
</link>
<joint name="Rev22" type="revolute">
<parent link="Leg_Roll_v4_2"/>
<child link="Upper_Leg_v4_2"/>
<axis xyz="0 -1 0"/>
<limit effort="10000" velocity="10"/>
<origin xyz="0 -0.075 0.075" rpy="0 0 0"/>
</joint>
<link name="Upper_Leg_v4_2">
</link>
<joint name="Rev23" type="revolute">
<parent link="Upper_Leg_v4_2"/>
<child link="Lower_Leg_v6_2"/>
<axis xyz="-1 0 0"/>
<limit effort="10000" velocity="10"/>
<origin xyz="0.05 -0.2982 0" rpy="0 0 0"/>
</joint>
<link name="Lower_Leg_v6_2">
</link>
<joint name="Rev24" type="revolute">
<parent link="Lower_Leg_v6_2"/>
<child link="Ankle_Link_v5_2"/>
<axis xyz="0 0 1"/>
<limit effort="10000" velocity="10"/>
<origin xyz="-0.05 -0.3532 -0.03" rpy="0 0 0"/>
</joint>
<link name="Ankle_Link_v5_2">
</link>
<joint name="Rev25" type="revolute">
<parent link="Ankle_Link_v5_2"/>
<child link="Foot_v4_2"/>
<axis xyz="1 0 0"/>
<limit effort="10000" velocity="10"/>
<origin xyz="0.02 -0.035 0.03" rpy="0 0 0"/>
</joint>
<link name="Foot_v4_2">
</link>
<joint name="Rev12" type="revolute">
<parent link="base_link"/>
<child link="Leg_Pitch_v5_1"/>
<axis xyz="-1 0 0"/>
<limit effort="10000" velocity="10"/>
<origin xyz="0 0.812 0.1" rpy="0 0 0"/>
</joint>
<link name="Leg_Pitch_v5_1">
</link>
<joint name="Rev13" type="revolute">
<parent link="Leg_Pitch_v5_1"/>
<child link="Leg_Roll_v4_1"/>
<axis xyz="0 0 -1"/>
<limit effort="10000" velocity="10"/>
<origin xyz="-0.05 0 -0.075" rpy="0 0 0"/>
</joint>
<link name="Leg_Roll_v4_1">
</link>
<joint name="Rev14" type="revolute">
<parent link="Leg_Roll_v4_1"/>
<child link="Upper_Leg_v4_1"/>
<axis xyz="0 -1 0"/>
<limit effort="10000" velocity="10"/>
<origin xyz="0 -0.075 0.075" rpy="0 0 0"/>
</joint>
<link name="Upper_Leg_v4_1">
</link>
<joint name="Rev15" type="revolute">
<parent link="Upper_Leg_v4_1"/>
<child link="Lower_Leg_v6_1"/>
<axis xyz="1 0 0"/>
<limit effort="10000" velocity="10"/>
<origin xyz="-0.05 -0.2982 0" rpy="0 0 0"/>
</joint>
<link name="Lower_Leg_v6_1">
</link>
<joint name="Rev16" type="revolute">
<parent link="Lower_Leg_v6_1"/>
<child link="Ankle_Link_v5_1"/>
<axis xyz="0 0 1"/>
<limit effort="10000" velocity="10"/>
<origin xyz="0.05 -0.3532 -0.03" rpy="0 0 0"/>
</joint>
<link name="Ankle_Link_v5_1">
</link>
<joint name="Rev19" type="revolute">
<parent link="Ankle_Link_v5_1"/>
<child link="Foot_v4_1"/>
<axis xyz="-1 0 0"/>
<limit effort="10000" velocity="10"/>
<origin xyz="-0.02 -0.035 0.03" rpy="0 0 0"/>
</joint>
<link name="Foot_v4_1">
</link>
<joint name="Rev1" type="revolute">
<parent link="base_link"/>
<child link="Pelvis_v7_1"/>
<axis xyz="1 0 0"/>
<limit effort="10000" velocity="10"/>
<origin xyz="0.05 0.912 0.1" rpy="0 0 0"/>
</joint>
<link name="Pelvis_v7_1">
</link>
<joint name="Rev2" type="revolute">
<parent link="Pelvis_v7_1"/>
<child link="Chest_v13_1"/>
<axis xyz="0 0 -1"/>
<limit effort="10000" velocity="10"/>
<origin xyz="0.05 0.075 -0.0375" rpy="0 0 0"/>
</joint>
<link name="Chest_v13_1">
</link>
<joint name="Rev7" type="revolute">
<parent link="Chest_v13_1"/>
<child link="Upper_Arm_Link_type_b_v9_2"/>
<axis xyz="1 0 0"/>
<limit effort="10000" velocity="10"/>
<origin xyz="0.275 0.5164 0.0375" rpy="0 0 0"/>
</joint>
<link name="Upper_Arm_Link_type_b_v9_2">
</link>
<joint name="Rev8" type="revolute">
<parent link="Upper_Arm_Link_type_b_v9_2"/>
<child link="Upper_Arm_Roll_Link_v5_2"/>
<axis xyz="0 0 -1"/>
<limit effort="10000" velocity="10"/>
<origin xyz="0.075 -0.0125 -0.05" rpy="0 0 0"/>
</joint>
<link name="Upper_Arm_Roll_Link_v5_2">
</link>
<joint name="Rev9" type="revolute">
<parent link="Upper_Arm_Roll_Link_v5_2"/>
<child link="Upper_Arm_v10_3"/>
<axis xyz="0 -1 0"/>
<limit effort="10000" velocity="10"/>
<origin xyz="0 -0.05635 0.05" rpy="0 0 0"/>
</joint>
<link name="Upper_Arm_v10_3">
</link>
<joint name="Rev10" type="revolute">
<parent link="Upper_Arm_v10_3"/>
<child link="Lower_Arm_v8_2"/>
<axis xyz="0 0 1"/>
<limit effort="10000" velocity="10"/>
<origin xyz="0 -0.3675 -0.05" rpy="0 0 0"/>
</joint>
<link name="Lower_Arm_v8_2">
</link>
<joint name="Rev3" type="revolute">
<parent link="Chest_v13_1"/>
<child link="Upper_Arm_Link_type_b_v9_1"/>
<axis xyz="-1 0 0"/>
<limit effort="10000" velocity="10"/>
<origin xyz="-0.275 0.5164 0.0375" rpy="0 0 0"/>
</joint>
<link name="Upper_Arm_Link_type_b_v9_1">
</link>
<joint name="Rev4" type="revolute">
<parent link="Upper_Arm_Link_type_b_v9_1"/>
<child link="Upper_Arm_Roll_Link_v5_1"/>
<axis xyz="0 0 -1"/>
<limit effort="10000" velocity="10"/>
<origin xyz="-0.075 -0.0125 -0.05" rpy="0 0 0"/>
</joint>
<link name="Upper_Arm_Roll_Link_v5_1">
</link>
<joint name="Rev5" type="revolute">
<parent link="Upper_Arm_Roll_Link_v5_1"/>
<child link="Upper_Arm_v10_1"/>
<axis xyz="0 -1 0"/>
<limit effort="10000" velocity="10"/>
<origin xyz="0 -0.05635 0.05" rpy="0 0 0"/>
</joint>
<link name="Upper_Arm_v10_1">
</link>
<joint name="Rev6" type="revolute">
<parent link="Upper_Arm_v10_1"/>
<child link="Lower_Arm_v8_1"/>
<axis xyz="0 0 -1"/>
<limit effort="10000" velocity="10"/>
<origin xyz="0 -0.3675 0.05" rpy="0 0 0"/>
</joint>
<link name="Lower_Arm_v8_1">
</link>
<joint name="Rev11" type="revolute">
<parent link="Chest_v13_1"/>
<child link="Box_Head_v5_1"/>
<axis xyz="0 1 0"/>
<limit effort="10000" velocity="10"/>
<origin xyz="0 0.5664 0.0375" rpy="0 0 0"/>
</joint>
<link name="Box_Head_v5_1">
</link>
</robot>

View File

@ -0,0 +1,95 @@
digraph robot {
link_base_link [label=base_link color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev20 [label=Rev20 color=green fillcolor=lightgrey style=filled]
link_base_link -> joint_Rev20
link_Leg_Pitch_v5_2 [label=Leg_Pitch_v5_2 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev20 -> link_Leg_Pitch_v5_2
joint_Rev21 [label=Rev21 color=green fillcolor=lightgrey style=filled]
link_Leg_Pitch_v5_2 -> joint_Rev21
link_Leg_Roll_v4_2 [label=Leg_Roll_v4_2 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev21 -> link_Leg_Roll_v4_2
joint_Rev22 [label=Rev22 color=green fillcolor=lightgrey style=filled]
link_Leg_Roll_v4_2 -> joint_Rev22
link_Upper_Leg_v4_2 [label=Upper_Leg_v4_2 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev22 -> link_Upper_Leg_v4_2
joint_Rev23 [label=Rev23 color=green fillcolor=lightgrey style=filled]
link_Upper_Leg_v4_2 -> joint_Rev23
link_Lower_Leg_v6_2 [label=Lower_Leg_v6_2 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev23 -> link_Lower_Leg_v6_2
joint_Rev24 [label=Rev24 color=green fillcolor=lightgrey style=filled]
link_Lower_Leg_v6_2 -> joint_Rev24
link_Ankle_Link_v5_2 [label=Ankle_Link_v5_2 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev24 -> link_Ankle_Link_v5_2
joint_Rev25 [label=Rev25 color=green fillcolor=lightgrey style=filled]
link_Ankle_Link_v5_2 -> joint_Rev25
link_Foot_v4_2 [label=Foot_v4_2 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev25 -> link_Foot_v4_2
joint_Rev12 [label=Rev12 color=green fillcolor=lightgrey style=filled]
link_base_link -> joint_Rev12
link_Leg_Pitch_v5_1 [label=Leg_Pitch_v5_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev12 -> link_Leg_Pitch_v5_1
joint_Rev13 [label=Rev13 color=green fillcolor=lightgrey style=filled]
link_Leg_Pitch_v5_1 -> joint_Rev13
link_Leg_Roll_v4_1 [label=Leg_Roll_v4_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev13 -> link_Leg_Roll_v4_1
joint_Rev14 [label=Rev14 color=green fillcolor=lightgrey style=filled]
link_Leg_Roll_v4_1 -> joint_Rev14
link_Upper_Leg_v4_1 [label=Upper_Leg_v4_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev14 -> link_Upper_Leg_v4_1
joint_Rev15 [label=Rev15 color=green fillcolor=lightgrey style=filled]
link_Upper_Leg_v4_1 -> joint_Rev15
link_Lower_Leg_v6_1 [label=Lower_Leg_v6_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev15 -> link_Lower_Leg_v6_1
joint_Rev16 [label=Rev16 color=green fillcolor=lightgrey style=filled]
link_Lower_Leg_v6_1 -> joint_Rev16
link_Ankle_Link_v5_1 [label=Ankle_Link_v5_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev16 -> link_Ankle_Link_v5_1
joint_Rev19 [label=Rev19 color=green fillcolor=lightgrey style=filled]
link_Ankle_Link_v5_1 -> joint_Rev19
link_Foot_v4_1 [label=Foot_v4_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev19 -> link_Foot_v4_1
joint_Rev1 [label=Rev1 color=green fillcolor=lightgrey style=filled]
link_base_link -> joint_Rev1
link_Pelvis_v7_1 [label=Pelvis_v7_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev1 -> link_Pelvis_v7_1
joint_Rev2 [label=Rev2 color=green fillcolor=lightgrey style=filled]
link_Pelvis_v7_1 -> joint_Rev2
link_Chest_v13_1 [label=Chest_v13_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev2 -> link_Chest_v13_1
joint_Rev7 [label=Rev7 color=green fillcolor=lightgrey style=filled]
link_Chest_v13_1 -> joint_Rev7
link_Upper_Arm_Link_type_b_v9_2 [label=Upper_Arm_Link_type_b_v9_2 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev7 -> link_Upper_Arm_Link_type_b_v9_2
joint_Rev8 [label=Rev8 color=green fillcolor=lightgrey style=filled]
link_Upper_Arm_Link_type_b_v9_2 -> joint_Rev8
link_Upper_Arm_Roll_Link_v5_2 [label=Upper_Arm_Roll_Link_v5_2 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev8 -> link_Upper_Arm_Roll_Link_v5_2
joint_Rev9 [label=Rev9 color=green fillcolor=lightgrey style=filled]
link_Upper_Arm_Roll_Link_v5_2 -> joint_Rev9
link_Upper_Arm_v10_3 [label=Upper_Arm_v10_3 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev9 -> link_Upper_Arm_v10_3
joint_Rev10 [label=Rev10 color=green fillcolor=lightgrey style=filled]
link_Upper_Arm_v10_3 -> joint_Rev10
link_Lower_Arm_v8_2 [label=Lower_Arm_v8_2 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev10 -> link_Lower_Arm_v8_2
joint_Rev3 [label=Rev3 color=green fillcolor=lightgrey style=filled]
link_Chest_v13_1 -> joint_Rev3
link_Upper_Arm_Link_type_b_v9_1 [label=Upper_Arm_Link_type_b_v9_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev3 -> link_Upper_Arm_Link_type_b_v9_1
joint_Rev4 [label=Rev4 color=green fillcolor=lightgrey style=filled]
link_Upper_Arm_Link_type_b_v9_1 -> joint_Rev4
link_Upper_Arm_Roll_Link_v5_1 [label=Upper_Arm_Roll_Link_v5_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev4 -> link_Upper_Arm_Roll_Link_v5_1
joint_Rev5 [label=Rev5 color=green fillcolor=lightgrey style=filled]
link_Upper_Arm_Roll_Link_v5_1 -> joint_Rev5
link_Upper_Arm_v10_1 [label=Upper_Arm_v10_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev5 -> link_Upper_Arm_v10_1
joint_Rev6 [label=Rev6 color=green fillcolor=lightgrey style=filled]
link_Upper_Arm_v10_1 -> joint_Rev6
link_Lower_Arm_v8_1 [label=Lower_Arm_v8_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev6 -> link_Lower_Arm_v8_1
joint_Rev11 [label=Rev11 color=green fillcolor=lightgrey style=filled]
link_Chest_v13_1 -> joint_Rev11
link_Box_Head_v5_1 [label=Box_Head_v5_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev11 -> link_Box_Head_v5_1
}

Binary file not shown.

View File

@ -0,0 +1,142 @@
from controller import Robot, Supervisor, Display
import time
from shapely.geometry.polygon import Polygon
from shapely.geometry.point import Point
# import tinyik #https://github.com/lanius/tinyik
import numpy as np
import matplotlib
import matplotlib.pyplot as plt
from mpl_toolkits.mplot3d import Axes3D
import ikpy
import ikpy.chain
import numpy as np
import ikpy.utils.plot as plot_utils
from ikpy.urdf.utils import get_urdf_tree
from sklearn.preprocessing import PolynomialFeatures
from sklearn.linear_model import LinearRegression
from sklearn.metrics import mean_squared_error
import sympy as sym
#robot - wb_supervisor_node
#supervisor - wb_robot
#so basically supervisor is the robot and robot is the supervisor
#hooray for poor nomenclature
import math
#supervisor.getUrdf() - get urdf from proto (wow)
supervisor = Supervisor()
global TIMESTEP
TIMESTEP = int(supervisor.getBasicTimeStep())
startTime = time.time()
robotNode = supervisor.getRoot()
children = robotNode.getField("children")
robot = children.getMFNode(5)
right_shoulder_roll = supervisor.getDevice("Rev4")
left_shoulder_roll = supervisor.getDevice("Rev8")
right_arm_uzi = supervisor.getDevice("Rev3")
left_arm_uzi = supervisor.getDevice("Rev7")
torso_pitch = supervisor.getDevice("Rev1")
torso_roll = supervisor.getDevice("Rev2")
# torso_yaw = supervisor.getDevice("Rev")
right_torso_pitch = supervisor.getDevice("Rev12")
left_torso_pitch = supervisor.getDevice("Rev20")
right_torso_roll = supervisor.getDevice("Rev13")
left_torso_roll = supervisor.getDevice("Rev21")
right_knee_pitch = supervisor.getDevice("Rev15")
left_knee_pitch = supervisor.getDevice("Rev23")
right_ankle_pitch = supervisor.getDevice("Rev19")
left_ankle_pitch = supervisor.getDevice("Rev25")
right_ankle_roll = supervisor.getDevice("Rev16")
left_ankle_roll = supervisor.getDevice("Rev24")
def shiftTorsoLeft():
value = 0
print(robot.getCenterOfMass())
while(robot.getCenterOfMass()[0] < 0.15):
print(robot.getCenterOfMass())
value += 0.005
right_torso_roll.setPosition(value)
left_torso_roll.setPosition(value)
right_ankle_roll.setPosition(value)
left_ankle_roll.setPosition(value)
supervisor.step(TIMESTEP)
return value
def stepRightFoot():
value = 0
# print(robot.getCenterOfMass())
while(value < 0.1):
# print(robot.getCenterOfMass())
value += 0.005
right_torso_pitch.setPosition(value)
right_knee_pitch.setPosition(value)
right_ankle_pitch.setPosition(value * -1)
left_torso_pitch.setPosition(value)
left_ankle_pitch.setPosition(value * -1)
left_knee_pitch.setPosition(value * -1)
# right_ankle_pitch.setPosition(value * -1)
supervisor.step(TIMESTEP)
def shiftTorsoRight(value):
print(robot.getCenterOfMass())
while(robot.getCenterOfMass()[0] > 0.05):
print(robot.getCenterOfMass())
value -= 0.005
right_torso_roll.setPosition(value)
left_torso_roll.setPosition(value)
right_ankle_roll.setPosition(value)
left_ankle_roll.setPosition(value)
supervisor.step(TIMESTEP)
def stepLeftFoot():
value = 0.1
# print(robot.getCenterOfMass())
while(value > -0.1):
# print(robot.getCenterOfMass())
value -= 0.001
right_torso_pitch.setPosition(value)
right_knee_pitch.setPosition(value * -1)
right_ankle_pitch.setPosition(value * -1)
left_torso_pitch.setPosition(value)
left_ankle_pitch.setPosition(value * -1)
left_knee_pitch.setPosition(value )
# right_ankle_pitch.setPosition(value * -1)
supervisor.step(TIMESTEP)
torso_pitch.setPosition(0.3)
value = shiftTorsoLeft()
stepRightFoot()
shiftTorsoRight(value)
# stepLeftFoot()

View File

@ -0,0 +1,314 @@
from controller import Robot, Supervisor, Display
import time
from shapely.geometry.polygon import Polygon
from shapely.geometry.point import Point
# import tinyik #https://github.com/lanius/tinyik
import numpy as np
import matplotlib
import matplotlib.pyplot as plt
from mpl_toolkits.mplot3d import Axes3D
import ikpy
import ikpy.chain
import numpy as np
import ikpy.utils.plot as plot_utils
from ikpy.urdf.utils import get_urdf_tree
from sklearn.preprocessing import PolynomialFeatures
from sklearn.linear_model import LinearRegression
from sklearn.metrics import mean_squared_error
import sympy as sym
#robot - wb_supervisor_node
#supervisor - wb_robot
#so basically supervisor is the robot and robot is the supervisor
#hooray for poor nomenclature
import math
#supervisor.getUrdf() - get urdf from proto (wow)
supervisor = Supervisor()
global TIMESTEP
TIMESTEP = int(supervisor.getBasicTimeStep())
startTime = time.time()
robotNode = supervisor.getRoot()
children = robotNode.getField("children")
robot = children.getMFNode(5)
right_shoulder_roll = supervisor.getDevice("Rev4")
left_shoulder_roll = supervisor.getDevice("Rev8")
right_arm_uzi = supervisor.getDevice("Rev3")
left_arm_uzi = supervisor.getDevice("Rev7")
torso_pitch = supervisor.getDevice("Rev1")
torso_roll = supervisor.getDevice("Rev2")
# torso_yaw = supervisor.getDevice("Rev")
right_torso_pitch = supervisor.getDevice("Rev12")
left_torso_pitch = supervisor.getDevice("Rev20")
right_torso_roll = supervisor.getDevice("Rev13")
left_torso_roll = supervisor.getDevice("Rev21")
right_knee_pitch = supervisor.getDevice("Rev15")
left_knee_pitch = supervisor.getDevice("Rev23")
right_ankle_pitch = supervisor.getDevice("Rev19")
left_ankle_pitch = supervisor.getDevice("Rev25")
right_ankle_roll = supervisor.getDevice("Rev16")
left_ankle_roll = supervisor.getDevice("Rev24")
ankleRollValue = 0.05
ankleRollValue2 = 0.06
def walk(value):
left_ankle_roll.setPosition(0)
right_ankle_roll.setPosition(-1 * ankleRollValue)
# right_ankle_roll.setPosition(-1 * value/2)
# torso_yaw.setPosition(value/4)
# torso_roll.setPosition(0.1 + value/50)
left_torso_pitch.setPosition(-1 * value)
left_knee_pitch.setPosition(value * -1)
right_arm_uzi.setPosition(-1 * value)
left_arm_uzi.setPosition(value)
def walk2(value1, value2):
left_ankle_roll.setPosition(ankleRollValue2)
right_ankle_roll.setPosition(0)
# left_ankle_roll.setPosition(value2/2)
# right_ankle_roll.setPosition(-1 * value1/2)
# torso_yaw.setPosition(value/4)
left_torso_pitch.setPosition(-1 * value1)
left_knee_pitch.setPosition(value1 * -1)
right_torso_pitch.setPosition( value2)
right_knee_pitch.setPosition(value2)
# torso_roll.setPosition(0.1 + value/50)
# # left_ankle_pitch.setPosition(value)
right_arm_uzi.setPosition(-1 * value)
left_arm_uzi.setPosition(value)
def walk3(value1, value2):
left_ankle_roll.setPosition(0)
right_ankle_roll.setPosition(-1 * ankleRollValue2)
# left_ankle_roll.setPosition(value2/2)
# right_ankle_roll.setPosition(-1 *value1/2)
# torso_yaw.setPosition(value/4)
left_torso_pitch.setPosition(-1 * value1)
left_knee_pitch.setPosition(value1 * -1)
right_torso_pitch.setPosition(value2)
right_knee_pitch.setPosition(value2)
right_arm_uzi.setPosition(-1 * value)
left_arm_uzi.setPosition(value)
# torso_roll.setPosition(0.1 + value/50)
# # left_ankle_pitch.setPosition(value)
first1 = True
first2 = True
first3 = True
value = 0
value2 = 0
# increment = 0.001
increment = 0.001
leftFoot = True
doneWithFirstStep = False
doneWithSecondStep = False
doneWithThirdStep = False
# coreValue = 0.25
fallingForward = True
wantActuation = True
numOfCrosses = 0
numOfCrosses2 = 0
coreValue = 0.25
tertiaryValue = 0.1
timeCompleted = 0
while supervisor.step(TIMESTEP) != -1:
# if(time.time() - startTime >= 1 and first1 == True):
# right_shoulder_roll.setPosition(1.39)
# left_shoulder_roll.setPosition(-1.39)
if(time.time() - startTime >= 2 and wantActuation == True):
#torso_pitch.setPosition(0.25)
torso_pitch.setPosition(0.3)
if(doneWithFirstStep == False):
value += increment
walk(value)
if(value >= coreValue ):
timeCompleted = time.time()
doneWithFirstStep = True
elif(doneWithFirstStep == True and doneWithSecondStep == False):
if (time.time() - timeCompleted >= 1):
value -= increment
value2 += increment
walk2(value, value2)
if(value2 >= coreValue):
timeCompleted = time.time()
doneWithSecondStep = True
doneWithThirdStep = False
elif(doneWithFirstStep == True and doneWithThirdStep == False):
if(time.time() - timeCompleted >= 1):
value += increment
value2 -= increment
walk3(value, value2)
if(value >= coreValue):
timeCompleted = time.time()
doneWithThirdStep = True
doneWithSecondStep = False
# if(doneWithFirstStep == True and time.time() - startTime >= 5 and time.time() - startTime < 10):
# #break
# # if(numOfCrosses2 == 3):
# # leftFoot = True
# if(value >= coreValue):
# leftFoot = False
# # elif(numOfCrosses == 3 and numOfCrosses2 != 3):
# # leftFoot = False
# # print("switching")
# elif(value <= 0):
# value = 0.01
# value2 = 0.25
# # leftFoot = True
# # break
# # print("switching")
# if(leftFoot == True):
# value += increment
# value2 -= increment
# walk3(value, value2)
# elif(leftFoot == False):
# # print("leftfoot false")
# value -= increment
# value2 += increment
# walk2(value, value2)
# elif(doneWithFirstStep == True and time.time() - startTime >= 10 and time.time() - startTime < 15):
# #break
# # if(numOfCrosses2 == 3):
# # leftFoot = True
# if(value >= coreValue):
# # leftFoot = True
# break
# # elif(numOfCrosses == 3 and numOfCrosses2 != 3):
# # leftFoot = False
# # print("switching")
# elif(value <= 0):
# leftFoot = True
# # break
# # print("switching")
# if(leftFoot == True):
# value += increment
# value2 -= increment
# walk3(value, value2)
# elif(leftFoot == False):
# # print("leftfoot false")
# value -= increment
# value2 += increment
# walk2(value, value2)

View File

@ -0,0 +1,95 @@
digraph robot {
link_base_link [label=base_link color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev20 [label=Rev20 color=green fillcolor=lightgrey style=filled]
link_base_link -> joint_Rev20
link_Leg_Pitch_v5_2 [label=Leg_Pitch_v5_2 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev20 -> link_Leg_Pitch_v5_2
joint_Rev21 [label=Rev21 color=green fillcolor=lightgrey style=filled]
link_Leg_Pitch_v5_2 -> joint_Rev21
link_Leg_Roll_v4_2 [label=Leg_Roll_v4_2 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev21 -> link_Leg_Roll_v4_2
joint_Rev22 [label=Rev22 color=green fillcolor=lightgrey style=filled]
link_Leg_Roll_v4_2 -> joint_Rev22
link_Upper_Leg_v4_2 [label=Upper_Leg_v4_2 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev22 -> link_Upper_Leg_v4_2
joint_Rev23 [label=Rev23 color=green fillcolor=lightgrey style=filled]
link_Upper_Leg_v4_2 -> joint_Rev23
link_Lower_Leg_v6_2 [label=Lower_Leg_v6_2 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev23 -> link_Lower_Leg_v6_2
joint_Rev24 [label=Rev24 color=green fillcolor=lightgrey style=filled]
link_Lower_Leg_v6_2 -> joint_Rev24
link_Ankle_Link_v5_2 [label=Ankle_Link_v5_2 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev24 -> link_Ankle_Link_v5_2
joint_Rev25 [label=Rev25 color=green fillcolor=lightgrey style=filled]
link_Ankle_Link_v5_2 -> joint_Rev25
link_Foot_v4_2 [label=Foot_v4_2 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev25 -> link_Foot_v4_2
joint_Rev12 [label=Rev12 color=green fillcolor=lightgrey style=filled]
link_base_link -> joint_Rev12
link_Leg_Pitch_v5_1 [label=Leg_Pitch_v5_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev12 -> link_Leg_Pitch_v5_1
joint_Rev13 [label=Rev13 color=green fillcolor=lightgrey style=filled]
link_Leg_Pitch_v5_1 -> joint_Rev13
link_Leg_Roll_v4_1 [label=Leg_Roll_v4_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev13 -> link_Leg_Roll_v4_1
joint_Rev14 [label=Rev14 color=green fillcolor=lightgrey style=filled]
link_Leg_Roll_v4_1 -> joint_Rev14
link_Upper_Leg_v4_1 [label=Upper_Leg_v4_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev14 -> link_Upper_Leg_v4_1
joint_Rev15 [label=Rev15 color=green fillcolor=lightgrey style=filled]
link_Upper_Leg_v4_1 -> joint_Rev15
link_Lower_Leg_v6_1 [label=Lower_Leg_v6_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev15 -> link_Lower_Leg_v6_1
joint_Rev16 [label=Rev16 color=green fillcolor=lightgrey style=filled]
link_Lower_Leg_v6_1 -> joint_Rev16
link_Ankle_Link_v5_1 [label=Ankle_Link_v5_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev16 -> link_Ankle_Link_v5_1
joint_Rev19 [label=Rev19 color=green fillcolor=lightgrey style=filled]
link_Ankle_Link_v5_1 -> joint_Rev19
link_Foot_v4_1 [label=Foot_v4_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev19 -> link_Foot_v4_1
joint_Rev1 [label=Rev1 color=green fillcolor=lightgrey style=filled]
link_base_link -> joint_Rev1
link_Pelvis_v7_1 [label=Pelvis_v7_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev1 -> link_Pelvis_v7_1
joint_Rev2 [label=Rev2 color=green fillcolor=lightgrey style=filled]
link_Pelvis_v7_1 -> joint_Rev2
link_Chest_v13_1 [label=Chest_v13_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev2 -> link_Chest_v13_1
joint_Rev7 [label=Rev7 color=green fillcolor=lightgrey style=filled]
link_Chest_v13_1 -> joint_Rev7
link_Upper_Arm_Link_type_b_v9_2 [label=Upper_Arm_Link_type_b_v9_2 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev7 -> link_Upper_Arm_Link_type_b_v9_2
joint_Rev8 [label=Rev8 color=green fillcolor=lightgrey style=filled]
link_Upper_Arm_Link_type_b_v9_2 -> joint_Rev8
link_Upper_Arm_Roll_Link_v5_2 [label=Upper_Arm_Roll_Link_v5_2 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev8 -> link_Upper_Arm_Roll_Link_v5_2
joint_Rev9 [label=Rev9 color=green fillcolor=lightgrey style=filled]
link_Upper_Arm_Roll_Link_v5_2 -> joint_Rev9
link_Upper_Arm_v10_3 [label=Upper_Arm_v10_3 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev9 -> link_Upper_Arm_v10_3
joint_Rev10 [label=Rev10 color=green fillcolor=lightgrey style=filled]
link_Upper_Arm_v10_3 -> joint_Rev10
link_Lower_Arm_v8_2 [label=Lower_Arm_v8_2 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev10 -> link_Lower_Arm_v8_2
joint_Rev3 [label=Rev3 color=green fillcolor=lightgrey style=filled]
link_Chest_v13_1 -> joint_Rev3
link_Upper_Arm_Link_type_b_v9_1 [label=Upper_Arm_Link_type_b_v9_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev3 -> link_Upper_Arm_Link_type_b_v9_1
joint_Rev4 [label=Rev4 color=green fillcolor=lightgrey style=filled]
link_Upper_Arm_Link_type_b_v9_1 -> joint_Rev4
link_Upper_Arm_Roll_Link_v5_1 [label=Upper_Arm_Roll_Link_v5_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev4 -> link_Upper_Arm_Roll_Link_v5_1
joint_Rev5 [label=Rev5 color=green fillcolor=lightgrey style=filled]
link_Upper_Arm_Roll_Link_v5_1 -> joint_Rev5
link_Upper_Arm_v10_1 [label=Upper_Arm_v10_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev5 -> link_Upper_Arm_v10_1
joint_Rev6 [label=Rev6 color=green fillcolor=lightgrey style=filled]
link_Upper_Arm_v10_1 -> joint_Rev6
link_Lower_Arm_v8_1 [label=Lower_Arm_v8_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev6 -> link_Lower_Arm_v8_1
joint_Rev11 [label=Rev11 color=green fillcolor=lightgrey style=filled]
link_Chest_v13_1 -> joint_Rev11
link_Box_Head_v5_1 [label=Box_Head_v5_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev11 -> link_Box_Head_v5_1
}

View File

@ -0,0 +1,95 @@
digraph robot {
link_base_link [label=base_link color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev20 [label=Rev20 color=green fillcolor=lightgrey style=filled]
link_base_link -> joint_Rev20
link_Leg_Pitch_v5_2 [label=Leg_Pitch_v5_2 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev20 -> link_Leg_Pitch_v5_2
joint_Rev21 [label=Rev21 color=green fillcolor=lightgrey style=filled]
link_Leg_Pitch_v5_2 -> joint_Rev21
link_Leg_Roll_v4_2 [label=Leg_Roll_v4_2 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev21 -> link_Leg_Roll_v4_2
joint_Rev22 [label=Rev22 color=green fillcolor=lightgrey style=filled]
link_Leg_Roll_v4_2 -> joint_Rev22
link_Upper_Leg_v4_2 [label=Upper_Leg_v4_2 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev22 -> link_Upper_Leg_v4_2
joint_Rev23 [label=Rev23 color=green fillcolor=lightgrey style=filled]
link_Upper_Leg_v4_2 -> joint_Rev23
link_Lower_Leg_v6_2 [label=Lower_Leg_v6_2 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev23 -> link_Lower_Leg_v6_2
joint_Rev24 [label=Rev24 color=green fillcolor=lightgrey style=filled]
link_Lower_Leg_v6_2 -> joint_Rev24
link_Ankle_Link_v5_2 [label=Ankle_Link_v5_2 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev24 -> link_Ankle_Link_v5_2
joint_Rev25 [label=Rev25 color=green fillcolor=lightgrey style=filled]
link_Ankle_Link_v5_2 -> joint_Rev25
link_Foot_v4_2 [label=Foot_v4_2 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev25 -> link_Foot_v4_2
joint_Rev12 [label=Rev12 color=green fillcolor=lightgrey style=filled]
link_base_link -> joint_Rev12
link_Leg_Pitch_v5_1 [label=Leg_Pitch_v5_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev12 -> link_Leg_Pitch_v5_1
joint_Rev13 [label=Rev13 color=green fillcolor=lightgrey style=filled]
link_Leg_Pitch_v5_1 -> joint_Rev13
link_Leg_Roll_v4_1 [label=Leg_Roll_v4_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev13 -> link_Leg_Roll_v4_1
joint_Rev14 [label=Rev14 color=green fillcolor=lightgrey style=filled]
link_Leg_Roll_v4_1 -> joint_Rev14
link_Upper_Leg_v4_1 [label=Upper_Leg_v4_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev14 -> link_Upper_Leg_v4_1
joint_Rev15 [label=Rev15 color=green fillcolor=lightgrey style=filled]
link_Upper_Leg_v4_1 -> joint_Rev15
link_Lower_Leg_v6_1 [label=Lower_Leg_v6_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev15 -> link_Lower_Leg_v6_1
joint_Rev16 [label=Rev16 color=green fillcolor=lightgrey style=filled]
link_Lower_Leg_v6_1 -> joint_Rev16
link_Ankle_Link_v5_1 [label=Ankle_Link_v5_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev16 -> link_Ankle_Link_v5_1
joint_Rev19 [label=Rev19 color=green fillcolor=lightgrey style=filled]
link_Ankle_Link_v5_1 -> joint_Rev19
link_Foot_v4_1 [label=Foot_v4_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev19 -> link_Foot_v4_1
joint_Rev1 [label=Rev1 color=green fillcolor=lightgrey style=filled]
link_base_link -> joint_Rev1
link_Pelvis_v7_1 [label=Pelvis_v7_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev1 -> link_Pelvis_v7_1
joint_Rev2 [label=Rev2 color=green fillcolor=lightgrey style=filled]
link_Pelvis_v7_1 -> joint_Rev2
link_Chest_v13_1 [label=Chest_v13_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev2 -> link_Chest_v13_1
joint_Rev7 [label=Rev7 color=green fillcolor=lightgrey style=filled]
link_Chest_v13_1 -> joint_Rev7
link_Upper_Arm_Link_type_b_v9_2 [label=Upper_Arm_Link_type_b_v9_2 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev7 -> link_Upper_Arm_Link_type_b_v9_2
joint_Rev8 [label=Rev8 color=green fillcolor=lightgrey style=filled]
link_Upper_Arm_Link_type_b_v9_2 -> joint_Rev8
link_Upper_Arm_Roll_Link_v5_2 [label=Upper_Arm_Roll_Link_v5_2 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev8 -> link_Upper_Arm_Roll_Link_v5_2
joint_Rev9 [label=Rev9 color=green fillcolor=lightgrey style=filled]
link_Upper_Arm_Roll_Link_v5_2 -> joint_Rev9
link_Upper_Arm_v10_3 [label=Upper_Arm_v10_3 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev9 -> link_Upper_Arm_v10_3
joint_Rev10 [label=Rev10 color=green fillcolor=lightgrey style=filled]
link_Upper_Arm_v10_3 -> joint_Rev10
link_Lower_Arm_v8_2 [label=Lower_Arm_v8_2 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev10 -> link_Lower_Arm_v8_2
joint_Rev3 [label=Rev3 color=green fillcolor=lightgrey style=filled]
link_Chest_v13_1 -> joint_Rev3
link_Upper_Arm_Link_type_b_v9_1 [label=Upper_Arm_Link_type_b_v9_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev3 -> link_Upper_Arm_Link_type_b_v9_1
joint_Rev4 [label=Rev4 color=green fillcolor=lightgrey style=filled]
link_Upper_Arm_Link_type_b_v9_1 -> joint_Rev4
link_Upper_Arm_Roll_Link_v5_1 [label=Upper_Arm_Roll_Link_v5_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev4 -> link_Upper_Arm_Roll_Link_v5_1
joint_Rev5 [label=Rev5 color=green fillcolor=lightgrey style=filled]
link_Upper_Arm_Roll_Link_v5_1 -> joint_Rev5
link_Upper_Arm_v10_1 [label=Upper_Arm_v10_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev5 -> link_Upper_Arm_v10_1
joint_Rev6 [label=Rev6 color=green fillcolor=lightgrey style=filled]
link_Upper_Arm_v10_1 -> joint_Rev6
link_Lower_Arm_v8_1 [label=Lower_Arm_v8_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev6 -> link_Lower_Arm_v8_1
joint_Rev11 [label=Rev11 color=green fillcolor=lightgrey style=filled]
link_Chest_v13_1 -> joint_Rev11
link_Box_Head_v5_1 [label=Box_Head_v5_1 color=blue fillcolor=lightgrey shape=box style=filled]
joint_Rev11 -> link_Box_Head_v5_1
}

Binary file not shown.

View File

@ -0,0 +1,138 @@
from controller import Robot, Supervisor, Display
import time
from shapely.geometry.polygon import Polygon
from shapely.geometry.point import Point
# import tinyik #https://github.com/lanius/tinyik
import numpy as np
import matplotlib
import matplotlib.pyplot as plt
from mpl_toolkits.mplot3d import Axes3D
import ikpy
import ikpy.chain
import numpy as np
import ikpy.utils.plot as plot_utils
from ikpy.urdf.utils import get_urdf_tree
from sklearn.preprocessing import PolynomialFeatures
from sklearn.linear_model import LinearRegression
from sklearn.metrics import mean_squared_error
import sympy as sym
#robot - wb_supervisor_node
#supervisor - wb_robot
#so basically supervisor is the robot and robot is the supervisor
#hooray for poor nomenclature
import math
#supervisor.getUrdf() - get urdf from proto (wow)
supervisor = Supervisor()
global TIMESTEP
TIMESTEP = int(supervisor.getBasicTimeStep())
startTime = time.time()
robotNode = supervisor.getRoot()
children = robotNode.getField("children")
robot = children.getMFNode(5)
right_shoulder_roll = supervisor.getDevice("Rev4")
left_shoulder_roll = supervisor.getDevice("Rev8")
right_arm_uzi = supervisor.getDevice("Rev3")
left_arm_uzi = supervisor.getDevice("Rev7")
torso_pitch = supervisor.getDevice("Rev1")
torso_roll = supervisor.getDevice("Rev2")
# torso_yaw = supervisor.getDevice("Rev")
right_torso_pitch = supervisor.getDevice("Rev12")
left_torso_pitch = supervisor.getDevice("Rev20")
right_torso_roll = supervisor.getDevice("Rev13")
left_torso_roll = supervisor.getDevice("Rev21")
right_knee_pitch = supervisor.getDevice("Rev15")
left_knee_pitch = supervisor.getDevice("Rev23")
right_ankle_pitch = supervisor.getDevice("Rev19")
left_ankle_pitch = supervisor.getDevice("Rev25")
right_ankle_roll = supervisor.getDevice("Rev16")
left_ankle_roll = supervisor.getDevice("Rev24")
def squatDown():
i = 0
while(i < 0.7):
i += 0.005
left_torso_pitch.setPosition(i*-1)
right_torso_pitch.setPosition(i )
left_knee_pitch.setPosition(i * -2)
right_knee_pitch.setPosition(i * 2)
left_ankle_pitch.setPosition(i * -1)
right_ankle_pitch.setPosition(i)
supervisor.step(TIMESTEP)
def squat():
i = 0
while(i < 0.7):
i += 0.005
left_torso_pitch.setPosition(i*-1)
right_torso_pitch.setPosition(i )
left_knee_pitch.setPosition(i * -2)
right_knee_pitch.setPosition(i * 2)
left_ankle_pitch.setPosition(i * -1)
right_ankle_pitch.setPosition(i)
supervisor.step(TIMESTEP)
while(i > 0):
i -= 0.005
left_torso_pitch.setPosition(i*-1)
right_torso_pitch.setPosition(i )
left_knee_pitch.setPosition(i * -2)
right_knee_pitch.setPosition(i * 2)
left_ankle_pitch.setPosition(i * -1)
right_ankle_pitch.setPosition(i)
supervisor.step(TIMESTEP)
testingTorque = 20 #nm
left_torso_pitch.setAvailableTorque(testingTorque)
right_torso_pitch.setAvailableTorque(testingTorque)
left_knee_pitch.setAvailableTorque(testingTorque)
right_knee_pitch.setAvailableTorque(testingTorque)
left_ankle_pitch.setAvailableTorque(testingTorque)
right_ankle_pitch.setAvailableTorque(testingTorque)
for i in range(0,5):
squat()
# stepLeftFoot()

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

View File

@ -0,0 +1,19 @@
import pybullet as p
import time
import pybullet_data
physicsClient = p.connect(p.GUI)#or p.DIRECT for non-graphical version
p.setAdditionalSearchPath(pybullet_data.getDataPath()) #optionally
p.setGravity(0,0,-10)
planeId = p.loadURDF("plane.urdf")
cubeStartPos = [0,0,0]
cubeStartOrientation = p.getQuaternionFromEuler([0,0,0])
robotId = p.loadURDF("olympian.urdf",cubeStartPos, cubeStartOrientation,
# useMaximalCoordinates=1, ## New feature in Pybullet
flags=p.URDF_USE_INERTIA_FROM_FILE)
for i in range (10000):
p.stepSimulation()
time.sleep(1./240.)
cubePos, cubeOrn = p.getBasePositionAndOrientation(robotId)
print(cubePos,cubeOrn)
p.disconnect()

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

View File

@ -0,0 +1,927 @@
<?xml version="1.0" ?>
<robot name="olympian">
<material name="silver">
<color rgba="0.700 0.700 0.700 1.000"/>
</material>
<link name="base_link">
<inertial>
<origin rpy="0 0 0" xyz="0.10000000000000007 0.8721666232732109 0.09999999999999991"/>
<mass value="1.1521008690150791"/>
<inertia ixx="0.005223496631877045" ixy="1.3877787807814457e-17" ixz="-5.204170427930421e-18" iyy="0.008530264202422193" iyz="1.3877787807814457e-17" izz="0.00899190194325905"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/base_link.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
<material/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/base_link.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="Pelvis_v7_1">
<inertial>
<origin rpy="0 0 0" xyz="0.0500000000000001 0.029353425629582097 -8.326672684688674e-17"/>
<mass value="0.5947505206015595"/>
<inertia ixx="0.001878872568180423" ixy="-6.938893903907228e-18" ixz="8.673617379884035e-19" iyy="0.0010976440297574865" iyz="0.0" izz="0.0020170369281690137"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="-0.05 -0.912 -0.1"/>
<geometry>
<mesh filename="meshes/Pelvis_v7_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
<material/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="-0.05 -0.912 -0.1"/>
<geometry>
<mesh filename="meshes/Pelvis_v7_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="Chest_v13_1">
<inertial>
<origin rpy="0 0 0" xyz="-8.16883662474871e-05 0.29542660059637427 0.03749999999999985"/>
<mass value="5.882339234080889"/>
<inertia ixx="0.3281120038896237" ixy="-0.00011552947303483663" ixz="-4.85722573273506e-17" iyy="0.23780786856479746" iyz="0.0" izz="0.462024450225778"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="-0.1 -0.987 -0.0625"/>
<geometry>
<mesh filename="meshes/Chest_v13_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
<material/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="-0.1 -0.987 -0.0625"/>
<geometry>
<mesh filename="meshes/Chest_v13_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="Box_Head_v5_1">
<inertial>
<origin rpy="0 0 0" xyz="7.216449660063518e-16 0.12700000029388225 -7.494005416219807e-16"/>
<mass value="0.4129840000000015"/>
<inertia ixx="0.00953546956266682" ixy="0.0" ixz="-1.231653667943533e-16" iyy="0.009535469562666835" iyz="-6.938893903907228e-17" izz="0.009535469562666599"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="-0.1 -1.5534 -0.1"/>
<geometry>
<mesh filename="meshes/Box_Head_v5_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
<material/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="-0.1 -1.5534 -0.1"/>
<geometry>
<mesh filename="meshes/Box_Head_v5_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="Upper_Arm_Link_type_b_v9_1">
<inertial>
<origin rpy="0 0 0" xyz="-0.03931045800644403 -0.01095588172168327 -1.1102230246251565e-16"/>
<mass value="0.11011202726048713"/>
<inertia ixx="0.00016930933911268875" ixy="-1.8614392972189642e-05" ixz="0.0" iyy="0.00022075846035969106" iyz="0.0" izz="0.00018206077085142214"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0.175 -1.5034 -0.1"/>
<geometry>
<mesh filename="meshes/Upper_Arm_Link_type_b_v9_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
<material/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0.175 -1.5034 -0.1"/>
<geometry>
<mesh filename="meshes/Upper_Arm_Link_type_b_v9_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="Upper_Arm_Roll_Link_v5_1">
<inertial>
<origin rpy="0 0 0" xyz="2.7755575615628914e-16 -0.022135117628713674 0.04999999999999977"/>
<mass value="0.29143432706119626"/>
<inertia ixx="0.001232763287600247" ixy="-1.3877787807814457e-17" ixz="0.0" iyy="0.0011938412922212066" iyz="0.0" izz="0.0002924682777396548"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0.25 -1.4909 -0.05"/>
<geometry>
<mesh filename="meshes/Upper_Arm_Roll_Link_v5_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
<material/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0.25 -1.4909 -0.05"/>
<geometry>
<mesh filename="meshes/Upper_Arm_Roll_Link_v5_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="Upper_Arm_v10_1">
<inertial>
<origin rpy="0 0 0" xyz="-9.4696507857428e-09 -0.2073127422998453 -2.498001805406602e-16"/>
<mass value="0.9419240929020993"/>
<inertia ixx="0.019683528982801235" ixy="-1.6353899900956037e-09" ixz="5.370703881624195e-15" iyy="0.0034983199985584718" iyz="4.163336342344337e-17" izz="0.018812734327518177"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0.25 -1.43455 -0.1"/>
<geometry>
<mesh filename="meshes/Upper_Arm_v10_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
<material/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0.25 -1.43455 -0.1"/>
<geometry>
<mesh filename="meshes/Upper_Arm_v10_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="Lower_Arm_v8_1">
<inertial>
<origin rpy="0 0 0" xyz="-1.6264767310758543e-14 -0.22711717106463236 -0.05000000000000018"/>
<mass value="1.1287862597517475"/>
<inertia ixx="0.025545638419054995" ixy="1.7486012637846216e-15" ixz="5.367234434672241e-15" iyy="0.0030604925430051527" iyz="0.0" izz="0.025477987567271376"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0.25 -1.06705 -0.15"/>
<geometry>
<mesh filename="meshes/Lower_Arm_v8_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
<material/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0.25 -1.06705 -0.15"/>
<geometry>
<mesh filename="meshes/Lower_Arm_v8_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="Upper_Arm_Link_type_b_v9_2">
<inertial>
<origin rpy="0 0 0" xyz="0.039310458006444615 -0.01095588172168327 -2.3592239273284576e-16"/>
<mass value="0.11011202726048713"/>
<inertia ixx="0.00016930933911268875" ixy="1.861439297219658e-05" ixz="8.673617379884035e-19" iyy="0.00022075846035969626" iyz="3.469446951953614e-18" izz="0.00018206077085142214"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="-0.375 -1.5034 -0.1"/>
<geometry>
<mesh filename="meshes/Upper_Arm_Link_type_b_v9_2.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
<material/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="-0.375 -1.5034 -0.1"/>
<geometry>
<mesh filename="meshes/Upper_Arm_Link_type_b_v9_2.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="Upper_Arm_Roll_Link_v5_2">
<inertial>
<origin rpy="0 0 0" xyz="1.1102230246251565e-16 -0.022135117628713674 0.04999999999999988"/>
<mass value="0.29143432706119626"/>
<inertia ixx="0.001232763287600247" ixy="-2.7755575615628914e-17" ixz="-3.469446951953614e-18" iyy="0.0011938412922212066" iyz="6.938893903907228e-18" izz="0.0002924682777396548"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="-0.45 -1.4909 -0.05"/>
<geometry>
<mesh filename="meshes/Upper_Arm_Roll_Link_v5_2.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
<material/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="-0.45 -1.4909 -0.05"/>
<geometry>
<mesh filename="meshes/Upper_Arm_Roll_Link_v5_2.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="Upper_Arm_v10_3">
<inertial>
<origin rpy="0 0 0" xyz="-9.469650730231649e-09 -0.2073127422998453 -1.249000902703301e-16"/>
<mass value="0.9419240929020993"/>
<inertia ixx="0.019683528982801235" ixy="-1.63538982356215e-09" ixz="5.377642775528102e-15" iyy="0.00349831999855843" iyz="2.7755575615628914e-17" izz="0.018812734327517733"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="-0.45 -1.43455 -0.1"/>
<geometry>
<mesh filename="meshes/Upper_Arm_v10_3.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
<material/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="-0.45 -1.43455 -0.1"/>
<geometry>
<mesh filename="meshes/Upper_Arm_v10_3.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="Lower_Arm_v8_2">
<inertial>
<origin rpy="0 0 0" xyz="-1.6264767310758543e-14 -0.22711717106463236 0.04999999999999989"/>
<mass value="1.1287862597517475"/>
<inertia ixx="0.025545638419054995" ixy="1.7208456881689926e-15" ixz="5.370703881624195e-15" iyy="0.0030604925430051666" iyz="0.0" izz="0.02547798756727171"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="-0.45 -1.06705 -0.05"/>
<geometry>
<mesh filename="meshes/Lower_Arm_v8_2.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
<material/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="-0.45 -1.06705 -0.05"/>
<geometry>
<mesh filename="meshes/Lower_Arm_v8_2.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="Leg_Pitch_v5_1">
<inertial>
<origin rpy="0 0 0" xyz="-0.04683508876022923 0.003164911239771029 -1.249000902703301e-16"/>
<mass value="0.3280666863874879"/>
<inertia ixx="0.0010883631339249633" ixy="5.307553597740794e-05" ixz="0.0" iyy="0.0010883631339250101" iyz="-3.469446951953614e-18" izz="0.0009464761938969279"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="-0.0 -0.812 -0.1"/>
<geometry>
<mesh filename="meshes/Leg_Pitch_v5_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
<material/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="-0.0 -0.812 -0.1"/>
<geometry>
<mesh filename="meshes/Leg_Pitch_v5_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="Leg_Roll_v4_1">
<inertial>
<origin rpy="0 0 0" xyz="4.163336342344337e-17 -0.035223067053444135 0.07499999999999987"/>
<mass value="1.3532798434145876"/>
<inertia ixx="0.008928053332240893" ixy="2.0816681711721685e-17" ixz="2.6020852139652106e-18" iyy="0.008372644528454914" iyz="1.3877787807814457e-17" izz="0.002693883608054226"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0.05 -0.812 -0.025"/>
<geometry>
<mesh filename="meshes/Leg_Roll_v4_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
<material/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0.05 -0.812 -0.025"/>
<geometry>
<mesh filename="meshes/Leg_Roll_v4_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="Upper_Leg_v4_1">
<inertial>
<origin rpy="0 0 0" xyz="1.1102230246251565e-16 -0.15757232755407236 -1.8041124150158794e-16"/>
<mass value="1.7214182603818151"/>
<inertia ixx="0.023647064861463618" ixy="6.938893903907228e-18" ixz="1.734723475976807e-18" iyy="0.012028681141913265" iyz="0.0" izz="0.02456431452088892"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0.05 -0.737 -0.1"/>
<geometry>
<mesh filename="meshes/Upper_Leg_v4_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
<material/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0.05 -0.737 -0.1"/>
<geometry>
<mesh filename="meshes/Upper_Leg_v4_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="Lower_Leg_v6_1">
<inertial>
<origin rpy="0 0 0" xyz="0.04999999999999136 -0.14147821247779935 -2.220446049250313e-16"/>
<mass value="1.4272888897799032"/>
<inertia ixx="0.020272030317633083" ixy="-1.321859288694327e-15" ixz="-2.2083029849184754e-15" iyy="0.0030707995313369076" iyz="2.0816681711721685e-17" izz="0.0202788236044206"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0.1 -0.4388 -0.1"/>
<geometry>
<mesh filename="meshes/Lower_Leg_v6_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
<material/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0.1 -0.4388 -0.1"/>
<geometry>
<mesh filename="meshes/Lower_Leg_v6_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="Ankle_Link_v5_1">
<inertial>
<origin rpy="0 0 0" xyz="1.3877787807814457e-16 -0.014239102534719106 0.02999999999999975"/>
<mass value="0.02966359637804546"/>
<inertia ixx="3.134717230673462e-05" ixy="4.0657581468206416e-20" ixz="-2.710505431213761e-20" iyy="1.4582407636994814e-05" iyz="-8.131516293641283e-20" izz="2.6914982867941583e-05"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0.05 -0.0856 -0.07"/>
<geometry>
<mesh filename="meshes/Ankle_Link_v5_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
<material/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0.05 -0.0856 -0.07"/>
<geometry>
<mesh filename="meshes/Ankle_Link_v5_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="Foot_v4_1">
<inertial>
<origin rpy="0 0 0" xyz="0.019685521169740886 -0.04039401004788472 0.03625642783112948"/>
<mass value="0.8921618023336354"/>
<inertia ixx="0.005514801902865251" ixy="-1.2922841769047867e-06" ixz="2.766319069131759e-06" iyy="0.0072372522773541705" iyz="0.00014898811458507826" izz="0.0019767483724834646"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0.07 -0.0506 -0.1"/>
<geometry>
<mesh filename="meshes/Foot_v4_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
<material/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0.07 -0.0506 -0.1"/>
<geometry>
<mesh filename="meshes/Foot_v4_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="Leg_Pitch_v5_2">
<inertial>
<origin rpy="0 0 0" xyz="0.046835088760229515 0.003164911239771029 -1.1102230246251565e-16"/>
<mass value="0.3280666863874879"/>
<inertia ixx="0.0010883631339249633" ixy="-5.307553597741488e-05" ixz="-1.734723475976807e-18" iyy="0.0010883631339250188" iyz="0.0" izz="0.0009464761938969279"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="-0.2 -0.812 -0.1"/>
<geometry>
<mesh filename="meshes/Leg_Pitch_v5_2.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
<material/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="-0.2 -0.812 -0.1"/>
<geometry>
<mesh filename="meshes/Leg_Pitch_v5_2.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="Leg_Roll_v4_2">
<inertial>
<origin rpy="0 0 0" xyz="3.3306690738754696e-16 -0.035223067053444135 0.0749999999999999"/>
<mass value="1.3532798434145876"/>
<inertia ixx="0.008928053332240893" ixy="-5.551115123125783e-17" ixz="-6.938893903907228e-18" iyy="0.008372644528454903" iyz="-1.3877787807814457e-17" izz="0.002693883608054337"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="-0.25 -0.812 -0.025"/>
<geometry>
<mesh filename="meshes/Leg_Roll_v4_2.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
<material/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="-0.25 -0.812 -0.025"/>
<geometry>
<mesh filename="meshes/Leg_Roll_v4_2.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="Upper_Leg_v4_2">
<inertial>
<origin rpy="0 0 0" xyz="3.885780586188048e-16 -0.15757232755407236 -1.249000902703301e-16"/>
<mass value="1.7214182603818151"/>
<inertia ixx="0.023647064861463618" ixy="-5.551115123125783e-17" ixz="0.0" iyy="0.012028681141913258" iyz="0.0" izz="0.02456431452088892"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="-0.25 -0.737 -0.1"/>
<geometry>
<mesh filename="meshes/Upper_Leg_v4_2.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
<material/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="-0.25 -0.737 -0.1"/>
<geometry>
<mesh filename="meshes/Upper_Leg_v4_2.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="Lower_Leg_v6_2">
<inertial>
<origin rpy="0 0 0" xyz="-0.05000000000000834 -0.14147821247779935 -9.71445146547012e-17"/>
<mass value="1.4272888897799032"/>
<inertia ixx="0.02027203031763311" ixy="-1.2906342661267445e-15" ixz="-2.2065682614424986e-15" iyy="0.003070799531336932" iyz="2.7755575615628914e-17" izz="0.0202788236044206"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="-0.3 -0.4388 -0.1"/>
<geometry>
<mesh filename="meshes/Lower_Leg_v6_2.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
<material/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="-0.3 -0.4388 -0.1"/>
<geometry>
<mesh filename="meshes/Lower_Leg_v6_2.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="Ankle_Link_v5_2">
<inertial>
<origin rpy="0 0 0" xyz="3.3306690738754696e-16 -0.014239102534719106 0.03"/>
<mass value="0.02966359637804546"/>
<inertia ixx="3.134717230673467e-05" ixy="-1.0842021724855044e-19" ixz="1.0842021724855044e-19" iyy="1.4582407636995302e-05" iyz="-8.131516293641283e-20" izz="2.6914982867942694e-05"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="-0.25 -0.0856 -0.07"/>
<geometry>
<mesh filename="meshes/Ankle_Link_v5_2.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
<material/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="-0.25 -0.0856 -0.07"/>
<geometry>
<mesh filename="meshes/Ankle_Link_v5_2.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="Foot_v4_2">
<inertial>
<origin rpy="0 0 0" xyz="-0.020314478830258637 -0.040394010047884774 0.03625642783112962"/>
<mass value="0.8921618023336354"/>
<inertia ixx="0.0055148019028652545" ixy="-1.2922841769041904e-06" ixz="2.766319069126555e-06" iyy="0.007237252277354292" iyz="0.00014898811458507587" izz="0.001976748372483461"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="-0.27 -0.0506 -0.1"/>
<geometry>
<mesh filename="meshes/Foot_v4_2.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
<material/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="-0.27 -0.0506 -0.1"/>
<geometry>
<mesh filename="meshes/Foot_v4_2.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<joint name="Rev1" type="continuous">
<origin rpy="0 0 0" xyz="0.05 0.912 0.1"/>
<parent link="base_link"/>
<child link="Pelvis_v7_1"/>
<axis xyz="1.0 -0.0 -0.0"/>
</joint>
<transmission name="Rev1_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="Rev1">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="Rev1_actr">
<hardwareInterface>PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<joint name="Rev2" type="continuous">
<origin rpy="0 0 0" xyz="0.05 0.075 -0.0375"/>
<parent link="Pelvis_v7_1"/>
<child link="Chest_v13_1"/>
<axis xyz="-0.0 -0.0 -1.0"/>
</joint>
<transmission name="Rev2_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="Rev2">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="Rev2_actr">
<hardwareInterface>PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<joint name="Rev11" type="continuous">
<origin rpy="0 0 0" xyz="0.0 0.5664 0.0375"/>
<parent link="Chest_v13_1"/>
<child link="Box_Head_v5_1"/>
<axis xyz="0.0 1.0 -0.0"/>
</joint>
<transmission name="Rev11_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="Rev11">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="Rev11_actr">
<hardwareInterface>PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<joint name="Rev3" type="continuous">
<origin rpy="0 0 0" xyz="-0.275 0.5164 0.0375"/>
<parent link="Chest_v13_1"/>
<child link="Upper_Arm_Link_type_b_v9_1"/>
<axis xyz="-1.0 0.0 0.0"/>
</joint>
<transmission name="Rev3_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="Rev3">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="Rev3_actr">
<hardwareInterface>PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<joint name="Rev4" type="continuous">
<origin rpy="0 0 0" xyz="-0.075 -0.0125 -0.05"/>
<parent link="Upper_Arm_Link_type_b_v9_1"/>
<child link="Upper_Arm_Roll_Link_v5_1"/>
<axis xyz="0.0 -0.0 -1.0"/>
</joint>
<transmission name="Rev4_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="Rev4">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="Rev4_actr">
<hardwareInterface>PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<joint name="Rev5" type="continuous">
<origin rpy="0 0 0" xyz="0.0 -0.05635 0.05"/>
<parent link="Upper_Arm_Roll_Link_v5_1"/>
<child link="Upper_Arm_v10_1"/>
<axis xyz="-0.0 -1.0 0.0"/>
</joint>
<transmission name="Rev5_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="Rev5">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="Rev5_actr">
<hardwareInterface>PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<joint name="Rev6" type="continuous">
<origin rpy="0 0 0" xyz="0.0 -0.3675 0.05"/>
<parent link="Upper_Arm_v10_1"/>
<child link="Lower_Arm_v8_1"/>
<axis xyz="0.0 -0.0 -1.0"/>
</joint>
<transmission name="Rev6_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="Rev6">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="Rev6_actr">
<hardwareInterface>PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<joint name="Rev7" type="continuous">
<origin rpy="0 0 0" xyz="0.275 0.5164 0.0375"/>
<parent link="Chest_v13_1"/>
<child link="Upper_Arm_Link_type_b_v9_2"/>
<axis xyz="1.0 -0.0 -0.0"/>
</joint>
<transmission name="Rev7_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="Rev7">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="Rev7_actr">
<hardwareInterface>PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<joint name="Rev8" type="continuous">
<origin rpy="0 0 0" xyz="0.075 -0.0125 -0.05"/>
<parent link="Upper_Arm_Link_type_b_v9_2"/>
<child link="Upper_Arm_Roll_Link_v5_2"/>
<axis xyz="0.0 -0.0 -1.0"/>
</joint>
<transmission name="Rev8_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="Rev8">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="Rev8_actr">
<hardwareInterface>PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<joint name="Rev9" type="continuous">
<origin rpy="0 0 0" xyz="0.0 -0.05635 0.05"/>
<parent link="Upper_Arm_Roll_Link_v5_2"/>
<child link="Upper_Arm_v10_3"/>
<axis xyz="0.0 -1.0 0.0"/>
</joint>
<transmission name="Rev9_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="Rev9">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="Rev9_actr">
<hardwareInterface>PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<joint name="Rev10" type="continuous">
<origin rpy="0 0 0" xyz="0.0 -0.3675 -0.05"/>
<parent link="Upper_Arm_v10_3"/>
<child link="Lower_Arm_v8_2"/>
<axis xyz="-0.0 0.0 1.0"/>
</joint>
<transmission name="Rev10_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="Rev10">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="Rev10_actr">
<hardwareInterface>PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<joint name="Rev12" type="continuous">
<origin rpy="0 0 0" xyz="0.0 0.812 0.1"/>
<parent link="base_link"/>
<child link="Leg_Pitch_v5_1"/>
<axis xyz="-1.0 0.0 0.0"/>
</joint>
<transmission name="Rev12_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="Rev12">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="Rev12_actr">
<hardwareInterface>PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<joint name="Rev13" type="continuous">
<origin rpy="0 0 0" xyz="-0.05 0.0 -0.075"/>
<parent link="Leg_Pitch_v5_1"/>
<child link="Leg_Roll_v4_1"/>
<axis xyz="0.0 0.0 -1.0"/>
</joint>
<transmission name="Rev13_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="Rev13">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="Rev13_actr">
<hardwareInterface>PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<joint name="Rev14" type="continuous">
<origin rpy="0 0 0" xyz="0.0 -0.075 0.075"/>
<parent link="Leg_Roll_v4_1"/>
<child link="Upper_Leg_v4_1"/>
<axis xyz="0.0 -1.0 0.0"/>
</joint>
<transmission name="Rev14_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="Rev14">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="Rev14_actr">
<hardwareInterface>PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<joint name="Rev15" type="continuous">
<origin rpy="0 0 0" xyz="-0.05 -0.2982 0.0"/>
<parent link="Upper_Leg_v4_1"/>
<child link="Lower_Leg_v6_1"/>
<axis xyz="1.0 -0.0 -0.0"/>
</joint>
<transmission name="Rev15_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="Rev15">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="Rev15_actr">
<hardwareInterface>PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<joint name="Rev16" type="continuous">
<origin rpy="0 0 0" xyz="0.05 -0.3532 -0.03"/>
<parent link="Lower_Leg_v6_1"/>
<child link="Ankle_Link_v5_1"/>
<axis xyz="-0.0 0.0 1.0"/>
</joint>
<transmission name="Rev16_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="Rev16">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="Rev16_actr">
<hardwareInterface>PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<joint name="Rev19" type="continuous">
<origin rpy="0 0 0" xyz="-0.02 -0.035 0.03"/>
<parent link="Ankle_Link_v5_1"/>
<child link="Foot_v4_1"/>
<axis xyz="-1.0 0.0 0.0"/>
</joint>
<transmission name="Rev19_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="Rev19">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="Rev19_actr">
<hardwareInterface>PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<joint name="Rev20" type="continuous">
<origin rpy="0 0 0" xyz="0.2 0.812 0.1"/>
<parent link="base_link"/>
<child link="Leg_Pitch_v5_2"/>
<axis xyz="1.0 -0.0 -0.0"/>
</joint>
<transmission name="Rev20_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="Rev20">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="Rev20_actr">
<hardwareInterface>PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<joint name="Rev21" type="continuous">
<origin rpy="0 0 0" xyz="0.05 0.0 -0.075"/>
<parent link="Leg_Pitch_v5_2"/>
<child link="Leg_Roll_v4_2"/>
<axis xyz="-0.0 -0.0 -1.0"/>
</joint>
<transmission name="Rev21_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="Rev21">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="Rev21_actr">
<hardwareInterface>PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<joint name="Rev22" type="continuous">
<origin rpy="0 0 0" xyz="0.0 -0.075 0.075"/>
<parent link="Leg_Roll_v4_2"/>
<child link="Upper_Leg_v4_2"/>
<axis xyz="0.0 -1.0 0.0"/>
</joint>
<transmission name="Rev22_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="Rev22">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="Rev22_actr">
<hardwareInterface>PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<joint name="Rev23" type="continuous">
<origin rpy="0 0 0" xyz="0.05 -0.2982 0.0"/>
<parent link="Upper_Leg_v4_2"/>
<child link="Lower_Leg_v6_2"/>
<axis xyz="-1.0 0.0 0.0"/>
</joint>
<transmission name="Rev23_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="Rev23">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="Rev23_actr">
<hardwareInterface>PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<joint name="Rev24" type="continuous">
<origin rpy="0 0 0" xyz="-0.05 -0.3532 -0.03"/>
<parent link="Lower_Leg_v6_2"/>
<child link="Ankle_Link_v5_2"/>
<axis xyz="-0.0 0.0 1.0"/>
</joint>
<transmission name="Rev24_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="Rev24">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="Rev24_actr">
<hardwareInterface>PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<joint name="Rev25" type="continuous">
<origin rpy="0 0 0" xyz="0.02 -0.035 0.03"/>
<parent link="Ankle_Link_v5_2"/>
<child link="Foot_v4_2"/>
<axis xyz="1.0 -0.0 -0.0"/>
</joint>
<transmission name="Rev25_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="Rev25">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="Rev25_actr">
<hardwareInterface>PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</robot>

View File

@ -0,0 +1,21 @@
#VRML_SIM R2021b utf8
WorldInfo {
coordinateSystem "NUE"
}
Viewpoint {
orientation -0.327371148027798 0.9433342304028307 0.05430157630548854 0.3481123552732844
position 2.1847428400064097 1.561713095144657 5.520447064408197
}
TexturedBackground {
}
TexturedBackgroundLight {
}
Floor {
appearance Parquetry {
type "dark strip"
}
}
Olympian {
controller "squatanalysis"
supervisor TRUE
}