Merge branch 'master' into marcgpuig/windows_build
This commit is contained in:
commit
f0273d5465
|
@ -1,8 +1,12 @@
|
|||
## Latest Changes
|
||||
|
||||
* Added manual_control_steeringwheel.py to control agents using Logitech G29 steering wheels (and maybe others).
|
||||
* Fixed `manual_control.py` and `no_rendering_mode.py` to prevent crashes when used in "no rendering mode"
|
||||
* Added movable props present in the map (e.g. chairs and tables) as actors so they can be controlled from Python
|
||||
* Refactored `no_rendering_mode.py` to improve performance and interface
|
||||
* Fixed basic build system for Windows
|
||||
* Several improvements to the basic build system for Windows
|
||||
* Improved time-out related error messages
|
||||
* Fixed issue of retrieving an empty list when calling `world.get_actors()` right after creating the world
|
||||
|
||||
|
||||
## CARLA 0.9.3
|
||||
|
||||
|
|
|
@ -9,6 +9,7 @@
|
|||
#include "carla/Exception.h"
|
||||
#include "carla/Time.h"
|
||||
|
||||
#include <boost/optional.hpp>
|
||||
#include <boost/variant.hpp>
|
||||
|
||||
#include <condition_variable>
|
||||
|
@ -19,7 +20,9 @@
|
|||
namespace carla {
|
||||
|
||||
namespace detail {
|
||||
|
||||
class SharedException;
|
||||
|
||||
} // namespace detail
|
||||
|
||||
// ===========================================================================
|
||||
|
@ -36,7 +39,9 @@ namespace detail {
|
|||
|
||||
/// Wait until the next value is set. Any number of threads can be waiting
|
||||
/// simultaneously.
|
||||
T WaitFor(time_duration timeout);
|
||||
///
|
||||
/// @return empty optional if the timeout is met.
|
||||
boost::optional<T> WaitFor(time_duration timeout);
|
||||
|
||||
/// Set the value and notify all waiting threads.
|
||||
template <typename T2>
|
||||
|
@ -96,12 +101,12 @@ namespace detail {
|
|||
} // namespace detail
|
||||
|
||||
template <typename T>
|
||||
T RecurrentSharedFuture<T>::WaitFor(time_duration timeout) {
|
||||
boost::optional<T> RecurrentSharedFuture<T>::WaitFor(time_duration timeout) {
|
||||
std::unique_lock<std::mutex> lock(_mutex);
|
||||
auto &r = _map[&detail::thread_tag];
|
||||
r.should_wait = true;
|
||||
if (!_cv.wait_for(lock, timeout.to_chrono(), [&]() { return !r.should_wait; })) {
|
||||
throw_exception(std::runtime_error("RecurrentSharedFuture.WaitFor: time-out"));
|
||||
return {};
|
||||
}
|
||||
if (r.value.which() == 1) {
|
||||
throw_exception(boost::get<SharedException>(r.value));
|
||||
|
|
|
@ -0,0 +1,23 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "carla/client/TimeoutException.h"
|
||||
|
||||
namespace carla {
|
||||
namespace client {
|
||||
|
||||
using namespace std::string_literals;
|
||||
|
||||
TimeoutException::TimeoutException(
|
||||
const std::string &endpoint,
|
||||
time_duration timeout)
|
||||
: std::runtime_error(
|
||||
"time-out of "s + std::to_string(timeout.milliseconds()) +
|
||||
"ms while waiting for the simulator, "
|
||||
"make sure the simulator is ready and connected to " + endpoint) {}
|
||||
|
||||
} // namespace client
|
||||
} // namespace carla
|
|
@ -0,0 +1,26 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "carla/Time.h"
|
||||
|
||||
#include <stdexcept>
|
||||
#include <string>
|
||||
|
||||
namespace carla {
|
||||
namespace client {
|
||||
|
||||
class TimeoutException : public std::runtime_error {
|
||||
public:
|
||||
|
||||
explicit TimeoutException(
|
||||
const std::string &endpoint,
|
||||
time_duration timeout);
|
||||
};
|
||||
|
||||
} // namespace client
|
||||
} // namespace carla
|
|
@ -6,7 +6,9 @@
|
|||
|
||||
#include "carla/client/detail/Client.h"
|
||||
|
||||
#include "carla/Exception.h"
|
||||
#include "carla/Version.h"
|
||||
#include "carla/client/TimeoutException.h"
|
||||
#include "carla/rpc/ActorDescription.h"
|
||||
#include "carla/rpc/Client.h"
|
||||
#include "carla/rpc/DebugShape.h"
|
||||
|
@ -15,6 +17,8 @@
|
|||
#include "carla/rpc/WalkerControl.h"
|
||||
#include "carla/streaming/Client.h"
|
||||
|
||||
#include <rpc/rpc_error.h>
|
||||
|
||||
#include <thread>
|
||||
|
||||
namespace carla {
|
||||
|
@ -35,18 +39,31 @@ namespace detail {
|
|||
// ===========================================================================
|
||||
|
||||
class Client::Pimpl {
|
||||
private:
|
||||
|
||||
template <typename... Args>
|
||||
auto Call(const std::string &function, Args &&... args) {
|
||||
try {
|
||||
return rpc_client.call(function, std::forward<Args>(args)...);
|
||||
} catch (const ::rpc::timeout &) {
|
||||
throw_exception(TimeoutException(endpoint, GetTimeout()));
|
||||
}
|
||||
}
|
||||
|
||||
public:
|
||||
|
||||
Pimpl(const std::string &host, uint16_t port, size_t worker_threads)
|
||||
: rpc_client(host, port),
|
||||
: endpoint(host + ":" + std::to_string(port)),
|
||||
rpc_client(host, port),
|
||||
streaming_client(host) {
|
||||
rpc_client.set_timeout(10u);
|
||||
streaming_client.AsyncRun(
|
||||
worker_threads > 0u ? worker_threads : std::thread::hardware_concurrency());
|
||||
}
|
||||
|
||||
template <typename T, typename ... Args>
|
||||
auto CallAndWait(const std::string &function, Args && ... args) {
|
||||
auto object = rpc_client.call(function, std::forward<Args>(args) ...);
|
||||
template <typename T, typename... Args>
|
||||
auto CallAndWait(const std::string &function, Args &&... args) {
|
||||
auto object = Call(function, std::forward<Args>(args)...);
|
||||
using R = typename carla::rpc::Response<T>;
|
||||
auto response = object.template as<R>();
|
||||
if (response.HasError()) {
|
||||
|
@ -55,12 +72,20 @@ namespace detail {
|
|||
return Get(response);
|
||||
}
|
||||
|
||||
template <typename ... Args>
|
||||
void AsyncCall(const std::string &function, Args && ... args) {
|
||||
template <typename... Args>
|
||||
void AsyncCall(const std::string &function, Args &&... args) {
|
||||
// Discard returned future.
|
||||
rpc_client.async_call(function, std::forward<Args>(args) ...);
|
||||
rpc_client.async_call(function, std::forward<Args>(args)...);
|
||||
}
|
||||
|
||||
time_duration GetTimeout() const {
|
||||
auto timeout = rpc_client.get_timeout();
|
||||
DEBUG_ASSERT(timeout.has_value());
|
||||
return time_duration::milliseconds(*timeout);
|
||||
}
|
||||
|
||||
const std::string endpoint;
|
||||
|
||||
rpc::Client rpc_client;
|
||||
|
||||
streaming::Client streaming_client;
|
||||
|
@ -82,6 +107,14 @@ namespace detail {
|
|||
_pimpl->rpc_client.set_timeout(timeout.milliseconds());
|
||||
}
|
||||
|
||||
time_duration Client::GetTimeout() const {
|
||||
return _pimpl->GetTimeout();
|
||||
}
|
||||
|
||||
const std::string &Client::GetEndpoint() const {
|
||||
return _pimpl->endpoint;
|
||||
}
|
||||
|
||||
std::string Client::GetClientVersion() {
|
||||
return ::carla::version();
|
||||
}
|
||||
|
|
|
@ -59,6 +59,10 @@ namespace detail {
|
|||
|
||||
void SetTimeout(time_duration timeout);
|
||||
|
||||
time_duration GetTimeout() const;
|
||||
|
||||
const std::string &GetEndpoint() const;
|
||||
|
||||
std::string GetClientVersion();
|
||||
|
||||
std::string GetServerVersion();
|
||||
|
|
|
@ -53,7 +53,7 @@ namespace detail {
|
|||
|
||||
std::vector<rpc::Actor> GetActors();
|
||||
|
||||
Timestamp WaitForState(time_duration timeout) {
|
||||
boost::optional<Timestamp> WaitForState(time_duration timeout) {
|
||||
return _timestamp.WaitFor(timeout);
|
||||
}
|
||||
|
||||
|
|
|
@ -6,10 +6,13 @@
|
|||
|
||||
#include "carla/client/detail/Simulator.h"
|
||||
|
||||
#include "carla/Exception.h"
|
||||
#include "carla/Logging.h"
|
||||
#include "carla/RecurrentSharedFuture.h"
|
||||
#include "carla/client/BlueprintLibrary.h"
|
||||
#include "carla/client/Map.h"
|
||||
#include "carla/client/Sensor.h"
|
||||
#include "carla/client/TimeoutException.h"
|
||||
#include "carla/client/detail/ActorFactory.h"
|
||||
#include "carla/sensor/Deserializer.h"
|
||||
|
||||
|
@ -60,6 +63,7 @@ namespace detail {
|
|||
ValidateVersions(_client);
|
||||
_episode = std::make_shared<Episode>(_client);
|
||||
_episode->Listen();
|
||||
WaitForTick(_client.GetTimeout());
|
||||
}
|
||||
return EpisodeProxy{shared_from_this()};
|
||||
}
|
||||
|
@ -68,6 +72,19 @@ namespace detail {
|
|||
return MakeShared<Map>(_client.GetMapInfo());
|
||||
}
|
||||
|
||||
// ===========================================================================
|
||||
// -- Tick -------------------------------------------------------------------
|
||||
// ===========================================================================
|
||||
|
||||
Timestamp Simulator::WaitForTick(time_duration timeout) {
|
||||
DEBUG_ASSERT(_episode != nullptr);
|
||||
auto result = _episode->WaitForState(timeout);
|
||||
if (!result.has_value()) {
|
||||
throw_exception(TimeoutException(_client.GetEndpoint(), timeout));
|
||||
}
|
||||
return *result;
|
||||
}
|
||||
|
||||
// ===========================================================================
|
||||
// -- Access to global objects in the episode --------------------------------
|
||||
// ===========================================================================
|
||||
|
|
|
@ -107,10 +107,7 @@ namespace detail {
|
|||
// =========================================================================
|
||||
/// @{
|
||||
|
||||
Timestamp WaitForTick(time_duration timeout) {
|
||||
DEBUG_ASSERT(_episode != nullptr);
|
||||
return _episode->WaitForState(timeout);
|
||||
}
|
||||
Timestamp WaitForTick(time_duration timeout);
|
||||
|
||||
void RegisterOnTickEvent(std::function<void(Timestamp)> callback) {
|
||||
DEBUG_ASSERT(_episode != nullptr);
|
||||
|
|
|
@ -22,8 +22,9 @@ TEST(recurrent_shared_future, use_case) {
|
|||
|
||||
threads.CreateThreads(number_of_threads, [&]() {
|
||||
while (!done) {
|
||||
int result = future.WaitFor(1s);
|
||||
ASSERT_EQ(result, 42);
|
||||
auto result = future.WaitFor(1s);
|
||||
ASSERT_TRUE(result.has_value());
|
||||
ASSERT_EQ(*result, 42);
|
||||
++count;
|
||||
}
|
||||
});
|
||||
|
@ -42,7 +43,8 @@ TEST(recurrent_shared_future, use_case) {
|
|||
TEST(recurrent_shared_future, timeout) {
|
||||
using namespace carla;
|
||||
RecurrentSharedFuture<int> future;
|
||||
ASSERT_THROW(future.WaitFor(1ns), std::runtime_error);
|
||||
auto result = future.WaitFor(1ns);
|
||||
ASSERT_FALSE(result.has_value());
|
||||
}
|
||||
|
||||
TEST(recurrent_shared_future, exception) {
|
||||
|
|
|
@ -12,7 +12,7 @@ import numpy as np
|
|||
import networkx as nx
|
||||
|
||||
import carla
|
||||
from local_planner import RoadOption
|
||||
from agents.navigation.local_planner import RoadOption
|
||||
|
||||
|
||||
class GlobalRoutePlanner(object):
|
||||
|
|
|
@ -73,6 +73,14 @@ try:
|
|||
except IndexError:
|
||||
pass
|
||||
|
||||
# ==============================================================================
|
||||
# -- add PythonAPI for release mode --------------------------------------------
|
||||
# ==============================================================================
|
||||
try:
|
||||
sys.path.append(glob.glob('PythonAPI')[0])
|
||||
except IndexError:
|
||||
pass
|
||||
|
||||
import carla
|
||||
from carla import ColorConverter as cc
|
||||
from agents.navigation.roaming_agent import *
|
||||
|
|
|
@ -0,0 +1,855 @@
|
|||
#!/usr/bin/env python
|
||||
|
||||
# Copyright (c) 2019 Intel Labs
|
||||
#
|
||||
# This work is licensed under the terms of the MIT license.
|
||||
# For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
# Allows controlling a vehicle with a keyboard. For a simpler and more
|
||||
# documented example, please take a look at tutorial.py.
|
||||
|
||||
"""
|
||||
Welcome to CARLA manual control with steering wheel Logitech G29.
|
||||
|
||||
To drive start by preshing the brake pedal.
|
||||
Change your wheel_config.ini according to your steering wheel.
|
||||
|
||||
To find out the values of your steering wheel use jstest-gtk in Ubuntu.
|
||||
|
||||
"""
|
||||
|
||||
from __future__ import print_function
|
||||
|
||||
|
||||
# ==============================================================================
|
||||
# -- find carla module ---------------------------------------------------------
|
||||
# ==============================================================================
|
||||
|
||||
|
||||
import glob
|
||||
import os
|
||||
import sys
|
||||
|
||||
try:
|
||||
sys.path.append(glob.glob('**/carla-*%d.%d-%s.egg' % (
|
||||
sys.version_info.major,
|
||||
sys.version_info.minor,
|
||||
'win-amd64' if os.name == 'nt' else 'linux-x86_64'))[0])
|
||||
except IndexError:
|
||||
pass
|
||||
|
||||
|
||||
# ==============================================================================
|
||||
# -- imports -------------------------------------------------------------------
|
||||
# ==============================================================================
|
||||
|
||||
|
||||
import carla
|
||||
|
||||
from carla import ColorConverter as cc
|
||||
|
||||
import argparse
|
||||
import collections
|
||||
from configparser import ConfigParser
|
||||
import datetime
|
||||
import logging
|
||||
import math
|
||||
import random
|
||||
import re
|
||||
import weakref
|
||||
|
||||
try:
|
||||
import pygame
|
||||
from pygame.locals import KMOD_CTRL
|
||||
from pygame.locals import KMOD_SHIFT
|
||||
from pygame.locals import K_0
|
||||
from pygame.locals import K_9
|
||||
from pygame.locals import K_BACKQUOTE
|
||||
from pygame.locals import K_BACKSPACE
|
||||
from pygame.locals import K_COMMA
|
||||
from pygame.locals import K_DOWN
|
||||
from pygame.locals import K_ESCAPE
|
||||
from pygame.locals import K_F1
|
||||
from pygame.locals import K_LEFT
|
||||
from pygame.locals import K_PERIOD
|
||||
from pygame.locals import K_RIGHT
|
||||
from pygame.locals import K_SLASH
|
||||
from pygame.locals import K_SPACE
|
||||
from pygame.locals import K_TAB
|
||||
from pygame.locals import K_UP
|
||||
from pygame.locals import K_a
|
||||
from pygame.locals import K_c
|
||||
from pygame.locals import K_d
|
||||
from pygame.locals import K_h
|
||||
from pygame.locals import K_m
|
||||
from pygame.locals import K_p
|
||||
from pygame.locals import K_q
|
||||
from pygame.locals import K_r
|
||||
from pygame.locals import K_s
|
||||
from pygame.locals import K_w
|
||||
except ImportError:
|
||||
raise RuntimeError('cannot import pygame, make sure pygame package is installed')
|
||||
|
||||
try:
|
||||
import numpy as np
|
||||
except ImportError:
|
||||
raise RuntimeError('cannot import numpy, make sure numpy package is installed')
|
||||
|
||||
|
||||
# ==============================================================================
|
||||
# -- Global functions ----------------------------------------------------------
|
||||
# ==============================================================================
|
||||
|
||||
|
||||
def find_weather_presets():
|
||||
rgx = re.compile('.+?(?:(?<=[a-z])(?=[A-Z])|(?<=[A-Z])(?=[A-Z][a-z])|$)')
|
||||
name = lambda x: ' '.join(m.group(0) for m in rgx.finditer(x))
|
||||
presets = [x for x in dir(carla.WeatherParameters) if re.match('[A-Z].+', x)]
|
||||
return [(getattr(carla.WeatherParameters, x), name(x)) for x in presets]
|
||||
|
||||
|
||||
def get_actor_display_name(actor, truncate=250):
|
||||
name = ' '.join(actor.type_id.replace('_', '.').title().split('.')[1:])
|
||||
return (name[:truncate-1] + u'\u2026') if len(name) > truncate else name
|
||||
|
||||
|
||||
# ==============================================================================
|
||||
# -- World ---------------------------------------------------------------------
|
||||
# ==============================================================================
|
||||
|
||||
|
||||
class World(object):
|
||||
def __init__(self, carla_world, hud, actor_filter):
|
||||
self.world = carla_world
|
||||
self.hud = hud
|
||||
self.player = None
|
||||
self.collision_sensor = None
|
||||
self.lane_invasion_sensor = None
|
||||
self.gnss_sensor = None
|
||||
self.camera_manager = None
|
||||
self._weather_presets = find_weather_presets()
|
||||
self._weather_index = 0
|
||||
self._actor_filter = actor_filter
|
||||
self.restart()
|
||||
self.world.on_tick(hud.on_world_tick)
|
||||
|
||||
def restart(self):
|
||||
# Keep same camera config if the camera manager exists.
|
||||
cam_index = self.camera_manager._index if self.camera_manager is not None else 0
|
||||
cam_pos_index = self.camera_manager._transform_index if self.camera_manager is not None else 0
|
||||
# Get a random blueprint.
|
||||
blueprint = random.choice(self.world.get_blueprint_library().filter(self._actor_filter))
|
||||
blueprint.set_attribute('role_name', 'hero')
|
||||
if blueprint.has_attribute('color'):
|
||||
color = random.choice(blueprint.get_attribute('color').recommended_values)
|
||||
blueprint.set_attribute('color', color)
|
||||
# Spawn the player.
|
||||
if self.player is not None:
|
||||
spawn_point = self.player.get_transform()
|
||||
spawn_point.location.z += 2.0
|
||||
spawn_point.rotation.roll = 0.0
|
||||
spawn_point.rotation.pitch = 0.0
|
||||
self.destroy()
|
||||
self.player = self.world.try_spawn_actor(blueprint, spawn_point)
|
||||
while self.player is None:
|
||||
spawn_points = self.world.get_map().get_spawn_points()
|
||||
spawn_point = random.choice(spawn_points) if spawn_points else carla.Transform()
|
||||
self.player = self.world.try_spawn_actor(blueprint, spawn_point)
|
||||
# Set up the sensors.
|
||||
self.collision_sensor = CollisionSensor(self.player, self.hud)
|
||||
self.lane_invasion_sensor = LaneInvasionSensor(self.player, self.hud)
|
||||
self.gnss_sensor = GnssSensor(self.player)
|
||||
self.camera_manager = CameraManager(self.player, self.hud)
|
||||
self.camera_manager._transform_index = cam_pos_index
|
||||
self.camera_manager.set_sensor(cam_index, notify=False)
|
||||
actor_type = get_actor_display_name(self.player)
|
||||
self.hud.notification(actor_type)
|
||||
|
||||
def next_weather(self, reverse=False):
|
||||
self._weather_index += -1 if reverse else 1
|
||||
self._weather_index %= len(self._weather_presets)
|
||||
preset = self._weather_presets[self._weather_index]
|
||||
self.hud.notification('Weather: %s' % preset[1])
|
||||
self.player.get_world().set_weather(preset[0])
|
||||
|
||||
def tick(self, clock):
|
||||
self.hud.tick(self, clock)
|
||||
|
||||
def render(self, display):
|
||||
self.camera_manager.render(display)
|
||||
self.hud.render(display)
|
||||
|
||||
def destroy(self):
|
||||
actors = [
|
||||
self.camera_manager.sensor,
|
||||
self.collision_sensor.sensor,
|
||||
self.lane_invasion_sensor.sensor,
|
||||
self.gnss_sensor.sensor,
|
||||
self.player]
|
||||
for actor in actors:
|
||||
if actor is not None:
|
||||
actor.destroy()
|
||||
|
||||
|
||||
# ==============================================================================
|
||||
# -- DualControl -----------------------------------------------------------
|
||||
# ==============================================================================
|
||||
|
||||
|
||||
class DualControl(object):
|
||||
def __init__(self, world, start_in_autopilot):
|
||||
self._autopilot_enabled = start_in_autopilot
|
||||
if isinstance(world.player, carla.Vehicle):
|
||||
self._control = carla.VehicleControl()
|
||||
world.player.set_autopilot(self._autopilot_enabled)
|
||||
elif isinstance(world.player, carla.Walker):
|
||||
self._control = carla.WalkerControl()
|
||||
self._autopilot_enabled = False
|
||||
self._rotation = world.player.get_transform().rotation
|
||||
else:
|
||||
raise NotImplementedError("Actor type not supported")
|
||||
self._steer_cache = 0.0
|
||||
world.hud.notification("Press 'H' or '?' for help.", seconds=4.0)
|
||||
|
||||
# initialize steering wheel
|
||||
pygame.joystick.init()
|
||||
|
||||
joystick_count = pygame.joystick.get_count()
|
||||
if joystick_count > 1:
|
||||
raise ValueError("Please Connect Just One Joystick")
|
||||
|
||||
self._joystick = pygame.joystick.Joystick(0)
|
||||
self._joystick.init()
|
||||
|
||||
self._parser = ConfigParser()
|
||||
self._parser.read('wheel_config.ini')
|
||||
self._steer_idx = int(
|
||||
self._parser.get('G29 Racing Wheel', 'steering_wheel'))
|
||||
self._throttle_idx = int(
|
||||
self._parser.get('G29 Racing Wheel', 'throttle'))
|
||||
self._brake_idx = int(self._parser.get('G29 Racing Wheel', 'brake'))
|
||||
self._reverse_idx = int(self._parser.get('G29 Racing Wheel', 'reverse'))
|
||||
self._handbrake_idx = int(
|
||||
self._parser.get('G29 Racing Wheel', 'handbrake'))
|
||||
|
||||
def parse_events(self, world, clock):
|
||||
for event in pygame.event.get():
|
||||
if event.type == pygame.QUIT:
|
||||
return True
|
||||
elif event.type == pygame.JOYBUTTONDOWN:
|
||||
if event.button == 0:
|
||||
world.restart()
|
||||
elif event.button == 1:
|
||||
world.hud.toggle_info()
|
||||
elif event.button == 2:
|
||||
world.camera_manager.toggle_camera()
|
||||
elif event.button == 3:
|
||||
world.next_weather()
|
||||
elif event.button == self._reverse_idx:
|
||||
self._control.gear = 1 if self._control.reverse else -1
|
||||
elif event.button == 23:
|
||||
world.camera_manager.next_sensor()
|
||||
|
||||
elif event.type == pygame.KEYUP:
|
||||
if self._is_quit_shortcut(event.key):
|
||||
return True
|
||||
elif event.key == K_BACKSPACE:
|
||||
world.restart()
|
||||
elif event.key == K_F1:
|
||||
world.hud.toggle_info()
|
||||
elif event.key == K_h or (event.key == K_SLASH and pygame.key.get_mods() & KMOD_SHIFT):
|
||||
world.hud.help.toggle()
|
||||
elif event.key == K_TAB:
|
||||
world.camera_manager.toggle_camera()
|
||||
elif event.key == K_c and pygame.key.get_mods() & KMOD_SHIFT:
|
||||
world.next_weather(reverse=True)
|
||||
elif event.key == K_c:
|
||||
world.next_weather()
|
||||
elif event.key == K_BACKQUOTE:
|
||||
world.camera_manager.next_sensor()
|
||||
elif event.key > K_0 and event.key <= K_9:
|
||||
world.camera_manager.set_sensor(event.key - 1 - K_0)
|
||||
elif event.key == K_r:
|
||||
world.camera_manager.toggle_recording()
|
||||
if isinstance(self._control, carla.VehicleControl):
|
||||
if event.key == K_q:
|
||||
self._control.gear = 1 if self._control.reverse else -1
|
||||
elif event.key == K_m:
|
||||
self._control.manual_gear_shift = not self._control.manual_gear_shift
|
||||
self._control.gear = world.player.get_control().gear
|
||||
world.hud.notification('%s Transmission' % ('Manual' if self._control.manual_gear_shift else 'Automatic'))
|
||||
elif self._control.manual_gear_shift and event.key == K_COMMA:
|
||||
self._control.gear = max(-1, self._control.gear - 1)
|
||||
elif self._control.manual_gear_shift and event.key == K_PERIOD:
|
||||
self._control.gear = self._control.gear + 1
|
||||
elif event.key == K_p:
|
||||
self._autopilot_enabled = not self._autopilot_enabled
|
||||
world.player.set_autopilot(self._autopilot_enabled)
|
||||
world.hud.notification('Autopilot %s' % ('On' if self._autopilot_enabled else 'Off'))
|
||||
|
||||
if not self._autopilot_enabled:
|
||||
if isinstance(self._control, carla.VehicleControl):
|
||||
self._parse_vehicle_keys(pygame.key.get_pressed(), clock.get_time())
|
||||
self._parse_vehicle_wheel()
|
||||
self._control.reverse = self._control.gear < 0
|
||||
elif isinstance(self._control, carla.WalkerControl):
|
||||
self._parse_walker_keys(pygame.key.get_pressed(), clock.get_time())
|
||||
world.player.apply_control(self._control)
|
||||
|
||||
def _parse_vehicle_keys(self, keys, milliseconds):
|
||||
self._control.throttle = 1.0 if keys[K_UP] or keys[K_w] else 0.0
|
||||
steer_increment = 5e-4 * milliseconds
|
||||
if keys[K_LEFT] or keys[K_a]:
|
||||
self._steer_cache -= steer_increment
|
||||
elif keys[K_RIGHT] or keys[K_d]:
|
||||
self._steer_cache += steer_increment
|
||||
else:
|
||||
self._steer_cache = 0.0
|
||||
self._steer_cache = min(0.7, max(-0.7, self._steer_cache))
|
||||
self._control.steer = round(self._steer_cache, 1)
|
||||
self._control.brake = 1.0 if keys[K_DOWN] or keys[K_s] else 0.0
|
||||
self._control.hand_brake = keys[K_SPACE]
|
||||
|
||||
def _parse_vehicle_wheel(self):
|
||||
numAxes = self._joystick.get_numaxes()
|
||||
jsInputs = [float(self._joystick.get_axis(i)) for i in range(numAxes)]
|
||||
# print (jsInputs)
|
||||
jsButtons = [float(self._joystick.get_button(i)) for i in
|
||||
range(self._joystick.get_numbuttons())]
|
||||
|
||||
# Custom function to map range of inputs [1, -1] to outputs [0, 1] i.e 1 from inputs means nothing is pressed
|
||||
# For the steering, it seems fine as it is
|
||||
K1 = 1.0 # 0.55
|
||||
steerCmd = K1 * math.tan(1.1 * jsInputs[self._steer_idx])
|
||||
|
||||
K2 = 1.6 # 1.6
|
||||
throttleCmd = K2 + (2.05 * math.log10(
|
||||
-0.7 * jsInputs[self._throttle_idx] + 1.4) - 1.2) / 0.92
|
||||
if throttleCmd <= 0:
|
||||
throttleCmd = 0
|
||||
elif throttleCmd > 1:
|
||||
throttleCmd = 1
|
||||
|
||||
brakeCmd = 1.6 + (2.05 * math.log10(
|
||||
-0.7 * jsInputs[self._brake_idx] + 1.4) - 1.2) / 0.92
|
||||
if brakeCmd <= 0:
|
||||
brakeCmd = 0
|
||||
elif brakeCmd > 1:
|
||||
brakeCmd = 1
|
||||
|
||||
self._control.steer = steerCmd
|
||||
self._control.brake = brakeCmd
|
||||
self._control.throttle = throttleCmd
|
||||
|
||||
#toggle = jsButtons[self._reverse_idx]
|
||||
|
||||
|
||||
self._control.hand_brake = bool(jsButtons[self._handbrake_idx])
|
||||
|
||||
|
||||
def _parse_walker_keys(self, keys, milliseconds):
|
||||
self._control.speed = 0.0
|
||||
if keys[K_DOWN] or keys[K_s]:
|
||||
self._control.speed = 0.0
|
||||
if keys[K_LEFT] or keys[K_a]:
|
||||
self._control.speed = .01
|
||||
self._rotation.yaw -= 0.08 * milliseconds
|
||||
if keys[K_RIGHT] or keys[K_d]:
|
||||
self._control.speed = .01
|
||||
self._rotation.yaw += 0.08 * milliseconds
|
||||
if keys[K_UP] or keys[K_w]:
|
||||
self._control.speed = 5.556 if pygame.key.get_mods() & KMOD_SHIFT else 2.778
|
||||
self._control.jump = keys[K_SPACE]
|
||||
self._rotation.yaw = round(self._rotation.yaw, 1)
|
||||
self._control.direction = self._rotation.get_forward_vector()
|
||||
|
||||
@staticmethod
|
||||
def _is_quit_shortcut(key):
|
||||
return (key == K_ESCAPE) or (key == K_q and pygame.key.get_mods() & KMOD_CTRL)
|
||||
|
||||
|
||||
# ==============================================================================
|
||||
# -- HUD -----------------------------------------------------------------------
|
||||
# ==============================================================================
|
||||
|
||||
|
||||
class HUD(object):
|
||||
def __init__(self, width, height):
|
||||
self.dim = (width, height)
|
||||
font = pygame.font.Font(pygame.font.get_default_font(), 20)
|
||||
fonts = [x for x in pygame.font.get_fonts() if 'mono' in x]
|
||||
default_font = 'ubuntumono'
|
||||
mono = default_font if default_font in fonts else fonts[0]
|
||||
mono = pygame.font.match_font(mono)
|
||||
self._font_mono = pygame.font.Font(mono, 14)
|
||||
self._notifications = FadingText(font, (width, 40), (0, height - 40))
|
||||
self.help = HelpText(pygame.font.Font(mono, 24), width, height)
|
||||
self.server_fps = 0
|
||||
self.frame_number = 0
|
||||
self.simulation_time = 0
|
||||
self._show_info = True
|
||||
self._info_text = []
|
||||
self._server_clock = pygame.time.Clock()
|
||||
|
||||
def on_world_tick(self, timestamp):
|
||||
self._server_clock.tick()
|
||||
self.server_fps = self._server_clock.get_fps()
|
||||
self.frame_number = timestamp.frame_count
|
||||
self.simulation_time = timestamp.elapsed_seconds
|
||||
|
||||
def tick(self, world, clock):
|
||||
self._notifications.tick(world, clock)
|
||||
if not self._show_info:
|
||||
return
|
||||
t = world.player.get_transform()
|
||||
v = world.player.get_velocity()
|
||||
c = world.player.get_control()
|
||||
heading = 'N' if abs(t.rotation.yaw) < 89.5 else ''
|
||||
heading += 'S' if abs(t.rotation.yaw) > 90.5 else ''
|
||||
heading += 'E' if 179.5 > t.rotation.yaw > 0.5 else ''
|
||||
heading += 'W' if -0.5 > t.rotation.yaw > -179.5 else ''
|
||||
colhist = world.collision_sensor.get_collision_history()
|
||||
collision = [colhist[x + self.frame_number - 200] for x in range(0, 200)]
|
||||
max_col = max(1.0, max(collision))
|
||||
collision = [x / max_col for x in collision]
|
||||
vehicles = world.world.get_actors().filter('vehicle.*')
|
||||
self._info_text = [
|
||||
'Server: % 16.0f FPS' % self.server_fps,
|
||||
'Client: % 16.0f FPS' % clock.get_fps(),
|
||||
'',
|
||||
'Vehicle: % 20s' % get_actor_display_name(world.player, truncate=20),
|
||||
'Map: % 20s' % world.world.map_name,
|
||||
'Simulation time: % 12s' % datetime.timedelta(seconds=int(self.simulation_time)),
|
||||
'',
|
||||
'Speed: % 15.0f km/h' % (3.6 * math.sqrt(v.x**2 + v.y**2 + v.z**2)),
|
||||
u'Heading:% 16.0f\N{DEGREE SIGN} % 2s' % (t.rotation.yaw, heading),
|
||||
'Location:% 20s' % ('(% 5.1f, % 5.1f)' % (t.location.x, t.location.y)),
|
||||
'GNSS:% 24s' % ('(% 2.6f, % 3.6f)' % (world.gnss_sensor.lat, world.gnss_sensor.lon)),
|
||||
'Height: % 18.0f m' % t.location.z,
|
||||
'']
|
||||
if isinstance(c, carla.VehicleControl):
|
||||
self._info_text += [
|
||||
('Throttle:', c.throttle, 0.0, 1.0),
|
||||
('Steer:', c.steer, -1.0, 1.0),
|
||||
('Brake:', c.brake, 0.0, 1.0),
|
||||
('Reverse:', c.reverse),
|
||||
('Hand brake:', c.hand_brake),
|
||||
('Manual:', c.manual_gear_shift),
|
||||
'Gear: %s' % {-1: 'R', 0: 'N'}.get(c.gear, c.gear)]
|
||||
elif isinstance(c, carla.WalkerControl):
|
||||
self._info_text += [
|
||||
('Speed:', c.speed, 0.0, 5.556),
|
||||
('Jump:', c.jump)]
|
||||
self._info_text += [
|
||||
'',
|
||||
'Collision:',
|
||||
collision,
|
||||
'',
|
||||
'Number of vehicles: % 8d' % len(vehicles)]
|
||||
if len(vehicles) > 1:
|
||||
self._info_text += ['Nearby vehicles:']
|
||||
distance = lambda l: math.sqrt((l.x - t.location.x)**2 + (l.y - t.location.y)**2 + (l.z - t.location.z)**2)
|
||||
vehicles = [(distance(x.get_location()), x) for x in vehicles if x.id != world.player.id]
|
||||
for d, vehicle in sorted(vehicles):
|
||||
if d > 200.0:
|
||||
break
|
||||
vehicle_type = get_actor_display_name(vehicle, truncate=22)
|
||||
self._info_text.append('% 4dm %s' % (d, vehicle_type))
|
||||
|
||||
def toggle_info(self):
|
||||
self._show_info = not self._show_info
|
||||
|
||||
def notification(self, text, seconds=2.0):
|
||||
self._notifications.set_text(text, seconds=seconds)
|
||||
|
||||
def error(self, text):
|
||||
self._notifications.set_text('Error: %s' % text, (255, 0, 0))
|
||||
|
||||
def render(self, display):
|
||||
if self._show_info:
|
||||
info_surface = pygame.Surface((220, self.dim[1]))
|
||||
info_surface.set_alpha(100)
|
||||
display.blit(info_surface, (0, 0))
|
||||
v_offset = 4
|
||||
bar_h_offset = 100
|
||||
bar_width = 106
|
||||
for item in self._info_text:
|
||||
if v_offset + 18 > self.dim[1]:
|
||||
break
|
||||
if isinstance(item, list):
|
||||
if len(item) > 1:
|
||||
points = [(x + 8, v_offset + 8 + (1.0 - y) * 30) for x, y in enumerate(item)]
|
||||
pygame.draw.lines(display, (255, 136, 0), False, points, 2)
|
||||
item = None
|
||||
v_offset += 18
|
||||
elif isinstance(item, tuple):
|
||||
if isinstance(item[1], bool):
|
||||
rect = pygame.Rect((bar_h_offset, v_offset + 8), (6, 6))
|
||||
pygame.draw.rect(display, (255, 255, 255), rect, 0 if item[1] else 1)
|
||||
else:
|
||||
rect_border = pygame.Rect((bar_h_offset, v_offset + 8), (bar_width, 6))
|
||||
pygame.draw.rect(display, (255, 255, 255), rect_border, 1)
|
||||
f = (item[1] - item[2]) / (item[3] - item[2])
|
||||
if item[2] < 0.0:
|
||||
rect = pygame.Rect((bar_h_offset + f * (bar_width - 6), v_offset + 8), (6, 6))
|
||||
else:
|
||||
rect = pygame.Rect((bar_h_offset, v_offset + 8), (f * bar_width, 6))
|
||||
pygame.draw.rect(display, (255, 255, 255), rect)
|
||||
item = item[0]
|
||||
if item: # At this point has to be a str.
|
||||
surface = self._font_mono.render(item, True, (255, 255, 255))
|
||||
display.blit(surface, (8, v_offset))
|
||||
v_offset += 18
|
||||
self._notifications.render(display)
|
||||
self.help.render(display)
|
||||
|
||||
|
||||
# ==============================================================================
|
||||
# -- FadingText ----------------------------------------------------------------
|
||||
# ==============================================================================
|
||||
|
||||
|
||||
class FadingText(object):
|
||||
def __init__(self, font, dim, pos):
|
||||
self.font = font
|
||||
self.dim = dim
|
||||
self.pos = pos
|
||||
self.seconds_left = 0
|
||||
self.surface = pygame.Surface(self.dim)
|
||||
|
||||
def set_text(self, text, color=(255, 255, 255), seconds=2.0):
|
||||
text_texture = self.font.render(text, True, color)
|
||||
self.surface = pygame.Surface(self.dim)
|
||||
self.seconds_left = seconds
|
||||
self.surface.fill((0, 0, 0, 0))
|
||||
self.surface.blit(text_texture, (10, 11))
|
||||
|
||||
def tick(self, _, clock):
|
||||
delta_seconds = 1e-3 * clock.get_time()
|
||||
self.seconds_left = max(0.0, self.seconds_left - delta_seconds)
|
||||
self.surface.set_alpha(500.0 * self.seconds_left)
|
||||
|
||||
def render(self, display):
|
||||
display.blit(self.surface, self.pos)
|
||||
|
||||
|
||||
# ==============================================================================
|
||||
# -- HelpText ------------------------------------------------------------------
|
||||
# ==============================================================================
|
||||
|
||||
|
||||
class HelpText(object):
|
||||
def __init__(self, font, width, height):
|
||||
lines = __doc__.split('\n')
|
||||
self.font = font
|
||||
self.dim = (680, len(lines) * 22 + 12)
|
||||
self.pos = (0.5 * width - 0.5 * self.dim[0], 0.5 * height - 0.5 * self.dim[1])
|
||||
self.seconds_left = 0
|
||||
self.surface = pygame.Surface(self.dim)
|
||||
self.surface.fill((0, 0, 0, 0))
|
||||
for n, line in enumerate(lines):
|
||||
text_texture = self.font.render(line, True, (255, 255, 255))
|
||||
self.surface.blit(text_texture, (22, n * 22))
|
||||
self._render = False
|
||||
self.surface.set_alpha(220)
|
||||
|
||||
def toggle(self):
|
||||
self._render = not self._render
|
||||
|
||||
def render(self, display):
|
||||
if self._render:
|
||||
display.blit(self.surface, self.pos)
|
||||
|
||||
|
||||
# ==============================================================================
|
||||
# -- CollisionSensor -----------------------------------------------------------
|
||||
# ==============================================================================
|
||||
|
||||
|
||||
class CollisionSensor(object):
|
||||
def __init__(self, parent_actor, hud):
|
||||
self.sensor = None
|
||||
self._history = []
|
||||
self._parent = parent_actor
|
||||
self._hud = hud
|
||||
world = self._parent.get_world()
|
||||
bp = world.get_blueprint_library().find('sensor.other.collision')
|
||||
self.sensor = world.spawn_actor(bp, carla.Transform(), attach_to=self._parent)
|
||||
# We need to pass the lambda a weak reference to self to avoid circular
|
||||
# reference.
|
||||
weak_self = weakref.ref(self)
|
||||
self.sensor.listen(lambda event: CollisionSensor._on_collision(weak_self, event))
|
||||
|
||||
def get_collision_history(self):
|
||||
history = collections.defaultdict(int)
|
||||
for frame, intensity in self._history:
|
||||
history[frame] += intensity
|
||||
return history
|
||||
|
||||
@staticmethod
|
||||
def _on_collision(weak_self, event):
|
||||
self = weak_self()
|
||||
if not self:
|
||||
return
|
||||
actor_type = get_actor_display_name(event.other_actor)
|
||||
self._hud.notification('Collision with %r' % actor_type)
|
||||
impulse = event.normal_impulse
|
||||
intensity = math.sqrt(impulse.x**2 + impulse.y**2 + impulse.z**2)
|
||||
self._history.append((event.frame_number, intensity))
|
||||
if len(self._history) > 4000:
|
||||
self._history.pop(0)
|
||||
|
||||
|
||||
# ==============================================================================
|
||||
# -- LaneInvasionSensor --------------------------------------------------------
|
||||
# ==============================================================================
|
||||
|
||||
|
||||
class LaneInvasionSensor(object):
|
||||
def __init__(self, parent_actor, hud):
|
||||
self.sensor = None
|
||||
self._parent = parent_actor
|
||||
self._hud = hud
|
||||
world = self._parent.get_world()
|
||||
bp = world.get_blueprint_library().find('sensor.other.lane_detector')
|
||||
self.sensor = world.spawn_actor(bp, carla.Transform(), attach_to=self._parent)
|
||||
# We need to pass the lambda a weak reference to self to avoid circular
|
||||
# reference.
|
||||
weak_self = weakref.ref(self)
|
||||
self.sensor.listen(lambda event: LaneInvasionSensor._on_invasion(weak_self, event))
|
||||
|
||||
@staticmethod
|
||||
def _on_invasion(weak_self, event):
|
||||
self = weak_self()
|
||||
if not self:
|
||||
return
|
||||
text = ['%r' % str(x).split()[-1] for x in set(event.crossed_lane_markings)]
|
||||
self._hud.notification('Crossed line %s' % ' and '.join(text))
|
||||
|
||||
# ==============================================================================
|
||||
# -- GnssSensor --------------------------------------------------------
|
||||
# ==============================================================================
|
||||
|
||||
|
||||
class GnssSensor(object):
|
||||
def __init__(self, parent_actor):
|
||||
self.sensor = None
|
||||
self._parent = parent_actor
|
||||
self.lat = 0.0
|
||||
self.lon = 0.0
|
||||
world = self._parent.get_world()
|
||||
bp = world.get_blueprint_library().find('sensor.other.gnss')
|
||||
self.sensor = world.spawn_actor(bp, carla.Transform(carla.Location(x=1.0, z=2.8)), attach_to=self._parent)
|
||||
# We need to pass the lambda a weak reference to self to avoid circular
|
||||
# reference.
|
||||
weak_self = weakref.ref(self)
|
||||
self.sensor.listen(lambda event: GnssSensor._on_gnss_event(weak_self, event))
|
||||
|
||||
@staticmethod
|
||||
def _on_gnss_event(weak_self, event):
|
||||
self = weak_self()
|
||||
if not self:
|
||||
return
|
||||
self.lat = event.latitude
|
||||
self.lon = event.longitude
|
||||
|
||||
|
||||
# ==============================================================================
|
||||
# -- CameraManager -------------------------------------------------------------
|
||||
# ==============================================================================
|
||||
|
||||
|
||||
class CameraManager(object):
|
||||
def __init__(self, parent_actor, hud):
|
||||
self.sensor = None
|
||||
self._surface = None
|
||||
self._parent = parent_actor
|
||||
self._hud = hud
|
||||
self._recording = False
|
||||
self._camera_transforms = [
|
||||
carla.Transform(carla.Location(x=-5.5, z=2.8), carla.Rotation(pitch=-15)),
|
||||
carla.Transform(carla.Location(x=1.6, z=1.7))]
|
||||
self._transform_index = 1
|
||||
self._sensors = [
|
||||
['sensor.camera.rgb', cc.Raw, 'Camera RGB'],
|
||||
['sensor.camera.depth', cc.Raw, 'Camera Depth (Raw)'],
|
||||
['sensor.camera.depth', cc.Depth, 'Camera Depth (Gray Scale)'],
|
||||
['sensor.camera.depth', cc.LogarithmicDepth, 'Camera Depth (Logarithmic Gray Scale)'],
|
||||
['sensor.camera.semantic_segmentation', cc.Raw, 'Camera Semantic Segmentation (Raw)'],
|
||||
['sensor.camera.semantic_segmentation', cc.CityScapesPalette, 'Camera Semantic Segmentation (CityScapes Palette)'],
|
||||
['sensor.lidar.ray_cast', None, 'Lidar (Ray-Cast)']]
|
||||
world = self._parent.get_world()
|
||||
bp_library = world.get_blueprint_library()
|
||||
for item in self._sensors:
|
||||
bp = bp_library.find(item[0])
|
||||
if item[0].startswith('sensor.camera'):
|
||||
bp.set_attribute('image_size_x', str(hud.dim[0]))
|
||||
bp.set_attribute('image_size_y', str(hud.dim[1]))
|
||||
elif item[0].startswith('sensor.lidar'):
|
||||
bp.set_attribute('range', '5000')
|
||||
item.append(bp)
|
||||
self._index = None
|
||||
|
||||
def toggle_camera(self):
|
||||
self._transform_index = (self._transform_index + 1) % len(self._camera_transforms)
|
||||
self.sensor.set_transform(self._camera_transforms[self._transform_index])
|
||||
|
||||
def set_sensor(self, index, notify=True):
|
||||
index = index % len(self._sensors)
|
||||
needs_respawn = True if self._index is None \
|
||||
else self._sensors[index][0] != self._sensors[self._index][0]
|
||||
if needs_respawn:
|
||||
if self.sensor is not None:
|
||||
self.sensor.destroy()
|
||||
self._surface = None
|
||||
self.sensor = self._parent.get_world().spawn_actor(
|
||||
self._sensors[index][-1],
|
||||
self._camera_transforms[self._transform_index],
|
||||
attach_to=self._parent)
|
||||
# We need to pass the lambda a weak reference to self to avoid
|
||||
# circular reference.
|
||||
weak_self = weakref.ref(self)
|
||||
self.sensor.listen(lambda image: CameraManager._parse_image(weak_self, image))
|
||||
if notify:
|
||||
self._hud.notification(self._sensors[index][2])
|
||||
self._index = index
|
||||
|
||||
def next_sensor(self):
|
||||
self.set_sensor(self._index + 1)
|
||||
|
||||
def toggle_recording(self):
|
||||
self._recording = not self._recording
|
||||
self._hud.notification('Recording %s' % ('On' if self._recording else 'Off'))
|
||||
|
||||
def render(self, display):
|
||||
if self._surface is not None:
|
||||
display.blit(self._surface, (0, 0))
|
||||
|
||||
@staticmethod
|
||||
def _parse_image(weak_self, image):
|
||||
self = weak_self()
|
||||
if not self:
|
||||
return
|
||||
if self._sensors[self._index][0].startswith('sensor.lidar'):
|
||||
points = np.frombuffer(image.raw_data, dtype=np.dtype('f4'))
|
||||
points = np.reshape(points, (int(points.shape[0]/3), 3))
|
||||
lidar_data = np.array(points[:, :2])
|
||||
lidar_data *= min(self._hud.dim) / 100.0
|
||||
lidar_data += (0.5 * self._hud.dim[0], 0.5 * self._hud.dim[1])
|
||||
lidar_data = np.fabs(lidar_data)
|
||||
lidar_data = lidar_data.astype(np.int32)
|
||||
lidar_data = np.reshape(lidar_data, (-1, 2))
|
||||
lidar_img_size = (self._hud.dim[0], self._hud.dim[1], 3)
|
||||
lidar_img = np.zeros(lidar_img_size)
|
||||
lidar_img[tuple(lidar_data.T)] = (255, 255, 255)
|
||||
self._surface = pygame.surfarray.make_surface(lidar_img)
|
||||
else:
|
||||
image.convert(self._sensors[self._index][1])
|
||||
array = np.frombuffer(image.raw_data, dtype=np.dtype("uint8"))
|
||||
array = np.reshape(array, (image.height, image.width, 4))
|
||||
array = array[:, :, :3]
|
||||
array = array[:, :, ::-1]
|
||||
self._surface = pygame.surfarray.make_surface(array.swapaxes(0, 1))
|
||||
if self._recording:
|
||||
image.save_to_disk('_out/%08d' % image.frame_number)
|
||||
|
||||
|
||||
# ==============================================================================
|
||||
# -- game_loop() ---------------------------------------------------------------
|
||||
# ==============================================================================
|
||||
|
||||
|
||||
def game_loop(args):
|
||||
pygame.init()
|
||||
pygame.font.init()
|
||||
world = None
|
||||
|
||||
try:
|
||||
client = carla.Client(args.host, args.port)
|
||||
client.set_timeout(2.0)
|
||||
|
||||
display = pygame.display.set_mode(
|
||||
(args.width, args.height),
|
||||
pygame.HWSURFACE | pygame.DOUBLEBUF)
|
||||
|
||||
hud = HUD(args.width, args.height)
|
||||
world = World(client.get_world(), hud, args.filter)
|
||||
controller = DualControl(world, args.autopilot)
|
||||
|
||||
clock = pygame.time.Clock()
|
||||
while True:
|
||||
clock.tick_busy_loop(60)
|
||||
if controller.parse_events(world, clock):
|
||||
return
|
||||
world.tick(clock)
|
||||
world.render(display)
|
||||
pygame.display.flip()
|
||||
|
||||
finally:
|
||||
|
||||
if world is not None:
|
||||
world.destroy()
|
||||
|
||||
pygame.quit()
|
||||
|
||||
|
||||
# ==============================================================================
|
||||
# -- main() --------------------------------------------------------------------
|
||||
# ==============================================================================
|
||||
|
||||
|
||||
def main():
|
||||
argparser = argparse.ArgumentParser(
|
||||
description='CARLA Manual Control Client')
|
||||
argparser.add_argument(
|
||||
'-v', '--verbose',
|
||||
action='store_true',
|
||||
dest='debug',
|
||||
help='print debug information')
|
||||
argparser.add_argument(
|
||||
'--host',
|
||||
metavar='H',
|
||||
default='127.0.0.1',
|
||||
help='IP of the host server (default: 127.0.0.1)')
|
||||
argparser.add_argument(
|
||||
'-p', '--port',
|
||||
metavar='P',
|
||||
default=2000,
|
||||
type=int,
|
||||
help='TCP port to listen to (default: 2000)')
|
||||
argparser.add_argument(
|
||||
'-a', '--autopilot',
|
||||
action='store_true',
|
||||
help='enable autopilot')
|
||||
argparser.add_argument(
|
||||
'--res',
|
||||
metavar='WIDTHxHEIGHT',
|
||||
default='1280x720',
|
||||
help='window resolution (default: 1280x720)')
|
||||
argparser.add_argument(
|
||||
'--filter',
|
||||
metavar='PATTERN',
|
||||
default='vehicle.*',
|
||||
help='actor filter (default: "vehicle.*")')
|
||||
args = argparser.parse_args()
|
||||
|
||||
args.width, args.height = [int(x) for x in args.res.split('x')]
|
||||
|
||||
log_level = logging.DEBUG if args.debug else logging.INFO
|
||||
logging.basicConfig(format='%(levelname)s: %(message)s', level=log_level)
|
||||
|
||||
logging.info('listening to server %s:%s', args.host, args.port)
|
||||
|
||||
print(__doc__)
|
||||
|
||||
try:
|
||||
|
||||
game_loop(args)
|
||||
|
||||
except KeyboardInterrupt:
|
||||
print('\nCancelled by user. Bye!')
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
|
||||
main()
|
|
@ -141,7 +141,7 @@ MODULE_WORLD = 'WORLD'
|
|||
MODULE_HUD = 'HUD'
|
||||
MODULE_INPUT = 'INPUT'
|
||||
|
||||
PIXELS_PER_METER = 15
|
||||
PIXELS_PER_METER = 12
|
||||
|
||||
MAP_DEFAULT_SCALE = 0.1
|
||||
HERO_DEFAULT_SCALE = 1.0
|
||||
|
@ -155,7 +155,7 @@ PIXELS_AHEAD_VEHICLE = 150
|
|||
|
||||
def get_actor_display_name(actor, truncate=250):
|
||||
name = ' '.join(actor.type_id.replace('_', '.').title().split('.')[1:])
|
||||
return (name[:truncate-1] + u'\u2026') if len(name) > truncate else name
|
||||
return (name[:truncate - 1] + u'\u2026') if len(name) > truncate else name
|
||||
|
||||
|
||||
class Util(object):
|
||||
|
@ -186,7 +186,7 @@ class ModuleManager(object):
|
|||
module.tick(clock)
|
||||
|
||||
def render(self, display):
|
||||
display.fill(COLOR_ALUMINIUM_5)
|
||||
display.fill(COLOR_ALUMINIUM_4)
|
||||
for module in self.modules:
|
||||
module.render(display)
|
||||
|
||||
|
@ -200,7 +200,6 @@ class ModuleManager(object):
|
|||
module.start()
|
||||
|
||||
|
||||
|
||||
# ==============================================================================
|
||||
# -- FadingText ----------------------------------------------------------------
|
||||
# ==============================================================================
|
||||
|
@ -243,9 +242,9 @@ class HelpText(object):
|
|||
self.pos = (0.5 * width - 0.5 * self.dim[0], 0.5 * height - 0.5 * self.dim[1])
|
||||
self.seconds_left = 0
|
||||
self.surface = pygame.Surface(self.dim)
|
||||
self.surface.fill((0, 0, 0, 0))
|
||||
self.surface.fill(COLOR_BLACK)
|
||||
for n, line in enumerate(lines):
|
||||
text_texture = self.font.render(line, True, (255, 255, 255))
|
||||
text_texture = self.font.render(line, True, COLOR_WHITE)
|
||||
self.surface.blit(text_texture, (22, n * 22))
|
||||
self._render = False
|
||||
self.surface.set_alpha(220)
|
||||
|
@ -280,7 +279,7 @@ class ModuleHUD (object):
|
|||
mono = default_font if default_font in fonts else fonts[0]
|
||||
mono = pygame.font.match_font(mono)
|
||||
self._font_mono = pygame.font.Font(mono, 14)
|
||||
self._header_font = pygame.font.SysFont('Arial', 14)
|
||||
self._header_font = pygame.font.SysFont('Arial', 14, True)
|
||||
self.help = HelpText(pygame.font.Font(mono, 24), *self.dim)
|
||||
self._notifications = FadingText(
|
||||
pygame.font.Font(pygame.font.get_default_font(), 20),
|
||||
|
@ -300,25 +299,26 @@ class ModuleHUD (object):
|
|||
def add_info(self, module_name, info):
|
||||
self._info_text[module_name] = info
|
||||
|
||||
def render_actors_ids(self, vehicle_id_surface, list_actors, world_to_pixel, hero_actor):
|
||||
def render_vehicles_ids(self, vehicle_id_surface, list_actors, world_to_pixel, hero_actor, hero_transform):
|
||||
vehicle_id_surface.fill(COLOR_BLACK)
|
||||
if self.show_actor_ids:
|
||||
vehicle_id_surface.set_alpha(150)
|
||||
for actor in list_actors:
|
||||
location = actor.get_location()
|
||||
x, y = world_to_pixel(location)
|
||||
x, y = world_to_pixel(actor[1].location)
|
||||
|
||||
angle = 0
|
||||
if hero_actor is not None:
|
||||
angle = -hero_actor.get_transform().rotation.yaw - 90
|
||||
angle = -hero_transform.rotation.yaw - 90
|
||||
|
||||
color = COLOR_ORANGE_0
|
||||
if actor.attributes['role_name'] == 'hero':
|
||||
color = COLOR_SCARLET_RED_0
|
||||
color = COLOR_SKY_BLUE_0
|
||||
if int(actor[0].attributes['number_of_wheels']) == 2:
|
||||
color = COLOR_CHOCOLATE_0
|
||||
if actor[0].attributes['role_name'] == 'hero':
|
||||
color = COLOR_CHAMELEON_0
|
||||
|
||||
font_surface = self._header_font.render(str(actor.id), True, color)
|
||||
rotated_font_surface = pygame.transform.rotate(font_surface, angle).convert_alpha()
|
||||
rect = rotated_font_surface.get_rect(center=(x,y))
|
||||
font_surface = self._header_font.render(str(actor[0].id), True, color)
|
||||
rotated_font_surface = pygame.transform.rotate(font_surface, angle)
|
||||
rect = rotated_font_surface.get_rect(center=(x, y))
|
||||
vehicle_id_surface.blit(rotated_font_surface, rect)
|
||||
|
||||
return vehicle_id_surface
|
||||
|
@ -382,13 +382,13 @@ class TrafficLightSurfaces(object):
|
|||
def make_surface(tl):
|
||||
w = 40
|
||||
surface = pygame.Surface((w, 3 * w), pygame.SRCALPHA)
|
||||
surface.fill((31, 31, 31) if tl != 'h' else (245, 121, 0))
|
||||
surface.fill(COLOR_ALUMINIUM_5 if tl != 'h' else COLOR_ORANGE_2)
|
||||
if tl != 'h':
|
||||
hw = int(w / 2)
|
||||
off = (48, 48, 48)
|
||||
red = (239, 41, 41)
|
||||
yellow = (252, 175, 62)
|
||||
green = (138, 226, 52)
|
||||
off = COLOR_ALUMINIUM_4
|
||||
red = COLOR_SCARLET_RED_0
|
||||
yellow = COLOR_BUTTER_0
|
||||
green = COLOR_CHAMELEON_0
|
||||
pygame.draw.circle(surface, red if tl == tls.Red else off, (hw, hw), int(0.4 * w))
|
||||
pygame.draw.circle(surface, yellow if tl == tls.Yellow else off, (hw, w + hw), int(0.4 * w))
|
||||
pygame.draw.circle(surface, green if tl == tls.Green else off, (hw, 2 * w + hw), int(0.4 * w))
|
||||
|
@ -435,18 +435,18 @@ class MapImage(object):
|
|||
self.surface = self._big_map_surface
|
||||
|
||||
def draw_road_map(self, map_surface, carla_map, world_to_pixel):
|
||||
map_surface.fill(COLOR_ALUMINIUM_5)
|
||||
map_surface.fill(COLOR_ALUMINIUM_4)
|
||||
precision = 0.05
|
||||
|
||||
def draw_lane_marking(surface, points, solid=True):
|
||||
if solid:
|
||||
pygame.draw.lines(surface, (252, 175, 62), False, points, 2)
|
||||
pygame.draw.lines(surface, COLOR_ORANGE_0, False, points, 2)
|
||||
else:
|
||||
broken_lines = [x for n, x in enumerate(zip(*(iter(points),) * 20)) if n % 3 == 0]
|
||||
for line in broken_lines:
|
||||
pygame.draw.lines(surface, (251, 241, 199), False, line, 2)
|
||||
pygame.draw.lines(surface, COLOR_ORANGE_0, False, line, 2)
|
||||
|
||||
def draw_arrow(surface, transform, color=(31, 31, 31)):
|
||||
def draw_arrow(surface, transform, color=COLOR_ALUMINIUM_2):
|
||||
transform.rotation.yaw += 180
|
||||
forward = transform.get_forward_vector()
|
||||
transform.rotation.yaw += 90
|
||||
|
@ -491,8 +491,8 @@ class MapImage(object):
|
|||
polygon = left_marking + [x for x in reversed(right_marking)]
|
||||
polygon = [world_to_pixel(x) for x in polygon]
|
||||
|
||||
pygame.draw.polygon(map_surface, (38, 38, 38), polygon, 10)
|
||||
pygame.draw.polygon(map_surface, (38, 38, 38), polygon)
|
||||
pygame.draw.polygon(map_surface, COLOR_ALUMINIUM_5, polygon, 10)
|
||||
pygame.draw.polygon(map_surface, COLOR_ALUMINIUM_5, polygon)
|
||||
|
||||
if not waypoint.is_intersection:
|
||||
sample = waypoints[int(len(waypoints) / 2)]
|
||||
|
@ -540,8 +540,7 @@ class ModuleWorld(object):
|
|||
# World data
|
||||
self.world = None
|
||||
self.town_map = None
|
||||
self.actors = None
|
||||
|
||||
self.actors_with_transforms = []
|
||||
# Store necessary modules
|
||||
self.module_hud = None
|
||||
self.module_input = None
|
||||
|
@ -551,6 +550,8 @@ class ModuleWorld(object):
|
|||
self.scaled_size = 0
|
||||
# Hero actor
|
||||
self.hero_actor = None
|
||||
self.hero_transform = None
|
||||
|
||||
self.scale_offset = [0, 0]
|
||||
|
||||
self.vehicle_id_surface = None
|
||||
|
@ -565,15 +566,14 @@ class ModuleWorld(object):
|
|||
|
||||
world = self.client.get_world()
|
||||
town_map = world.get_map()
|
||||
actors = world.get_actors()
|
||||
return (world, town_map, actors)
|
||||
return (world, town_map)
|
||||
|
||||
except Exception as ex:
|
||||
logging.error(ex)
|
||||
exit_game()
|
||||
|
||||
def start(self):
|
||||
self.world, self.town_map, self.actors = self._get_data_from_carla(self.host, self.port, self.timeout)
|
||||
self.world, self.town_map = self._get_data_from_carla(self.host, self.port, self.timeout)
|
||||
|
||||
# Create Surfaces
|
||||
self.map_image = MapImage(self.town_map, PIXELS_PER_METER)
|
||||
|
@ -600,8 +600,8 @@ class ModuleWorld(object):
|
|||
self.border_round_surface.fill(COLOR_BLACK)
|
||||
|
||||
center_offset = (int(self.module_hud.dim[0] / 2), int(self.module_hud.dim[1] / 2))
|
||||
pygame.draw.circle(self.border_round_surface, COLOR_ALUMINIUM_2, center_offset, int(self.module_hud.dim[1]/ 2))
|
||||
pygame.draw.circle(self.border_round_surface, COLOR_WHITE, center_offset, int((self.module_hud.dim[1] - 8)/ 2))
|
||||
pygame.draw.circle(self.border_round_surface, COLOR_ALUMINIUM_1, center_offset, int(self.module_hud.dim[1] / 2))
|
||||
pygame.draw.circle(self.border_round_surface, COLOR_WHITE, center_offset, int((self.module_hud.dim[1] - 8) / 2))
|
||||
|
||||
scaled_original_size = self.original_surface_size * (1.0 / 0.9)
|
||||
self.hero_surface = pygame.Surface((scaled_original_size, scaled_original_size)).convert()
|
||||
|
@ -609,14 +609,21 @@ class ModuleWorld(object):
|
|||
self.result_surface = pygame.Surface((self.surface_size, self.surface_size)).convert()
|
||||
self.result_surface.set_colorkey(COLOR_BLACK)
|
||||
|
||||
# Start hero mode by default
|
||||
self.select_hero_actor()
|
||||
self.hero_actor.set_autopilot(False)
|
||||
self.module_input.wheel_offset = HERO_DEFAULT_SCALE
|
||||
self.module_input._control = carla.VehicleControl()
|
||||
|
||||
weak_self = weakref.ref(self)
|
||||
self.world.on_tick(lambda timestamp: ModuleWorld.on_world_tick(weak_self, timestamp))
|
||||
|
||||
def select_hero_actor(self):
|
||||
hero_vehicles = [
|
||||
actor for actor in self.actors if 'vehicle' in actor.type_id and actor.attributes['role_name'] == 'hero']
|
||||
actor for actor in self.world.get_actors() if 'vehicle' in actor.type_id and actor.attributes['role_name'] == 'hero']
|
||||
if len(hero_vehicles) > 0:
|
||||
self.hero_actor = random.choice(hero_vehicles)
|
||||
self.hero_transform = self.hero_actor.get_transform()
|
||||
else:
|
||||
self._spawn_hero()
|
||||
|
||||
|
@ -633,10 +640,13 @@ class ModuleWorld(object):
|
|||
spawn_points = self.world.get_map().get_spawn_points()
|
||||
spawn_point = random.choice(spawn_points) if spawn_points else carla.Transform()
|
||||
self.hero_actor = self.world.try_spawn_actor(blueprint, spawn_point)
|
||||
if self.hero_actor is not None:
|
||||
self.hero_actor.set_autopilot()
|
||||
self.hero_transform = self.hero_actor.get_transform()
|
||||
|
||||
def tick(self, clock):
|
||||
actors = self.world.get_actors()
|
||||
self.actors_with_transforms = [(actor, actor.get_transform()) for actor in actors]
|
||||
if self.hero_actor is not None:
|
||||
self.hero_transform = self.hero_actor.get_transform()
|
||||
self.update_hud_info(clock)
|
||||
|
||||
def update_hud_info(self, clock):
|
||||
|
@ -674,7 +684,7 @@ class ModuleWorld(object):
|
|||
'Server: % 16s FPS' % self.server_fps,
|
||||
'Client: % 16s FPS' % round(clock.get_fps()),
|
||||
'Simulation Time: % 12s' % datetime.timedelta(seconds=int(self.simulation_time)),
|
||||
'Map Name: %10s' % self.world.map_name,
|
||||
'Map Name: %10s' % self.town_map.name,
|
||||
]
|
||||
|
||||
module_info_text = module_info_text
|
||||
|
@ -692,30 +702,32 @@ class ModuleWorld(object):
|
|||
self.server_fps = self.server_clock.get_fps()
|
||||
self.simulation_time = timestamp.elapsed_seconds
|
||||
|
||||
self.world = self.client.get_world()
|
||||
self.actors = self.world.get_actors()
|
||||
|
||||
def _split_actors(self, actors):
|
||||
def _split_actors(self):
|
||||
vehicles = []
|
||||
traffic_lights = []
|
||||
speed_limits = []
|
||||
stop_signals = []
|
||||
walkers = []
|
||||
|
||||
for actor in actors:
|
||||
for actor_with_transform in self.actors_with_transforms:
|
||||
actor = actor_with_transform[0]
|
||||
if 'vehicle' in actor.type_id:
|
||||
vehicles.append(actor)
|
||||
vehicles.append(actor_with_transform)
|
||||
elif 'traffic_light' in actor.type_id:
|
||||
traffic_lights.append(actor)
|
||||
traffic_lights.append(actor_with_transform)
|
||||
elif 'speed_limit' in actor.type_id:
|
||||
speed_limits.append(actor)
|
||||
speed_limits.append(actor_with_transform)
|
||||
elif 'stop' in actor.type_id:
|
||||
stop_signals.append(actor_with_transform)
|
||||
elif 'walker' in actor.type_id:
|
||||
walkers.append(actor)
|
||||
walkers.append(actor_with_transform)
|
||||
|
||||
info_text = []
|
||||
if self.hero_actor is not None and len(vehicles) > 1:
|
||||
location = self.hero_actor.get_location()
|
||||
vehicle_list = [x for x in vehicles if x.id != self.hero_actor.id]
|
||||
distance = lambda v: location.distance(v.get_location())
|
||||
location = self.hero_transform.location
|
||||
vehicle_list = [x[0] for x in vehicles if x[0].id != self.hero_actor.id]
|
||||
|
||||
def distance(v): return location.distance(v.get_location())
|
||||
for n, vehicle in enumerate(sorted(vehicle_list, key=distance)):
|
||||
if n > 15:
|
||||
break
|
||||
|
@ -725,7 +737,7 @@ class ModuleWorld(object):
|
|||
'NEARBY VEHICLES',
|
||||
info_text)
|
||||
|
||||
return (vehicles, traffic_lights, speed_limits, walkers)
|
||||
return (vehicles, traffic_lights, speed_limits, stop_signals, walkers)
|
||||
|
||||
def _render_traffic_lights(self, surface, list_tl, world_to_pixel):
|
||||
for tl in list_tl:
|
||||
|
@ -750,16 +762,16 @@ class ModuleWorld(object):
|
|||
# Render speed limit
|
||||
white_circle_radius = int(radius * 0.75)
|
||||
|
||||
pygame.draw.circle(surface, (239, 41, 41), (x, y), radius)
|
||||
pygame.draw.circle(surface, (251, 241, 199), (x, y), white_circle_radius)
|
||||
pygame.draw.circle(surface, COLOR_SCARLET_RED_1, (x, y), radius)
|
||||
pygame.draw.circle(surface, COLOR_ALUMINIUM_0, (x, y), white_circle_radius)
|
||||
|
||||
limit = sl.type_id.split('.')[2]
|
||||
font_surface = font.render(limit, False, (31, 31, 31))
|
||||
font_surface = font.render(limit, True, COLOR_ALUMINIUM_5)
|
||||
|
||||
# Blit
|
||||
if self.hero_actor is not None:
|
||||
# Rotate font surface with respect to hero vehicle front
|
||||
angle = -self.hero_actor.get_transform().rotation.yaw - 90.0
|
||||
angle = -self.hero_transform.rotation.yaw - 90.0
|
||||
font_surface = pygame.transform.rotate(font_surface, angle)
|
||||
offset = font_surface.get_rect(center=(x, y))
|
||||
surface.blit(font_surface, offset)
|
||||
|
@ -769,28 +781,30 @@ class ModuleWorld(object):
|
|||
|
||||
def _render_walkers(self, surface, list_w, world_to_pixel):
|
||||
for w in list_w:
|
||||
color = COLOR_ALUMINIUM_0
|
||||
color = COLOR_PLUM_0
|
||||
|
||||
# Compute bounding box points
|
||||
bb = w.bounding_box.extent
|
||||
bb = w[0].bounding_box.extent
|
||||
corners = [
|
||||
carla.Location(x=-bb.x, y=-bb.y),
|
||||
carla.Location(x=bb.x, y=-bb.y),
|
||||
carla.Location(x=bb.x, y=bb.y),
|
||||
carla.Location(x=-bb.x, y=bb.y)]
|
||||
|
||||
t = w.get_transform()
|
||||
t.transform(corners)
|
||||
w[1].transform(corners)
|
||||
corners = [world_to_pixel(p) for p in corners]
|
||||
pygame.draw.polygon(surface, color, corners)
|
||||
|
||||
def _render_vehicles(self, surface, list_v, world_to_pixel, world_to_pixel_width, scale_factor):
|
||||
|
||||
for v in list_v:
|
||||
color = COLOR_ORANGE_1
|
||||
if v.attributes['role_name'] == 'hero':
|
||||
color = COLOR_SCARLET_RED_2
|
||||
color = COLOR_SKY_BLUE_0
|
||||
if int(v[0].attributes['number_of_wheels']) == 2:
|
||||
color = COLOR_CHOCOLATE_1
|
||||
if v[0].attributes['role_name'] == 'hero':
|
||||
color = COLOR_CHAMELEON_0
|
||||
# Compute bounding box points
|
||||
bb = v.bounding_box.extent
|
||||
bb = v[0].bounding_box.extent
|
||||
corners = [carla.Location(x=-bb.x, y=-bb.y),
|
||||
carla.Location(x=bb.x - 0.8, y=-bb.y),
|
||||
carla.Location(x=bb.x, y=0),
|
||||
|
@ -798,25 +812,61 @@ class ModuleWorld(object):
|
|||
carla.Location(x=-bb.x, y=bb.y),
|
||||
carla.Location(x=-bb.x, y=-bb.y)
|
||||
]
|
||||
t = v.get_transform()
|
||||
t.transform(corners)
|
||||
v[1].transform(corners)
|
||||
corners = [world_to_pixel(p) for p in corners]
|
||||
pygame.draw.lines(surface, color, False, corners, 2)
|
||||
pygame.draw.lines(surface, color, False, corners, int(math.ceil(4.0 * self.map_image.scale)))
|
||||
|
||||
def render_actors(self, surface, vehicles, traffic_lights, speed_limits, walkers, scale_factor):
|
||||
def _render_stop_signals(self, surface, list_s, world_to_pixel, world_to_pixel_width):
|
||||
font_size = world_to_pixel_width(1.3)
|
||||
width = world_to_pixel_width(2)
|
||||
height = world_to_pixel_width(0.9)
|
||||
font = pygame.font.SysFont('Arial', font_size, True)
|
||||
|
||||
for sl in list_s:
|
||||
|
||||
x, y = world_to_pixel(sl.get_location())
|
||||
|
||||
# Render stop signal
|
||||
lines = [[x + width, y + height], [x + width, y - height],
|
||||
[x + height, y - width], [x - height, y - width],
|
||||
[x - width, y - height], [x - width, y + height],
|
||||
[x - width, y + height], [x - height, y + width],
|
||||
[x + height, y + width]
|
||||
]
|
||||
pygame.draw.polygon(surface, COLOR_ALUMINIUM_3, lines, 5)
|
||||
pygame.draw.polygon(surface, COLOR_SCARLET_RED_1, lines)
|
||||
|
||||
font_surface = font.render("STOP", False, COLOR_ALUMINIUM_1)
|
||||
|
||||
# Blit
|
||||
if self.hero_actor is not None:
|
||||
# Rotate font surface with respect to hero vehicle front
|
||||
angle = -self.hero_transform.rotation.yaw - 90.0
|
||||
font_surface = pygame.transform.rotate(font_surface, angle)
|
||||
offset = font_surface.get_rect(center=(x, y))
|
||||
surface.blit(font_surface, offset)
|
||||
|
||||
else:
|
||||
surface.blit(font_surface, (x - font_surface.get_width() / 2, y - font_surface.get_height() / 2))
|
||||
|
||||
def render_actors(self, surface, vehicles, traffic_lights, speed_limits, stop_signals, walkers, scale_factor):
|
||||
# Dynamic actors
|
||||
self._render_vehicles(surface, vehicles, self.map_image.world_to_pixel,
|
||||
self.map_image.world_to_pixel_width, scale_factor)
|
||||
self._render_traffic_lights(surface, traffic_lights, self.map_image.world_to_pixel)
|
||||
self._render_speed_limits(surface, speed_limits, self.map_image.world_to_pixel,
|
||||
self.map_image.world_to_pixel_width)
|
||||
self._render_walkers(surface, walkers, self.map_image.world_to_pixel)
|
||||
|
||||
# Static actors
|
||||
self._render_traffic_lights(surface, [tl[0] for tl in traffic_lights], self.map_image.world_to_pixel)
|
||||
self._render_speed_limits(surface, [sl[0] for sl in speed_limits], self.map_image.world_to_pixel,
|
||||
self.map_image.world_to_pixel_width)
|
||||
self._render_stop_signals(surface, [ss[0] for ss in stop_signals], self.map_image.world_to_pixel,
|
||||
self.map_image.world_to_pixel_width)
|
||||
|
||||
def clip_surfaces(self, clipping_rect):
|
||||
self.actors_surface.set_clip(clipping_rect)
|
||||
self.vehicle_id_surface.set_clip(clipping_rect)
|
||||
self.result_surface.set_clip(clipping_rect)
|
||||
|
||||
|
||||
def _compute_scale(self, scale_factor):
|
||||
m = self.module_input.mouse_pos
|
||||
|
||||
|
@ -827,10 +877,10 @@ class ModuleWorld(object):
|
|||
# Offset will be the previously accumulated offset added with the
|
||||
# difference of mouse positions in the old and new scales
|
||||
diff_between_scales = ((float(self.prev_scaled_size) * px) - (float(self.scaled_size) * px),
|
||||
(float(self.prev_scaled_size) * py) - (float(self.scaled_size) * py))
|
||||
(float(self.prev_scaled_size) * py) - (float(self.scaled_size) * py))
|
||||
|
||||
self.scale_offset = (self.scale_offset[0] + diff_between_scales[0],
|
||||
self.scale_offset[1] + diff_between_scales[1])
|
||||
self.scale_offset[1] + diff_between_scales[1])
|
||||
|
||||
# Update previous scale
|
||||
self.prev_scaled_size = self.scaled_size
|
||||
|
@ -839,8 +889,10 @@ class ModuleWorld(object):
|
|||
self.map_image.scale_map(scale_factor)
|
||||
|
||||
def render(self, display):
|
||||
if self.actors_with_transforms is None:
|
||||
return
|
||||
self.result_surface.fill(COLOR_BLACK)
|
||||
vehicles, traffic_lights, speed_limits, walkers = self._split_actors(self.actors)
|
||||
vehicles, traffic_lights, speed_limits, stop_signals, walkers = self._split_actors()
|
||||
|
||||
scale_factor = self.module_input.wheel_offset
|
||||
self.scaled_size = int(self.map_image._width * scale_factor)
|
||||
|
@ -849,16 +901,19 @@ class ModuleWorld(object):
|
|||
|
||||
# Render Actors
|
||||
|
||||
hero_vehicles = [v for v in vehicles if v.attributes['role_name'] == 'hero']
|
||||
if len(hero_vehicles) == 0:
|
||||
self.hero_actor = None
|
||||
|
||||
self.actors_surface.fill(COLOR_BLACK)
|
||||
self.render_actors(self.actors_surface, vehicles, traffic_lights, speed_limits, walkers, scale_factor)
|
||||
self.render_actors(
|
||||
self.actors_surface,
|
||||
vehicles,
|
||||
traffic_lights,
|
||||
speed_limits,
|
||||
stop_signals,
|
||||
walkers,
|
||||
scale_factor)
|
||||
|
||||
# Render Ids
|
||||
self.module_hud.render_actors_ids(self.vehicle_id_surface, vehicles,
|
||||
self.map_image.world_to_pixel, self.hero_actor)
|
||||
self.module_hud.render_vehicles_ids(self.vehicle_id_surface, vehicles,
|
||||
self.map_image.world_to_pixel, self.hero_actor, self.hero_transform)
|
||||
|
||||
# Blit surfaces
|
||||
surfaces = ((self.map_image.surface, (0, 0)),
|
||||
|
@ -866,14 +921,14 @@ class ModuleWorld(object):
|
|||
(self.vehicle_id_surface, (0, 0)),
|
||||
)
|
||||
|
||||
angle = 0.0 if self.hero_actor is None else self.hero_actor.get_transform().rotation.yaw + 90.0
|
||||
angle = 0.0 if self.hero_actor is None else self.hero_transform.rotation.yaw + 90.0
|
||||
self.traffic_light_surfaces.rotozoom(-angle, self.map_image.scale)
|
||||
|
||||
center_offset = (0, 0)
|
||||
if self.hero_actor is not None:
|
||||
|
||||
hero_location_screen = self.map_image.world_to_pixel(self.hero_actor.get_location())
|
||||
hero_front = self.hero_actor.get_transform().get_forward_vector()
|
||||
hero_location_screen = self.map_image.world_to_pixel(self.hero_transform.location)
|
||||
hero_front = self.hero_transform.get_forward_vector()
|
||||
translation_offset = (hero_location_screen[0] - self.hero_surface.get_width() / 2 + hero_front.x * PIXELS_AHEAD_VEHICLE,
|
||||
(hero_location_screen[1] - self.hero_surface.get_height() / 2 + hero_front.y * PIXELS_AHEAD_VEHICLE))
|
||||
|
||||
|
@ -888,7 +943,7 @@ class ModuleWorld(object):
|
|||
|
||||
self.border_round_surface.set_clip(clipping_rect)
|
||||
|
||||
self.hero_surface.fill(COLOR_ALUMINIUM_5)
|
||||
self.hero_surface.fill(COLOR_ALUMINIUM_4)
|
||||
self.hero_surface.blit(self.result_surface, (-translation_offset[0],
|
||||
-translation_offset[1]))
|
||||
|
||||
|
@ -898,12 +953,12 @@ class ModuleWorld(object):
|
|||
rotation_pivot = rotated_result_surface.get_rect(center=center)
|
||||
display.blit(rotated_result_surface, rotation_pivot)
|
||||
|
||||
display.blit(self.border_round_surface, (0,0))
|
||||
display.blit(self.border_round_surface, (0, 0))
|
||||
else:
|
||||
# Translation offset
|
||||
translation_offset = (self.module_input.mouse_offset[0] * scale_factor + self.scale_offset[0],
|
||||
self.module_input.mouse_offset[1] * scale_factor + self.scale_offset[1])
|
||||
center_offset = ((display.get_width() - self.surface_size) / 2 * scale_factor, 0)
|
||||
center_offset = (abs(display.get_width() - self.surface_size) / 2 * scale_factor, 0)
|
||||
|
||||
# Apply clipping rect
|
||||
clipping_rect = pygame.Rect(-translation_offset[0] - center_offset[0], -translation_offset[1],
|
||||
|
@ -929,7 +984,7 @@ class ModuleInput(object):
|
|||
self.wheel_amount = 0.025
|
||||
self._steer_cache = 0.0
|
||||
self._control = None
|
||||
self._autopilot_enabled = True
|
||||
self._autopilot_enabled = False
|
||||
|
||||
def start(self):
|
||||
hud = module_manager.get_module(MODULE_HUD)
|
||||
|
@ -959,13 +1014,12 @@ class ModuleInput(object):
|
|||
module_world.select_hero_actor()
|
||||
self.wheel_offset = HERO_DEFAULT_SCALE
|
||||
self._control = carla.VehicleControl()
|
||||
self._autopilot_enabled = False
|
||||
module_hud.notification('Hero Mode')
|
||||
else:
|
||||
self.wheel_offset = MAP_DEFAULT_SCALE
|
||||
self.mouse_offset = [0, 0]
|
||||
self.mouse_pos = [0,0]
|
||||
module_world.scale_offset = [0,0]
|
||||
self.mouse_pos = [0, 0]
|
||||
module_world.scale_offset = [0, 0]
|
||||
module_world.hero_actor = None
|
||||
module_hud.notification('Map Mode')
|
||||
elif event.key == K_F1:
|
||||
|
@ -989,11 +1043,12 @@ class ModuleInput(object):
|
|||
elif self._control.manual_gear_shift and event.key == K_PERIOD:
|
||||
self._control.gear = self._control.gear + 1
|
||||
elif event.key == K_p:
|
||||
self._autopilot_enabled = not self._autopilot_enabled
|
||||
world = module_manager.get_module(MODULE_WORLD)
|
||||
world.hero_actor.set_autopilot(self._autopilot_enabled)
|
||||
module_hud = module_manager.get_module(MODULE_HUD)
|
||||
module_hud.notification('Autopilot %s' % ('On' if self._autopilot_enabled else 'Off'))
|
||||
if world.hero_actor is not None:
|
||||
self._autopilot_enabled = not self._autopilot_enabled
|
||||
world.hero_actor.set_autopilot(self._autopilot_enabled)
|
||||
module_hud = module_manager.get_module(MODULE_HUD)
|
||||
module_hud.notification('Autopilot %s' % ('On' if self._autopilot_enabled else 'Off'))
|
||||
elif event.type == pygame.MOUSEBUTTONDOWN:
|
||||
if event.button == 4:
|
||||
self.wheel_offset += self.wheel_amount
|
||||
|
@ -1022,8 +1077,8 @@ class ModuleInput(object):
|
|||
def _parse_mouse(self):
|
||||
if pygame.mouse.get_pressed()[0]:
|
||||
x, y = pygame.mouse.get_pos()
|
||||
self.mouse_offset[0] += (1.0 / self.wheel_offset) * (x - self.mouse_pos[0])
|
||||
self.mouse_offset[1] += (1.0 / self.wheel_offset) * (y - self.mouse_pos[1])
|
||||
self.mouse_offset[0] += (1.0 / self.wheel_offset) * (x - self.mouse_pos[0])
|
||||
self.mouse_offset[1] += (1.0 / self.wheel_offset) * (y - self.mouse_pos[1])
|
||||
self.mouse_pos = (x, y)
|
||||
|
||||
def parse_input(self, clock):
|
||||
|
@ -1063,7 +1118,7 @@ def game_loop(args):
|
|||
|
||||
font = pygame.font.Font(pygame.font.get_default_font(), 20)
|
||||
text_surface = font.render('Rendering map...', True, COLOR_WHITE)
|
||||
display.blit(text_surface, text_surface.get_rect(center=(args.width/2, args.height/2)))
|
||||
display.blit(text_surface, text_surface.get_rect(center=(args.width / 2, args.height / 2)))
|
||||
pygame.display.flip()
|
||||
|
||||
# Init modules
|
||||
|
|
|
@ -12,6 +12,7 @@
|
|||
#include "Carla/Vehicle/VehicleSpawnPoint.h"
|
||||
|
||||
#include "EngineUtils.h"
|
||||
#include "Engine/StaticMeshActor.h"
|
||||
#include "GameFramework/SpectatorPawn.h"
|
||||
|
||||
static FString UCarlaEpisode_GetTrafficSignId(ETrafficSignState State)
|
||||
|
@ -108,4 +109,19 @@ void UCarlaEpisode::InitializeAtBeginPlay()
|
|||
Description.Class = Actor->GetClass();
|
||||
ActorDispatcher->RegisterActor(*Actor, Description);
|
||||
}
|
||||
|
||||
for (TActorIterator<AStaticMeshActor> It(World); It; ++It)
|
||||
{
|
||||
auto Actor = *It;
|
||||
check(Actor != nullptr);
|
||||
auto MeshComponent = Actor->GetStaticMeshComponent();
|
||||
check(MeshComponent != nullptr);
|
||||
if (MeshComponent->Mobility == EComponentMobility::Movable)
|
||||
{
|
||||
FActorDescription Description;
|
||||
Description.Id = TEXT("static.prop");
|
||||
Description.Class = Actor->GetClass();
|
||||
ActorDispatcher->RegisterActor(*Actor, Description);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -0,0 +1,6 @@
|
|||
[G29 Racing Wheel]
|
||||
steering_wheel = 0
|
||||
throttle = 2
|
||||
brake = 3
|
||||
reverse = 5
|
||||
handbrake = 4
|
Loading…
Reference in New Issue