forked from tjmccue00/Thesis-Code
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Move_Cart_Pole.py
executable file
·138 lines (110 loc) · 4.23 KB
/
Move_Cart_Pole.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
import math
import numpy as np
from isaacgym import gymapi, gymutil
def clamp(x, min_value, max_value):
return max(min(x, max_value), min_value)
model_file = r"/home/tjmccue/Documents/Thesis/Cart and Pendulum Model/URDF Model v2/Cart and Pendelum Assembly/urdf"
model_file_name = r"Cart and Pendelum Assembly.urdf"
gym = gymapi.acquire_gym()
sim_Params = gymapi.SimParams()
dt = 1.0/60
use_GPU = True
GPU_pipeline = False
sim_Params.physx.solver_type = 1
sim_Params.physx.num_position_iterations = 6
sim_Params.physx.num_position_iterations = 1
sim_Params.physx.use_gpu = use_GPU
sim_Params.dt = dt
sim = gym.create_sim(0, 0, gymapi.SimType.SIM_PHYSX, sim_Params)
if sim is None:
print("Couldn't create simulation")
quit()
plane_parameters = gymapi.PlaneParams()
gym.add_ground(sim, plane_parameters)
camera = gym.create_viewer(sim, gymapi.CameraProperties())
if camera is None:
print("Couldn't create camera")
quit()
asset_opts = gymapi.AssetOptions()
asset_opts.fix_base_link = True
asset_opts.use_mesh_materials = True
asset_opts.collapse_fixed_joints = True
asset_opts.default_dof_drive_mode = gymapi.DOF_MODE_POS
asset_opts.thickness = 0.001
asset = gym.load_asset(sim, model_file, model_file_name, asset_opts)
joint_names = gym.get_asset_dof_names(asset)
joint_props = gym.get_asset_dof_properties(asset)
num_joints = gym.get_asset_dof_count(asset)
joint_state = np.zeros(num_joints, dtype=gymapi.DofState.dtype)
joint_types = [gym.get_asset_dof_type(asset, i) for i in range(num_joints)]
joint_pos = joint_state['pos']
has_lim = joint_props['hasLimits']
low_lim = joint_props['lower']
up_lim = joint_props['upper']
defaults = np.zeros(num_joints)
speeds = np.zeros(num_joints)
for i in range(num_joints):
if has_lim[i]:
if joint_types[i] == gymapi.DOF_ROTATION:
low_lim[i] = clamp(low_lim[i], -math.pi, math.pi)
up_lim[i] = clamp(up_lim[i], -math.pi, math.pi)
if low_lim[i] > 0:
defaults[i] = low_lim[i]
elif up_lim[i] < 0:
defaults[i] = up_lim[i]
else:
if joint_types[i] == gymapi.DOF_ROTATION:
low_lim[i] = -math.pi/2
up_lim[i] = math.pi/2
elif joint_types[i] == gymapi.DOF_TRANSLATION:
low_lim[i] = -0.5
up_lim[i] = 0.5
joint_pos[i] = defaults[i]
if joint_types[i] == gymapi.DOF_ROTATION:
speeds[i] = 0.5 * clamp(2 * (up_lim[i] - low_lim[i]), 0.25 * math.pi, 3.0 * math.pi)
else:
speeds[i] = 0.5 * clamp(2 * (up_lim[i] - low_lim[i]), 0.1, 5.0)
env_lower = gymapi.Vec3(-1, 0.0, -1)
env_upper = gymapi.Vec3(1, 1, 1)
environ = gym.create_env(sim, env_lower, env_upper, 1)
pose = gymapi.Transform()
pose.p = gymapi.Vec3(0.0, 0, 0.0)
pose.r = gymapi.Quat(0.7071, 0, 0, -0.7071)
actor_handle = gym.create_actor(environ, asset, pose)
gym.set_actor_dof_states(environ, actor_handle, joint_state, gymapi.STATE_ALL)
print(joint_state)
ANIM_LOWER = 1
ANIM_UPPER = 2
ANIM_DEFAULT = 3
ANIM_FINISHED = 4
animation = ANIM_LOWER
current_joint = 0
while not gym.query_viewer_has_closed(camera):
gym.simulate(sim)
gym.fetch_results(sim, True)
speed = speeds[current_joint]
if animation == ANIM_LOWER:
joint_pos[current_joint] -= speed * dt
if joint_pos[current_joint] <= low_lim[current_joint]:
joint_pos[current_joint] = low_lim[current_joint]
animation = ANIM_UPPER
elif animation == ANIM_UPPER:
joint_pos[current_joint] += speed * dt
if joint_pos[current_joint] >= up_lim[current_joint]:
joint_pos[current_joint] = up_lim[current_joint]
animation = ANIM_DEFAULT
elif animation == ANIM_DEFAULT:
joint_pos[current_joint] -= speed * dt
if joint_pos[current_joint] <= defaults[current_joint]:
joint_pos[current_joint] = defaults[current_joint]
animation = ANIM_FINISHED
elif animation == ANIM_FINISHED:
joint_pos[current_joint] = defaults[current_joint]
current_joint = (current_joint + 1) % num_joints
animation = ANIM_LOWER
gym.set_actor_dof_states(environ, actor_handle, joint_state, gymapi.STATE_POS)
gym.step_graphics(sim)
gym.draw_viewer(camera, sim, True)
gym.sync_frame_time(sim)
gym.destroy_viewer(camera)
gym.destroy_sim(sim)