-
Notifications
You must be signed in to change notification settings - Fork 0
/
random_obstacles_avoidance_dribble_env.py
141 lines (125 loc) · 5.98 KB
/
random_obstacles_avoidance_dribble_env.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
139
140
141
import numpy as np
from mujoco_py import load_model_from_path, MjSim, MjViewer
from mymjviewer import MyMjViewer
from matplotlib import pyplot as plt
import random
import glfw
import time
import math
import os
import datetime
class Dribble_Env(object):
def __init__(self):
self.model = load_model_from_path("./xml/world7.xml")
self.sim = MjSim(self.model)
self.viewer = MyMjViewer(self.sim)
self.max_vel = [-1000,1000]
self.x_motor = 0
self.y_motor = 0
self.date_time = datetime.datetime.now()
self.path = "./datas/path_date_random" + str(self.date_time.strftime("_%Y%m%d_%H%M%S"))
os.mkdir(self.path)
def step(self,action):
self.x_motor = ((action %3)-1) * 200
self.y_motor = ((action//3)-1) * 200
self.sim.data.ctrl[0] = self.x_motor
self.sim.data.ctrl[1] = self.y_motor
self.sim.step()
def get_state(self):
robot_x, robot_y = self.sim.data.body_xpos[1][0:2]
robot_xv, robot_yv = self.sim.data.qvel[0:2]
ball_x, ball_y = self.sim.data.body_xpos[2][0:2]
ball_xv, ball_yv = self.sim.data.qvel[2:4]
ball_pos_local = -(robot_x - ball_x), -(robot_y - ball_y)
object1_x, object1_y= self.sim.data.body_xpos[3][0] - robot_x, self.sim.data.body_xpos[3][1] - robot_y
object2_x, object2_y= self.sim.data.body_xpos[4][0] - robot_x, self.sim.data.body_xpos[4][1] - robot_y
object3_x, object3_y= self.sim.data.body_xpos[5][0] - robot_x, self.sim.data.body_xpos[5][1] - robot_y
object4_x, object4_y= self.sim.data.body_xpos[6][0] - robot_x, self.sim.data.body_xpos[6][1] - robot_y
return [robot_x, robot_y, ball_pos_local[0], ball_pos_local[1], \
robot_xv, robot_yv,object1_x,object1_y,object2_x,object2_y,object3_x,object3_y,object4_x,object4_y,\
ball_x, ball_y,ball_xv,ball_yv]
def check_done(self):
ball_x ,ball_y = self.get_state()[14:16]
if ball_x > 80 and -25 < ball_y < 25:
return True
else:
return False
def check_wall(self):
ball_x, ball_y = self.get_state()[14:16]
if math.fabs(ball_y) > 51:
return True
elif ball_x > 81 and math.fabs(ball_y) > 25:
return True
else:
return False
def check_avoidaince(self,object_num=4):
for i in range(object_num):
if math.fabs(self.sim.data.qvel[5+i*3]) > 0.1 or math.fabs(self.sim.data.qvel[6+3*i]) > 0.1:
return True
return False
def reset(self):
self.x_motor = 0
self.y_motor = 0
self.robot_x_data = []
self.robot_y_data = []
self.ball_x_data = []
self.ball_y_data = []
self.object1_x_data = []
self.object1_y_data = []
self.object2_x_data = []
self.object2_y_data = []
self.object3_x_data = []
self.object3_y_data = []
self.object4_x_data = []
self.object4_y_data = []
self.sim.reset()
# self.sim.data.qpos[0] = np.random.randint(-3,3)
self.sim.data.qpos[1] = np.random.randint(-5,5)
self.sim.data.qpos[5] = np.random.randint(-5,5)
self.sim.data.qpos[6] = np.random.randint(-50,50)
self.sim.data.qpos[8] = np.random.randint(-5,5)
self.sim.data.qpos[9] = np.random.randint(-50,50)
self.sim.data.qpos[11] = np.random.randint(-5,5)
self.sim.data.qpos[12] = np.random.randint(-50,50)
self.sim.data.qpos[14] = np.random.randint(-5,5)
self.sim.data.qpos[15] = np.random.randint(-50,50)
def render(self):
self.viewer.render()
def plot_data(self,step,t,done,episode,flag,reward):
self.field_x = [-90,-90,90,90,-90]
self.field_y = [-60,60,60,-60,-60]
self.robot_x_data.append(self.sim.data.body_xpos[1][0])
self.robot_y_data.append(self.sim.data.body_xpos[1][1])
self.ball_x_data.append(self.sim.data.body_xpos[2][0])
self.ball_y_data.append(self.sim.data.body_xpos[2][1])
self.object1_x_data.append(self.sim.data.body_xpos[3][0])
self.object1_y_data.append(self.sim.data.body_xpos[3][1])
self.object2_x_data.append(self.sim.data.body_xpos[4][0])
self.object2_y_data.append(self.sim.data.body_xpos[4][1])
self.object3_x_data.append(self.sim.data.body_xpos[5][0])
self.object3_y_data.append(self.sim.data.body_xpos[5][1])
self.object4_x_data.append(self.sim.data.body_xpos[6][0])
self.object4_y_data.append(self.sim.data.body_xpos[6][1])
datas = str(self.robot_x_data[-1])+" "+str(self.robot_y_data[-1])+" "\
+str(self.ball_x_data[-1])+" "+str(self.ball_y_data[-1])+" "\
+str(self.object1_x_data[-1])+" "+str(self.object1_y_data[-1])+" "\
+str(self.object2_x_data[-1])+" "+str(self.object2_y_data[-1])+" "\
+str(self.object3_x_data[-1])+" "+str(self.object3_y_data[-1])+" "\
+str(self.object4_x_data[-1])+" "+str(self.object4_y_data[-1])+" "\
+str(reward)
with open(self.path + '/plotdata_' + str(episode+1).zfill(4)+ '.txt','a') as f:
f.write(str(datas)+'\n')
if (t >= step-1 or done) and flag:
fig1 = plt.figure()
plt.ion()
plt.show()
plt.plot(self.ball_x_data,self.ball_y_data,marker='o',markersize=2,color="red",label="ball")
plt.plot(self.robot_x_data,self.robot_y_data,marker="o",markersize=2,color='blue',label="robot")
plt.plot(self.object_x_data,self.object_y_data,marker="o",markersize=10,label="object")
plt.plot(self.sim.data.body_xpos[3][0],self.sim.data.body_xpos[3][1],marker="o",markersize=16,color='black')
plt.plot(self.field_x,self.field_y,markersize=1,color="black")
plt.plot(80,0,marker="X",color="green",label="goal")
plt.legend(loc="lower right")
plt.draw()
plt.pause(0.001)
plt.close(1)