-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathcodrone_env.py
263 lines (263 loc) · 10.3 KB
/
codrone_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
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
{
"cells": [
{
"cell_type": "code",
"execution_count": null,
"metadata": {},
"outputs": [],
"source": [
"#!/usr/bin/env python\n",
"\n",
"import gym\n",
"import rospy\n",
"import time\n",
"import numpy as np\n",
"import tf\n",
"import time\n",
"from gym import utils, spaces\n",
"from geometry_msgs.msg import Twist, Vector3Stamped, Pose\n",
"from hector_uav_msgs.msg import Altimeter\n",
"from sensor_msgs.msg import Imu\n",
"from std_msgs.msg import Empty as EmptyTopicMsg\n",
"from gym.utils import seeding\n",
"from gym.envs.registration import register\n",
"from gazebo_connection import GazeboConnection\n",
"\n",
"#register the training environment in the gym as an available one\n",
"reg = register(\n",
" id='CodroneEnv-v0',\n",
" entry_point='codrone_env:CodroneEnv',\n",
" timestep_limit=1000,\n",
" )\n",
"\n",
"class CodroneEnv(gym.Env):\n",
"\n",
" def __init__(self):\n",
" \n",
" # We assume that a ROS node has already been created\n",
" # before initialising the environment\n",
" \n",
" self.vel_pub = rospy.Publisher('/cmd_vel', Twist, queue_size=5)\n",
" self.takeoff_pub = rospy.Publisher('/drone/takeoff', EmptyTopicMsg, queue_size=0)\n",
" \n",
" # gets training parameters from param server\n",
" self.speed_value = rospy.get_param(\"/speed_value\")\n",
" self.desired_pose = Pose()\n",
" self.desired_pose.position.z = rospy.get_param(\"/desired_pose/z\")\n",
" self.desired_pose.position.x = rospy.get_param(\"/desired_pose/x\")\n",
" self.desired_pose.position.y = rospy.get_param(\"/desired_pose/y\")\n",
" self.running_step = rospy.get_param(\"/running_step\")\n",
" self.max_incl = rospy.get_param(\"/max_incl\")\n",
" self.max_altitude = rospy.get_param(\"/max_altitude\")\n",
" \n",
" # stablishes connection with simulator\n",
" self.gazebo = GazeboConnection()\n",
" \n",
" self.action_space = spaces.Discrete(5) #Forward,Left,Right,Up,Down\n",
" self.reward_range = (-np.inf, np.inf)\n",
"\n",
" self._seed()\n",
"\n",
" # A function to initialize the random generator\n",
" def _seed(self, seed=None):\n",
" self.np_random, seed = seeding.np_random(seed)\n",
" return [seed]\n",
" \n",
" # Resets the state of the environment and returns an initial observation.\n",
" def _reset(self):\n",
" \n",
" # 1st: resets the simulation to initial values\n",
" self.gazebo.resetSim()\n",
"\n",
" # 2nd: Unpauses simulation\n",
" self.gazebo.unpauseSim()\n",
"\n",
" # 3rd: resets the robot to initial conditions\n",
" self.check_topic_publishers_connection()\n",
" self.init_desired_pose()\n",
" self.takeoff_sequence()\n",
"\n",
" # 4th: takes an observation of the initial condition of the robot\n",
" data_pose, data_imu = self.take_observation()\n",
" observation = [data_pose.position.z]\n",
" \n",
" # 5th: pauses simulation\n",
" self.gazebo.pauseSim()\n",
"\n",
" return observation\n",
"\n",
" def _step(self, action):\n",
"\n",
" # Given the action selected by the learning algorithm,\n",
" # we perform the corresponding movement of the robot\n",
" \n",
" # 1st, we decide which velocity command corresponds\n",
" vel_cmd = Twist()\n",
" if action == 0: #FORWARD\n",
" vel_cmd.linear.x = self.speed_value\n",
" vel_cmd.angular.z = 0.0\n",
" elif action == 1: #LEFT\n",
" vel_cmd.linear.x = 0.05\n",
" vel_cmd.angular.z = self.speed_value\n",
" elif action == 2: #RIGHT\n",
" vel_cmd.linear.x = 0.05\n",
" vel_cmd.angular.z = -self.speed_value\n",
" elif action == 3: #Up\n",
" vel_cmd.linear.z = self.speed_value\n",
" vel_cmd.angular.z = 0.0\n",
" elif action == 4: #Down\n",
" vel_cmd.linear.z = -self.speed_value\n",
" vel_cmd.angular.z = 0.0\n",
"\n",
" # Then we send the command to the robot and let it go\n",
" # for running_step seconds\n",
" self.gazebo.unpauseSim()\n",
" self.vel_pub.publish(vel_cmd)\n",
" time.sleep(self.running_step)\n",
" data_pose, data_imu = self.take_observation()\n",
" self.gazebo.pauseSim()\n",
"\n",
" # finally we get an evaluation based on what happened in the sim\n",
" reward,done = self.process_data(data_pose, data_imu)\n",
"\n",
" # Promote going forwards instead of turning\n",
" if action == 0:\n",
" reward -= 50\n",
" elif action == 1 or action == 2:\n",
" reward -= 50\n",
" elif action == 3:\n",
" reward += 100\n",
" else:\n",
" reward -= 50\n",
"\n",
" state = [data_pose.position.x]\n",
" return state, reward, done, {}\n",
"\n",
"\n",
" def take_observation (self):\n",
" data_pose = None\n",
" while data_pose is None:\n",
" try:\n",
" data_pose = rospy.wait_for_message('/drone/gt_pose', Pose, timeout=5)\n",
" except:\n",
" rospy.loginfo(\"Current drone pose not ready yet, retrying for getting robot pose\")\n",
"\n",
" data_imu = None\n",
" while data_imu is None:\n",
" try:\n",
" data_imu = rospy.wait_for_message('/drone/imu', Imu, timeout=5)\n",
" except:\n",
" rospy.loginfo(\"Current drone imu not ready yet, retrying for getting robot imu\")\n",
" \n",
" return data_pose, data_imu\n",
"\n",
" def calculate_dist_between_two_Points(self,p_init,p_end):\n",
" a = np.array((p_init.x ,p_init.y, p_init.z))\n",
" b = np.array((p_end.x ,p_end.y, p_end.z))\n",
" \n",
" dist = np.linalg.norm(a-b)\n",
" \n",
" return dist\n",
"\n",
"\n",
" def init_desired_pose(self):\n",
" \n",
" current_init_pose, imu = self.take_observation()\n",
" \n",
" self.best_dist = self.calculate_dist_between_two_Points(current_init_pose.position, self.desired_pose.position)\n",
" \n",
"\n",
" def check_topic_publishers_connection(self):\n",
" \n",
" rate = rospy.Rate(10) # 10hz\n",
" while(self.takeoff_pub.get_num_connections() == 0):\n",
" rospy.loginfo(\"No susbribers to Takeoff yet so we wait and try again\")\n",
" rate.sleep();\n",
" rospy.loginfo(\"Takeoff Publisher Connected\")\n",
"\n",
" while(self.vel_pub.get_num_connections() == 0):\n",
" rospy.loginfo(\"No susbribers to Cmd_vel yet so we wait and try again\")\n",
" rate.sleep();\n",
" rospy.loginfo(\"Cmd_vel Publisher Connected\")\n",
" \n",
"\n",
" def reset_cmd_vel_commands(self):\n",
" # We send an empty null Twist\n",
" vel_cmd = Twist()\n",
" vel_cmd.linear.z = 0.0\n",
" vel_cmd.angular.z = 0.0\n",
" self.vel_pub.publish(vel_cmd)\n",
"\n",
"\n",
" def takeoff_sequence(self, seconds_taking_off=1):\n",
" # Before taking off be sure that cmd_vel value there is is null to avoid drifts\n",
" self.reset_cmd_vel_commands()\n",
" \n",
" takeoff_msg = EmptyTopicMsg()\n",
" rospy.loginfo( \"Taking-Off Start\")\n",
" self.takeoff_pub.publish(takeoff_msg)\n",
" time.sleep(seconds_taking_off)\n",
" rospy.loginfo( \"Taking-Off sequence completed\")\n",
" \n",
"\n",
" def improved_distance_reward(self, current_pose):\n",
" current_dist = self.calculate_dist_between_two_Points(current_pose.position, self.desired_pose.position)\n",
" #rospy.loginfo(\"Calculated Distance = \"+str(current_dist))\n",
" \n",
" if current_dist < self.best_dist:\n",
" reward = 100\n",
" self.best_dist = current_dist\n",
" elif current_dist == self.best_dist:\n",
" reward = 0\n",
" else:\n",
" reward = -100\n",
" #print \"Made Distance bigger= \"+str(self.best_dist)\n",
" \n",
" return reward\n",
" \n",
" def process_data(self, data_position, data_imu):\n",
"\n",
" done = False\n",
" \n",
" euler = tf.transformations.euler_from_quaternion([data_imu.orientation.x,data_imu.orientation.y,data_imu.orientation.z,data_imu.orientation.w])\n",
" roll = euler[0]\n",
" pitch = euler[1]\n",
" yaw = euler[2]\n",
"\n",
" pitch_bad = not(-self.max_incl < pitch < self.max_incl)\n",
" roll_bad = not(-self.max_incl < roll < self.max_incl)\n",
" altitude_bad = data_position.position.z > self.max_altitude\n",
"\n",
" if altitude_bad or pitch_bad or roll_bad:\n",
" rospy.loginfo (\"(Drone flight status is wrong) >>> (\"+str(altitude_bad)+\",\"+str(pitch_bad)+\",\"+str(roll_bad)+\")\")\n",
" done = True\n",
" reward = -200\n",
" else:\n",
" reward = self.improved_distance_reward(data_position)\n",
"\n",
" return reward,done"
]
}
],
"metadata": {
"kernelspec": {
"display_name": "Python 3",
"language": "python",
"name": "python3"
},
"language_info": {
"codemirror_mode": {
"name": "ipython",
"version": 3
},
"file_extension": ".py",
"mimetype": "text/x-python",
"name": "python",
"nbconvert_exporter": "python",
"pygments_lexer": "ipython3",
"version": "3.6.6"
}
},
"nbformat": 4,
"nbformat_minor": 2
}