manual_control copy.py 43 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049
  1. #!/usr/bin/env python
  2. # Copyright (c) 2019 Computer Vision Center (CVC) at the Universitat Autonoma de
  3. # Barcelona (UAB).
  4. #
  5. # This work is licensed under the terms of the MIT license.
  6. # For a copy, see <https://opensource.org/licenses/MIT>.
  7. # Allows controlling a vehicle with a keyboard. For a simpler and more
  8. # documented example, please take a look at tutorial.py.
  9. """
  10. Welcome to CARLA manual control.
  11. Use ARROWS or WASD keys for control.
  12. W : throttle
  13. S : brake
  14. A/D : steer left/right
  15. Q : toggle reverse
  16. Space : hand-brake
  17. P : toggle autopilot
  18. M : toggle manual transmission
  19. ,/. : gear up/down
  20. L : toggle next light type
  21. SHIFT + L : toggle high beam
  22. Z/X : toggle right/left blinker
  23. I : toggle interior light
  24. TAB : change camera position
  25. R : toggle recording images to disk
  26. CTRL + R : toggle recording of simulation (replacing any previous)
  27. CTRL + P : start replaying last recorded simulation
  28. CTRL + + : increments the start time of the replay by 1 second (+SHIFT = 10 seconds)
  29. CTRL + - : decrements the start time of the replay by 1 second (+SHIFT = 10 seconds)
  30. F1 : toggle HUD
  31. H/? : toggle help
  32. ESC : quit
  33. """
  34. from __future__ import print_function
  35. # ==============================================================================
  36. # -- imports -------------------------------------------------------------------
  37. # ==============================================================================
  38. import carla
  39. from carla import ColorConverter as cc
  40. import argparse
  41. import os
  42. import sys
  43. import time
  44. import collections
  45. import datetime
  46. import logging
  47. import math
  48. import weakref
  49. import csv
  50. import random
  51. try:
  52. import pygame
  53. from pygame.locals import K_ESCAPE
  54. from pygame.locals import K_F1
  55. from pygame.locals import KMOD_CTRL
  56. from pygame.locals import KMOD_SHIFT
  57. from pygame.locals import K_BACKSPACE
  58. from pygame.locals import K_TAB
  59. from pygame.locals import K_SPACE
  60. from pygame.locals import K_UP
  61. from pygame.locals import K_DOWN
  62. from pygame.locals import K_LEFT
  63. from pygame.locals import K_RIGHT
  64. from pygame.locals import K_w
  65. from pygame.locals import K_a
  66. from pygame.locals import K_s
  67. from pygame.locals import K_d
  68. from pygame.locals import K_q
  69. from pygame.locals import K_m
  70. from pygame.locals import K_COMMA
  71. from pygame.locals import K_PERIOD
  72. from pygame.locals import K_p
  73. from pygame.locals import K_i
  74. from pygame.locals import K_l
  75. from pygame.locals import K_z
  76. from pygame.locals import K_x
  77. from pygame.locals import K_r
  78. from pygame.locals import K_MINUS
  79. from pygame.locals import K_EQUALS
  80. except ImportError:
  81. raise RuntimeError('cannot import pygame, make sure pygame package is installed')
  82. try:
  83. import numpy as np
  84. except ImportError:
  85. raise RuntimeError('cannot import numpy, make sure numpy package is installed')
  86. number_record = 0
  87. rannumber = random.randint(10000000, 90000000)
  88. # ==============================================================================
  89. # -- Global functions ----------------------------------------------------------
  90. # ==============================================================================
  91. def get_actor_display_name(actor, truncate=250):
  92. name = ' '.join(actor.type_id.replace('_', '.').title().split('.')[1:])
  93. return (name[:truncate - 1] + u'\u2026') if len(name) > truncate else name
  94. # ==============================================================================
  95. # -- World ---------------------------------------------------------------------
  96. # ==============================================================================
  97. class World(object):
  98. restarted = False
  99. def __init__(self, carla_world, hud, args):
  100. self.world = carla_world
  101. try:
  102. self.map = self.world.get_map()
  103. except RuntimeError as error:
  104. print('RuntimeError: {}'.format(error))
  105. print(' The server could not send the OpenDRIVE (.xodr) file:')
  106. print(' Make sure it exists, has the same name of your town, and is correct.')
  107. sys.exit(1)
  108. self.hud = hud
  109. self.player = None
  110. self.collision_sensor = None
  111. self.lane_invasion_sensor = None
  112. self.gnss_sensor = None
  113. self.imu_sensor = None
  114. self.radar_sensor = None
  115. self.camera_manager = None
  116. self.restart()
  117. self.world.on_tick(hud.on_world_tick)
  118. self.recording_enabled = False
  119. self.recording_start = 0
  120. def restart(self):
  121. if self.restarted:
  122. return
  123. self.restarted = True
  124. self.player_max_speed = 1.589
  125. self.player_max_speed_fast = 3.713
  126. # Keep same camera config if the camera manager exists.
  127. cam_index = self.camera_manager.index if self.camera_manager is not None else 0
  128. cam_pos_index = self.camera_manager.transform_index if self.camera_manager is not None else 1
  129. # Get the ego vehicle
  130. while self.player is None:
  131. print("Waiting for the ego vehicle...")
  132. time.sleep(1)
  133. possible_vehicles = self.world.get_actors().filter('vehicle.*')
  134. for vehicle in possible_vehicles:
  135. if vehicle.attributes['role_name'] == 'hero':
  136. print("Ego vehicle found")
  137. self.player = vehicle
  138. # print(vehicle.get_control().steer)
  139. break
  140. self.player_name = self.player.type_id
  141. # Set up the sensors.
  142. self.collision_sensor = CollisionSensor(self.player, self.hud)
  143. self.lane_invasion_sensor = LaneInvasionSensor(self.player, self.hud)
  144. self.gnss_sensor = GnssSensor(self.player)
  145. self.imu_sensor = IMUSensor(self.player)
  146. self.camera_manager = CameraManager(self.player, self.hud)
  147. self.camera_manager.transform_index = cam_pos_index
  148. self.camera_manager.set_sensor(cam_index, self.player, notify=False)
  149. actor_type = get_actor_display_name(self.player)
  150. self.hud.notification(actor_type)
  151. self.world.wait_for_tick()
  152. def tick(self, clock):
  153. if len(self.world.get_actors().filter(self.player_name)) < 1:
  154. return False
  155. self.hud.tick(self, clock)
  156. return True
  157. def render(self, display):
  158. self.camera_manager.render(display)
  159. self.hud.render(display)
  160. def destroy_sensors(self):
  161. self.camera_manager.sensor.destroy()
  162. self.camera_manager.sensor = None
  163. self.camera_manager.index = None
  164. def destroy(self):
  165. sensors = [
  166. self.camera_manager.sensor,
  167. self.collision_sensor.sensor,
  168. self.lane_invasion_sensor.sensor,
  169. self.gnss_sensor.sensor,
  170. self.imu_sensor.sensor]
  171. for sensor in sensors:
  172. if sensor is not None:
  173. sensor.stop()
  174. sensor.destroy()
  175. if self.player is not None:
  176. self.player.destroy()
  177. # ==============================================================================
  178. # -- KeyboardControl -----------------------------------------------------------
  179. # ==============================================================================
  180. class KeyboardControl(object):
  181. """Class that handles keyboard input."""
  182. def __init__(self, world, start_in_autopilot):
  183. self._autopilot_enabled = start_in_autopilot
  184. self._control = carla.VehicleControl()
  185. self._lights = carla.VehicleLightState.NONE
  186. self._steer_cache = 0.0
  187. world.player.set_autopilot(self._autopilot_enabled)
  188. if (self._autopilot_enabled == True):
  189. world.camera_manager.toggle_recording()
  190. world.player.set_light_state(self._lights)
  191. world.hud.notification("Press 'H' or '?' for help.", seconds=4.0)
  192. def parse_events(self, client, world, clock):
  193. current_lights = self._lights
  194. for event in pygame.event.get():
  195. if event.type == pygame.QUIT:
  196. return True
  197. elif event.type == pygame.KEYUP:
  198. if self._is_quit_shortcut(event.key):
  199. return True
  200. elif event.key == K_BACKSPACE:
  201. if self._autopilot_enabled:
  202. world.player.set_autopilot(False)
  203. world.restart()
  204. world.player.set_autopilot(True)
  205. else:
  206. world.restart()
  207. elif event.key == K_F1:
  208. world.hud.toggle_info()
  209. elif event.key == K_TAB:
  210. world.camera_manager.toggle_camera(world.player)
  211. elif event.key == K_r and not (pygame.key.get_mods() & KMOD_CTRL):
  212. world.camera_manager.toggle_recording()
  213. elif event.key == K_r and (pygame.key.get_mods() & KMOD_CTRL):
  214. if (world.recording_enabled):
  215. client.stop_recorder()
  216. world.recording_enabled = False
  217. world.hud.notification("Recorder is OFF")
  218. else:
  219. client.start_recorder("manual_recording.rec")
  220. world.recording_enabled = True
  221. world.hud.notification("Recorder is ON")
  222. elif event.key == K_p and (pygame.key.get_mods() & KMOD_CTRL):
  223. # stop recorder
  224. client.stop_recorder()
  225. world.recording_enabled = False
  226. # work around to fix camera at start of replaying
  227. current_index = world.camera_manager.index
  228. world.destroy_sensors()
  229. # disable autopilot
  230. self._autopilot_enabled = False
  231. world.player.set_autopilot(self._autopilot_enabled)
  232. world.hud.notification("Replaying file 'manual_recording.rec'")
  233. # replayer
  234. client.replay_file("manual_recording.rec", world.recording_start, 0, 0)
  235. world.camera_manager.set_sensor(current_index)
  236. elif event.key == K_MINUS and (pygame.key.get_mods() & KMOD_CTRL):
  237. if pygame.key.get_mods() & KMOD_SHIFT:
  238. world.recording_start -= 10
  239. else:
  240. world.recording_start -= 1
  241. world.hud.notification("Recording start time is %d" % (world.recording_start))
  242. elif event.key == K_EQUALS and (pygame.key.get_mods() & KMOD_CTRL):
  243. if pygame.key.get_mods() & KMOD_SHIFT:
  244. world.recording_start += 10
  245. else:
  246. world.recording_start += 1
  247. world.hud.notification("Recording start time is %d" % (world.recording_start))
  248. elif event.key == K_q:
  249. self._control.gear = 1 if self._control.reverse else -1
  250. elif event.key == K_m:
  251. self._control.manual_gear_shift = not self._control.manual_gear_shift
  252. self._control.gear = world.player.get_control().gear
  253. world.hud.notification('%s Transmission' %
  254. ('Manual' if self._control.manual_gear_shift else 'Automatic'))
  255. elif self._control.manual_gear_shift and event.key == K_COMMA:
  256. self._control.gear = max(-1, self._control.gear - 1)
  257. elif self._control.manual_gear_shift and event.key == K_PERIOD:
  258. self._control.gear = self._control.gear + 1
  259. elif event.key == K_p and not pygame.key.get_mods() & KMOD_CTRL:
  260. self._autopilot_enabled = not self._autopilot_enabled
  261. world.player.set_autopilot(self._autopilot_enabled)
  262. world.hud.notification(
  263. 'Autopilot %s' % ('On' if self._autopilot_enabled else 'Off'))
  264. world.camera_manager.toggle_recording()
  265. elif event.key == K_l and pygame.key.get_mods() & KMOD_CTRL:
  266. current_lights ^= carla.VehicleLightState.Special1
  267. elif event.key == K_l and pygame.key.get_mods() & KMOD_SHIFT:
  268. current_lights ^= carla.VehicleLightState.HighBeam
  269. elif event.key == K_l:
  270. # Use 'L' key to switch between lights:
  271. # closed -> position -> low beam -> fog
  272. if not self._lights & carla.VehicleLightState.Position:
  273. world.hud.notification("Position lights")
  274. current_lights |= carla.VehicleLightState.Position
  275. else:
  276. world.hud.notification("Low beam lights")
  277. current_lights |= carla.VehicleLightState.LowBeam
  278. if self._lights & carla.VehicleLightState.LowBeam:
  279. world.hud.notification("Fog lights")
  280. current_lights |= carla.VehicleLightState.Fog
  281. if self._lights & carla.VehicleLightState.Fog:
  282. world.hud.notification("Lights off")
  283. current_lights ^= carla.VehicleLightState.Position
  284. current_lights ^= carla.VehicleLightState.LowBeam
  285. current_lights ^= carla.VehicleLightState.Fog
  286. elif event.key == K_i:
  287. current_lights ^= carla.VehicleLightState.Interior
  288. elif event.key == K_z:
  289. current_lights ^= carla.VehicleLightState.LeftBlinker
  290. elif event.key == K_x:
  291. current_lights ^= carla.VehicleLightState.RightBlinker
  292. if not self._autopilot_enabled:
  293. self._parse_vehicle_keys(pygame.key.get_pressed(), clock.get_time())
  294. self._control.reverse = self._control.gear < 0
  295. # Set automatic control-related vehicle lights
  296. if self._control.brake:
  297. current_lights |= carla.VehicleLightState.Brake
  298. else: # Remove the Brake flag
  299. current_lights &= ~carla.VehicleLightState.Brake
  300. if self._control.reverse:
  301. current_lights |= carla.VehicleLightState.Reverse
  302. else: # Remove the Reverse flag
  303. current_lights &= ~carla.VehicleLightState.Reverse
  304. if current_lights != self._lights: # Change the light state only if necessary
  305. self._lights = current_lights
  306. world.player.set_light_state(carla.VehicleLightState(self._lights))
  307. world.player.apply_control(self._control)
  308. def _parse_vehicle_keys(self, keys, milliseconds):
  309. if keys[K_UP] or keys[K_w]:
  310. self._control.throttle = min(self._control.throttle + 0.1, 1.00)
  311. else:
  312. self._control.throttle = 0.0
  313. if keys[K_DOWN] or keys[K_s]:
  314. self._control.brake = min(self._control.brake + 0.2, 1)
  315. else:
  316. self._control.brake = 0
  317. steer_increment = 5e-4 * milliseconds
  318. if keys[K_LEFT] or keys[K_a]:
  319. if self._steer_cache > 0:
  320. self._steer_cache = 0
  321. else:
  322. self._steer_cache -= steer_increment
  323. elif keys[K_RIGHT] or keys[K_d]:
  324. if self._steer_cache < 0:
  325. self._steer_cache = 0
  326. else:
  327. self._steer_cache += steer_increment
  328. else:
  329. self._steer_cache = 0.0
  330. self._steer_cache = min(1.0, max(-1.0, self._steer_cache))
  331. self._control.steer = round(self._steer_cache, 1)
  332. self._control.hand_brake = keys[K_SPACE]
  333. @staticmethod
  334. def _is_quit_shortcut(key):
  335. return (key == K_ESCAPE) or (key == K_q and pygame.key.get_mods() & KMOD_CTRL)
  336. # ==============================================================================
  337. # -- HUD -----------------------------------------------------------------------
  338. # ==============================================================================
  339. class HUD(object):
  340. def __init__(self, width, height):
  341. self.dim = (width, height)
  342. font = pygame.font.Font(pygame.font.get_default_font(), 20)
  343. font_name = 'courier' if os.name == 'nt' else 'mono'
  344. fonts = [x for x in pygame.font.get_fonts() if font_name in x]
  345. default_font = 'ubuntumono'
  346. mono = default_font if default_font in fonts else fonts[0]
  347. mono = pygame.font.match_font(mono)
  348. self._font_mono = pygame.font.Font(mono, 12 if os.name == 'nt' else 14)
  349. self._notifications = FadingText(font, (width, 40), (0, height - 40))
  350. self.help = HelpText(pygame.font.Font(mono, 16), width, height)
  351. self.server_fps = 0
  352. self.frame = 0
  353. self.simulation_time = 0
  354. self._show_info = True
  355. self._info_text = []
  356. self._server_clock = pygame.time.Clock()
  357. def on_world_tick(self, timestamp):
  358. self._server_clock.tick()
  359. self.server_fps = self._server_clock.get_fps()
  360. self.frame = timestamp.frame
  361. self.simulation_time = timestamp.elapsed_seconds
  362. def tick(self, world, clock):
  363. self._notifications.tick(world, clock)
  364. if not self._show_info:
  365. return
  366. t = world.player.get_transform()
  367. v = world.player.get_velocity()
  368. c = world.player.get_control()
  369. # print(c.steer)
  370. compass = world.imu_sensor.compass
  371. heading = 'N' if compass > 270.5 or compass < 89.5 else ''
  372. heading += 'S' if 90.5 < compass < 269.5 else ''
  373. heading += 'E' if 0.5 < compass < 179.5 else ''
  374. heading += 'W' if 180.5 < compass < 359.5 else ''
  375. colhist = world.collision_sensor.get_collision_history()
  376. collision = [colhist[x + self.frame - 200] for x in range(0, 200)]
  377. max_col = max(1.0, max(collision))
  378. collision = [x / max_col for x in collision]
  379. vehicles = world.world.get_actors().filter('vehicle.*')
  380. self._info_text = [
  381. 'Server: % 16.0f FPS' % self.server_fps,
  382. 'Client: % 16.0f FPS' % clock.get_fps(),
  383. '',
  384. 'Vehicle: % 20s' % get_actor_display_name(world.player, truncate=20),
  385. 'Map: % 20s' % world.map.name.split('/')[-1],
  386. 'Simulation time: % 12s' % datetime.timedelta(seconds=int(self.simulation_time)),
  387. '',
  388. 'Speed: % 15.0f km/h' % (3.6 * math.sqrt(v.x ** 2 + v.y ** 2 + v.z ** 2)),
  389. u'Compass:% 17.0f\N{DEGREE SIGN} % 2s' % (compass, heading),
  390. 'Accelero: (%5.1f,%5.1f,%5.1f)' % (world.imu_sensor.accelerometer),
  391. 'Gyroscop: (%5.1f,%5.1f,%5.1f)' % (world.imu_sensor.gyroscope),
  392. 'Location:% 20s' % ('(% 5.1f, % 5.1f)' % (t.location.x, t.location.y)),
  393. 'GNSS:% 24s' % ('(% 2.6f, % 3.6f)' % (world.gnss_sensor.lat, world.gnss_sensor.lon)),
  394. 'Height: % 18.0f m' % t.location.z,
  395. '']
  396. self._info_text += [
  397. ('Throttle:', c.throttle, 0.0, 1.0),
  398. ('Steer:', c.steer, -1.0, 1.0),
  399. ('Brake:', c.brake, 0.0, 1.0),
  400. ('Reverse:', c.reverse),
  401. ('Hand brake:', c.hand_brake),
  402. ('Manual:', c.manual_gear_shift),
  403. 'Gear: %s' % {-1: 'R', 0: 'N'}.get(c.gear, c.gear)]
  404. self._info_text += [
  405. '',
  406. 'Collision:',
  407. collision,
  408. '',
  409. 'Number of vehicles: % 8d' % len(vehicles)]
  410. if len(vehicles) > 1:
  411. self._info_text += ['Nearby vehicles:']
  412. distance = lambda l: math.sqrt(
  413. (l.x - t.location.x) ** 2 + (l.y - t.location.y) ** 2 + (l.z - t.location.z) ** 2)
  414. vehicles = [(distance(x.get_location()), x) for x in vehicles if x.id != world.player.id]
  415. for d, vehicle in sorted(vehicles, key=lambda vehicles: vehicles[0]):
  416. if d > 200.0:
  417. break
  418. vehicle_type = get_actor_display_name(vehicle, truncate=22)
  419. self._info_text.append('% 4dm %s' % (d, vehicle_type))
  420. def toggle_info(self):
  421. self._show_info = not self._show_info
  422. def notification(self, text, seconds=2.0):
  423. self._notifications.set_text(text, seconds=seconds)
  424. def error(self, text):
  425. self._notifications.set_text('Error: %s' % text, (255, 0, 0))
  426. def render(self, display):
  427. if self._show_info:
  428. info_surface = pygame.Surface((220, self.dim[1]))
  429. info_surface.set_alpha(100)
  430. display.blit(info_surface, (0, 0))
  431. v_offset = 4
  432. bar_h_offset = 100
  433. bar_width = 106
  434. for item in self._info_text:
  435. if v_offset + 18 > self.dim[1]:
  436. break
  437. if isinstance(item, list):
  438. if len(item) > 1:
  439. points = [(x + 8, v_offset + 8 + (1.0 - y) * 30) for x, y in enumerate(item)]
  440. pygame.draw.lines(display, (255, 136, 0), False, points, 2)
  441. item = None
  442. v_offset += 18
  443. elif isinstance(item, tuple):
  444. if isinstance(item[1], bool):
  445. rect = pygame.Rect((bar_h_offset, v_offset + 8), (6, 6))
  446. pygame.draw.rect(display, (255, 255, 255), rect, 0 if item[1] else 1)
  447. else:
  448. rect_border = pygame.Rect((bar_h_offset, v_offset + 8), (bar_width, 6))
  449. pygame.draw.rect(display, (255, 255, 255), rect_border, 1)
  450. f = (item[1] - item[2]) / (item[3] - item[2])
  451. if item[2] < 0.0:
  452. rect = pygame.Rect((bar_h_offset + f * (bar_width - 6), v_offset + 8), (6, 6))
  453. else:
  454. rect = pygame.Rect((bar_h_offset, v_offset + 8), (f * bar_width, 6))
  455. pygame.draw.rect(display, (255, 255, 255), rect)
  456. item = item[0]
  457. if item: # At this point has to be a str.
  458. surface = self._font_mono.render(item, True, (255, 255, 255))
  459. display.blit(surface, (8, v_offset))
  460. v_offset += 18
  461. self._notifications.render(display)
  462. self.help.render(display)
  463. # ==============================================================================
  464. # -- FadingText ----------------------------------------------------------------
  465. # ==============================================================================
  466. class FadingText(object):
  467. def __init__(self, font, dim, pos):
  468. self.font = font
  469. self.dim = dim
  470. self.pos = pos
  471. self.seconds_left = 0
  472. self.surface = pygame.Surface(self.dim)
  473. def set_text(self, text, color=(255, 255, 255), seconds=2.0):
  474. text_texture = self.font.render(text, True, color)
  475. self.surface = pygame.Surface(self.dim)
  476. self.seconds_left = seconds
  477. self.surface.fill((0, 0, 0, 0))
  478. self.surface.blit(text_texture, (10, 11))
  479. def tick(self, _, clock):
  480. delta_seconds = 1e-3 * clock.get_time()
  481. self.seconds_left = max(0.0, self.seconds_left - delta_seconds)
  482. self.surface.set_alpha(500.0 * self.seconds_left)
  483. def render(self, display):
  484. display.blit(self.surface, self.pos)
  485. # ==============================================================================
  486. # -- HelpText ------------------------------------------------------------------
  487. # ==============================================================================
  488. class HelpText(object):
  489. """Helper class to handle text output using pygame"""
  490. def __init__(self, font, width, height):
  491. lines = __doc__.split('\n')
  492. self.font = font
  493. self.line_space = 18
  494. self.dim = (780, len(lines) * self.line_space + 12)
  495. self.pos = (0.5 * width - 0.5 * self.dim[0], 0.5 * height - 0.5 * self.dim[1])
  496. self.seconds_left = 0
  497. self.surface = pygame.Surface(self.dim)
  498. self.surface.fill((0, 0, 0, 0))
  499. for n, line in enumerate(lines):
  500. text_texture = self.font.render(line, True, (255, 255, 255))
  501. self.surface.blit(text_texture, (22, n * self.line_space))
  502. self._render = False
  503. self.surface.set_alpha(220)
  504. def toggle(self):
  505. self._render = not self._render
  506. def render(self, display):
  507. if self._render:
  508. display.blit(self.surface, self.pos)
  509. # ==============================================================================
  510. # -- CollisionSensor -----------------------------------------------------------
  511. # ==============================================================================
  512. class CollisionSensor(object):
  513. def __init__(self, parent_actor, hud):
  514. self.sensor = None
  515. self.history = []
  516. self._parent = parent_actor
  517. self.hud = hud
  518. world = self._parent.get_world()
  519. bp = world.get_blueprint_library().find('sensor.other.collision')
  520. self.sensor = world.spawn_actor(bp, carla.Transform(), attach_to=self._parent)
  521. # We need to pass the lambda a weak reference to self to avoid circular
  522. # reference.
  523. weak_self = weakref.ref(self)
  524. self.sensor.listen(lambda event: CollisionSensor._on_collision(weak_self, event))
  525. def get_collision_history(self):
  526. history = collections.defaultdict(int)
  527. for frame, intensity in self.history:
  528. history[frame] += intensity
  529. return history
  530. @staticmethod
  531. def _on_collision(weak_self, event):
  532. self = weak_self()
  533. if not self:
  534. return
  535. actor_type = get_actor_display_name(event.other_actor)
  536. self.hud.notification('Collision with %r' % actor_type)
  537. impulse = event.normal_impulse
  538. intensity = math.sqrt(impulse.x ** 2 + impulse.y ** 2 + impulse.z ** 2)
  539. self.history.append((event.frame, intensity))
  540. if len(self.history) > 4000:
  541. self.history.pop(0)
  542. # ==============================================================================
  543. # -- LaneInvasionSensor --------------------------------------------------------
  544. # ==============================================================================
  545. class LaneInvasionSensor(object):
  546. def __init__(self, parent_actor, hud):
  547. self.sensor = None
  548. # If the spawn object is not a vehicle, we cannot use the Lane Invasion Sensor
  549. if parent_actor.type_id.startswith("vehicle."):
  550. self._parent = parent_actor
  551. self.hud = hud
  552. world = self._parent.get_world()
  553. bp = world.get_blueprint_library().find('sensor.other.lane_invasion')
  554. self.sensor = world.spawn_actor(bp, carla.Transform(), attach_to=self._parent)
  555. # We need to pass the lambda a weak reference to self to avoid circular
  556. # reference.
  557. weak_self = weakref.ref(self)
  558. self.sensor.listen(lambda event: LaneInvasionSensor._on_invasion(weak_self, event))
  559. @staticmethod
  560. def _on_invasion(weak_self, event):
  561. self = weak_self()
  562. if not self:
  563. return
  564. lane_types = set(x.type for x in event.crossed_lane_markings)
  565. text = ['%r' % str(x).split()[-1] for x in lane_types]
  566. self.hud.notification('Crossed line %s' % ' and '.join(text))
  567. # ==============================================================================
  568. # -- GnssSensor ----------------------------------------------------------------
  569. # ==============================================================================
  570. class GnssSensor(object):
  571. def __init__(self, parent_actor):
  572. self.sensor = None
  573. self._parent = parent_actor
  574. self.lat = 0.0
  575. self.lon = 0.0
  576. world = self._parent.get_world()
  577. bp = world.get_blueprint_library().find('sensor.other.gnss')
  578. self.sensor = world.spawn_actor(bp, carla.Transform(carla.Location(x=1.0, z=2.8)), attach_to=self._parent)
  579. # We need to pass the lambda a weak reference to self to avoid circular
  580. # reference.
  581. weak_self = weakref.ref(self)
  582. self.sensor.listen(lambda event: GnssSensor._on_gnss_event(weak_self, event))
  583. @staticmethod
  584. def _on_gnss_event(weak_self, event):
  585. self = weak_self()
  586. if not self:
  587. return
  588. self.lat = event.latitude
  589. self.lon = event.longitude
  590. # ==============================================================================
  591. # -- IMUSensor -----------------------------------------------------------------
  592. # ==============================================================================
  593. class IMUSensor(object):
  594. def __init__(self, parent_actor):
  595. self.sensor = None
  596. self._parent = parent_actor
  597. self.accelerometer = (0.0, 0.0, 0.0)
  598. self.gyroscope = (0.0, 0.0, 0.0)
  599. self.compass = 0.0
  600. world = self._parent.get_world()
  601. bp = world.get_blueprint_library().find('sensor.other.imu')
  602. self.sensor = world.spawn_actor(
  603. bp, carla.Transform(), attach_to=self._parent)
  604. # We need to pass the lambda a weak reference to self to avoid circular
  605. # reference.
  606. weak_self = weakref.ref(self)
  607. self.sensor.listen(
  608. lambda sensor_data: IMUSensor._IMU_callback(weak_self, sensor_data))
  609. @staticmethod
  610. def _IMU_callback(weak_self, sensor_data):
  611. self = weak_self()
  612. if not self:
  613. return
  614. limits = (-99.9, 99.9)
  615. self.accelerometer = (
  616. max(limits[0], min(limits[1], sensor_data.accelerometer.x)),
  617. max(limits[0], min(limits[1], sensor_data.accelerometer.y)),
  618. max(limits[0], min(limits[1], sensor_data.accelerometer.z)))
  619. self.gyroscope = (
  620. max(limits[0], min(limits[1], math.degrees(sensor_data.gyroscope.x))),
  621. max(limits[0], min(limits[1], math.degrees(sensor_data.gyroscope.y))),
  622. max(limits[0], min(limits[1], math.degrees(sensor_data.gyroscope.z))))
  623. self.compass = math.degrees(sensor_data.compass)
  624. # ==============================================================================
  625. # -- RadarSensor ---------------------------------------------------------------
  626. # ==============================================================================
  627. class RadarSensor(object):
  628. def __init__(self, parent_actor):
  629. self.sensor = None
  630. self._parent = parent_actor
  631. bound_x = 0.5 + self._parent.bounding_box.extent.x
  632. bound_y = 0.5 + self._parent.bounding_box.extent.y
  633. bound_z = 0.5 + self._parent.bounding_box.extent.z
  634. self.velocity_range = 7.5 # m/s
  635. world = self._parent.get_world()
  636. self.debug = world.debug
  637. bp = world.get_blueprint_library().find('sensor.other.radar')
  638. bp.set_attribute('horizontal_fov', str(35))
  639. bp.set_attribute('vertical_fov', str(20))
  640. self.sensor = world.spawn_actor(
  641. bp,
  642. carla.Transform(
  643. carla.Location(x=bound_x + 0.05, z=bound_z + 0.05),
  644. carla.Rotation(pitch=5)),
  645. attach_to=self._parent)
  646. # We need a weak reference to self to avoid circular reference.
  647. weak_self = weakref.ref(self)
  648. self.sensor.listen(
  649. lambda radar_data: RadarSensor._Radar_callback(weak_self, radar_data))
  650. @staticmethod
  651. def _Radar_callback(weak_self, radar_data):
  652. self = weak_self()
  653. if not self:
  654. return
  655. # To get a numpy [[vel, altitude, azimuth, depth],...[,,,]]:
  656. # points = np.frombuffer(radar_data.raw_data, dtype=np.dtype('f4'))
  657. # points = np.reshape(points, (len(radar_data), 4))
  658. current_rot = radar_data.transform.rotation
  659. for detect in radar_data:
  660. azi = math.degrees(detect.azimuth)
  661. alt = math.degrees(detect.altitude)
  662. # The 0.25 adjusts a bit the distance so the dots can
  663. # be properly seen
  664. fw_vec = carla.Vector3D(x=detect.depth - 0.25)
  665. carla.Transform(
  666. carla.Location(),
  667. carla.Rotation(
  668. pitch=current_rot.pitch + alt,
  669. yaw=current_rot.yaw + azi,
  670. roll=current_rot.roll)).transform(fw_vec)
  671. def clamp(min_v, max_v, value):
  672. return max(min_v, min(value, max_v))
  673. norm_velocity = detect.velocity / self.velocity_range # range [-1, 1]
  674. r = int(clamp(0.0, 1.0, 1.0 - norm_velocity) * 255.0)
  675. g = int(clamp(0.0, 1.0, 1.0 - abs(norm_velocity)) * 255.0)
  676. b = int(abs(clamp(- 1.0, 0.0, - 1.0 - norm_velocity)) * 255.0)
  677. self.debug.draw_point(
  678. radar_data.transform.location + fw_vec,
  679. size=0.075,
  680. life_time=0.06,
  681. persistent_lines=False,
  682. color=carla.Color(r, g, b))
  683. # ==============================================================================
  684. # -- CameraManager -------------------------------------------------------------
  685. # ==============================================================================
  686. class CameraManager(object):
  687. def __init__(self, parent_actor, hud):
  688. self.sensor = None
  689. self.surface = None
  690. self._parent = parent_actor
  691. self.hud = hud
  692. self.recording = False
  693. bound_x = 0.5 + self._parent.bounding_box.extent.x
  694. bound_y = 0.5 + self._parent.bounding_box.extent.y
  695. bound_z = 0.5 + self._parent.bounding_box.extent.z
  696. Attachment = carla.AttachmentType
  697. self._camera_transforms = [
  698. (carla.Transform(carla.Location(x=-2.0 * bound_x, y=+0.0 * bound_y, z=2.0 * bound_z),
  699. carla.Rotation(pitch=8.0)), Attachment.SpringArm),
  700. (carla.Transform(carla.Location(x=+0.8 * bound_x, y=+0.0 * bound_y, z=1.3 * bound_z)), Attachment.Rigid),
  701. (
  702. carla.Transform(carla.Location(x=+1.9 * bound_x, y=+1.0 * bound_y, z=1.2 * bound_z)), Attachment.SpringArm),
  703. (carla.Transform(carla.Location(x=-2.8 * bound_x, y=+0.0 * bound_y, z=4.6 * bound_z),
  704. carla.Rotation(pitch=6.0)), Attachment.SpringArm),
  705. (carla.Transform(carla.Location(x=-1.0, y=-1.0 * bound_y, z=0.4 * bound_z)), Attachment.Rigid)]
  706. self.transform_index = 1
  707. self.sensors = [['sensor.camera.rgb', cc.Raw, 'Camera RGB']]
  708. world = self._parent.get_world()
  709. bp_library = world.get_blueprint_library()
  710. for item in self.sensors:
  711. bp = bp_library.find(item[0])
  712. bp.set_attribute('image_size_x', str(hud.dim[0]))
  713. bp.set_attribute('image_size_y', str(hud.dim[1]))
  714. bp.set_attribute('gamma', '2.2')
  715. # bp.set_attribute('sensor_tick', '0.02')
  716. item.append(bp)
  717. self.index = None
  718. def toggle_camera(self, player):
  719. self.transform_index = (self.transform_index + 1) % len(self._camera_transforms)
  720. self.set_sensor(self.index, player, notify=False, force_respawn=True)
  721. def set_sensor(self, index, player, notify=True, force_respawn=False):
  722. index = index % len(self.sensors)
  723. needs_respawn = True if self.index is None else \
  724. (force_respawn or (self.sensors[index][2] != self.sensors[self.index][2]))
  725. if needs_respawn:
  726. if self.sensor is not None:
  727. self.sensor.destroy()
  728. self.surface = None
  729. self.sensor = self._parent.get_world().spawn_actor(
  730. self.sensors[index][-1],
  731. self._camera_transforms[self.transform_index][0],
  732. attach_to=self._parent,
  733. attachment_type=self._camera_transforms[self.transform_index][1])
  734. # We need to pass the lambda a weak reference to self to avoid
  735. # circular reference.
  736. weak_self = weakref.ref(self)
  737. self.sensor.listen(lambda image: CameraManager._parse_image(weak_self, image, player))
  738. if notify:
  739. self.hud.notification(self.sensors[index][2])
  740. self.index = index
  741. def toggle_recording(self):
  742. self.recording = not self.recording
  743. self.hud.notification('Recording %s' % ('On' if self.recording else 'Off'))
  744. def render(self, display):
  745. if self.surface is not None:
  746. display.blit(self.surface, (0, 0))
  747. @staticmethod
  748. def _parse_image(weak_self, image, player):
  749. self = weak_self()
  750. if not self:
  751. return
  752. if self.sensors[self.index][0].startswith('sensor.lidar'):
  753. points = np.frombuffer(image.raw_data, dtype=np.dtype('f4'))
  754. points = np.reshape(points, (int(points.shape[0] / 4), 4))
  755. lidar_data = np.array(points[:, :2])
  756. lidar_data *= min(self.hud.dim) / (2.0 * self.lidar_range)
  757. lidar_data += (0.5 * self.hud.dim[0], 0.5 * self.hud.dim[1])
  758. lidar_data = np.fabs(lidar_data) # pylint: disable=E1111
  759. lidar_data = lidar_data.astype(np.int32)
  760. lidar_data = np.reshape(lidar_data, (-1, 2))
  761. lidar_img_size = (self.hud.dim[0], self.hud.dim[1], 3)
  762. lidar_img = np.zeros((lidar_img_size), dtype=np.uint8)
  763. lidar_img[tuple(lidar_data.T)] = (255, 255, 255)
  764. self.surface = pygame.surfarray.make_surface(lidar_img)
  765. elif self.sensors[self.index][0].startswith('sensor.camera.dvs'):
  766. # Example of converting the raw_data from a carla.DVSEventArray
  767. # sensor into a NumPy array and using it as an image
  768. dvs_events = np.frombuffer(image.raw_data, dtype=np.dtype([
  769. ('x', np.uint16), ('y', np.uint16), ('t', np.int64), ('pol', np.bool)]))
  770. dvs_img = np.zeros((image.height, image.width, 3), dtype=np.uint8)
  771. # Blue is positive, red is negative
  772. dvs_img[dvs_events[:]['y'], dvs_events[:]['x'], dvs_events[:]['pol'] * 2] = 255
  773. self.surface = pygame.surfarray.make_surface(dvs_img.swapaxes(0, 1))
  774. elif self.sensors[self.index][0].startswith('sensor.camera.optical_flow'):
  775. image = image.get_color_coded_flow()
  776. array = np.frombuffer(image.raw_data, dtype=np.dtype("uint8"))
  777. array = np.reshape(array, (image.height, image.width, 4))
  778. array = array[:, :, :3]
  779. array = array[:, :, ::-1]
  780. self.surface = pygame.surfarray.make_surface(array.swapaxes(0, 1))
  781. else:
  782. image.convert(self.sensors[self.index][1])
  783. array = np.frombuffer(image.raw_data, dtype=np.dtype("uint8"))
  784. array = np.reshape(array, (image.height, image.width, 4))
  785. array = array[:, :, :3]
  786. array = array[:, :, ::-1]
  787. self.surface = pygame.surfarray.make_surface(array.swapaxes(0, 1))
  788. if self.recording:
  789. global number_record
  790. global rannumber
  791. number_record = number_record + 1
  792. if number_record > 15 and number_record <= 140:
  793. print("number_record"+str(number_record))
  794. frameid = image.frame + rannumber
  795. image.save_to_disk('/home/vangogh/code/fileSystem/downloadDir/simulation_result/%08d' % frameid)
  796. print("frameid"+str(frameid))
  797. image_name = "%08d" % frameid
  798. steering = player.get_control().steer
  799. list_1 = [str(image_name) + ".png", steering, steering * 4]
  800. #list_1 = [str(image_name) + ".png", str(seed_name), steering * 4, number_record-15]
  801. file_path = '/home/vangogh/code/fileSystem/downloadDir/simulation_result/label_test.csv'
  802. with open(file_path, 'a+', encoding='utf-8') as f:
  803. csv_writer = csv.writer(f)
  804. csv_writer.writerow(list_1)
  805. print("***********************len*****************************")
  806. print(number_record)
  807. # ==============================================================================
  808. # -- game_loop() ---------------------------------------------------------------
  809. # ==============================================================================
  810. def game_loop(args):
  811. pygame.init()
  812. pygame.font.init()
  813. world = None
  814. try:
  815. client = carla.Client(args.host, args.port)
  816. client.set_timeout(200) # 200
  817. sim_world = client.get_world()
  818. display = pygame.display.set_mode(
  819. (args.width, args.height),
  820. pygame.HWSURFACE | pygame.DOUBLEBUF)
  821. display.fill((0, 0, 0))
  822. pygame.display.flip()
  823. hud = HUD(args.width, args.height)
  824. world = World(sim_world, hud, args)
  825. controller = KeyboardControl(world, args.autopilot)
  826. sim_world.wait_for_tick()
  827. clock = pygame.time.Clock()
  828. while True:
  829. clock.tick_busy_loop(60)
  830. if controller.parse_events(client, world, clock):
  831. return
  832. if not world.tick(clock):
  833. return
  834. world.render(display)
  835. pygame.display.flip()
  836. finally:
  837. if (world and world.recording_enabled):
  838. client.stop_recorder()
  839. if world is not None:
  840. # prevent destruction of ego vehicle
  841. if args.keep_ego_vehicle:
  842. world.player = None
  843. world.destroy()
  844. pygame.quit()
  845. sys.exit()
  846. # ==============================================================================
  847. # -- main() --------------------------------------------------------------------
  848. # ==============================================================================
  849. def main():
  850. argparser = argparse.ArgumentParser(
  851. description='CARLA Manual Control Client')
  852. argparser.add_argument(
  853. '-v', '--verbose',
  854. action='store_true',
  855. dest='debug',
  856. help='print debug information')
  857. argparser.add_argument(
  858. '--host',
  859. metavar='H',
  860. default='127.0.0.1',
  861. help='IP of the host server (default: 127.0.0.1)')
  862. argparser.add_argument(
  863. '-p', '--port',
  864. metavar='P',
  865. default=3000,
  866. type=int,
  867. help='TCP port to listen to (default: 3000)')
  868. argparser.add_argument(
  869. '-a', '--autopilot',
  870. action='store_true',
  871. help='enable autopilot. This does not autocomplete the scenario')
  872. argparser.add_argument(
  873. '--rolename',
  874. metavar='NAME',
  875. default='hero',
  876. help='role name of ego vehicle to control (default: "hero")')
  877. argparser.add_argument(
  878. '--res',
  879. metavar='WIDTHxHEIGHT',
  880. default='1280x720',
  881. help='window resolution (default: 1280x720)')
  882. argparser.add_argument(
  883. '--keep_ego_vehicle',
  884. action='store_true',
  885. help='do not destroy ego vehicle on exit')
  886. argparser.add_argument( # add name
  887. '--name',
  888. type=str,
  889. help='seed name')
  890. args = argparser.parse_args()
  891. args.width, args.height = [int(x) for x in args.res.split('x')]
  892. log_level = logging.DEBUG if args.debug else logging.INFO
  893. logging.basicConfig(format='%(levelname)s: %(message)s', level=log_level)
  894. logging.info('listening to server %s:%s', args.host, args.port)
  895. print(__doc__)
  896. global seed_name
  897. seed_name = args.name
  898. try:
  899. game_loop(args)
  900. except KeyboardInterrupt:
  901. print('\nCancelled by user. Bye!')
  902. except Exception as error:
  903. logging.exception(error)
  904. if __name__ == '__main__':
  905. main()