From 4179a60fd792cf0347b65cc27462516a37bbf81f Mon Sep 17 00:00:00 2001 From: George Laurent Date: Wed, 27 Jun 2018 13:24:14 +0200 Subject: [PATCH 01/71] Update Readme.md --- carla_ros_bridge/Readme.md | 1 + 1 file changed, 1 insertion(+) diff --git a/carla_ros_bridge/Readme.md b/carla_ros_bridge/Readme.md index 7a69406b3..31ad35a9f 100644 --- a/carla_ros_bridge/Readme.md +++ b/carla_ros_bridge/Readme.md @@ -66,6 +66,7 @@ Run the following command after replacing [PATH_TO_CARLA] with the actual path t rosdep install --from-paths ~/ros/catkin_ws_for_carla cd ~/ros/catkin_ws_for_carla catkin_make + source ~/ros/catkin_ws_for_carla/devel/setup.bash ### Test your installation From 084fe6c0f62e746a8ef8f5d6db753341bb386867 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Wed, 4 Jul 2018 11:11:49 +0200 Subject: [PATCH 02/71] Add LibCarla module --- LibCarla/cmake/CMakeLists.txt | 19 ++ LibCarla/cmake/client/CMakeLists.txt | 42 +++ LibCarla/cmake/server/CMakeLists.txt | 25 ++ LibCarla/cmake/test/CMakeLists.txt | 36 +++ LibCarla/source/carla/.gitignore | 1 + LibCarla/source/carla/Debug.h | 29 ++ LibCarla/source/carla/Logging.h | 148 +++++++++++ LibCarla/source/carla/NonCopyable.h | 21 ++ LibCarla/source/carla/StopWatch.h | 56 ++++ LibCarla/source/carla/ThreadGroup.h | 52 ++++ LibCarla/source/carla/Version.h.in | 15 ++ LibCarla/source/carla/client/Actor.h | 69 +++++ .../source/carla/client/ActorBlueprint.cpp | 37 +++ LibCarla/source/carla/client/ActorBlueprint.h | 44 ++++ .../source/carla/client/BlueprintLibrary.h | 77 ++++++ LibCarla/source/carla/client/Client.cpp | 37 +++ LibCarla/source/carla/client/Client.h | 78 ++++++ LibCarla/source/carla/client/Control.h | 17 ++ LibCarla/source/carla/client/Memory.h | 31 +++ LibCarla/source/carla/client/Transform.h | 19 ++ LibCarla/source/carla/client/World.cpp | 26 ++ LibCarla/source/carla/client/World.h | 58 ++++ LibCarla/source/carla/profiler/Profiler.cpp | 88 +++++++ LibCarla/source/carla/profiler/Profiler.h | 124 +++++++++ LibCarla/source/carla/rpc/Actor.h | 27 ++ LibCarla/source/carla/rpc/ActorBlueprint.h | 49 ++++ LibCarla/source/carla/rpc/Client.h | 17 ++ LibCarla/source/carla/rpc/MsgPack.h | 9 + LibCarla/source/carla/rpc/Server.h | 116 ++++++++ LibCarla/source/carla/rpc/Transform.h | 102 +++++++ LibCarla/source/carla/rpc/VehicleControl.h | 46 ++++ LibCarla/source/carla/streaming/Client.h | 58 ++++ LibCarla/source/carla/streaming/Message.h | 142 ++++++++++ LibCarla/source/carla/streaming/Server.h | 65 +++++ LibCarla/source/carla/streaming/Stream.h | 68 +++++ .../source/carla/streaming/low_level/Client.h | 52 ++++ .../carla/streaming/low_level/Dispatcher.h | 68 +++++ .../source/carla/streaming/low_level/Server.h | 60 +++++ .../carla/streaming/low_level/Session.h | 19 ++ .../carla/streaming/low_level/StreamState.h | 74 ++++++ .../source/carla/streaming/low_level/Token.h | 164 ++++++++++++ .../source/carla/streaming/low_level/Types.h | 21 ++ .../carla/streaming/low_level/tcp/Client.h | 249 ++++++++++++++++++ .../carla/streaming/low_level/tcp/Server.h | 76 ++++++ .../streaming/low_level/tcp/ServerSession.h | 173 ++++++++++++ .../carla/streaming/low_level/tcp/Timeout.h | 62 +++++ LibCarla/source/compiler/disable-ue4-macros.h | 18 ++ LibCarla/source/compiler/enable-ue4-macros.h | 9 + LibCarla/source/test/test.h | 26 ++ .../source/test/test_benchmark_streaming.cpp | 137 ++++++++++ LibCarla/source/test/test_miscellaneous.cpp | 13 + LibCarla/source/test/test_rpc.cpp | 58 ++++ .../source/test/test_streaming_low_level.cpp | 55 ++++ .../test/test_streaming_low_level_tcp.cpp | 57 ++++ .../source/test/test_streaming_message.cpp | 52 ++++ LibCarla/source/test/util/Message.cpp | 45 ++++ LibCarla/source/test/util/Message.h | 81 ++++++ 57 files changed, 3417 insertions(+) create mode 100644 LibCarla/cmake/CMakeLists.txt create mode 100644 LibCarla/cmake/client/CMakeLists.txt create mode 100644 LibCarla/cmake/server/CMakeLists.txt create mode 100644 LibCarla/cmake/test/CMakeLists.txt create mode 100644 LibCarla/source/carla/.gitignore create mode 100644 LibCarla/source/carla/Debug.h create mode 100644 LibCarla/source/carla/Logging.h create mode 100644 LibCarla/source/carla/NonCopyable.h create mode 100644 LibCarla/source/carla/StopWatch.h create mode 100644 LibCarla/source/carla/ThreadGroup.h create mode 100644 LibCarla/source/carla/Version.h.in create mode 100644 LibCarla/source/carla/client/Actor.h create mode 100644 LibCarla/source/carla/client/ActorBlueprint.cpp create mode 100644 LibCarla/source/carla/client/ActorBlueprint.h create mode 100644 LibCarla/source/carla/client/BlueprintLibrary.h create mode 100644 LibCarla/source/carla/client/Client.cpp create mode 100644 LibCarla/source/carla/client/Client.h create mode 100644 LibCarla/source/carla/client/Control.h create mode 100644 LibCarla/source/carla/client/Memory.h create mode 100644 LibCarla/source/carla/client/Transform.h create mode 100644 LibCarla/source/carla/client/World.cpp create mode 100644 LibCarla/source/carla/client/World.h create mode 100644 LibCarla/source/carla/profiler/Profiler.cpp create mode 100644 LibCarla/source/carla/profiler/Profiler.h create mode 100644 LibCarla/source/carla/rpc/Actor.h create mode 100644 LibCarla/source/carla/rpc/ActorBlueprint.h create mode 100644 LibCarla/source/carla/rpc/Client.h create mode 100644 LibCarla/source/carla/rpc/MsgPack.h create mode 100644 LibCarla/source/carla/rpc/Server.h create mode 100644 LibCarla/source/carla/rpc/Transform.h create mode 100644 LibCarla/source/carla/rpc/VehicleControl.h create mode 100644 LibCarla/source/carla/streaming/Client.h create mode 100644 LibCarla/source/carla/streaming/Message.h create mode 100644 LibCarla/source/carla/streaming/Server.h create mode 100644 LibCarla/source/carla/streaming/Stream.h create mode 100644 LibCarla/source/carla/streaming/low_level/Client.h create mode 100644 LibCarla/source/carla/streaming/low_level/Dispatcher.h create mode 100644 LibCarla/source/carla/streaming/low_level/Server.h create mode 100644 LibCarla/source/carla/streaming/low_level/Session.h create mode 100644 LibCarla/source/carla/streaming/low_level/StreamState.h create mode 100644 LibCarla/source/carla/streaming/low_level/Token.h create mode 100644 LibCarla/source/carla/streaming/low_level/Types.h create mode 100644 LibCarla/source/carla/streaming/low_level/tcp/Client.h create mode 100644 LibCarla/source/carla/streaming/low_level/tcp/Server.h create mode 100644 LibCarla/source/carla/streaming/low_level/tcp/ServerSession.h create mode 100644 LibCarla/source/carla/streaming/low_level/tcp/Timeout.h create mode 100644 LibCarla/source/compiler/disable-ue4-macros.h create mode 100644 LibCarla/source/compiler/enable-ue4-macros.h create mode 100644 LibCarla/source/test/test.h create mode 100644 LibCarla/source/test/test_benchmark_streaming.cpp create mode 100644 LibCarla/source/test/test_miscellaneous.cpp create mode 100644 LibCarla/source/test/test_rpc.cpp create mode 100644 LibCarla/source/test/test_streaming_low_level.cpp create mode 100644 LibCarla/source/test/test_streaming_low_level_tcp.cpp create mode 100644 LibCarla/source/test/test_streaming_message.cpp create mode 100644 LibCarla/source/test/util/Message.cpp create mode 100644 LibCarla/source/test/util/Message.h diff --git a/LibCarla/cmake/CMakeLists.txt b/LibCarla/cmake/CMakeLists.txt new file mode 100644 index 000000000..c4e182be8 --- /dev/null +++ b/LibCarla/cmake/CMakeLists.txt @@ -0,0 +1,19 @@ +cmake_minimum_required(VERSION 3.9.0) +project(libcarla) + +message(STATUS "Building ${PROJECT_NAME} version ${CARLA_VERSION}") + +set(libcarla_source_path "${PROJECT_SOURCE_DIR}/../source") + +include_directories(${libcarla_source_path}) + +configure_file(${libcarla_source_path}/carla/Version.h.in ${libcarla_source_path}/carla/Version.h) + +if (CMAKE_BUILD_TYPE STREQUAL "Client") + add_subdirectory("client") +elseif (CMAKE_BUILD_TYPE STREQUAL "Server") + add_subdirectory("server") + add_subdirectory("test") +else () + message(FATAL_ERROR "Unknown build type '${CMAKE_BUILD_TYPE}'") +endif () diff --git a/LibCarla/cmake/client/CMakeLists.txt b/LibCarla/cmake/client/CMakeLists.txt new file mode 100644 index 000000000..456788dbe --- /dev/null +++ b/LibCarla/cmake/client/CMakeLists.txt @@ -0,0 +1,42 @@ +cmake_minimum_required(VERSION 3.9.0) +project(libcarla-client) + +# Install rpclib. +install(DIRECTORY "${RPCLIB_INCLUDE_PATH}/rpc" DESTINATION include) +install(FILES "${RPCLIB_LIB_PATH}/librpc.a" DESTINATION lib) + +file(GLOB_RECURSE libcarla_client_sources + "${libcarla_source_path}/carla/client/*.h" + "${libcarla_source_path}/carla/client/*.cpp") + +# Create targets for debug and release in the same build type. +foreach(target carla_client_debug carla_client) + add_library(${target} STATIC ${libcarla_client_sources}) + + target_include_directories(${target} PRIVATE + "${BOOST_INCLUDE_PATH}" + "${RPCLIB_INCLUDE_PATH}") + + install(TARGETS ${target} DESTINATION lib) +endforeach(target) + +# Specific options for debug. +set_target_properties(carla_client_debug PROPERTIES COMPILE_FLAGS ${CMAKE_CXX_FLAGS_DEBUG}) +target_compile_definitions(carla_client_debug PUBLIC -DBOOST_ASIO_ENABLE_BUFFER_DEBUGGING) + +# Specific options for release. +set_target_properties(carla_client PROPERTIES COMPILE_FLAGS ${CMAKE_CXX_FLAGS_RELEASE}) + +# Install headers. + +file(GLOB libcarla_carla_headers "${libcarla_source_path}/carla/*.h") +install(FILES ${libcarla_carla_headers} DESTINATION include/carla) + +file(GLOB libcarla_carla_client_headers "${libcarla_source_path}/carla/client/*.h") +install(FILES ${libcarla_carla_client_headers} DESTINATION include/carla/client) + +file(GLOB libcarla_carla_rpc_headers "${libcarla_source_path}/carla/rpc/*.h") +install(FILES ${libcarla_carla_rpc_headers} DESTINATION include/carla/rpc) + +file(GLOB libcarla_carla_streaming_headers "${libcarla_source_path}/carla/streaming/*.h") +install(FILES ${libcarla_carla_streaming_headers} DESTINATION include/carla/streaming) diff --git a/LibCarla/cmake/server/CMakeLists.txt b/LibCarla/cmake/server/CMakeLists.txt new file mode 100644 index 000000000..5af82c109 --- /dev/null +++ b/LibCarla/cmake/server/CMakeLists.txt @@ -0,0 +1,25 @@ +cmake_minimum_required(VERSION 3.9.0) +project(libcarla-server) + +# Install libc++ shared libraries. +file(GLOB LibCXX_Libraries "${LLVM_LIB_PATH}/libc++*") +install(FILES ${LibCXX_Libraries} DESTINATION lib) + +# Install rpclib. +install(DIRECTORY "${RPCLIB_INCLUDE_PATH}/rpc" DESTINATION include) +install(FILES "${RPCLIB_LIB_PATH}/librpc.a" DESTINATION lib) + +# Install headers. + +install(DIRECTORY "${libcarla_source_path}/compiler" DESTINATION include) + +file(GLOB libcarla_carla_headers "${libcarla_source_path}/carla/*.h") +install(FILES ${libcarla_carla_headers} DESTINATION include/carla) + +file(GLOB libcarla_carla_rpc_headers "${libcarla_source_path}/carla/rpc/*.h") +install(FILES ${libcarla_carla_rpc_headers} DESTINATION include/carla/rpc) + +file(GLOB libcarla_carla_streaming_headers "${libcarla_source_path}/carla/streaming/*.h") +install(FILES ${libcarla_carla_streaming_headers} DESTINATION include/carla/streaming) + +install(DIRECTORY "${BOOST_INCLUDE_PATH}/boost" DESTINATION include) diff --git a/LibCarla/cmake/test/CMakeLists.txt b/LibCarla/cmake/test/CMakeLists.txt new file mode 100644 index 000000000..376d94879 --- /dev/null +++ b/LibCarla/cmake/test/CMakeLists.txt @@ -0,0 +1,36 @@ +cmake_minimum_required(VERSION 3.9.0) +project(libcarla-unit-tests) + +file(GLOB_RECURSE libcarla_test_sources + "${libcarla_source_path}/carla/profiler/*.h" + "${libcarla_source_path}/carla/profiler/*.cpp" + "${libcarla_source_path}/test/*.h" + "${libcarla_source_path}/test/*.cpp") + +link_directories( + ${RPCLIB_LIB_PATH} + ${GTEST_LIB_PATH}) + +# Create targets for debug and release in the same build type. +foreach(target libcarla_test_debug libcarla_test_release) + add_executable(${target} ${libcarla_test_sources}) + + target_compile_definitions(${target} PUBLIC + -DLIBCARLA_ENABLE_PROFILER + -DLIBCARLA_WITH_GTEST) + + target_include_directories(${target} PRIVATE + "${BOOST_INCLUDE_PATH}" + "${RPCLIB_INCLUDE_PATH}" + "${GTEST_INCLUDE_PATH}") + target_link_libraries(${target} "-lrpc -lgtest_main -lgtest") + + install(TARGETS ${target} DESTINATION test) +endforeach(target) + +# Specific options for debug. +set_target_properties(libcarla_test_debug PROPERTIES COMPILE_FLAGS ${CMAKE_CXX_FLAGS_DEBUG}) +target_compile_definitions(libcarla_test_debug PUBLIC -DBOOST_ASIO_ENABLE_BUFFER_DEBUGGING) + +# Specific options for release. +set_target_properties(libcarla_test_release PROPERTIES COMPILE_FLAGS ${CMAKE_CXX_FLAGS_RELEASE}) diff --git a/LibCarla/source/carla/.gitignore b/LibCarla/source/carla/.gitignore new file mode 100644 index 000000000..38ba24e29 --- /dev/null +++ b/LibCarla/source/carla/.gitignore @@ -0,0 +1 @@ +Version.h diff --git a/LibCarla/source/carla/Debug.h b/LibCarla/source/carla/Debug.h new file mode 100644 index 000000000..5803cca70 --- /dev/null +++ b/LibCarla/source/carla/Debug.h @@ -0,0 +1,29 @@ +// 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 . + +#pragma once + +#ifndef NDEBUG +# include +#endif // NDEBUG + +#ifdef NDEBUG +# define DEBUG_ONLY(code) +#else +# define DEBUG_ONLY(code) code +#endif // NDEBUG + +#define DEBUG_ASSERT(predicate) DEBUG_ONLY(assert(predicate)); + +#ifdef LIBCARLA_WITH_GTEST +# include + +# define DEBUG_ASSERT_EQ(lhs, rhs) DEBUG_ONLY(EXPECT_EQ(lhs, rhs));DEBUG_ASSERT(lhs == rhs); +# define DEBUG_ASSERT_NE(lhs, rhs) DEBUG_ONLY(EXPECT_NE(lhs, rhs));DEBUG_ASSERT(lhs != rhs); +#else +# define DEBUG_ASSERT_EQ(lhs, rhs) DEBUG_ASSERT((lhs) == (rhs)) +# define DEBUG_ASSERT_NE(lhs, rhs) DEBUG_ASSERT((lhs) != (rhs)) +#endif // LIBCARLA_WITH_GTEST diff --git a/LibCarla/source/carla/Logging.h b/LibCarla/source/carla/Logging.h new file mode 100644 index 000000000..43dd1f800 --- /dev/null +++ b/LibCarla/source/carla/Logging.h @@ -0,0 +1,148 @@ +// 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 . + +#pragma once + +#define LIBCARLA_LOG_LEVEL_DEBUG 10 +#define LIBCARLA_LOG_LEVEL_INFO 20 +#define LIBCARLA_LOG_LEVEL_WARNING 30 +#define LIBCARLA_LOG_LEVEL_ERROR 40 +#define LIBCARLA_LOG_LEVEL_CRITICAL 50 +#define LIBCARLA_LOG_LEVEL_NONE 100 + +#ifndef LIBCARLA_LOG_LEVEL +# ifdef NDEBUG +# define LIBCARLA_LOG_LEVEL LIBCARLA_LOG_LEVEL_WARNING +# else +# define LIBCARLA_LOG_LEVEL LIBCARLA_LOG_LEVEL_INFO +# endif // NDEBUG +#endif // LIBCARLA_LOG_LEVEL + +// The following log functions are available, they are only active if +// LIBCARLA_LOG_LEVEL is greater equal the function's log level. +// +// * log_debug +// * log_info +// * log_error +// * log_critical +// +// And macros +// +// * LOG_DEBUG_ONLY(/* code here */) +// * LOG_INFO_ONLY(/* code here */) + +// ============================================================================= +// -- Implementation of log functions ------------------------------------------ +// ============================================================================= + +#include + +namespace carla { + +namespace logging { + + // https://stackoverflow.com/a/27375675 + template + static void write_to_stream(std::ostream &out, Arg &&arg, Args && ... args) { + out << std::boolalpha << std::forward(arg); + using expander = int[]; + (void) expander{0, (void(out << ' ' << std::forward(args)), 0) ...}; + } + + template + static inline void log(Args && ... args) { + logging::write_to_stream(std::cout, std::forward(args) ..., '\n'); + } + +} // namespace logging + +#if LIBCARLA_LOG_LEVEL <= LIBCARLA_LOG_LEVEL_DEBUG + + template + static inline void log_debug(Args && ... args) { + logging::write_to_stream(std::cout, "DEBUG:", std::forward(args) ..., '\n'); + } + +#else + + template + static inline void log_debug(Args && ...) {} + +#endif + +#if LIBCARLA_LOG_LEVEL <= LIBCARLA_LOG_LEVEL_INFO + + template + static inline void log_info(Args && ... args) { + logging::write_to_stream(std::cout, "INFO: ", std::forward(args) ..., '\n'); + } + +#else + + template + static inline void log_info(Args && ...) {} + +#endif + +#if LIBCARLA_LOG_LEVEL <= LIBCARLA_LOG_LEVEL_WARNING + + template + static inline void log_warning(Args && ... args) { + logging::write_to_stream(std::cerr, "WARNING:", std::forward(args) ..., '\n'); + } + +#else + + template + static inline void log_warning(Args && ...) {} + +#endif + +#if LIBCARLA_LOG_LEVEL <= LIBCARLA_LOG_LEVEL_ERROR + + template + static inline void log_error(Args && ... args) { + logging::write_to_stream(std::cerr, "ERROR:", std::forward(args) ..., '\n'); + } + +#else + + template + static inline void log_error(Args && ...) {} + +#endif + +#if LIBCARLA_LOG_LEVEL <= LIBCARLA_LOG_LEVEL_CRITICAL + + template + static inline void log_critical(Args && ... args) { + logging::write_to_stream(std::cerr, "CRITICAL:", std::forward(args) ..., '\n'); + } + +#else + + template + static inline void log_critical(Args && ...) {} + +#endif + +} // namespace carla + +// ============================================================================= +// -- Implementation of macros ------------------------------------------------- +// ============================================================================= + +#if LIBCARLA_LOG_LEVEL <= LIBCARLA_LOG_LEVEL_DEBUG +# define LOG_DEBUG_ONLY(code) code +#else +# define LOG_DEBUG_ONLY(code) +#endif + +#if LIBCARLA_LOG_LEVEL <= LIBCARLA_LOG_LEVEL_INFO +# define LOG_INFO_ONLY(code) code +#else +# define LOG_INFO_ONLY(code) +#endif diff --git a/LibCarla/source/carla/NonCopyable.h b/LibCarla/source/carla/NonCopyable.h new file mode 100644 index 000000000..41747bc41 --- /dev/null +++ b/LibCarla/source/carla/NonCopyable.h @@ -0,0 +1,21 @@ +// 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 . + +#pragma once + +namespace carla { + + class NonCopyable { + public: + + NonCopyable() = default; + + NonCopyable(const NonCopyable &) = delete; + + void operator=(const NonCopyable &x) = delete; + }; + +} // namespace carla diff --git a/LibCarla/source/carla/StopWatch.h b/LibCarla/source/carla/StopWatch.h new file mode 100644 index 000000000..db29b93d3 --- /dev/null +++ b/LibCarla/source/carla/StopWatch.h @@ -0,0 +1,56 @@ +// 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 . + +#pragma once + +#include + +namespace carla { + + template + class StopWatchTmpl { + static_assert(CLOCK::is_steady, "The StopWatch's clock must be steady"); + public: + + using clock = CLOCK; + + StopWatchTmpl() : _start(clock::now()), _end(), _is_running(true) {} + + void Restart() { + _is_running = true; + _start = clock::now(); + } + + void Stop() { + _end = clock::now(); + _is_running = false; + } + + typename clock::duration GetDuration() const { + return _is_running ? clock::now() - _start : _end - _start; + } + + template + typename RESOLUTION::rep GetElapsedTime() const { + return std::chrono::duration_cast(GetDuration()).count(); + } + + bool IsRunning() const { + return _is_running; + } + + private: + + typename clock::time_point _start; + + typename clock::time_point _end; + + bool _is_running; + }; + + using StopWatch = StopWatchTmpl; + +} // namespace carla diff --git a/LibCarla/source/carla/ThreadGroup.h b/LibCarla/source/carla/ThreadGroup.h new file mode 100644 index 000000000..b81cf17a7 --- /dev/null +++ b/LibCarla/source/carla/ThreadGroup.h @@ -0,0 +1,52 @@ +// 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 . + +#pragma once + +#include +#include + +namespace carla { + + class ThreadGroup { + public: + + ThreadGroup() {} + + ThreadGroup(const ThreadGroup &) = delete; + ThreadGroup &operator=(const ThreadGroup &) = delete; + + ~ThreadGroup() { + JoinAll(); + } + + template + void CreateThread(F &&functor) { + _threads.emplace_back(std::forward(functor)); + } + + template + void CreateThreads(size_t count, F functor) { + _threads.reserve(_threads.size() + count); + for (size_t i = 0u; i < count; ++i) { + CreateThread(functor); + } + } + + void JoinAll() { + for (auto &thread : _threads) { + if (thread.joinable()) { + thread.join(); + } + } + } + + private: + + std::vector _threads; + }; + +} // namespace carla diff --git a/LibCarla/source/carla/Version.h.in b/LibCarla/source/carla/Version.h.in new file mode 100644 index 000000000..6656a7117 --- /dev/null +++ b/LibCarla/source/carla/Version.h.in @@ -0,0 +1,15 @@ +// 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 . + +#pragma once + +namespace carla { + + constexpr const char *version() { + return "${CARLA_VERSION}"; + } + +} // namespace carla diff --git a/LibCarla/source/carla/client/Actor.h b/LibCarla/source/carla/client/Actor.h new file mode 100644 index 000000000..45fbfa590 --- /dev/null +++ b/LibCarla/source/carla/client/Actor.h @@ -0,0 +1,69 @@ +// 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 . + +#pragma once + +#include "carla/Debug.h" +#include "carla/NonCopyable.h" +#include "carla/client/Control.h" +#include "carla/client/Memory.h" +#include "carla/client/World.h" +#include "carla/rpc/Actor.h" + +namespace carla { +namespace client { + + class Client; + + class Actor + : public EnableSharedFromThis, + private NonCopyable { + public: + + Actor(Actor &&) = default; + Actor &operator=(Actor &&) = default; + + auto GetId() const { + return _actor.id; + } + + const std::string &GetTypeId() const { + return _actor.blueprint.type_id; + } + + ActorBlueprint GetBlueprint() const { + return _actor.blueprint; + } + + SharedPtr GetWorld() const { + return _world; + } + + void ApplyControl(const VehicleControl &control) { + _world->ApplyControlToActor(*this, control); + } + + const auto &Serialize() const { + return _actor; + } + + private: + + friend class Client; + + Actor(carla::rpc::Actor actor, SharedPtr world) + : _actor(actor), + _world(std::move(world)) { + DEBUG_ASSERT(_world != nullptr); + } + + carla::rpc::Actor _actor; + + SharedPtr _world; + }; + +} // namespace client +} // namespace carla diff --git a/LibCarla/source/carla/client/ActorBlueprint.cpp b/LibCarla/source/carla/client/ActorBlueprint.cpp new file mode 100644 index 000000000..b006b0d5b --- /dev/null +++ b/LibCarla/source/carla/client/ActorBlueprint.cpp @@ -0,0 +1,37 @@ +// 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 . + +#include "carla/client/ActorBlueprint.h" + +#include + +#ifdef _WIN32 +# include +#else +# include +#endif // _WIN32 + +namespace carla { +namespace client { + + static bool MatchWildcards(const std::string &str, const std::string &test) { +#ifdef _WIN32 + return PathMatchSpecA(str.c_str(), test.c_str()); +#else + return 0 == fnmatch(test.c_str(), str.c_str(), 0); +#endif // _WIN32 + } + + bool ActorBlueprint::StartsWith(const std::string &test) const { + return boost::starts_with(GetTypeId(), test); + } + + bool ActorBlueprint::MatchWildcards(const std::string &test) const { + return ::carla::client::MatchWildcards(GetTypeId(), test); + } + +} // namespace client +} // namespace carla diff --git a/LibCarla/source/carla/client/ActorBlueprint.h b/LibCarla/source/carla/client/ActorBlueprint.h new file mode 100644 index 000000000..7ec49828d --- /dev/null +++ b/LibCarla/source/carla/client/ActorBlueprint.h @@ -0,0 +1,44 @@ +// 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 . + +#pragma once + +#include "carla/Debug.h" +#include "carla/rpc/ActorBlueprint.h" + +namespace carla { +namespace client { + + class ActorBlueprint { + public: + + ActorBlueprint(carla::rpc::ActorBlueprint blueprint) + : _blueprint(std::move(blueprint)) {} + + ActorBlueprint(const ActorBlueprint &) = default; + ActorBlueprint(ActorBlueprint &&) = default; + ActorBlueprint &operator=(const ActorBlueprint &) = default; + ActorBlueprint &operator=(ActorBlueprint &&) = default; + + const std::string &GetTypeId() const { + return _blueprint.type_id; + } + + bool StartsWith(const std::string &test) const; + + bool MatchWildcards(const std::string &test) const; + + const auto &Serialize() const { + return _blueprint; + } + + private: + + carla::rpc::ActorBlueprint _blueprint; + }; + +} // namespace client +} // namespace carla diff --git a/LibCarla/source/carla/client/BlueprintLibrary.h b/LibCarla/source/carla/client/BlueprintLibrary.h new file mode 100644 index 000000000..3b97acf78 --- /dev/null +++ b/LibCarla/source/carla/client/BlueprintLibrary.h @@ -0,0 +1,77 @@ +// 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 . + +#pragma once + +#include "carla/Debug.h" +#include "carla/NonCopyable.h" +#include "carla/client/ActorBlueprint.h" + +#include +#include + +namespace carla { +namespace client { + + class Client; + + class BlueprintLibrary /*: private NonCopyable*/ { + using list_type = std::vector; + public: + + // BlueprintLibrary() = default; + + // BlueprintLibrary(BlueprintLibrary &&) = default; + // BlueprintLibrary &operator=(BlueprintLibrary &&) = default; + + using value_type = list_type::value_type; + using size_type = list_type::size_type; + using const_iterator = list_type::const_iterator; + using const_reference = list_type::const_reference; + + BlueprintLibrary Filter(const std::string &wildcard_pattern) const { + list_type result; + std::copy_if(begin(), end(), std::back_inserter(result), [&](const auto &x) { + return x.MatchWildcards(wildcard_pattern); + }); + return result; + } + + const_reference operator[](size_type pos) const { + return _blueprints[pos]; + } + + const_iterator begin() const /*noexcept*/ { + return _blueprints.begin(); + } + + const_iterator end() const /*noexcept*/ { + return _blueprints.end(); + } + + bool empty() const /*noexcept*/ { + return _blueprints.empty(); + } + + size_type size() const /*noexcept*/ { + return _blueprints.size(); + } + + private: + + friend class Client; + + BlueprintLibrary(list_type blueprints) + : _blueprints(std::move(blueprints)) {} + + BlueprintLibrary(const std::vector &blueprints) + : _blueprints(blueprints.begin(), blueprints.end()) {} + + list_type _blueprints; + }; + +} // namespace client +} // namespace carla diff --git a/LibCarla/source/carla/client/Client.cpp b/LibCarla/source/carla/client/Client.cpp new file mode 100644 index 000000000..f8dfb30da --- /dev/null +++ b/LibCarla/source/carla/client/Client.cpp @@ -0,0 +1,37 @@ +// 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 . + +#include "carla/client/Client.h" + +#include "carla/client/Actor.h" +#include "carla/client/Control.h" +#include "carla/client/World.h" + +namespace carla { +namespace client { + + SharedPtr Client::GetWorld() { + if (_active_world == nullptr) { + _active_world.reset(new World(shared_from_this())); + } + return _active_world; + } + + SharedPtr Client::SpawnActor( + const ActorBlueprint &blueprint, + const Transform &transform) { + auto actor = Call("spawn_actor", blueprint.Serialize(), transform); + return SharedPtr(new Actor{actor, GetWorld()}); + } + + void Client::ApplyControlToActor( + const Actor &actor, + const VehicleControl &control) { + _client.call("apply_control_to_actor", actor.Serialize(), control); + } + +} // namespace client +} // namespace carla diff --git a/LibCarla/source/carla/client/Client.h b/LibCarla/source/carla/client/Client.h new file mode 100644 index 000000000..12bcae4fd --- /dev/null +++ b/LibCarla/source/carla/client/Client.h @@ -0,0 +1,78 @@ +// 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 . + +#pragma once + +#include "carla/NonCopyable.h" +#include "carla/Version.h" +#include "carla/client/BlueprintLibrary.h" +#include "carla/client/Control.h" +#include "carla/client/Memory.h" +#include "carla/client/Transform.h" +#include "carla/rpc/Client.h" + +#include + +namespace carla { +namespace client { + + class Actor; + class ActorBlueprint; + class World; + + class Client + : public EnableSharedFromThis, + private NonCopyable { + public: + + template + explicit Client(Args && ... args) + : _client(std::forward(args) ...) { + SetTimeout(10'000); + } + + void SetTimeout(int64_t milliseconds) { + _client.set_timeout(milliseconds); + } + + template + T Call(const std::string &function, Args && ... args) { + return _client.call(function, std::forward(args) ...).template as(); + } + + std::string GetClientVersion() const { + return ::carla::version(); + } + + std::string GetServerVersion() { + return Call("version"); + } + + bool Ping() { + return Call("ping"); + } + + SharedPtr GetWorld(); + + BlueprintLibrary GetBlueprintLibrary() { + return Call>("get_blueprints"); + } + + SharedPtr SpawnActor(const ActorBlueprint &blueprint, const Transform &transform); + + void ApplyControlToActor( + const Actor &actor, + const VehicleControl &control); + + private: + + carla::rpc::Client _client; + + SharedPtr _active_world; + }; + +} // namespace client +} // namespace carla diff --git a/LibCarla/source/carla/client/Control.h b/LibCarla/source/carla/client/Control.h new file mode 100644 index 000000000..2726507f0 --- /dev/null +++ b/LibCarla/source/carla/client/Control.h @@ -0,0 +1,17 @@ +// 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 . + +#pragma once + +#include "carla/rpc/VehicleControl.h" + +namespace carla { +namespace client { + + using VehicleControl = carla::rpc::VehicleControl; + +} // namespace client +} // namespace carla diff --git a/LibCarla/source/carla/client/Memory.h b/LibCarla/source/carla/client/Memory.h new file mode 100644 index 000000000..1546d26bb --- /dev/null +++ b/LibCarla/source/carla/client/Memory.h @@ -0,0 +1,31 @@ +// 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 . + +#pragma once + +// In this namespace, we use boost::shared_ptr for now to make it compatible +// with boost::python, but it would be nice to make an adaptor for +// std::shared_ptr. +#include +#include +#include + +namespace carla { +namespace client { + + template + using EnableSharedFromThis = boost::enable_shared_from_this; + + template + using SharedPtr = boost::shared_ptr; + + template + auto MakeShared(Args && ... args) { + return boost::make_shared(std::forward(args) ...); + } + +} // namespace client +} // namespace carla diff --git a/LibCarla/source/carla/client/Transform.h b/LibCarla/source/carla/client/Transform.h new file mode 100644 index 000000000..a1259796d --- /dev/null +++ b/LibCarla/source/carla/client/Transform.h @@ -0,0 +1,19 @@ +// 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 . + +#pragma once + +#include "carla/rpc/Transform.h" + +namespace carla { +namespace client { + + using Location = carla::rpc::Location; + using Rotation = carla::rpc::Rotation; + using Transform = carla::rpc::Transform; + +} // namespace client +} // namespace carla diff --git a/LibCarla/source/carla/client/World.cpp b/LibCarla/source/carla/client/World.cpp new file mode 100644 index 000000000..0b720149e --- /dev/null +++ b/LibCarla/source/carla/client/World.cpp @@ -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 . + +#include "carla/client/World.h" + +#include "carla/Logging.h" + +namespace carla { +namespace client { + + SharedPtr World::TrySpawnActor( + const ActorBlueprint &blueprint, + const Transform &transform) { + try { + return SpawnActor(blueprint, transform); + } catch (const std::exception & DEBUG_ONLY(e)) { + DEBUG_ONLY(log_debug("TrySpawnActor: failed with:", e.what())); + return nullptr; + } + } + +} // namespace client +} // namespace carla diff --git a/LibCarla/source/carla/client/World.h b/LibCarla/source/carla/client/World.h new file mode 100644 index 000000000..4a1bc75cf --- /dev/null +++ b/LibCarla/source/carla/client/World.h @@ -0,0 +1,58 @@ +// 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 . + +#pragma once + +#include "carla/Debug.h" +#include "carla/NonCopyable.h" +#include "carla/client/Client.h" +#include "carla/client/Memory.h" + +namespace carla { +namespace client { + + class Actor; + + class World + : public EnableSharedFromThis, + private NonCopyable { + public: + + World(World &&) = default; + World &operator=(World &&) = default; + + BlueprintLibrary GetBlueprintLibrary() const { + return _parent->GetBlueprintLibrary(); + } + + SharedPtr TrySpawnActor( + const ActorBlueprint &blueprint, + const Transform &transform); + + SharedPtr SpawnActor( + const ActorBlueprint &blueprint, + const Transform &transform) { + return _parent->SpawnActor(blueprint, transform); + } + + template + void ApplyControlToActor(const Actor &actor, const ControlType &control) { + _parent->ApplyControlToActor(actor, control); + } + + private: + + friend class Client; + + explicit World(SharedPtr parent) : _parent(std::move(parent)) { + DEBUG_ASSERT(parent != nullptr); + } + + SharedPtr _parent; + }; + +} // namespace client +} // namespace carla diff --git a/LibCarla/source/carla/profiler/Profiler.cpp b/LibCarla/source/carla/profiler/Profiler.cpp new file mode 100644 index 000000000..9614e0957 --- /dev/null +++ b/LibCarla/source/carla/profiler/Profiler.cpp @@ -0,0 +1,88 @@ +// 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 . + +#ifndef LIBCARLA_ENABLE_PROFILER +# define LIBCARLA_ENABLE_PROFILER +#endif // LIBCARLA_ENABLE_PROFILER + +#include "carla/Logging.h" +#include "carla/Version.h" +#include "carla/profiler/Profiler.h" + +#include +#include +#include +#include + +namespace carla { +namespace profiler { +namespace detail { + + template + static void write_csv_to_stream(std::ostream &out, Arg &&arg, Args &&... args) { + out << std::boolalpha + << std::left << std::setw(44) + << std::forward(arg) + << std::right + << std::fixed << std::setprecision(2); + using expander = int[]; + (void)expander{0, (void(out << ", " << std::setw(10) << std::forward(args)),0)...}; + } + + class StaticProfiler { + public: + + StaticProfiler(std::string filename) + : _filename(std::move(filename)) { + logging::log("PROFILER: writing profiling data to", _filename); + std::string header = "# LibCarla Profiler "; + header += carla::version(); +#ifdef NDEBUG + header += " (release)"; +#else + header += " (debug)"; +#endif // NDEBUG + write_to_file(std::ios_base::out, header); + write_line("# context", "average", "maximum", "minimum", "units", "times"); + } + + template + void write_line(Args &&... args) { + write_to_file(std::ios_base::app|std::ios_base::out, std::forward(args)...); + } + + private: + + template + void write_to_file(std::ios_base::openmode mode, Args &&... args) { + if (!_filename.empty()) { + static std::mutex MUTEX; + std::lock_guard guard(MUTEX); + std::ofstream file(_filename, mode); + write_csv_to_stream(file, std::forward(args)...); + file << std::endl; + } + } + + const std::string _filename; + }; + + ProfilerData::~ProfilerData() { + static StaticProfiler PROFILER{"profiler.csv"}; + if (_count > 0u) { + if (_print_fps) { + PROFILER.write_line(_name, fps(average()), fps(minimum()), fps(maximum()), "FPS", _count); + } else { + PROFILER.write_line(_name, average(), maximum(), minimum(), "ms", _count); + } + } else { + log_error("profiler", _name, " was never run!"); + } + } + +} // namespace detail +} // namespace profiler +} // namespace carla diff --git a/LibCarla/source/carla/profiler/Profiler.h b/LibCarla/source/carla/profiler/Profiler.h new file mode 100644 index 000000000..f4aa9e0de --- /dev/null +++ b/LibCarla/source/carla/profiler/Profiler.h @@ -0,0 +1,124 @@ +// 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 . + +#pragma once + +#ifndef LIBCARLA_ENABLE_PROFILER +# define CARLA_PROFILE_SCOPE(context, profiler_name) +# define CARLA_PROFILE_FPS(context, profiler_name) +#else + +#include "carla/StopWatch.h" + +#include +#include + +namespace carla { +namespace profiler { +namespace detail { + + class ProfilerData { + public: + + explicit ProfilerData(std::string name, bool print_fps = false) + : _name(std::move(name)), + _print_fps(print_fps) {} + + ~ProfilerData(); + + void Annotate(const StopWatch &stop_watch) { + const size_t elapsed_microseconds = + stop_watch.GetElapsedTime(); + ++_count; + _total_microseconds += elapsed_microseconds; + _max_elapsed = std::max(elapsed_microseconds, _max_elapsed); + _min_elapsed = std::min(elapsed_microseconds, _min_elapsed); + } + + float average() const { + return ms(_total_microseconds) / static_cast(_count); + } + + float maximum() const { + return ms(_max_elapsed); + } + + float minimum() const { + return ms(_min_elapsed); + } + + private: + + static inline float ms(size_t microseconds) { + return 1e-3f * static_cast(microseconds); + } + + static inline float fps(float milliseconds) { + return 1e3f / milliseconds; + } + + const std::string _name; + + const bool _print_fps; + + size_t _count = 0u; + + size_t _total_microseconds = 0u; + + size_t _max_elapsed = 0u; + + size_t _min_elapsed = -1; + }; + + class ScopedProfiler { + public: + + explicit ScopedProfiler(ProfilerData &parent) : _profiler(parent) {} + + ~ScopedProfiler() { + _stop_watch.Stop(); + _profiler.Annotate(_stop_watch); + } + + private: + + ProfilerData &_profiler; + + StopWatch _stop_watch; + }; + +} // namespace detail +} // namespace profiler +} // namespace carla + +#ifdef LIBCARLA_WITH_GTEST +# define LIBCARLA_GTEST_GET_TEST_NAME() std::string(::testing::UnitTest::GetInstance()->current_test_info()->name()) +#else +# define LIBCARLA_GTEST_GET_TEST_NAME() std::string("") +#endif // LIBCARLA_WITH_GTEST + +#define CARLA_PROFILE_SCOPE(context, profiler_name) \ + static thread_local ::carla::profiler::detail::ProfilerData carla_profiler_ ## context ## _ ## profiler_name ## _data( \ + LIBCARLA_GTEST_GET_TEST_NAME() + "." #context "." #profiler_name); \ + ::carla::profiler::detail::ScopedProfiler carla_profiler_ ## context ## _ ## profiler_name ## _scoped_profiler( \ + carla_profiler_ ## context ## _ ## profiler_name ## _data); + +#define CARLA_PROFILE_FPS(context, profiler_name) \ + { \ + static thread_local ::carla::StopWatch stop_watch; \ + stop_watch.Stop(); \ + static thread_local bool first_time = true; \ + if (!first_time) { \ + static thread_local ::carla::profiler::detail::ProfilerData profiler_data( \ + LIBCARLA_GTEST_GET_TEST_NAME() + "." #context "." #profiler_name, true); \ + profiler_data.Annotate(stop_watch); \ + } else { \ + first_time = false; \ + } \ + stop_watch.Restart(); \ + } + +#endif // LIBCARLA_ENABLE_PROFILER diff --git a/LibCarla/source/carla/rpc/Actor.h b/LibCarla/source/carla/rpc/Actor.h new file mode 100644 index 000000000..de0366308 --- /dev/null +++ b/LibCarla/source/carla/rpc/Actor.h @@ -0,0 +1,27 @@ +// 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 . + +#pragma once + +#include "carla/rpc/ActorBlueprint.h" + +namespace carla { +namespace rpc { + + class Actor { + public: + + using id_type = uint32_t; + + id_type id; + + ActorBlueprint blueprint; + + MSGPACK_DEFINE_ARRAY(id, blueprint); + }; + +} // namespace rpc +} // namespace carla diff --git a/LibCarla/source/carla/rpc/ActorBlueprint.h b/LibCarla/source/carla/rpc/ActorBlueprint.h new file mode 100644 index 000000000..aab429ee7 --- /dev/null +++ b/LibCarla/source/carla/rpc/ActorBlueprint.h @@ -0,0 +1,49 @@ +// 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 . + +#pragma once + +#include "carla/rpc/MsgPack.h" + +#ifdef LIBCARLA_INCLUDED_FROM_UE4 +# include "UnrealString.h" +#endif // LIBCARLA_INCLUDED_FROM_UE4 + +#include + +namespace carla { +namespace rpc { + + class ActorBlueprint { + public: + + ActorBlueprint(std::string type_id) + : type_id(std::move(type_id)) {} + + ActorBlueprint() = default; + ActorBlueprint(const ActorBlueprint &) = default; + ActorBlueprint(ActorBlueprint &&) = default; + ActorBlueprint &operator=(const ActorBlueprint &) = default; + ActorBlueprint &operator=(ActorBlueprint &&) = default; + +#ifdef LIBCARLA_INCLUDED_FROM_UE4 + + // ActorBlueprint(const FString &Type) + // : type_id(TCHAR_TO_UTF8(*Type)) {} + + FString GetTypeIdAsFString() const { + return FString(type_id.size(), UTF8_TO_TCHAR(type_id.c_str())); + } + +#endif // LIBCARLA_INCLUDED_FROM_UE4 + + std::string type_id; + + MSGPACK_DEFINE_ARRAY(type_id); + }; + +} // namespace rpc +} // namespace carla diff --git a/LibCarla/source/carla/rpc/Client.h b/LibCarla/source/carla/rpc/Client.h new file mode 100644 index 000000000..2af83dbe7 --- /dev/null +++ b/LibCarla/source/carla/rpc/Client.h @@ -0,0 +1,17 @@ +// 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 . + +#pragma once + +#include + +namespace carla { +namespace rpc { + + using Client = ::rpc::client; + +} // namespace rpc +} // namespace carla diff --git a/LibCarla/source/carla/rpc/MsgPack.h b/LibCarla/source/carla/rpc/MsgPack.h new file mode 100644 index 000000000..aae91543f --- /dev/null +++ b/LibCarla/source/carla/rpc/MsgPack.h @@ -0,0 +1,9 @@ +// 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 . + +#pragma once + +#include diff --git a/LibCarla/source/carla/rpc/Server.h b/LibCarla/source/carla/rpc/Server.h new file mode 100644 index 000000000..2a84ed2e4 --- /dev/null +++ b/LibCarla/source/carla/rpc/Server.h @@ -0,0 +1,116 @@ +// 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 . + +#pragma once + +#include + +#include + +namespace carla { +namespace rpc { + +namespace detail { + + /// Function traits based on http://rpclib.net implementation. + /// MIT Licensed, Copyright (c) 2015-2017, Tamás Szelei + template + struct wrapper_function_traits : wrapper_function_traits {}; + + template + struct wrapper_function_traits : wrapper_function_traits {}; + + template + struct wrapper_function_traits : wrapper_function_traits {}; + + template struct wrapper_function_traits { + using result_type = R; + using function_type = std::function; + using packaged_task_type = std::packaged_task; + }; + + /// Wraps @a functor into a function type with equivalent signature. The wrap + /// function returned, when called, posts @a functor into the io_service and + /// waits for it to finish. + /// + /// This way, no matter from which thread the wrap function is called, the + /// @a functor provided is always called from the context of the io_service. + /// + /// @warning The wrap function blocks until @a functor is executed by the + /// io_service. + template + inline auto WrapSyncCall(boost::asio::io_service &io, F functor) { + using func_t = typename wrapper_function_traits::function_type; + using task_t = typename wrapper_function_traits::packaged_task_type; + + return func_t([&io, functor=std::move(functor)](auto && ... args) { + // We can pass arguments by ref to the lambda because the task will be + // executed before this function exits. + task_t task([functor=std::move(functor), &args...]() { + return functor(std::forward(args)...); + }); + auto result = task.get_future(); + io.post([&]() mutable { task(); }); + return result.get(); + }); + } + +} // namespace detail + + /// An RPC server in which functions can be bind to run synchronously or + /// asynchronously. + /// + /// Use `AsyncRun` to start the worker threads, and use `SyncRunFor` to + /// run a slice of work in the caller's thread. + /// + /// Functions that are bind using `BindAsync` will run asynchronously in the + /// worker threads. Functions that are bind using `BindSync` will run within + /// `SyncRunFor` function. + class Server { + public: + + template + explicit Server(Args && ... args) + : _server(std::forward(args) ...) { + _server.suppress_exceptions(true); + } + + template + void BindAsync(const std::string &name, Functor &&functor) { + _server.bind(name, std::forward(functor)); + } + + template + void BindSync(const std::string &name, Functor functor) { + _server.bind( + name, + detail::WrapSyncCall(_sync_io_service, std::move(functor))); + } + + void AsyncRun(size_t worker_threads) { + _server.async_run(worker_threads); + } + + template + void SyncRunFor(Duration duration) { + _sync_io_service.reset(); + _sync_io_service.run_for(duration); + } + + /// @warning does not stop the game thread. + void Stop() { + _server.stop(); + } + + private: + + boost::asio::io_service _sync_io_service; + + ::rpc::server _server; + }; + +} // namespace rpc +} // namespace carla diff --git a/LibCarla/source/carla/rpc/Transform.h b/LibCarla/source/carla/rpc/Transform.h new file mode 100644 index 000000000..2d97e2bf4 --- /dev/null +++ b/LibCarla/source/carla/rpc/Transform.h @@ -0,0 +1,102 @@ +// 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 . + +#pragma once + +#include "carla/rpc/MsgPack.h" + +#ifdef LIBCARLA_INCLUDED_FROM_UE4 +# include "Transform.h" +#endif // LIBCARLA_INCLUDED_FROM_UE4 + +namespace carla { +namespace rpc { + + class Location { + public: + + Location() = default; + + Location(float ix, float iy, float iz) + : x(ix), + y(iy), + z(iz) {} + + float x = 0.0f; + float y = 0.0f; + float z = 0.0f; + +#ifdef LIBCARLA_INCLUDED_FROM_UE4 + + Location(const FVector &vector) // from centimeters to meters. + : Location(1e-2f * vector.X, 1e-2f * vector.Y, 1e-2f * vector.Z) {} + + operator FVector() const { + return FVector{1e2f * x, 1e2f * y, 1e2f * z}; // from meters to centimeters. + } + +#endif // LIBCARLA_INCLUDED_FROM_UE4 + + MSGPACK_DEFINE_ARRAY(x, y, z); + }; + + class Rotation { + public: + + Rotation() = default; + + Rotation(float p, float y, float r) + : pitch(p), + yaw(y), + roll(r) {} + + float pitch = 0.0f; + float yaw = 0.0f; + float roll = 0.0f; + +#ifdef LIBCARLA_INCLUDED_FROM_UE4 + + Rotation(const FRotator &rotator) + : Rotation(rotator.Pitch, rotator.Yaw, rotator.Roll) {} + + operator FRotator() const { + return FRotator{pitch, yaw, roll}; + } + +#endif // LIBCARLA_INCLUDED_FROM_UE4 + + MSGPACK_DEFINE_ARRAY(pitch, yaw, roll); + }; + + class Transform { + public: + + Transform() = default; + + Transform(const Location &in_location, const Rotation &in_rotation) + : location(in_location), + rotation(in_rotation) {} + + Location location; + Rotation rotation; + +#ifdef LIBCARLA_INCLUDED_FROM_UE4 + + Transform(const FTransform &transform) + : Transform(Location(transform.GetLocation()), Rotation(transform.Rotator())) {} + + operator FTransform() const { + const FVector scale{1.0f, 1.0f, 1.0f}; + return FTransform{FRotator(rotation), FVector(location), scale}; + } + +#endif // LIBCARLA_INCLUDED_FROM_UE4 + + MSGPACK_DEFINE_ARRAY(location, rotation); + }; + +} // namespace rpc +} // namespace carla diff --git a/LibCarla/source/carla/rpc/VehicleControl.h b/LibCarla/source/carla/rpc/VehicleControl.h new file mode 100644 index 000000000..018977f85 --- /dev/null +++ b/LibCarla/source/carla/rpc/VehicleControl.h @@ -0,0 +1,46 @@ +// 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 . + +#pragma once + +#include "carla/rpc/MsgPack.h" + +namespace carla { +namespace rpc { + + class VehicleControl { + public: + + VehicleControl() = default; + + VehicleControl( + float in_throttle, + float in_steer, + float in_brake, + bool in_hand_brake, + bool in_reverse) + : throttle(in_throttle), + steer(in_steer), + brake(in_brake), + hand_brake(in_hand_brake), + reverse(in_reverse) {} + + float throttle = 0.0f; + float steer = 0.0f; + float brake = 0.0f; + bool hand_brake = false; + bool reverse = false; + + MSGPACK_DEFINE_ARRAY( + throttle, + steer, + brake, + hand_brake, + reverse); + }; + +} // namespace rpc +} // namespace carla diff --git a/LibCarla/source/carla/streaming/Client.h b/LibCarla/source/carla/streaming/Client.h new file mode 100644 index 000000000..3295c75b6 --- /dev/null +++ b/LibCarla/source/carla/streaming/Client.h @@ -0,0 +1,58 @@ +// 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 . + +#pragma once + +#include "carla/ThreadGroup.h" +#include "carla/streaming/low_level/Client.h" +#include "carla/streaming/low_level/tcp/Client.h" + +#include + +namespace carla { +namespace streaming { + + using stream_token = low_level::token_type; + + /// With this client you can subscribe to multiple streams. + class Client { + public: + + ~Client() { + Stop(); + } + + template + void Subscribe(const stream_token &token, Functor &&callback) { + _client.Subscribe(_io_service, token, std::forward(callback)); + } + + void Run() { + _io_service.run(); + } + + void AsyncRun(size_t worker_threads) { + _workers.CreateThreads(worker_threads, [this]() { Run(); }); + } + + void Stop() { + _io_service.stop(); + _workers.JoinAll(); + } + + private: + + using underlying_client = low_level::Client; + + boost::asio::io_service _io_service; + + ThreadGroup _workers; + + underlying_client _client; + }; + +} // namespace streaming +} // namespace carla diff --git a/LibCarla/source/carla/streaming/Message.h b/LibCarla/source/carla/streaming/Message.h new file mode 100644 index 000000000..18c1c7f31 --- /dev/null +++ b/LibCarla/source/carla/streaming/Message.h @@ -0,0 +1,142 @@ +// 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 . + +#pragma once + +#include "carla/Debug.h" + +#include + +#include +#include +#include +#include +#include + +namespace carla { +namespace streaming { + +namespace low_level { +namespace tcp { + + class Client; /// @todo + +} // namespace low_level +} // namespace tcp + + /// A message owns a buffer with raw data. + class Message { + + // ========================================================================= + // -- Typedefs ------------------------------------------------------------- + // ========================================================================= + + public: + + using value_type = unsigned char; + + using size_type = uint32_t; + + // ========================================================================= + // -- Construction and assignment ------------------------------------------ + // ========================================================================= + + public: + + Message() = default; + + explicit Message(size_type size) + : _size(size), + _data(std::make_unique(_size)) {} + + explicit Message(uint64_t size) + : Message([size]() { + if (size > std::numeric_limits::max()) { + throw std::invalid_argument("message size too big"); + } + return static_cast(size); + } ()) {} + + template + explicit Message(ConstBufferSequence source) + : Message(boost::asio::buffer_size(source)) { + DEBUG_ONLY(auto bytes_copied = ) + boost::asio::buffer_copy(buffer(), source); + DEBUG_ASSERT(bytes_copied == size()); + } + + Message(const Message &) = delete; + Message &operator=(const Message &) = delete; + + Message(Message &&rhs) noexcept + : _size(rhs._size), + _data(std::move(rhs._data)) { + rhs._size = 0u; + } + + Message &operator=(Message &&rhs) noexcept { + _size = rhs._size; + _data = std::move(rhs._data); + rhs._size = 0u; + return *this; + } + + // ========================================================================= + // -- Data access ---------------------------------------------------------- + // ========================================================================= + + public: + + bool empty() const { + return _size == 0u; + } + + size_type size() const { + return _size; + } + + const value_type *data() const { + return _data.get(); + } + + value_type *data() { + return _data.get(); + } + + // ========================================================================= + // -- Conversions ---------------------------------------------------------- + // ========================================================================= + + public: + + boost::asio::const_buffer buffer() const { + return {data(), size()}; + } + + boost::asio::mutable_buffer buffer() { + return {data(), size()}; + } + + std::array encode() const { + DEBUG_ASSERT(!empty()); + return {boost::asio::buffer(&_size, sizeof(_size)), buffer()}; + } + + // ========================================================================= + // -- Private members ------------------------------------------------------ + // ========================================================================= + + private: + + friend class low_level::tcp::Client; /// @todo + + size_type _size = 0u; + + std::unique_ptr _data = nullptr; + }; + +} // namespace streaming +} // namespace carla diff --git a/LibCarla/source/carla/streaming/Server.h b/LibCarla/source/carla/streaming/Server.h new file mode 100644 index 000000000..039176e36 --- /dev/null +++ b/LibCarla/source/carla/streaming/Server.h @@ -0,0 +1,65 @@ +// 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 . + +#pragma once + +#include "carla/ThreadGroup.h" +#include "carla/streaming/low_level/Server.h" +#include "carla/streaming/low_level/tcp/Server.h" + +#include + +namespace carla { +namespace streaming { + + class Server { + using underlying_server = low_level::Server; + public: + + using duration_type = underlying_server::duration_type; + + explicit Server(uint16_t port) + : _server(_io_service, port) {} + + explicit Server(const std::string &address, uint16_t port) + : _server(_io_service, address, port) {} + + ~Server() { + Stop(); + } + + void set_timeout(duration_type timeout) { + _server.set_timeout(timeout); + } + + Stream MakeStream() { + return _server.MakeStream(); + } + + void Run() { + _io_service.run(); + } + + void AsyncRun(size_t worker_threads) { + _workers.CreateThreads(worker_threads, [this](){ Run(); }); + } + + void Stop() { + _io_service.stop(); + _workers.JoinAll(); + } + + private: + + boost::asio::io_service _io_service; + + underlying_server _server; + + ThreadGroup _workers; + }; + +} // namespace streaming +} // namespace carla diff --git a/LibCarla/source/carla/streaming/Stream.h b/LibCarla/source/carla/streaming/Stream.h new file mode 100644 index 000000000..e2a1821a4 --- /dev/null +++ b/LibCarla/source/carla/streaming/Stream.h @@ -0,0 +1,68 @@ +// 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 . + +#pragma once + +#include "carla/Debug.h" +#include "carla/streaming/Message.h" +#include "carla/streaming/low_level/StreamState.h" +#include "carla/streaming/low_level/Token.h" + +#include + +#include + +namespace carla { +namespace streaming { + +namespace low_level { + + class Dispatcher; + +} // namespace low_level + + using stream_token = low_level::token_type; + + class Stream { + public: + + Stream() = delete; + + Stream(const Stream &) = default; + Stream(Stream &&) = default; + + Stream &operator=(const Stream &) = default; + Stream &operator=(Stream &&) = default; + + stream_token token() const { + return _shared_state->token(); + } + + template + void Write(ConstBufferSequence buffer) { + _shared_state->Write(std::make_shared(buffer)); + } + + template + Stream &operator<<(const T &rhs) { + Write(boost::asio::buffer(rhs)); + return *this; + } + + private: + + friend class low_level::Dispatcher; + + Stream(std::shared_ptr state) + : _shared_state(std::move(state)) { + DEBUG_ASSERT(_shared_state != nullptr); + } + + std::shared_ptr _shared_state; + }; + +} // namespace streaming +} // namespace carla diff --git a/LibCarla/source/carla/streaming/low_level/Client.h b/LibCarla/source/carla/streaming/low_level/Client.h new file mode 100644 index 000000000..c5234776e --- /dev/null +++ b/LibCarla/source/carla/streaming/low_level/Client.h @@ -0,0 +1,52 @@ +// 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 . + +#pragma once + +#include "carla/streaming/low_level/Token.h" + +#include + +#include + +namespace carla { +namespace streaming { +namespace low_level { + + /// Wrapper around low level clients. You can subscribe to multiple streams. + /// + /// @warning The client should not be destroyed before the @a io_service is + /// stopped. + /// @pre T has to be hashable. + template + class Client { + public: + + using underlying_client = T; + + template + void Subscribe( + boost::asio::io_service &io_service, + const token_type &token, + Functor &&callback) { + if (!token.protocol_is_tcp()) { + throw std::invalid_argument("invalid token, only TCP tokens supported"); + } + _clients.emplace( + io_service, + token.to_tcp_endpoint(), + token.get_stream_id(), + std::forward(callback)); + } + + private: + + std::unordered_set _clients; + }; + +} // namespace low_level +} // namespace streaming +} // namespace carla diff --git a/LibCarla/source/carla/streaming/low_level/Dispatcher.h b/LibCarla/source/carla/streaming/low_level/Dispatcher.h new file mode 100644 index 000000000..a74622541 --- /dev/null +++ b/LibCarla/source/carla/streaming/low_level/Dispatcher.h @@ -0,0 +1,68 @@ +// 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 . + +#pragma once + +#include "carla/streaming/Stream.h" +#include "carla/streaming/low_level/Session.h" +#include "carla/streaming/low_level/StreamState.h" +#include "carla/streaming/low_level/Token.h" + +#include +#include +#include +#include + +namespace carla { +namespace streaming { +namespace low_level { + + class Dispatcher { + public: + + template + explicit Dispatcher(const boost::asio::ip::basic_endpoint

&ep) + : _cached_token(0u, ep) {} + + Stream MakeStream() { + std::lock_guard lock(_mutex); + ++_cached_token._token.stream_id; // id zero only happens in overflow. + auto ptr = std::make_shared(_cached_token); + auto result = _stream_map.emplace(std::make_pair(_cached_token.get_stream_id(), ptr)); + if (!result.second) { + throw std::runtime_error("failed to create stream!"); + } + return ptr; + } + + void RegisterSession(std::shared_ptr session) { + DEBUG_ASSERT(session != nullptr); + std::lock_guard lock(_mutex); + auto search = _stream_map.find(session->get_stream_id()); + if (search != _stream_map.end()) { + DEBUG_ASSERT(search->second != nullptr); + search->second->set_session(std::move(session)); + } else { + log_error("Invalid session: no stream available with id", session->get_stream_id()); + } + } + + private: + + // We use a mutex here, but we assume that sessions and streams won't be + // created too often. + std::mutex _mutex; + + token_type _cached_token; + + std::unordered_map< + stream_id_type, + std::shared_ptr> _stream_map; + }; + +} // namespace low_level +} // namespace streaming +} // namespace carla diff --git a/LibCarla/source/carla/streaming/low_level/Server.h b/LibCarla/source/carla/streaming/low_level/Server.h new file mode 100644 index 000000000..6b61df677 --- /dev/null +++ b/LibCarla/source/carla/streaming/low_level/Server.h @@ -0,0 +1,60 @@ +// 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 . + +#pragma once + +#include "carla/streaming/low_level/Dispatcher.h" +#include "carla/streaming/Stream.h" + +#include + +namespace carla { +namespace streaming { +namespace low_level { + + /// Wrapper around low level servers. + template + class Server { + public: + + using underlying_server = T; + + using duration_type = typename underlying_server::duration_type; + using endpoint = typename underlying_server::endpoint; + using protocol_type = typename underlying_server::protocol_type; + + explicit Server(boost::asio::io_service &io_service, const endpoint &ep) + : _server(io_service, ep), + _dispatcher(ep) { + _server.Listen([this](auto session){ + _dispatcher.RegisterSession(session); + }); + } + + explicit Server(boost::asio::io_service &io_service, uint16_t port) + : Server(io_service, endpoint(protocol_type::v4(), port)) {} + + explicit Server(boost::asio::io_service &io_service, const std::string &address, uint16_t port) + : Server(io_service, endpoint(boost::asio::ip::address::from_string(address), port)) {} + + void set_timeout(duration_type timeout) { + _server.set_timeout(timeout); + } + + Stream MakeStream() { + return _dispatcher.MakeStream(); + } + + private: + + underlying_server _server; + + Dispatcher _dispatcher; + }; + +} // namespace low_level +} // namespace streaming +} // namespace carla diff --git a/LibCarla/source/carla/streaming/low_level/Session.h b/LibCarla/source/carla/streaming/low_level/Session.h new file mode 100644 index 000000000..9acf14d36 --- /dev/null +++ b/LibCarla/source/carla/streaming/low_level/Session.h @@ -0,0 +1,19 @@ +// 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 . + +#pragma once + +#include "carla/streaming/low_level/tcp/ServerSession.h" + +namespace carla { +namespace streaming { +namespace low_level { + + using Session = tcp::ServerSession; + +} // namespace low_level +} // namespace streaming +} // namespace carla diff --git a/LibCarla/source/carla/streaming/low_level/StreamState.h b/LibCarla/source/carla/streaming/low_level/StreamState.h new file mode 100644 index 000000000..852ae7b2b --- /dev/null +++ b/LibCarla/source/carla/streaming/low_level/StreamState.h @@ -0,0 +1,74 @@ +// 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 . + +#pragma once + +#include "carla/streaming/Message.h" +#include "carla/streaming/low_level/Session.h" +#include "carla/streaming/low_level/Token.h" + +#include +#include + +namespace carla { +namespace streaming { +namespace low_level { + +namespace detail { + + /// Handles the synchronization of the shared session. + class SessionHolder { + public: + + void set_session(std::shared_ptr session) { + std::lock_guard guard(_mutex); + _session = std::move(session); + } + + protected: + + std::shared_ptr get_session() const { + std::lock_guard guard(_mutex); + return _session; + } + + private: + + mutable std::mutex _mutex; /// @todo it can be atomic + + std::shared_ptr _session; + }; + +} // namespace detail + + /// Shared state among all the copies of a stream. Provides access to the + /// underlying UDP session if active. + class StreamState + : public detail::SessionHolder, + private boost::noncopyable { + public: + + explicit StreamState(const token_type &token) : _token(token) {} + + const token_type &token() const { + return _token; + } + + void Write(std::shared_ptr message) { + auto session = get_session(); + if (session != nullptr) { + session->Write(message); + } + } + + private: + + const token_type _token; + }; + +} // namespace low_level +} // namespace streaming +} // namespace carla diff --git a/LibCarla/source/carla/streaming/low_level/Token.h b/LibCarla/source/carla/streaming/low_level/Token.h new file mode 100644 index 000000000..0a9cef798 --- /dev/null +++ b/LibCarla/source/carla/streaming/low_level/Token.h @@ -0,0 +1,164 @@ +// 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 . + +#pragma once + +#include "carla/Debug.h" +#include "carla/streaming/low_level/Types.h" + +#include +#include +#include + +namespace carla { +namespace streaming { +namespace low_level { + +namespace detail { + +#pragma pack(push, 1) + + struct token { + stream_id_type stream_id; + + uint16_t port; + + enum class protocol : uint8_t { + not_set, + tcp, + udp + } protocol = protocol::not_set; + + enum class address : uint8_t { + not_set, + ip_v4, + ip_v6 + } address_type = address::not_set; + + union { + boost::asio::ip::address_v4::bytes_type v4; + boost::asio::ip::address_v6::bytes_type v6; + } address; + }; + +#pragma pack(pop) + + static_assert( + sizeof(token) == 24u, + "Size shouldn't be more than" + " v6 address : 128" + " + state : 16" + " + port : 16" + " + stream id : 32" + " -----------------" + " 192"); + +} // namespace detail + + /// Serializes a stream endpoint. Contains all the necessary information for a + /// client to subscribe to a stream. + class token_type { + private: + + template + static constexpr auto get_protocol() { + return std::is_same::value ? + detail::token::protocol::tcp : + detail::token::protocol::udp; + } + + void set_address(const boost::asio::ip::address &addr) { + if (addr.is_v4()) { + _token.address_type = detail::token::address::ip_v4; + _token.address.v4 = addr.to_v4().to_bytes(); + } else if (addr.is_v6()) { + _token.address_type = detail::token::address::ip_v6; + _token.address.v6 = addr.to_v6().to_bytes(); + } else { + throw std::invalid_argument("invalid ip address!"); + } + } + + boost::asio::ip::address get_address() const { + if (_token.address_type == detail::token::address::ip_v4) { + return boost::asio::ip::address_v4(_token.address.v4); + } + return boost::asio::ip::address_v6(_token.address.v6); + } + + template + boost::asio::ip::basic_endpoint

get_endpoint() const { + DEBUG_ASSERT(is_valid()); + DEBUG_ASSERT(get_protocol

() == _token.protocol); + return {get_address(), _token.port}; + } + + template + explicit token_type( + stream_id_type stream_id, + const boost::asio::ip::basic_endpoint

&ep) { + _token.stream_id = stream_id; + _token.port = ep.port(); + _token.protocol = get_protocol

(); + set_address(ep.address()); + } + + public: + + token_type() = default; + token_type(const token_type &) = default; + + auto get_stream_id() const { + return _token.stream_id; + } + + auto get_port() const { + return _token.port; + } + + bool is_valid() const { + return ((_token.protocol != detail::token::protocol::not_set) && + (_token.address_type != detail::token::address::not_set)); + } + + bool address_is_v4() const { + return _token.address_type == detail::token::address::ip_v4; + } + + bool address_is_v6() const { + return _token.address_type == detail::token::address::ip_v6; + } + + bool protocol_is_udp() const { + return _token.protocol == detail::token::protocol::udp; + } + + bool protocol_is_tcp() const { + return _token.protocol == detail::token::protocol::tcp; + } + + boost::asio::ip::udp::endpoint to_udp_endpoint() const { + return get_endpoint(); + } + + boost::asio::ip::tcp::endpoint to_tcp_endpoint() const { + return get_endpoint(); + } + + boost::asio::const_buffer as_buffer() const { + return boost::asio::buffer(&_token, sizeof(_token)); + } + + private: + + friend class Dispatcher; + + detail::token _token; + }; + +} // namespace low_level +} // namespace streaming +} // namespace carla diff --git a/LibCarla/source/carla/streaming/low_level/Types.h b/LibCarla/source/carla/streaming/low_level/Types.h new file mode 100644 index 000000000..1da5e93d7 --- /dev/null +++ b/LibCarla/source/carla/streaming/low_level/Types.h @@ -0,0 +1,21 @@ +// 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 . + +#pragma once + +#include + +namespace carla { +namespace streaming { +namespace low_level { + + using stream_id_type = uint32_t; + + using message_size_type = uint32_t; + +} // namespace low_level +} // namespace streaming +} // namespace carla diff --git a/LibCarla/source/carla/streaming/low_level/tcp/Client.h b/LibCarla/source/carla/streaming/low_level/tcp/Client.h new file mode 100644 index 000000000..6adea93e1 --- /dev/null +++ b/LibCarla/source/carla/streaming/low_level/tcp/Client.h @@ -0,0 +1,249 @@ +// 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 . + +#pragma once + +#include "carla/Debug.h" +#include "carla/Logging.h" +#include "carla/streaming/Message.h" +#include "carla/streaming/low_level/Types.h" +#include "carla/streaming/low_level/tcp/Timeout.h" + +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +namespace carla { +namespace streaming { +namespace low_level { +namespace tcp { + + class Encoder { + public: + + boost::asio::mutable_buffer header() { + return boost::asio::buffer(reinterpret_cast(&_size), sizeof(_size)); + } + + boost::asio::mutable_buffer body() { + DEBUG_ASSERT(_size > 0u); + DEBUG_ASSERT(_message == nullptr); + _message = std::make_shared(_size); + return _message->buffer(); + } + + auto size() const { + return _size; + } + + auto pop() { + return std::move(_message); + } + + private: + + message_size_type _size = 0u; + + std::shared_ptr _message; + }; + + /// @warning The client should not be destroyed before the @a io_service is + /// stopped. + class Client : private boost::noncopyable { + public: + + using endpoint = boost::asio::ip::tcp::endpoint; + + template + Client( + boost::asio::io_service &io_service, + endpoint ep, + stream_id_type stream_id, + Functor &&callback) + : _endpoint(std::move(ep)), + _stream_id(stream_id), + _callback(std::forward(callback)), + _socket(io_service), + _strand(io_service), + _connection_timer(io_service) { + Connect(); + } + + ~Client() { + Stop(); + } + + stream_id_type get_id() const { + return _stream_id; + } + + bool operator==(const Client &rhs) const { + return get_id() == rhs.get_id(); + } + + void Stop() { + _connection_timer.cancel(); + _strand.post([this]() { + _done = true; + if (_socket.is_open()) { + _socket.close(); + } + }); + } + + private: + + /// @todo Stop inlining and make cpp files. + + inline void Connect(); + + inline void Reconnect() { + _connection_timer.expires_from_now(timeout_type::seconds(1u)); + _connection_timer.async_wait([this](boost::system::error_code ec) { + if (!ec) { + Connect(); + } + }); + } + + inline void ReadData(); + + const endpoint _endpoint; + + const stream_id_type _stream_id; + + std::function)> _callback; + + boost::asio::ip::tcp::socket _socket; + + boost::asio::io_service::strand _strand; + + boost::asio::deadline_timer _connection_timer; + + bool _done = false; + }; + + void Client::Connect() { + _strand.post([this]() { + if (_done) { + return; + } + + using boost::system::error_code; + + if (_socket.is_open()) { + _socket.close(); + } + + auto handle_connect = [=](error_code ec) { + if (!ec) { + // Send the stream id to subscribe to the stream. + log_debug("streaming client: sending stream id", _stream_id); + boost::asio::async_write( + _socket, + boost::asio::buffer(&_stream_id, sizeof(_stream_id)), + _strand.wrap([=](error_code ec, size_t DEBUG_ONLY(bytes)) { + if (!ec) { + DEBUG_ASSERT_EQ(bytes, sizeof(_stream_id)); + // If succeeded start reading data. + ReadData(); + } else { + // Else try again. + log_debug("streaming client: failed to send stream id:", ec.message()); + Connect(); + } + })); + } else { + log_debug("streaming client: connection failed:", ec.message()); + Reconnect(); + } + }; + + log_debug("streaming client: connecting to", _endpoint); + _socket.async_connect(_endpoint, _strand.wrap(handle_connect)); + }); + } + + void Client::ReadData() { + _strand.post([this]() { + if (_done) { + return; + } + + log_debug("streaming client: Client::ReadData"); + + auto encoder = std::make_shared(); + + auto handle_read_data = [=](boost::system::error_code ec, size_t DEBUG_ONLY(bytes)) { + DEBUG_ONLY(log_debug("streaming client: Client::ReadData.handle_read_data", bytes, "bytes")); + if (!ec) { + DEBUG_ASSERT_EQ(bytes, encoder->size()); + DEBUG_ASSERT_NE(bytes, 0u); + // Move the buffer to the callback function and start reading the next + // piece of data. + log_debug("streaming client: success reading data, calling the callback"); + _socket.get_io_service().post([this, encoder]() { _callback(encoder->pop()); }); + ReadData(); + } else { + // As usual, if anything fails start over from the very top. + log_debug("streaming client: failed to read data:", ec.message()); + Connect(); + } + }; + + auto handle_read_header = [=](boost::system::error_code ec, size_t DEBUG_ONLY(bytes)) { + DEBUG_ONLY(log_debug("streaming client: Client::ReadData.handle_read_header", bytes, "bytes")); + if (!ec && (encoder->size() > 0u)) { + DEBUG_ASSERT_EQ(bytes, sizeof(message_size_type)); + // Now that we know the size of the coming buffer, we can allocate + // our buffer and start putting data into it. + boost::asio::async_read( + _socket, + encoder->body(), + _strand.wrap(handle_read_data)); + } else { + log_debug("streaming client: failed to read header:", ec.message()); + DEBUG_ONLY(log_debug("size = ", encoder->size())); + DEBUG_ONLY(log_debug("bytes = ", bytes)); + Connect(); + } + }; + + // Read the size of the buffer that is coming. + boost::asio::async_read( + _socket, + encoder->header(), + _strand.wrap(handle_read_header)); + }); + } + +} // namespace tcp +} // namespace low_level +} // namespace streaming +} // namespace carla + +namespace std { + + // Injecting a hash function for our clients into std namespace so we can + // directly insert them into std::unordered_set. + template <> + struct hash { + using argument_type = carla::streaming::low_level::tcp::Client; + using result_type = std::size_t; + result_type operator()(const argument_type &client) const noexcept { + return std::hash()(client.get_id()); + } + }; + +} // namespace std diff --git a/LibCarla/source/carla/streaming/low_level/tcp/Server.h b/LibCarla/source/carla/streaming/low_level/tcp/Server.h new file mode 100644 index 000000000..d87d101cf --- /dev/null +++ b/LibCarla/source/carla/streaming/low_level/tcp/Server.h @@ -0,0 +1,76 @@ +// 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 . + +#pragma once + +#include "carla/streaming/low_level/tcp/ServerSession.h" + +#include +#include + +#include +#include +#include + +namespace carla { +namespace streaming { +namespace low_level { +namespace tcp { + + class Server : private boost::noncopyable { + public: + + using endpoint = boost::asio::ip::tcp::endpoint; + using protocol_type = endpoint::protocol_type; + using duration_type = ServerSession::duration_type; + + explicit Server(boost::asio::io_service &io_service, endpoint ep) + : _acceptor(io_service, std::move(ep)), + _timeout(duration_type::seconds(10u)) {} + + /// Set session time-out. Applies only to newly created sessions. + void set_timeout(duration_type timeout) { + _timeout = timeout; + } + + template + void Listen(Functor callback) { + log_info("starting streaming server at port", _acceptor.local_endpoint().port()); + _acceptor.get_io_service().post([=]() { OpenSession(_timeout, callback); }); + } + + private: + + template + void OpenSession(duration_type timeout, Functor callback) { + using boost::system::error_code; + + auto session = std::make_shared(_acceptor.get_io_service(), timeout); + + auto handle_query = [=](const error_code &ec) { + if (!ec) { + session->Open(callback); + } else { + log_error("tcp accept error:", ec.message()); + } + }; + + _acceptor.async_accept(session->_socket, [=](error_code ec) { + // Handle query and open a new session immediately. + _acceptor.get_io_service().post([=]() { handle_query(ec); }); + OpenSession(timeout, callback); + }); + } + + boost::asio::ip::tcp::acceptor _acceptor; + + std::atomic _timeout; + }; + +} // namespace tcp +} // namespace low_level +} // namespace streaming +} // namespace carla diff --git a/LibCarla/source/carla/streaming/low_level/tcp/ServerSession.h b/LibCarla/source/carla/streaming/low_level/tcp/ServerSession.h new file mode 100644 index 000000000..2d1d5a3eb --- /dev/null +++ b/LibCarla/source/carla/streaming/low_level/tcp/ServerSession.h @@ -0,0 +1,173 @@ +// 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 . + +#pragma once + +#include "carla/Debug.h" +#include "carla/Logging.h" +#include "carla/streaming/Message.h" +#include "carla/streaming/low_level/Types.h" +#include "carla/streaming/low_level/tcp/Timeout.h" + +#include +#include +#include +#include +#include +#include + +#include +#include + +namespace carla { +namespace streaming { +namespace low_level { +namespace tcp { + +namespace detail { + + static std::atomic_size_t SESSION_COUNTER{0u}; + +} // namespace detail + + /// A TCP server session. When a session opens, it reads from the socket a + /// stream id object and passes itself to the callback functor. The session + /// closes itself after @a timeout of inactivity is met. + class ServerSession + : public std::enable_shared_from_this, + private boost::noncopyable { + public: + + using socket_type = boost::asio::ip::tcp::socket; + using duration_type = timeout_type; + + explicit ServerSession(boost::asio::io_service &io_service, duration_type timeout) + : _session_id(detail::SESSION_COUNTER++), + _socket(io_service), + _timeout(timeout), + _deadline(io_service), + _strand(io_service) {} + + ~ServerSession() { + _deadline.cancel(); + } + + /// Starts the session and calls @a callback after successfully reading the + /// stream id. + /// + /// @pre Callback function signature: + /// `void(std::shared_ptr)`. + template + void Open(Functor callback) { + StartTimer(); + auto self = shared_from_this(); // To keep myself alive. + _strand.post([=]() { + + auto handle_query = [this, self, callback]( + const boost::system::error_code &ec, + size_t DEBUG_ONLY(bytes_received)) { + DEBUG_ASSERT_EQ(bytes_received, sizeof(_stream_id)); + if (!ec) { + log_debug("session", _session_id, "for stream", _stream_id, " started"); + _socket.get_io_service().post([=]() { callback(self); }); + } else { + log_error("session", _session_id, ": error retrieving stream id :", ec.message()); + Close(); + } + }; + + // Read the stream id. + _deadline.expires_from_now(_timeout); + boost::asio::async_read( + _socket, + boost::asio::buffer(&_stream_id, sizeof(_stream_id)), + _strand.wrap(handle_query)); + }); + } + + stream_id_type get_stream_id() const { + // Note that the stream id isn't synchronized. This function should only be + // called from the @a callback function, and after that point the stream_id + // can't change. + return _stream_id; + } + + /// Writes some data to the socket. + void Write(std::shared_ptr message) { + auto self = shared_from_this(); + _strand.post([=]() { + + /// @todo has to be a better way of doing this... + if (_is_writing) { + // Repost and return; + Write(std::move(message)); + return; + } + _is_writing = true; + + auto handle_sent = [this, self, message](const boost::system::error_code &ec, size_t DEBUG_ONLY(bytes)) { + _is_writing = false; + if (ec) { + log_error("session", _session_id, ": error sending data :", ec.message()); + } else { + DEBUG_ONLY(log_debug("session", _session_id, ": successfully sent", bytes, "bytes")); + DEBUG_ASSERT_EQ(bytes, sizeof(message_size_type) + message->size()); + } + }; + + log_debug("session", _session_id, ": sending message of", message->size(), "bytes"); + + _deadline.expires_from_now(_timeout); + boost::asio::async_write( + _socket, + message->encode(), + _strand.wrap(handle_sent)); + }); + } + + void Close() { + _strand.post([this, self = shared_from_this()]() { + if (_socket.is_open()) { + _socket.close(); + } + log_debug("session", _session_id, "closed"); + }); + } + + private: + + void StartTimer() { + if (_deadline.expires_at() <= boost::asio::deadline_timer::traits_type::now()) { + log_debug("session", _session_id, "timed out"); + Close(); + } else { + _deadline.async_wait([self = shared_from_this()](boost::system::error_code) { + self->StartTimer(); + }); + } + } + + friend class Server; + + const size_t _session_id; + + stream_id_type _stream_id = 0u; + + socket_type _socket; + + duration_type _timeout; + + boost::asio::deadline_timer _deadline; + + boost::asio::io_service::strand _strand; + + bool _is_writing = false; + }; + +} // namespace tcp +} // namespace low_level +} // namespace streaming +} // namespace carla diff --git a/LibCarla/source/carla/streaming/low_level/tcp/Timeout.h b/LibCarla/source/carla/streaming/low_level/tcp/Timeout.h new file mode 100644 index 000000000..880eb7f31 --- /dev/null +++ b/LibCarla/source/carla/streaming/low_level/tcp/Timeout.h @@ -0,0 +1,62 @@ +// 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 . + +#pragma once + +#include + +#include + +namespace carla { +namespace streaming { +namespace low_level { +namespace tcp { + + /// Positive time-out up to milliseconds resolution. + class timeout_type { + public: + + static inline timeout_type seconds(size_t timeout) { + return std::chrono::seconds(timeout); + } + + static inline timeout_type milliseconds(size_t timeout) { + return std::chrono::milliseconds(timeout); + } + + constexpr timeout_type() : _milliseconds(0u) {} + + template + timeout_type(std::chrono::duration duration) + : _milliseconds(std::chrono::duration_cast(duration).count()) {} + + timeout_type(boost::posix_time::time_duration timeout) + : timeout_type(std::chrono::milliseconds(timeout.total_milliseconds())) {} + + timeout_type(const timeout_type &) = default; + timeout_type &operator=(const timeout_type &) = default; + + boost::posix_time::time_duration to_posix_time() const { + return boost::posix_time::milliseconds(_milliseconds); + } + + constexpr auto to_chrono() const { + return std::chrono::milliseconds(_milliseconds); + } + + operator boost::posix_time::time_duration() const { + return to_posix_time(); + } + + private: + + size_t _milliseconds; + }; + +} // namespace tcp +} // namespace low_level +} // namespace streaming +} // namespace carla diff --git a/LibCarla/source/compiler/disable-ue4-macros.h b/LibCarla/source/compiler/disable-ue4-macros.h new file mode 100644 index 000000000..6d3f61a0d --- /dev/null +++ b/LibCarla/source/compiler/disable-ue4-macros.h @@ -0,0 +1,18 @@ +// 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 . + +#pragma push_macro("check") +#undef check + +#define LIBCARLA_INCLUDED_FROM_UE4 + +#ifndef BOOST_ERROR_CODE_HEADER_ONLY +# define BOOST_ERROR_CODE_HEADER_ONLY +#endif // BOOST_ERROR_CODE_HEADER_ONLY + +#ifndef BOOST_COROUTINES_NO_DEPRECATION_WARNING +# define BOOST_COROUTINES_NO_DEPRECATION_WARNING +#endif // BOOST_COROUTINES_NO_DEPRECATION_WARNING diff --git a/LibCarla/source/compiler/enable-ue4-macros.h b/LibCarla/source/compiler/enable-ue4-macros.h new file mode 100644 index 000000000..b084365f8 --- /dev/null +++ b/LibCarla/source/compiler/enable-ue4-macros.h @@ -0,0 +1,9 @@ +// 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 . + +#pragma pop_macro("check") + +#undef LIBCARLA_INCLUDED_FROM_UE4 diff --git a/LibCarla/source/test/test.h b/LibCarla/source/test/test.h new file mode 100644 index 000000000..eb185bc0d --- /dev/null +++ b/LibCarla/source/test/test.h @@ -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 . + +#pragma once + +#ifndef NDEBUG +# define LIBCARLA_LOG_LEVEL LIBCARLA_LOG_LEVEL_INFO +#endif // NDEBUG + +#include "test/util/Message.h" + +#include +#include + +#include + +#include +#include +#include + +constexpr uint16_t TESTING_PORT = 8080u; + +using namespace std::chrono_literals; diff --git a/LibCarla/source/test/test_benchmark_streaming.cpp b/LibCarla/source/test/test_benchmark_streaming.cpp new file mode 100644 index 000000000..bfa40529d --- /dev/null +++ b/LibCarla/source/test/test_benchmark_streaming.cpp @@ -0,0 +1,137 @@ +// 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 . + +#include "test.h" + +#include +#include + +using namespace carla::streaming; + +static auto make_special_message(size_t size) { + std::vector v(size/sizeof(uint32_t), 42u); + Message msg(boost::asio::buffer(v)); + EXPECT_EQ(msg.size(), size); + return msg; +} + +class Benchmark { +public: + + Benchmark(uint16_t port, size_t message_size) + : _server(port), + _client(), + _message(make_special_message(message_size)), + _client_callback(), + _work_to_do(_client_callback) {} + + void AddStream() { + Stream stream = _server.MakeStream(); + + _client.Subscribe(stream.token(), [this](std::shared_ptr msg) { + DEBUG_ASSERT_EQ(msg->size(), _message.size()); + DEBUG_ASSERT(*msg == _message); + _client_callback.post([this]() { + CARLA_PROFILE_FPS(client, listen_callback); + ++_number_of_messages_received; + }); + }); + + _streams.push_back(stream); + } + + void AddStreams(size_t count) { + for (auto i = 0u; i < count; ++i) { + AddStream(); + } + } + + void Run(size_t number_of_messages) { + _threads.CreateThread([this]() { _client_callback.run(); }); + _server.AsyncRun(_streams.size()); + _client.AsyncRun(_streams.size()); + + std::this_thread::sleep_for(1s); // the client needs to be ready so we make + // sure we get all the messages. + + for (auto &&stream : _streams) { + _threads.CreateThread([=]() mutable { + for (auto i = 0u; i < number_of_messages; ++i) { + CARLA_PROFILE_SCOPE(game, write_to_stream); + stream << _message.buffer(); + } + }); + } + + for (auto i = 0u; i < 30; ++i) { + if (_number_of_messages_received >= (_streams.size() * number_of_messages)) { + break; + } + std::cout << "received only " << _number_of_messages_received + << " messages, waiting..." << std::endl; + std::this_thread::sleep_for(1s); + } + + _client_callback.stop(); + _threads.JoinAll(); + + std::cout << _number_of_messages_received << " messages received; done.\n"; + + _client.Stop(); + _server.Stop(); + } + +private: + + carla::ThreadGroup _threads; + + Server _server; + + Client _client; + + const Message _message; + + boost::asio::io_service _client_callback; + + boost::asio::io_service::work _work_to_do; + + std::vector _streams; + + std::atomic_size_t _number_of_messages_received{0u}; +}; + +static void benchmark_image( + const size_t dimensions, + const size_t number_of_streams = 1u) { + constexpr auto number_of_messages = 100u; + Benchmark benchmark(TESTING_PORT, 4u * dimensions); + benchmark.AddStreams(number_of_streams); + benchmark.Run(number_of_messages); +} + +TEST(benchmark_streaming, image_200x200) { + benchmark_image(200u * 200u); +} + +TEST(benchmark_streaming, image_800x600) { + benchmark_image(800u * 600u); +} + +TEST(benchmark_streaming, image_1920x1080) { + benchmark_image(1920u * 1080u); +} + +TEST(benchmark_streaming, image_200x200_mt) { + benchmark_image(200u * 200u, 9u); +} + +TEST(benchmark_streaming, image_800x600_mt) { + benchmark_image(800u * 600u, 9u); +} + +TEST(benchmark_streaming, image_1920x1080_mt) { + benchmark_image(1920u * 1080u, 9u); +} diff --git a/LibCarla/source/test/test_miscellaneous.cpp b/LibCarla/source/test/test_miscellaneous.cpp new file mode 100644 index 000000000..29b8b00d1 --- /dev/null +++ b/LibCarla/source/test/test_miscellaneous.cpp @@ -0,0 +1,13 @@ +// 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 . + +#include "test.h" + +#include + +TEST(miscellaneous, version) { + std::cout << "LibCarla " << carla::version() << std::endl; +} diff --git a/LibCarla/source/test/test_rpc.cpp b/LibCarla/source/test/test_rpc.cpp new file mode 100644 index 000000000..4f190ff17 --- /dev/null +++ b/LibCarla/source/test/test_rpc.cpp @@ -0,0 +1,58 @@ +// 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 . + +#include "test.h" + +#include +#include +#include + +#include + +using namespace carla::rpc; + +TEST(rpc, compilation_tests) { + Server server(TESTING_PORT); + server.BindSync("bind00", []() { return 2.0f; }); + server.BindSync("bind01", [](int x) { return x; }); + server.BindSync("bind02", [](int, float) { return 0.0; }); + server.BindSync("bind03", [](int, float, double, char) {}); +} + +TEST(rpc, server_bind_sync_run_on_game_thread) { + const auto main_thread_id = std::this_thread::get_id(); + + Server server(TESTING_PORT); + + server.BindSync("do_the_thing", [=](int x, int y) -> int { + EXPECT_EQ(std::this_thread::get_id(), main_thread_id); + return x + y; + }); + + server.AsyncRun(1u); + + std::atomic_bool done{false}; + + carla::ThreadGroup threads; + threads.CreateThread([&]() { + Client client("localhost", TESTING_PORT); + for (auto i = 0u; i < 300u; ++i) { + auto result = client.call("do_the_thing", i, 1).as(); + EXPECT_EQ(result, i + 1); + } + done = true; + }); + + auto i = 0u; + for (; i < 1'000'000u; ++i) { + server.SyncRunFor(2ms); + if (done) { + break; + } + } + std::cout << "game thread: run " << i << " slices.\n"; + ASSERT_TRUE(done); +} diff --git a/LibCarla/source/test/test_streaming_low_level.cpp b/LibCarla/source/test/test_streaming_low_level.cpp new file mode 100644 index 000000000..35ba19d8b --- /dev/null +++ b/LibCarla/source/test/test_streaming_low_level.cpp @@ -0,0 +1,55 @@ +// 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 . + +#include "test.h" + +#include +#include +#include +#include +#include + +#include + +TEST(streaming_low_level, sending_strings) { + using namespace util::message; + using namespace carla::streaming::low_level; + + constexpr auto number_of_messages = 5'000u; + const std::string message_text = "Hello client!"; + + std::atomic_size_t message_count{0u}; + + boost::asio::io_service io_service; + + Server srv(io_service, TESTING_PORT); + srv.set_timeout(1s); + + auto stream = srv.MakeStream(); + + Client c; + c.Subscribe(io_service, stream.token(), [&](auto message) { + ++message_count; + ASSERT_NE(message, nullptr); + ASSERT_EQ(message->size(), message_text.size()); + const std::string msg = as_string(*message); + ASSERT_EQ(msg, message_text); + }); + + carla::ThreadGroup threads; + threads.CreateThreads( + std::max(2u, std::thread::hardware_concurrency()), + [&]() { io_service.run(); }); + + for (auto i = 0u; i < number_of_messages; ++i) { + stream << message_text; + } + + std::this_thread::sleep_for(1s); + io_service.stop(); + + std::cout << "client received " << message_count << " messages\n"; +} diff --git a/LibCarla/source/test/test_streaming_low_level_tcp.cpp b/LibCarla/source/test/test_streaming_low_level_tcp.cpp new file mode 100644 index 000000000..95abcaa76 --- /dev/null +++ b/LibCarla/source/test/test_streaming_low_level_tcp.cpp @@ -0,0 +1,57 @@ +// 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 . + +#include "test.h" + +#include +#include +#include + +#include + +TEST(streaming_low_level_tcp, small_message) { + using namespace util::message; + using namespace carla::streaming::low_level; + using shared_session = std::shared_ptr; + + boost::asio::io_service io_service; + tcp::Server::endpoint ep(boost::asio::ip::tcp::v4(), TESTING_PORT); + + tcp::Server srv(io_service, ep); + srv.set_timeout(1s); + std::atomic_bool done{false}; + std::atomic_size_t message_count{0u}; + + srv.Listen([&](std::shared_ptr session) { + ASSERT_EQ(session->get_stream_id(), 42u); + const std::string msg = "Hola!"; + auto message = std::make_shared(boost::asio::buffer(msg)); + while (!done) { + session->Write(message); + std::this_thread::sleep_for(1ns); + } + std::cout << "done!\n"; + }); + + tcp::Client c(io_service, ep, 42u, [&](std::shared_ptr message) { + ++message_count; + ASSERT_NE(message, nullptr); + ASSERT_EQ(message->size(), 5u); + const std::string msg = as_string(*message); + ASSERT_EQ(msg, std::string("Hola!")); + }); + + // We need at least two threads because this server loop consumes one. + carla::ThreadGroup threads; + threads.CreateThreads( + std::max(2u, std::thread::hardware_concurrency()), + [&]() { io_service.run(); }); + + std::this_thread::sleep_for(2s); + io_service.stop(); + done = true; + std::cout << "client received " << message_count << " messages\n"; +} diff --git a/LibCarla/source/test/test_streaming_message.cpp b/LibCarla/source/test/test_streaming_message.cpp new file mode 100644 index 000000000..cda29f32b --- /dev/null +++ b/LibCarla/source/test/test_streaming_message.cpp @@ -0,0 +1,52 @@ +// 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 . + +#include "test.h" + +#include + +#include +#include +#include + +using namespace util::message; + +TEST(streaming_message, to_from_string) { + const std::string str = "The quick brown fox jumps over the lazy dog"; + Message msg(boost::asio::buffer(str)); + ASSERT_EQ(msg.size(), str.size()); + const std::string result = as_string(msg); + ASSERT_EQ(result, str); +} + +TEST(streaming_message, to_from_vector) { + constexpr auto size = 1000u; + using T = size_t; + std::vector v; + v.reserve(size); + for (auto i = 0u; i < size; ++i) { + v.emplace_back(i); + } + Message msg(boost::asio::buffer(v)); + ASSERT_EQ(msg.size(), sizeof(T) * size); + auto begin = reinterpret_cast(msg.data()); + std::vector result(begin, begin + size); + ASSERT_EQ(result, v); +} + +TEST(streaming_message, memcpy) { + const std::string str = "The quick brown fox jumps over the lazy dog"; + Message msg(str.size()); + ASSERT_EQ(msg.size(), str.size()); + auto buffer = msg.buffer(); + std::memcpy(buffer.data(), str.data(), buffer.size()); + const std::string result = as_string(msg); + ASSERT_EQ(result, str); +} + +TEST(streaming_message, message_too_big) { + ASSERT_THROW(Message(4294967296ul), std::invalid_argument); +} diff --git a/LibCarla/source/test/util/Message.cpp b/LibCarla/source/test/util/Message.cpp new file mode 100644 index 000000000..fb34fd9a4 --- /dev/null +++ b/LibCarla/source/test/util/Message.cpp @@ -0,0 +1,45 @@ +// 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 . + +#include "Message.h" + +#include +#include + +namespace util { +namespace message { + + shared_message make_empty(size_t size) { + return size == 0u ? + std::make_shared() : + std::make_shared(size); + } + + shared_message make_random(size_t size) { + if (size == 0u) + return make_empty(); + using random_bytes_engine = std::independent_bits_engine< + std::random_device, + CHAR_BIT, + unsigned char>; + random_bytes_engine rbe; + auto message = make_empty(size); + std::generate(begin(*message), end(*message), std::ref(rbe)); + return message; + } + + std::string to_hex_string(const Message &msg, size_t length) { + length = std::min(static_cast(msg.size()), length); + auto buffer = std::make_unique(2u * length + 1u); + for (auto i = 0u; i < length; ++i) + sprintf(&buffer[2u * i], "%02x", msg.data()[i]); + if (length < msg.size()) + return std::string(buffer.get()) + std::string("..."); + return std::string(buffer.get()); + } + +} // namespace message +} // namespace util diff --git a/LibCarla/source/test/util/Message.h b/LibCarla/source/test/util/Message.h new file mode 100644 index 000000000..d9eecc005 --- /dev/null +++ b/LibCarla/source/test/util/Message.h @@ -0,0 +1,81 @@ +// 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 . + +#pragma once + +#include + +#include +#include +#include +#include + +namespace util { +namespace message { + + using carla::streaming::Message; + + using shared_message = std::shared_ptr; + using const_shared_message = std::shared_ptr; + + static inline shared_message make_empty() { + return std::make_shared(); + } + + shared_message make_empty(size_t size); + + shared_message make_random(size_t size); + + template + static inline shared_message make(const T &buffer) { + return std::make_shared(boost::asio::buffer(buffer)); + } + + static inline std::string as_string(const Message &msg) { + return {reinterpret_cast(msg.data()), msg.size()}; + } + + std::string to_hex_string(const Message &msg, size_t length = 16u); + +} // namespace message +} // namespace util + +namespace carla { +namespace streaming { + + static inline unsigned char *begin(Message &msg) { + return msg.data(); + } + + static inline const unsigned char *begin(const Message &msg) { + return msg.data(); + } + + static inline unsigned char *end(Message &msg) { + return msg.data() + msg.size(); + } + + static inline const unsigned char *end(const Message &msg) { + return msg.data() + msg.size(); + } + + static inline std::ostream &operator<<(std::ostream &out, const Message &msg) { + out << "[" << msg.size() << " bytes] " << util::message::to_hex_string(msg); + return out; + } + + static inline bool operator==(const Message &lhs, const Message &rhs) { + return + (lhs.size() == rhs.size()) && + std::equal(begin(lhs), end(lhs), begin(rhs)); + } + + static inline bool operator!=(const Message &lhs, const Message &rhs) { + return !(lhs == rhs); + } + +} // namespace streaming +} // namespace carla From 3cf91c54f228c974711c882ae5ed9dfed2c430d8 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Wed, 4 Jul 2018 11:12:14 +0200 Subject: [PATCH 03/71] Add PythonAPI module --- PythonClient/.pep8 => .pep8 | 0 PythonAPI/.gitignore | 4 + PythonAPI/setup.py | 65 +++++++++++++ PythonAPI/source/carla/__init__.py | 7 ++ PythonAPI/source/libcarla/Actor.cpp | 39 ++++++++ PythonAPI/source/libcarla/Blueprint.cpp | 57 ++++++++++++ PythonAPI/source/libcarla/Client.cpp | 23 +++++ PythonAPI/source/libcarla/Control.cpp | 47 ++++++++++ PythonAPI/source/libcarla/Transform.cpp | 65 +++++++++++++ PythonAPI/source/libcarla/World.cpp | 21 +++++ PythonAPI/source/libcarla/libcarla.cpp | 25 +++++ PythonAPI/test/__init__.py | 11 +++ PythonAPI/test/test_client.py | 22 +++++ PythonAPI/test/test_transform.py | 117 ++++++++++++++++++++++++ PythonAPI/test/test_vehicle.py | 38 ++++++++ 15 files changed, 541 insertions(+) rename PythonClient/.pep8 => .pep8 (100%) create mode 100644 PythonAPI/.gitignore create mode 100644 PythonAPI/setup.py create mode 100644 PythonAPI/source/carla/__init__.py create mode 100644 PythonAPI/source/libcarla/Actor.cpp create mode 100644 PythonAPI/source/libcarla/Blueprint.cpp create mode 100644 PythonAPI/source/libcarla/Client.cpp create mode 100644 PythonAPI/source/libcarla/Control.cpp create mode 100644 PythonAPI/source/libcarla/Transform.cpp create mode 100644 PythonAPI/source/libcarla/World.cpp create mode 100644 PythonAPI/source/libcarla/libcarla.cpp create mode 100644 PythonAPI/test/__init__.py create mode 100644 PythonAPI/test/test_client.py create mode 100644 PythonAPI/test/test_transform.py create mode 100644 PythonAPI/test/test_vehicle.py diff --git a/PythonClient/.pep8 b/.pep8 similarity index 100% rename from PythonClient/.pep8 rename to .pep8 diff --git a/PythonAPI/.gitignore b/PythonAPI/.gitignore new file mode 100644 index 000000000..a94060236 --- /dev/null +++ b/PythonAPI/.gitignore @@ -0,0 +1,4 @@ +*.egg-info +build +dependencies +dist diff --git a/PythonAPI/setup.py b/PythonAPI/setup.py new file mode 100644 index 000000000..02af08a52 --- /dev/null +++ b/PythonAPI/setup.py @@ -0,0 +1,65 @@ +# 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 . + +from setuptools import setup, Extension + +import fnmatch +import glob +import os +import platform +import sys + + +def get_libcarla_extensions(): + libraries = ['carla_client', 'rpc'] + + if os.name == "posix": + if platform.dist()[0] == "Ubuntu": + libraries += ["boost_python-py%d%d" % (sys.version_info.major, + sys.version_info.minor)] + else: + libraries += ["boost_python"] + else: + raise NotImplementedError + + def walk(folder, file_filter='*'): + for root, _, filenames in os.walk(folder): + for filename in fnmatch.filter(filenames, file_filter): + yield os.path.join(root, filename) + + depends = [x for x in walk('dependencies')] + + def make_extension(name, sources): + return Extension( + name, + sources=sources, + include_dirs=[ + '/usr/local/include', + 'dependencies/include'], + library_dirs=[ + '/usr/local/lib/boost', + 'dependencies/lib'], + runtime_library_dirs=['/usr/local/lib/boost'], + libraries=libraries, + extra_compile_args=['-fPIC', '-std=c++17'], + language='c++17', + depends=depends) + + return [make_extension('carla.libcarla', glob.glob('source/libcarla/*.cpp'))] + + +setup( + name='carla', + version='0.9.0', + package_dir={'': 'source'}, + packages=['carla'], + ext_modules=get_libcarla_extensions(), + license='MIT License', + description='Python API for communicating with the CARLA server.', + url='https://github.com/carla-simulator/carla', + author='The CARLA team', + author_email='carla.simulator@gmail.com', + include_package_data=True) diff --git a/PythonAPI/source/carla/__init__.py b/PythonAPI/source/carla/__init__.py new file mode 100644 index 000000000..85ef8afe1 --- /dev/null +++ b/PythonAPI/source/carla/__init__.py @@ -0,0 +1,7 @@ +# 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 . + +from .libcarla import * diff --git a/PythonAPI/source/libcarla/Actor.cpp b/PythonAPI/source/libcarla/Actor.cpp new file mode 100644 index 000000000..09e323c8d --- /dev/null +++ b/PythonAPI/source/libcarla/Actor.cpp @@ -0,0 +1,39 @@ +// 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 . + +#include + +#include + +#include + +namespace carla { +namespace client { + + std::ostream &operator<<(std::ostream &out, const Actor &actor) { + out << "Actor(id=" << actor.GetId() << ", type_id=" << actor.GetTypeId() << ')'; + return out; + } + +} // namespace client +} // namespace carla + +void export_actor() { + using namespace boost::python; + namespace cc = carla::client; + + class_>("Actor", no_init) + .add_property("id", &cc::Actor::GetId) + .add_property("type_id", +[](const cc::Actor &self) -> std::string { + // Needs to copy the string by value. + return self.GetTypeId(); + }) + .add_property("blueprint", &cc::Actor::GetBlueprint) + .def("get_world", &cc::Actor::GetWorld) + .def("apply_control", &cc::Actor::ApplyControl) + .def(self_ns::str(self_ns::self)) + ; +} diff --git a/PythonAPI/source/libcarla/Blueprint.cpp b/PythonAPI/source/libcarla/Blueprint.cpp new file mode 100644 index 000000000..1baf51b8d --- /dev/null +++ b/PythonAPI/source/libcarla/Blueprint.cpp @@ -0,0 +1,57 @@ +// 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 . + +#include +#include + +#include + +#include + +namespace carla { +namespace client { + + std::ostream &operator<<(std::ostream &out, const ActorBlueprint &bp) { + out << bp.GetTypeId(); + return out; + } + + std::ostream &operator<<(std::ostream &out, const BlueprintLibrary &blueprints) { + auto it = blueprints.begin(); + out << '[' << *it; + for (++it; it != blueprints.end(); ++it) { + out << ", " << *it; + } + out << ']'; + return out; + } + +} // namespace client +} // namespace carla + +void export_blueprint() { + using namespace boost::python; + namespace cc = carla::client; + + class_("ActorBlueprint", no_init) + .add_property("type_id", +[](const cc::ActorBlueprint &self) -> std::string { + return self.GetTypeId(); + }) + .def("startswith", &cc::ActorBlueprint::StartsWith) + .def("match", &cc::ActorBlueprint::MatchWildcards) + .def(self_ns::str(self_ns::self)) + ; + + class_("BlueprintLibrary", no_init) + .def("filter", &cc::BlueprintLibrary::Filter) + .def("__getitem__", +[](const cc::BlueprintLibrary &self, size_t pos) -> cc::ActorBlueprint { + return self[pos]; + }) + .def("__len__", &cc::BlueprintLibrary::size) + .def("__iter__", range(&cc::BlueprintLibrary::begin, &cc::BlueprintLibrary::end)) + .def(self_ns::str(self_ns::self)) + ; +} diff --git a/PythonAPI/source/libcarla/Client.cpp b/PythonAPI/source/libcarla/Client.cpp new file mode 100644 index 000000000..bd8735ed7 --- /dev/null +++ b/PythonAPI/source/libcarla/Client.cpp @@ -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 . + +#include +#include + +#include + +void export_client() { + using namespace boost::python; + namespace cc = carla::client; + + class_>("Client", init()) + .def("set_timeout", &cc::Client::SetTimeout) + .def("get_client_version", &cc::Client::GetClientVersion) + .def("get_server_version", &cc::Client::GetServerVersion) + .def("ping", &cc::Client::Ping) + .def("get_world", &cc::Client::GetWorld) + ; +} diff --git a/PythonAPI/source/libcarla/Control.cpp b/PythonAPI/source/libcarla/Control.cpp new file mode 100644 index 000000000..a25a88465 --- /dev/null +++ b/PythonAPI/source/libcarla/Control.cpp @@ -0,0 +1,47 @@ +// 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 . + +#include + +#include + +#include + +namespace carla { +namespace rpc { + + std::ostream &operator<<(std::ostream &out, const VehicleControl &control) { + auto boolalpha = [](bool b) { return b ? "True" : "False"; }; + out << "VehicleControl(throttle=" << control.throttle + << ", steer=" << control.steer + << ", brake=" << control.brake + << ", hand_brake=" << boolalpha(control.hand_brake) + << ", reverse=" << boolalpha(control.reverse) << ')'; + return out; + } + +} // namespace rpc +} // namespace carla + +void export_control() { + using namespace boost::python; + namespace cc = carla::client; + + class_("VehicleControl") + .def(init( + (arg("throttle")=0.0f, + arg("steer")=0.0f, + arg("brake")=0.0f, + arg("hand_brake")=false, + arg("reverse")=false))) + .def_readwrite("throttle", &cc::VehicleControl::throttle) + .def_readwrite("steer", &cc::VehicleControl::steer) + .def_readwrite("brake", &cc::VehicleControl::brake) + .def_readwrite("hand_brake", &cc::VehicleControl::hand_brake) + .def_readwrite("reverse", &cc::VehicleControl::reverse) + .def(self_ns::str(self_ns::self)) + ; +} diff --git a/PythonAPI/source/libcarla/Transform.cpp b/PythonAPI/source/libcarla/Transform.cpp new file mode 100644 index 000000000..beb1a0e40 --- /dev/null +++ b/PythonAPI/source/libcarla/Transform.cpp @@ -0,0 +1,65 @@ +// 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 . + +#include + +#include + +#include + +namespace carla { +namespace rpc { + + std::ostream &operator<<(std::ostream &out, const Location &location) { + out << "Location(x=" << location.x + << ", y=" << location.y + << ", z=" << location.z << ')'; + return out; + } + + std::ostream &operator<<(std::ostream &out, const Rotation &rotation) { + out << "Rotation(pitch=" << rotation.pitch + << ", yaw=" << rotation.yaw + << ", roll=" << rotation.roll << ')'; + return out; + } + + std::ostream &operator<<(std::ostream &out, const Transform &transform) { + out << "Transform(" << transform.location << ", " << transform.rotation << ')'; + return out; + } + +} // namespace rpc +} // namespace carla + +void export_transform() { + using namespace boost::python; + namespace cc = carla::client; + + class_("Location") + .def(init((arg("x")=0.0f, arg("y")=0.0f, arg("z")=0.0f))) + .def_readwrite("x", &cc::Location::x) + .def_readwrite("y", &cc::Location::y) + .def_readwrite("z", &cc::Location::z) + .def(self_ns::str(self_ns::self)) + ; + + class_("Rotation") + .def(init((arg("pitch")=0.0f, arg("yaw")=0.0f, arg("roll")=0.0f))) + .def_readwrite("pitch", &cc::Rotation::pitch) + .def_readwrite("yaw", &cc::Rotation::yaw) + .def_readwrite("roll", &cc::Rotation::roll) + .def(self_ns::str(self_ns::self)) + ; + + class_("Transform") + .def(init( + (arg("location")=cc::Location(), arg("rotation")=cc::Rotation()))) + .def_readwrite("location", &cc::Transform::location) + .def_readwrite("rotation", &cc::Transform::rotation) + .def(self_ns::str(self_ns::self)) + ; +} diff --git a/PythonAPI/source/libcarla/World.cpp b/PythonAPI/source/libcarla/World.cpp new file mode 100644 index 000000000..d4140a0e3 --- /dev/null +++ b/PythonAPI/source/libcarla/World.cpp @@ -0,0 +1,21 @@ +// 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 . + +#include +#include + +#include + +void export_world() { + using namespace boost::python; + namespace cc = carla::client; + + class_>("World", no_init) + .def("get_blueprint_library", &cc::World::GetBlueprintLibrary) + .def("try_spawn_actor", &cc::World::TrySpawnActor) + .def("spawn_actor", &cc::World::SpawnActor) + ; +} diff --git a/PythonAPI/source/libcarla/libcarla.cpp b/PythonAPI/source/libcarla/libcarla.cpp new file mode 100644 index 000000000..fbb85e189 --- /dev/null +++ b/PythonAPI/source/libcarla/libcarla.cpp @@ -0,0 +1,25 @@ +// 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 . + +#include + +void export_actor(); +void export_blueprint(); +void export_client(); +void export_control(); +void export_transform(); +void export_world(); + +BOOST_PYTHON_MODULE(libcarla) { + using namespace boost::python; + scope().attr("__path__") = "libcarla"; + export_transform(); + export_control(); + export_blueprint(); + export_actor(); + export_world(); + export_client(); +} diff --git a/PythonAPI/test/__init__.py b/PythonAPI/test/__init__.py new file mode 100644 index 000000000..b57d14be6 --- /dev/null +++ b/PythonAPI/test/__init__.py @@ -0,0 +1,11 @@ +# 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 . + +import sys + +sys.path.append( + '../dist/carla-0.9.0-py%d.%d-linux-x86_64.egg' % (sys.version_info.major, + sys.version_info.minor)) diff --git a/PythonAPI/test/test_client.py b/PythonAPI/test/test_client.py new file mode 100644 index 000000000..cebce28fd --- /dev/null +++ b/PythonAPI/test/test_client.py @@ -0,0 +1,22 @@ +# 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 . + +import carla + +import sys +import unittest + +from subprocess import check_output + + +class testClient(unittest.TestCase): + def test_client_version(self): + c = carla.Client('localhost', 8080) + v = c.get_client_version() + out = check_output(['git', 'describe', '--tags', '--dirty', '--always', ]) + if sys.version_info > (3, 0): + out = out.decode('utf8') + self.assertEqual(str(v), str(out.strip())) diff --git a/PythonAPI/test/test_transform.py b/PythonAPI/test/test_transform.py new file mode 100644 index 000000000..897fae8bb --- /dev/null +++ b/PythonAPI/test/test_transform.py @@ -0,0 +1,117 @@ +# 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 . + +import carla + +import unittest + + +class testLocation(unittest.TestCase): + def test_default_values(self): + location = carla.Location() + self.assertEqual(location.x, 0.0) + self.assertEqual(location.y, 0.0) + self.assertEqual(location.z, 0.0) + location = carla.Location(1.0) + self.assertEqual(location.x, 1.0) + self.assertEqual(location.y, 0.0) + self.assertEqual(location.z, 0.0) + location = carla.Location(1.0, 2.0) + self.assertEqual(location.x, 1.0) + self.assertEqual(location.y, 2.0) + self.assertEqual(location.z, 0.0) + location = carla.Location(1.0, 2.0, 3.0) + self.assertEqual(location.x, 1.0) + self.assertEqual(location.y, 2.0) + self.assertEqual(location.z, 3.0) + + def test_named_args(self): + location = carla.Location(x=42.0) + self.assertEqual(location.x, 42.0) + self.assertEqual(location.y, 0.0) + self.assertEqual(location.z, 0.0) + location = carla.Location(y=42.0) + self.assertEqual(location.x, 0.0) + self.assertEqual(location.y, 42.0) + self.assertEqual(location.z, 0.0) + location = carla.Location(z=42.0) + self.assertEqual(location.x, 0.0) + self.assertEqual(location.y, 0.0) + self.assertEqual(location.z, 42.0) + location = carla.Location(z=3.0, x=1.0, y=2.0) + self.assertEqual(location.x, 1.0) + self.assertEqual(location.y, 2.0) + self.assertEqual(location.z, 3.0) + + +class testRotation(unittest.TestCase): + def test_default_values(self): + rotation = carla.Rotation() + self.assertEqual(rotation.pitch, 0.0) + self.assertEqual(rotation.yaw, 0.0) + self.assertEqual(rotation.roll, 0.0) + rotation = carla.Rotation(1.0) + self.assertEqual(rotation.pitch, 1.0) + self.assertEqual(rotation.yaw, 0.0) + self.assertEqual(rotation.roll, 0.0) + rotation = carla.Rotation(1.0, 2.0) + self.assertEqual(rotation.pitch, 1.0) + self.assertEqual(rotation.yaw, 2.0) + self.assertEqual(rotation.roll, 0.0) + rotation = carla.Rotation(1.0, 2.0, 3.0) + self.assertEqual(rotation.pitch, 1.0) + self.assertEqual(rotation.yaw, 2.0) + self.assertEqual(rotation.roll, 3.0) + + def test_named_args(self): + rotation = carla.Rotation(pitch=42.0) + self.assertEqual(rotation.pitch, 42.0) + self.assertEqual(rotation.yaw, 0.0) + self.assertEqual(rotation.roll, 0.0) + rotation = carla.Rotation(yaw=42.0) + self.assertEqual(rotation.pitch, 0.0) + self.assertEqual(rotation.yaw, 42.0) + self.assertEqual(rotation.roll, 0.0) + rotation = carla.Rotation(roll=42.0) + self.assertEqual(rotation.pitch, 0.0) + self.assertEqual(rotation.yaw, 0.0) + self.assertEqual(rotation.roll, 42.0) + rotation = carla.Rotation(roll=3.0, pitch=1.0, yaw=2.0) + self.assertEqual(rotation.pitch, 1.0) + self.assertEqual(rotation.yaw, 2.0) + self.assertEqual(rotation.roll, 3.0) + + +class testTransform(unittest.TestCase): + def test_values(self): + t = carla.Transform() + self.assertEqual(t.location.x, 0.0) + self.assertEqual(t.location.y, 0.0) + self.assertEqual(t.location.z, 0.0) + self.assertEqual(t.rotation.pitch, 0.0) + self.assertEqual(t.rotation.yaw, 0.0) + self.assertEqual(t.rotation.roll, 0.0) + t = carla.Transform(carla.Location(y=42.0)) + self.assertEqual(t.location.x, 0.0) + self.assertEqual(t.location.y, 42.0) + self.assertEqual(t.location.z, 0.0) + self.assertEqual(t.rotation.pitch, 0.0) + self.assertEqual(t.rotation.yaw, 0.0) + self.assertEqual(t.rotation.roll, 0.0) + t = carla.Transform(rotation=carla.Rotation(yaw=42.0)) + self.assertEqual(t.location.x, 0.0) + self.assertEqual(t.location.y, 0.0) + self.assertEqual(t.location.z, 0.0) + self.assertEqual(t.rotation.pitch, 0.0) + self.assertEqual(t.rotation.yaw, 42.0) + self.assertEqual(t.rotation.roll, 0.0) + + def test_print(self): + t = carla.Transform( + carla.Location(x=1.0, y=2.0, z=3.0), + carla.Rotation(pitch=4.0, yaw=5.0, roll=6.0)) + s = 'Transform(Location(x=1, y=2, z=3), Rotation(pitch=4, yaw=5, roll=6))' + self.assertEqual(str(t), s) diff --git a/PythonAPI/test/test_vehicle.py b/PythonAPI/test/test_vehicle.py new file mode 100644 index 000000000..96f0ae5f3 --- /dev/null +++ b/PythonAPI/test/test_vehicle.py @@ -0,0 +1,38 @@ +# 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 . + +import carla + +import unittest + + +class testVehicleControl(unittest.TestCase): + def test_default_values(self): + c = carla.VehicleControl() + self.assertEqual(c.throttle, 0.0) + self.assertEqual(c.steer, 0.0) + self.assertEqual(c.brake, 0.0) + self.assertEqual(c.hand_brake, False) + self.assertEqual(c.reverse, False) + c = carla.VehicleControl(1.0, 2.0, 3.0, True, True) + self.assertEqual(c.throttle, 1.0) + self.assertEqual(c.steer, 2.0) + self.assertEqual(c.brake, 3.0) + self.assertEqual(c.hand_brake, True) + self.assertEqual(c.reverse, True) + + def test_named_args(self): + c = carla.VehicleControl( + throttle=1.0, + steer=2.0, + brake=3.0, + hand_brake=True, + reverse=True) + self.assertEqual(c.throttle, 1.0) + self.assertEqual(c.steer, 2.0) + self.assertEqual(c.brake, 3.0) + self.assertEqual(c.hand_brake, True) + self.assertEqual(c.reverse, True) From 0b90c448bfeb45721ed1ccd111ead557b5fd052f Mon Sep 17 00:00:00 2001 From: nsubiron Date: Wed, 4 Jul 2018 11:59:59 +0200 Subject: [PATCH 04/71] Replace Linux build system --- .gitignore | 9 +- .travis.yml | 17 +- CARLA.sublime-project | 149 -- CMakeLists.txt | 6 + Docs/build_system.md | 110 + Docs/how_to_build_on_linux.md | 95 +- Docs/img/modules.png | Bin 0 -> 52675 bytes Docs/index.md | 3 +- Doxyfile | 4 +- Makefile | 104 +- Rebuild.sh | 121 - Setup.sh | 227 -- Unreal/CarlaUE4/.gitignore | 1 + Unreal/CarlaUE4/CarlaUE4.uproject | 2 +- Unreal/CarlaUE4/Config/DefaultGame.ini | 2 +- Unreal/CarlaUE4/Plugins/Carla/Carla.uplugin | 2 +- .../Plugins/Carla/Source/Carla/Carla.Build.cs | 31 +- .../Source/Carla/Server/CarlaEncoder.cpp | 4 + .../Carla/Source/Carla/Server/CarlaEncoder.h | 4 + .../Carla/Source/Carla/Server/CarlaServer.cpp | 62 +- .../Carla/Source/Carla/Server/RPCServer.cpp | 91 + .../Carla/Source/Carla/Server/RPCServer.h | 35 + .../Carla/Source/Carla/Server/Server.cpp | 72 + .../Carla/Source/Carla/Server/Server.h | 52 + .../Carla/Walker/WalkerAIController.cpp | 18 +- .../Source/Carla/Walker/WalkerAIController.h | 21 +- Util/BuildTools/BuildCarlaUE4.sh | 147 ++ Util/BuildTools/BuildLibCarla.sh | 131 + Util/BuildTools/BuildPythonAPI.sh | 99 + Util/BuildTools/Check.sh | 131 + Util/BuildTools/Environment.sh | 47 + Util/BuildTools/Linux.mk | 57 + Util/BuildTools/Linux.mk.help | 77 + Package.sh => Util/BuildTools/Package.sh | 100 +- Util/BuildTools/Prettify.sh | 137 + Util/BuildTools/Setup.sh | 267 ++ Util/BuildTools/Vars.mk | 22 + Util/BuildTools/Windows.mk | 2 + Util/BuildTools/uncrustify.cfg | 2239 +++++++++++++++++ Util/CARLA.sublime-project | 138 + mkdocs.yml | 1 + 41 files changed, 4067 insertions(+), 770 deletions(-) delete mode 100644 CARLA.sublime-project create mode 100644 CMakeLists.txt create mode 100644 Docs/build_system.md create mode 100644 Docs/img/modules.png delete mode 100755 Rebuild.sh delete mode 100755 Setup.sh create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/RPCServer.cpp create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/RPCServer.h create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/Server.cpp create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/Server.h create mode 100755 Util/BuildTools/BuildCarlaUE4.sh create mode 100755 Util/BuildTools/BuildLibCarla.sh create mode 100755 Util/BuildTools/BuildPythonAPI.sh create mode 100755 Util/BuildTools/Check.sh create mode 100644 Util/BuildTools/Environment.sh create mode 100644 Util/BuildTools/Linux.mk create mode 100644 Util/BuildTools/Linux.mk.help rename Package.sh => Util/BuildTools/Package.sh (59%) create mode 100755 Util/BuildTools/Prettify.sh create mode 100755 Util/BuildTools/Setup.sh create mode 100644 Util/BuildTools/Vars.mk create mode 100644 Util/BuildTools/Windows.mk create mode 100644 Util/BuildTools/uncrustify.cfg create mode 100644 Util/CARLA.sublime-project diff --git a/.gitignore b/.gitignore index eeb82282e..d025fb378 100644 --- a/.gitignore +++ b/.gitignore @@ -1,31 +1,38 @@ +Build Dist Doxygen PythonClient/dist Util/Build +Install *.VC.db *.VC.opendb +*.a *.egg-info *.kdev4 *.log *.pb.cc *.pb.h +*.o *.pid *.pri *.pro *.py[cod] *.sln +*.so *.stackdump *.sublime-workspace *.workspace *CodeCompletionFolders.txt *CodeLitePreProcessor.txt .codelite +.gdb_history .tags* .vs __pycache__ _benchmarks_results _images* -_out +_out* _site core +profiler.csv diff --git a/.travis.yml b/.travis.yml index 34a70fe9c..3a2830407 100644 --- a/.travis.yml +++ b/.travis.yml @@ -17,14 +17,15 @@ script: matrix: include: - - env: TEST="CppCheck" - install: true - addons: - apt: - packages: - - cppcheck - script: - - cppcheck . -iBuild -i.pb.cc --error-exitcode=1 --enable=warning --inline-suppr --quiet + # CppCheck does not support C++17. + # - env: TEST="CppCheck" + # install: true + # addons: + # apt: + # packages: + # - cppcheck + # script: + # - cppcheck . -iBuild -i.pb.cc --error-exitcode=1 --enable=warning --inline-suppr --quiet - env: TEST="MkDocs" install: diff --git a/CARLA.sublime-project b/CARLA.sublime-project deleted file mode 100644 index 2eab9615d..000000000 --- a/CARLA.sublime-project +++ /dev/null @@ -1,149 +0,0 @@ -{ - "folders": - [ - { - "path": ".", - "folder_exclude_patterns": - [ - ".clang", - ".codelite", - ".kdev4", - ".vs", - ".vscode", - "Binaries", - "Build", - "DerivedDataCache", - "Dist", - "Doxygen", - "Intermediate", - "Saved", - "Unreal/CarlaUE4/Content*", - "__pycache__", - "_site" - ], - "file_exclude_patterns": - [ - "*.VC.db", - "*.VC.opendb", - "*.kdev4", - "*.pri", - "*.pro", - "*.py[cod]", - "*.sln", - "*.stackdump", - "*.sublime-workspace", - "*.uasset", - "*.umap", - "*.workspace", - "*CodeCompletionFolders.txt", - "*CodeLitePreProcessor.txt", - ".tags*", - "core" - ] - } - ], - "settings": - { - "ensure_newline_at_eof_on_save": true, - "tab_size": 2, - "translate_tabs_to_spaces": true, - "trim_trailing_white_space_on_save": true - }, - "build_systems": - [ - { - "name": "CARLA - Pylint", - "working_dir": "${project_path}", - "file_regex": "^\\[([^:]*):([0-9]+):?([0-9]+)?\\]:? (.*)$", - "shell_cmd": "pylint --disable=R,C --rcfile=PythonClient/.pylintrc PythonClient/carla PythonClient/*.py --msg-template='[{path}:{line:3d}:{column}]: {msg_id} {msg}'" - }, - { - "name": "CARLA - CppCheck", - "working_dir": "${project_path}", - "file_regex": "^\\[([^:]*):([0-9]+):?([0-9]+)?\\]:? (.*)$", - "shell_cmd": "cppcheck . -iBuild -i.pb.cc --error-exitcode=0 --enable=warning --quiet" - }, - { - "name": "CARLA - Rebuild script", - "working_dir": "${project_path}", - "file_regex": "^(..[^:]*):([0-9]+):?([0-9]+)?:? (.*)$", - "linux": - { - "shell_cmd": "./Rebuild.sh" - }, - "windows": - { - "shell_cmd": "start Rebuild.bat" - } - }, - { - "name": "CARLA - make CarlaUE4", - "working_dir": "${project_path}/Unreal/CarlaUE4", - "file_regex": "Unreal\\/CarlaUE4\\/([^:]*):([0-9]+):?([0-9]+)?:? (.*)$", - "syntax": "Packages/Makefile/Make Output.sublime-syntax", - "linux": - { - "shell_cmd": "make CarlaUE4" - } - }, - { - "name": "CARLA - make CarlaUE4 ARGS=-clean", - "working_dir": "${project_path}/Unreal/CarlaUE4", - "file_regex": "Unreal\\/CarlaUE4\\/([^:]*):([0-9]+):?([0-9]+)?:? (.*)$", - "syntax": "Packages/Makefile/Make Output.sublime-syntax", - "linux": - { - "shell_cmd": "make CarlaUE4 ARGS=-clean" - } - }, - { - "name": "CARLA - make CarlaUE4Editor", - "working_dir": "${project_path}/Unreal/CarlaUE4", - "file_regex": "Unreal\\/CarlaUE4\\/([^:]*):([0-9]+):?([0-9]+)?:? (.*)$", - "syntax": "Packages/Makefile/Make Output.sublime-syntax", - "linux": - { - "shell_cmd": "make CarlaUE4Editor" - } - }, - { - "name": "CARLA - make CarlaUE4Editor ARGS=-clean", - "working_dir": "${project_path}/Unreal/CarlaUE4", - "file_regex": "Unreal\\/CarlaUE4\\/([^:]*):([0-9]+):?([0-9]+)?:? (.*)$", - "syntax": "Packages/Makefile/Make Output.sublime-syntax", - "linux": - { - "shell_cmd": "make CarlaUE4Editor ARGS=-clean" - } - }, - { - "name": "CARLA - make CarlaServer", - "working_dir": "${project_path}", - "file_regex": "^(..[^:]*):([0-9]+):?([0-9]+)?:? (.*)$", - "syntax": "Packages/Makefile/Make Output.sublime-syntax", - "linux": - { - "shell_cmd": "make" - } - }, - { - "name": "CARLA - check CarlaServer", - "working_dir": "${project_path}", - "file_regex": "^(..[^:]*):([0-9]+):?([0-9]+)?:? (.*)$", - "syntax": "Packages/Makefile/Make Output.sublime-syntax", - "linux": - { - "shell_cmd": "make check" - } - }, - { - "name": "CARLA - clean CarlaServer", - "working_dir": "${project_path}", - "syntax": "Packages/Makefile/Make Output.sublime-syntax", - "linux": - { - "shell_cmd": "make clean" - } - } - ] -} diff --git a/CMakeLists.txt b/CMakeLists.txt new file mode 100644 index 000000000..4721d53f3 --- /dev/null +++ b/CMakeLists.txt @@ -0,0 +1,6 @@ +cmake_minimum_required(VERSION 3.9.0) +project(CARLA) + +include("Build/CMakeLists.txt.in") + +add_subdirectory("LibCarla/cmake") diff --git a/Docs/build_system.md b/Docs/build_system.md new file mode 100644 index 000000000..a79226d23 --- /dev/null +++ b/Docs/build_system.md @@ -0,0 +1,110 @@ +

Build system

+ +> _This document is a work in progress, only the Linux build system is taken into account here._ + +The most challenging part of the setup is to compile all the dependencies and +modules to be compatible with a) Unreal Engine in the server-side, and b) Python +in the client-side. + +The goal is to be able to call Unreal Engine's functions from a separate Python +process. + +![modules](img/modules.png) + +In Linux, we compile CARLA and all the dependencies with clang-5.0 and C++17 +standard. We however link against different runtime C++ libraries depending on +where the code going to be used, since all the code that is going to be linked +with Unreal Engine needs to be compiled using `libc++`. + +#### Setup + +Command + +```sh +make setup +``` + +Get and compile dependencies + + * llvm-5.0 (libc++ and libc++abi) + * rpclib-2.2.1 (twice, with libstdc++ and libc++) + * boost-1.67 (headers only) + * googletest-1.8.0 (with libc++) + +#### LibCarla + +Compiled with CMake (minimum version required CMake 3.9). + +Command + +```sh +make LibCarla +``` + +Two configurations: + +| | Server | Client | +|-----------------|--------------|-----------| +| **Unit tests** | yes | no | +| **Requires** | rpclib, gtest, boost | rpclib, boost +| **std runtime** | LLVM's `libc++` | Default `libstdc++` | +| **Output** | headers and test exes | `libcarla_client.a` | +| **Required by** | Carla plugin | PythonAPI | + +#### CarlaUE4 and Carla plugin + +Both compiled at the same step with Unreal Engine 4.19 build tool. They require +the `UE4_ROOT` environment variable set. + +Command + +```sh +make CarlaUE4Editor +``` + +To launch Unreal Engine's Editor run + +```sh +make launch +``` + +#### PythonAPI + +Compiled using Python's `setuptools` ("setup.py"). Currently requires the +following to be installed in the machine: Python, libpython-dev, and +libboost-python-dev; both for Python 2.7 and 3.5. + +Command + +```sh +make PythonAPI +``` + +It creates two "egg" packages + + * `PythonAPI/dist/carla-0.9.0-py2.7-linux-x86_64.egg` + * `PythonAPI/dist/carla-0.9.0-py3.5-linux-x86_64.egg` + +This package can be directly imported into a Python script by adding it to the +system path + +```python +#!/usr/bin/env python + +import sys + +sys.path.append( + 'PythonAPI/dist/carla-0.9.0-py%d.%d-linux-x86_64.egg' % (sys.version_info.major, + sys.version_info.minor)) + +import carla + +# ... +``` + +or installed with `easy_install` + +```sh +easy_install2 --user --no-deps PythonAPI/dist/carla-0.9.0-py2.7-linux-x86_64.egg +easy_install3 --user --no-deps PythonAPI/dist/carla-0.9.0-py3.5-linux-x86_64.egg +``` diff --git a/Docs/how_to_build_on_linux.md b/Docs/how_to_build_on_linux.md index 5d880a3fd..360bbfcd6 100644 --- a/Docs/how_to_build_on_linux.md +++ b/Docs/how_to_build_on_linux.md @@ -5,15 +5,23 @@ Install the build tools and dependencies - $ sudo apt-get install build-essential clang-3.9 git cmake ninja-build python3-requests python-dev tzdata sed curl wget unzip autoconf libtool +``` +sudo add-apt-repository ppa:ubuntu-toolchain-r/test +sudo apt-get install build-essential clang-5.0 lld-5.0 g++-7 ninja-build python python-pip python3 python3-pip libboost-python-dev python-dev tzdata sed curl wget unzip autoconf libtool +pip2 install --user setuptools nose2 +pip3 install --user setuptools nose2 +``` To avoid compatibility issues between Unreal Engine and the CARLA dependencies, the best configuration is to compile everything with the same compiler version -and C++ runtime library. We use clang 3.9 and LLVM's libc++. You may need to -change your default clang version to compile Unreal +and C++ runtime library. We use clang 5.0 and LLVM's libc++. We recommend to +change your default clang version to compile Unreal Engine and the CARLA +dependencies - $ sudo update-alternatives --install /usr/bin/clang++ clang++ /usr/lib/llvm-3.9/bin/clang++ 100 - $ sudo update-alternatives --install /usr/bin/clang clang /usr/lib/llvm-3.9/bin/clang 100 +```sh +sudo update-alternatives --install /usr/bin/clang++ clang++ /usr/lib/llvm-5.0/bin/clang++ 101 +sudo update-alternatives --install /usr/bin/clang clang /usr/lib/llvm-5.0/bin/clang 101 +``` Build Unreal Engine ------------------- @@ -23,13 +31,15 @@ Build Unreal Engine need to add your GitHub username when you sign up at [www.unrealengine.com](https://www.unrealengine.com). -Download and compile Unreal Engine 4.18. Here we will assume you install it at -"~/UnrealEngine_4.18", but you can install it anywhere, just replace the path +Download and compile Unreal Engine 4.19. Here we will assume you install it at +`~/UnrealEngine_4.19", but you can install it anywhere, just replace the path where necessary. - $ git clone --depth=1 -b 4.18 https://github.com/EpicGames/UnrealEngine.git ~/UnrealEngine_4.18 - $ cd ~/UnrealEngine_4.18 - $ ./Setup.sh && ./GenerateProjectFiles.sh && make +```sh +git clone --depth=1 -b 4.19 https://github.com/EpicGames/UnrealEngine.git ~/UnrealEngine_4.19 +cd ~/UnrealEngine_4.19 +./Setup.sh && ./GenerateProjectFiles.sh && make +``` Check Unreal's documentation ["Building On Linux"](https://wiki.unrealengine.com/Building_On_Linux) if any of @@ -41,56 +51,47 @@ Build CARLA Clone or download the project from our [GitHub repository](https://github.com/carla-simulator/carla) - $ git clone https://github.com/carla-simulator/carla +```sh +git clone https://github.com/carla-simulator/carla +``` Note that the `master` branch contains the latest fixes and features, for the latest stable code may be best to switch to the latest release tag. -Run the setup script to download the content and build all dependencies. It -takes a while (you can speed up the process by parallelizing the script with the -`--jobs=8` flag) +Now you need to download the assets package, to do so we provide a handy script +that downloads and extracts the latest version (note that the package is >10GB, +this step might take some time depending on your connection) - $ ./Setup.sh +```sh +./Update.sh +``` -Once it's done it should print "Success" if everything went well. +For CARLA to find your Unreal Engine's installation folder you need to set the +following environment variable -To build CARLA, use the rebuild script. This script deletes all intermediate -files, rebuilds whole CARLA, and launches the editor. Use it too for making a -clean rebuild of CARLA +```sh +export UE4_ROOT=~/UnrealEngine_4.19 +``` - $ UE4_ROOT=~/UnrealEngine_4.18 ./Rebuild.sh +You can also add this variable to your `~/.bashrc` or `~/.profile`. -It looks at the environment variable `UE4_ROOT` to find the right version of -Unreal Engine. You can also add this variable to your "~/.bashrc" or similar. +Now that the environment is set up, you can run make to run different commands -Later, if you need to compile some changes without doing a full rebuild, you can -use the Makefile generated in the Unreal project folder - - $ cd Unreal/CarlaUE4 - $ make CarlaUE4Editor +```sh +make launch # Compiles CARLA and launches Unreal Engine's Editor. +make package # Compiles CARLA and creates a packaged version for distribution. +make help # Print all available commands. +``` Updating CARLA -------------- Every new release of CARLA we release a new package with the latest changes in -the CARLA assets. To download the latest version, run the "Update" script +the CARLA assets. To download the latest version and recompile CARLA, run - $ git pull - $ ./Update.sh - -Launching the editor --------------------- - -To open the editor once the project is already built - - $ cd Unreal/CarlaUE4 - $ ~/UnrealEngine_4.18/Engine/Binaries/Linux/UE4Editor "$PWD/CarlaUE4.uproject" - -Test (Optional) ---------------- - -A set of unit tests is available for testing the CarlaServer library (note that -these tests launch the python client, they require python3 and protobuf for -python3 installed, as well as ports 2000 and 4000 available) - - $ make check +```sh +make clean +git pull +./Update.sh +make launch +``` diff --git a/Docs/img/modules.png b/Docs/img/modules.png new file mode 100644 index 0000000000000000000000000000000000000000..4e9aff2cfbbea49c66e62287c1558c9c7079df2f GIT binary patch literal 52675 zcmcG$WmuJM*DZ`FAyU%PND2rDNSCB2EscOkcXz3jlqg6yC`e07OG}G%cXu~@b3Msr@!p7We@j4{Vt!Ac4;SQw-jNJvOnvd<+|kdTl=kdSWip`*ep zlPUjf;XkNvU&=@#-5~x>tILjpSMJ(9*K$Ncx`&VW_ZCt@5(&JB<|HdGg*K0N2lEaa zS+zwY5)w6%tmHFQxADy>S2tC)>(jlHx&h9$fJ1S-=d1D$aX%2yP!ruDW3iNKI96-e zn8&zwLeVYGuhwtXO<=0fMZv5KN)SWGMNao8LZ!{a{^!q_1oZ!TjqU-{i~qjFsr2=~zh;!i^xq$K zh$;WiZ@$I;K&HAKa!X-LAME)M;)fU&&c}>Tx2O_pJC62#Zu7|zJ^7?|NL?_=f8jdp3BNU zQ&aQDb@T9W7}0g@FVLx6o-KZAZdv?cJ6c1}{d)ny@SNRlzYLYKnwnG)HpQRrZlkq- z-&C`ehj<*r`TBH z>+9?M*Hw{IHLm#h_!7p(^r6J;ZEH?=q@ zMI$4+i3)4lr%$8*{#6Q-riIU0UhIf!X={s2Oza9FWZB)@YwYWbAY@VhoSZB#Cx>Zl zY|N@xOG0yphK9y!^4AwwYrF>!g1eR;($fd*?>oTd$I2~HfOULADT(&ezO|atQ<0WNeUTJ8^ym*0ug@q+4Dfu}jrY#VQ3>^nY zrf8(pZSO4x2FAzmaO0cnD|kfGnkfZ0H$FkvZKH$bp3}248vi##xoQN&#Q21St&M(Y zT6G>zZES4ZJUycl5<1f*g5W~gKYxB+>Wa-YCq>-zL`8U580Lo$AAV{Vtf;SMTnXL^SVbb>#A{5@y)^GzdiNNDKV-}KuM zHbzUG(eSym+uOY*#$9|KhfI5Wdjv#8B@oz1;^N|?KMiif?mc8+2pk{RCSuhTlb6Tp z@9*!qDNIYFCXkv-w5?B1OM3?&`H4!j_uu!I_KuFtBO|eDdFsW!H$L<8^GuH)8_zWb zz~b@f>#VJl#Xfsd~*weYeiSb$Hym5jsX!jdkgJrgE{!w3d!?uSvccx1KLs- zZrj&4+h-Hi&MeBx%6!QRDk>^Je*8FX^yGr`28V!@lvK0$EsC0&8Z26g>y92gYY-eO zhN$4Dmcw@QEq4(+-qmFY+py{+fQ*bhT4H=pOH0c?Fi=HVxp9A~%iPS2Z)f`OmYe&ld?L@6_;^`3uSZ8mUROsWsu~*j6cjy>j5Hg3gr7Zo2G3o8woC@G zDE0a^xx2eNt5(UKs1E!=g*N47a|ZxPiJ~@;0ZxT@b1?^uV4VKI3@{)7*a-lzMNSC1JZpwyodg{^8v(q zxbHOUJdRLi5J&OW$49TAcKf4aU|9GRm6fR?K`ctcxd|T8_tiyu+ZOgf9GwQz5DNAF z{(eHl!D?m%28}-nr_o2GmI~_$NgtnjB*_M!EB}Et0!5)cf20<8+ z#K(8XbIBmR9WOJ7OTi8>AR$7x*svY@*2f8(8hLb@meFEE6l#boMrIb40EKM);^N|_ zx5Xc0^?kIE-X3p`!5bewe0YZ%7MLF5^A2^2&$&5`KW=bvFfy*7%OgsxVdVU_#+4*9x5seC6toCd<5iTd-yiSMoB{7ku!e)vY z$^K-@^&UKyutynEOItWuVxMI!o34M43BK>uhCT}Q^=Z2(Joc}f>kAZWIHuIc+fyvv zCZ*5ifW&Ulp~wLl(5{CkJm zrfP`@YF|r~qR1npC$8JCzr@BeLJE}}Db$sck_vEJ2+t>?8TWl*fy^6u7c|C*W_ zi1VV;^Nk`D>g|RbA9!?p207TsTDRiSa?4l_63n-|vyDwArNJwyzIsUWQ?4_FkjNgg zu_?d-`UvGT81W>?xP3wgVRn4vZwG%UBjcKzo4|E}4G^Bw-t>?Z(sH~&Ia(=wUQd?Jts1B{f`d&0hd%Mjz_v8m!bX}+D zk@hMZuH-dYiSFa$(;j-%{m9M5vm7ZTd`BYal8-C?(SD)ru9%UD2_l)_6LZ>`)`h(v z%z2gAr)zGW!;#q2G&7?QDQIs`{p^^5k1cWq?V2-Mkx=EYNVFWG!k$Mg!cc? zBID+%7vRB3L&k-CDUROnWi6j7qB}S|9J0G>XTTXRsjI7dP{-qQ=?06%JMET<)G}S? zDdpl)fg}k}2FF7#o>K~GzO+vSA68vFdmtE6F8pq)@3s4ZaAImII~-UD0n7el`~D0m zWZWo5MI!j124CM>ACm=LLz;td?ulVi2&lsGqI8>mziioOQhJx2y=eLP4b)R)+)SAW zB8BW%LRW_a$heSE2mla0WM!3eS|61C8WR&zIpd>)^q&(6)%xwtnz@;t*laV{~3#-Y;Lj(&ek?#R<8WAhqb&*3ox%c1o`FCQF%_ z{ou2o_m30ytUzi>y*^}|a}r40uo}pce+%Uj8P~8a>^@s;UX^zeuWbsS%Vr!pCME%( zBI4-i=pO6cm+W

l+(VfDHnIf`a~ZblktW+VMr9ru5o<2J7N`+Dvta8W0dOCl?pu zkV*t$6Y?a=%O!BjBF)#GOe2;t173W{%={ur#9O;N?ui7_yzkA4Z@`odaYsi7GA`7o zw}3E^aqH{rn`|n10hmSzJ$%g;OTuTDhSUNTN=jNf5J^%+B@$PhyORH9ESvSU{Kt?G zJaP0Vj?3N4E)DhddS$jVdL)>r%KG~3DW2Q>w?5*CoX+yrU{fT>6KJ1=N<1Z#RF?`F zRVx-F&zWKl$*&T}?`7FfuAKJBgM!=a?z`+H0Jmi8%pTNCGfpa1)>gZT^K)XW_Ud@T zY3*MCB&Bdz?4PzXB9IG$Dl2*Qy^jb@O5>jxwkatoiCI`M!(-A52qZuSF)Y?35%m#* z%D}2!_HlcvW}wnm|KGp>q9R_N?vaE`*I(|xM817nRzZP*mp2yRl1=p*1H6#PMF|lg z2zV6%PjB5u{afW|3Q15#OX~rg?%y_*2XGGVQ&RTMHu`n+^_iY*PaW>eq^_=-sl0lX zQ&hyr&mVt&?onYiChp}W1b1u%1%!Zr;B!(^SYjgC#&ALN%uMRHZ*<2yGkx!Gqe0e2 z2hav+n@E0uM8u1)wYAmA$mnmjA{79MQ2@eAOG{zo{CKflt?=N%VPSMMH1Bn5T}z;SN1;^8v-gNpzpPyrzY(g8d>+88k`*M?`z%E}5XE90(qS`)9dnR>3M zxB}^)j*-!jg9K45-@kv4NzV7V&hx}!^)F2zHpL4iC0w|ulrlkK!?g#-y?Y(q-QR3y z>YY~qz6VgIqNdjR=L>D|#Fo`~S#Vq&$@$@$1VBVag`_tvAMd-lyBE7`X$uJpKM-=` z2*RPV@$uLm$i{&Zxwy3SB`)q`P!JkK9Y9g8H@}fSQ3$p{7Fe68v~^S;nzQ@-^{b@2 zJ3k<2r|rpjo2lwz%MrGakdWsuULaEo3nv4Phr-KeH;YtNRdu*A65+Bn{v{>lQ{x-z zM~{LbAw)(;OBLzWt&SGc0#t#6Qk36B+tK=LPGI{ylF1p_f3 zAb8y$fc9|v{{H?yeXcy51Sn`_K7IS~4J#!iBoxPGik+Lg4^(^Uf^WzP}Iiiy#*m+#&^w%V;v1|KwE!n4=PED^fN>Au9v}`m?PkT`ci~Ea zEe9HWZ=KnqETgYe}` zBVw-r&nEI%0}y%QacIV4J&u4pB)m4{-WSJp^CPog#vdpBG*U5SZ(Gi7E!67wzvo)V zZj(#wlZF0P=;Hnc|7?lR4xmBz`CvwfKh3-dLjoytM?=O5)ih0@*l>9$V+MfPMLjR) zmq;^D@#D4lrIjOnOqrRPPgg{5f*aq=b}**WQB$Y2c1EVA_T{SOJ%9duHo>yc+;d7t zC6ONY8&REN@#9$OSQIH`B_*WqXWqEfzrP(koc83XyRvCbOE5|sMJ>zumy+0F#7*kE z?A8u4s{COn zz*gBx@Xov3*KSnYXyF*6&0DAxWlu=eC zG_SC589?D2K$1*Iqf%XnKn7NNb~vDD&qrS3K!;5!^apele*5_r!i!J&onK3z%~w8X zp~_BU#_-IGu^+EK3Aw%?l&YFNa=h+sz1Beuu?A#r1h)r?{!c;_T}~?yIRxkwxjr=n z&Z8q_*3;d+2n-BR42#VC7a2+e027lQ8wDDRr_Q}94!Igv-AH?vZ|>jmWF|JWSJ(Se z@&FSRs8=9lL15{y9v&y#J;1^LZX6MBxpR|XLgl}mtk4cjpa=Hy2?-`K7AHHA*Y&@& zvI4VL{Q7xAou_*X51zce134n9;2oXpV`k7)V)Z=ks;TLCoqeH^2>cu!9gvzjqln%2 z#fJ(`Gcc5>qQuL&xGmhdvDtM=#9*?#m_egd;BV4)~u# zGZwGi=I9duHFxjbYwqd6O6-v~FrWcN0|D44od)FLD66V{hrkDP21z2Yp+Ph^R|Qz- zvuC$LGJs+#+SzeHVjjp=1SJEM96u~@^BL_W{eLCg#0awnaARt6pNq~He#Wc zRp}BjPt|4T5)vX;R8&+gUlK6SS7(7V1KA(sB%{jsmaqq0aeVd<0k&!^@;aKfYK*>) zjgfWbJ;mRizKTR{Evi2cu`H^KiHnP~^&?CE1U&gQ8?hf6j`RTc+qZ8KEZ{CS_VUq) zem0ycr_E7>Y_#8WkNtCMsv;BvmzrcyB|!XAkd?g)4+cq*mX4m@fP(}uBPWPb2%ThW zq7re^L5ks>ass)Ba1&@Sh;o3OR|m5D+#mQzDQlM{pQ=6c)?v=?Fq#J_Vhnhu1m!ct z5Fs%!m-#=sEV+1bfZ(Aq#-Mvaeoi_&STU@eFkX5Nqyv%pfYq?w_yw0@WSi8KAxRD? zt2l?;4my4XMIBVEN9^n?pke`5OvuQ12q{z=#5pLms%mQXAkIML<9FYu1HA&c;G1Gi zwuEwg@i(0DKz0EADWnL=!t=pjVWdw(KnA?^(`t;%m5$hf#ag}ODXlT}#u&~h4*$FE+yR{_`;sgM9Dk>@vb&S$Zbq2T#+$T6>BfrHE zk&|}=nLv3L8> z=-c{&=CixIOD!Nknye6%!34;K(ACuyc<|o-K8U5bpi#mn!+`>{A}01*%FiIE8Br~o zfi>KF2lyJ010uK$4ew%MEv4REGD3JVK72U;A?UXw&g+#AN;G#&O3!N5P~afs=4Om+ z^lu#fdR@pP%1|ti7P1o4UZrx|5n2sCcSBp7AT=qeMH@5+&aJJDy)_;yHO1L!xDf&P z&jJX*F;Qnwqxup+a}y-JL|6Ihq;3KIuv|1EpR0W1bn{cs!29b|As?{e3EqWH%K%_O z>PbCg%j|dS7wcbg=+Ak@C>=o=p237p^OqYdwo3{MBdB^ngMuG$nc$L>hv9yJlKC$5 z6Rnd#G9X_r_kAN+@4wvPK(+<|fnlOHs}WPD3}m%2StPXeXUaTcW{!M}$byCW`C)4V z*$2lHws1y;ZSZias;$e+4?c^9u_IMUo-vZs}MzfF}^$(tiHjt(9fM4!RAG z06A@^_5d63gvE55^L$G%LQagpQYS!>A1F*HZnCzx*8l>gmzURb1qG9>@$wQvNCQ%8 z8XBcW9e98Op(r;_Ow_b?I@oZE!GeGaXKiEh-RaCcAu!AQN3MrdVGybY)=W}DnC``r z;oj>e*|@5E&EhF7`3F_s94`M7`K(lbVn3e!HnK7H%bpg9-;$#5IX)ywvjiwKW+JW- zK2AL0tx#Uz5&dz0RVYIH@rcyzxW>n0&-#6!!js5ZU&i$1-p39KtVH*yymp~B?aun) zbf%MvrpqshTJw-8ik#6wDipdtT_`z*r&fkqNY3wY$FK44{K6NYM+oH?_ATmx)ZKT% z_>7zeP5z+@NL5LwXu@GyD^hy8sO7yXs;UH1BT422X6WfOxThrIYs-R>z0=J~+DsZt zTU$LfJN5UtjVYF5Vnqw(!RW*8U?lP&{ zt%w!_2)Dp`T7JL3ZTyp|7`h%=3dx<5RgS(e+sJxvTGwK?? zg9h-#xRXH7=gj#0XoK;#RB)nAbudWD@O-C<-q{NM3znF-n|w-l$~0LK;sC&BByM&` zd@{0$^$)ETzlPr?ZhBA(y0AWa^yq&Ml&b3PT6Sv2z}hc3=z9kTmc=CmgoFsKRKRsx z&daOzHKok?6hgyJ^*+`*pko7&VN>wrS0PX znN40<`94VbUt?ptqG+x}kfmy-dIfiCn?ck!?vafgoL^sGN3_Tgn*7`1GBYi5Y_y@F zp;0RyttWU$piVQvyTd31)l)FnG%TZZPQ#&C59Mk6H(Im`)PWiX<>nr4j^Xq2RuXxC zF3ibkY;L|?I>tJp@|B5|6@g5FN#l`_Fe!dK%qy!()-vf!dF*QPg)T=80OuW4RN#L# zM5)HFm6e|X`hixHRTLM?_b%J(%d;?&Cm*0y((&JWuhZ+JaGiVx4CcT04t<)lF8%8! z;De7?SSZ-AUHcwLJ$5GMbwR}7(6Dr2jZUzKwPN8 zDo!*3+;k;h&gOgL0=!$DgNKE>**>@ks0(`gSVtm1~AYi{8d+rnD_R#4$R>L>v^ zWEiiFm$N|qW_P^D-d|aGG|ljcwdSi+6DK^t>^}2 zbyw0lSK9uOYWx94q|(@1ezHNxf9?xEw%dDzA&$;1|E9qF+wSwHXM&H(M^*e&WzYcw z_|m;jq*fg4GqNo^I3rHwavW~pIJ1ysbQ>^u$9tVl87CZ`bk9J$tNeQEqAoLG@724*3Wz(>xn_rowf+7 znT(0M*SohfLLoJBxo!*jXZ)-3v_+-EqNU?Twxyy{s<$TA?o#vE7AV(#{56K4*i%Np z)73h&wk%F?`&TmXN^+ct;W4iLPL?7Ls23vVtF#OXNlaw2h~-FDV1yG#&B_`EMB&)< zD*42uwxhPsB+AK^F4)j8fs_V|o5sj#G`FxNiwa!|C0SuXg`VYHQgsBiHsiGw7rRS%8ioOx~sIt-C?dv0F z<f82jc6N^O zS}wbA%6@dqEMYjXP#JoO%BqBU-%}#4uP9A1_D?syHGJkvI|@%`XJ!2c{bgW2c^<>1 zt#9Z4!%G7dvY{uZcg=LEce~ZGYXQMDKySQRH4VV6J?soMO3~}q?b8qK(2W=<>>#zJ zRZad7RP?22W>hL{Pk=#~E5PNJgL_bDN9S};m#wf&#FOpAY7u0ey3(FL4>eVk((IJ0 z#8BC@c0D4mk`T7!nu<;y^M$r>*j*4P$1^Vej*N`F($st|CWZu!>w;Xe%kKDx+rJ!z ze7#oh+B`TxTeq<6=hm30mnK9htwBROHr^XcI&nYrr8EMKvViSfi6$#3l?FVCMdLiX zRVyimAc6xS^z!zWm6yMgKXwy2nYA0bp#;8>Ajg1cZf(PFQC%f(d7{mb@E|f`VE_rrMb0q{e&xs9aYv{P1ADUD8 zEIvtb+oreqb>@aUIL7(dA6A!e$FQZwl~<1IR_Svd16 z(0MG?aiG~-Nex9l%Ddb8AedsEg{*3=Uyr*&u$RoXj!m)C6)H+r{ge0rFQb?vdl;NRM!7vYrZ zcgl$bTh*`#Vs!YukJU77zL!SJa%XOQP>}EtU6Z1e$<7z;u11*z7GcqdsunLorr=kxTlcd^D$& zr>++z0_8hVud1fG*;kgZKVo|!!Ubl~eRn+F#c_SMH5MgRz?5N_`i9&kHh(UUNt5L4 zxsdJ6!ee*N-h{m!oL@&dBAOe8)6{!4N2zW)n2G;*-6xSEVcruFgeh3KFmX~$~JxDH9BpHCB zUjI%`uI0D1LGkj|PYibi)XWo-PLpGEnasqM)J#{Lst7~nQA0VEYLP)4`UA}tNW`Kf z&)HtrzWa1_)xS2VFPt~_=AVJX2ya9VE^?TOFzSG@*9(o`&F%g*mBnjI##RE?5tp+Y zhs>R0WPdk@Jc!<@Ib)b8HYvti68g&v@y*(ANE$279gw)3jf_vsBCP z&F0bxMJun_gOL>V@l)oohYR&4EY=$>%0UHv25L1=VgZPEfOIK+FYQ5ynP%op0 zxh7HL(kME~u!`m8<}tsu<(D1H%P_z`!J?x~FexnL>mdFMjj8 zyu5q7C%m(?w&pxNqpU{AZktNgJ#3L6{YDA*`aMm)PGzCm>r`Orv$nn$WKeuHHU(M3 z6?#>9{;m!x`AWwYWr+DrwZ>zxgnwd5?FQydf*E+A_fL%+!9L@;OrcAAK1XKQMJk|6 z_F-Ue1I;P>(h-L%bt)`K@fFANw)LCq&PhRsKv*1JUiK2Q=j+tl0;NH>cdguCb1T6*q0?0`2Dt5Kjt!{%X8P&JHAhi9lAer z-N1J-Gt+mDeutqn<$)G{T$HD1ln7aC7CVk3UnYq>{)(}wKT`5D6Z|+#kTzK}hJ6K3M@2&JvF&gH%Ue2D3S}PFMR^9WP zDB8h$r5fkUZ~CXFM|h`hYD{o7iNH&% zeKtks@-k@S`f}r{=E$m)FTppvPq26C5=$u!k|DXENB+>@7qHXdh+cBwGb*&Sw`WUr z{ey-ns6A~Uh0ZWnr$kVRD#UKrv6G(0%Q2`w*8OA2F5Ir`>-D*y=F{GG!*Z#?6o#Jf znY)lsT|(6D6}=VxYC!b{9^*Ey0fcX{ILdtTFx9YlTArVXo;jLFnI$3gk_$IYqin;T~^wnG=qf zLQA%C(xHn`XQs5I;(pM!`gSV6C9-fpeHeYp?IH{B6YbDi)`p@?%~4@=Ii zO0<9K_Ma)`?por1Zl)W_`Ek(_=NX2lWsVD-m8J4B@jogVA?WX!mW&FwfdC@FAw zm(J9Y=B268EB&dD{rM{?4OrAAp`v6Be~jDr@%`J+9QaD(Xk1&lF0a{E57);S8Ansq z|M2c?r>FORQcQ~vw#9nLF&U~>>M(km+WgCX^?^V-*KM0%gXw!~A4`p?4xDV4uiaU8 zzRh&Z-*lPuoxi$Me)5pLCaM2sAeqM1_3d$LrIJ@hpzn=2{)qzFyXmxx)|dB~Fn(RE z@|P_r9i)1LKNZ?p`^$;8deOXQW@b!amskKrb#BZw^*g9gNJd+eT|Z*c9IMVfH}b5! z4z?+et(kw{!7<6gK$HyH{-Tvjej)WwVlJu#rF}UlyeY-whLTY^% z#yTQ-CJ8A8=e~;Db?~jm#;mg{#l^A_c=57RTmA~{Ne(wxCzT=H5}=YIY&yznEywzVOaf=i&(nj$aZ(!g}%$yXkfDeqo*sw&2qqS0Pf{_{(GZtiN12W&fwEKJf|*wlj1-PMdf5ZT;IaS@)(hxtuuMF8ZbIPudCbZL@G;nPmgW_CqoduHMh{B7h2NQ92&Zks|DYi+QG#?%Y3I5d{)I-JZzY`;WoHEWC4 zs%ni!HsdEl{i{ukf4g7ZP%6kpxDc}rW%B-54QF;q3_Z`4K9r6oqgrc>L6K2%#)w&$ z4mq%JxAVZGxVW=7dLa?~5n=ZaOPV`;|FnVIGvLDhQ^k6j%W zGN8rFn&MF1@LJQ)0W1zq`-4II_ISDKGWic!1a5#(D6&j!twmJfQ?t zfhyF~}4KdXrsMR>wD*-oQ(#pThhM!&`jlMoD<2o1>4ced2 zNYvba#se4;f981;dyC)7a)e~IhOaTjqhIbDIXO1k4~?PCM=s!mu=IhII*}7oV~z#9 zj6swhAFCW!ppo5}wds*e=xV!Q9E|@|-j2H9W9P$rr8v{=@)1Xie~%wpbdmkh^!Q-T zVrzVUKB1%*U>zEn6lS9PPiT5O-% zx?-OIfG^GdQaxU+-p>G1CnwNWJDGV6@ONM$XtBR?_NU%-dmbiW$t`AR&7q<;kRd6cINSkQsnt? zFJ_604Wp$gs(U-OA!j@jpZf=EbF!+rn2FufV3eT%+_))Wdw!jENi4AadV60HJ}6~= z*Y+}rBbONiz<*(>*0}zF$hA_MrndGADJc}dr)_53Jf?}^(zFO))Xy<1a^O4An^AuC zN4W3`KipW;mje%|F16^V~ju-C(iZY3fu zz#ex!YM)-s=wEMH!X@buILD00Nbh|n_5&?C;3$b--Ou*3Ak7mIO^Z#su#n|uMqbGG zlBP;`!;jiFty_8q-evZmS%0SaZ8VHOHWpDwrg$*4AsD>Y|Ec#%LR0tzX$mzUlXn#z z{baG;JXq6$)V}IYGMax9Z6x=fzm?LnXCbTrayAUC8jD%`2~;eH7@<_C3=>|^jDA{t|1u|4Vrv?miaduKJm=1j9FKv7P z(f;@mR~H`ya1sp-n>-CPaq#pnY;S{aDXq3P2@GUlyj~kFAcJNrnCVi$91A@hFkh>x zs=nr+`wa$UrcN9eGG1=(pWvzn3kkp5E;T654?r{)I$zC%4h%S0UP8MTa7yj@dLE(& z3#5K0cY1C)7oA|sMG$U_27!M-lh0y{?TV#5zPFdw_mK&?NjSmhbAZ^8_r*m1j~UdM z6;8bn2b=dhS?aRc8vSI0_c((wYe zs#NHh^*ZvZdwYquKSlzIj(7IeDPGw5APN$3hOXIp5Kh z#83!o+kVQ}p{FnA6oHf*@>t_dvFCU5V_z06rIX2hzTDi3(|ta0WzvG!`T6tbnAEWx zrd6!K(BUZD55Lotk`&NTviH}L|2DYaC4^pSFNOKxYV>bk(ZsI!0hF?cZ80rb`-5WD zN#a-%nnsFa*lduW6PfxIDyPV>_Q z=rV)h7p!O03=COEPpvSZ{d;6e+*P5;I=bZo1_x-$nv<&MmGg70+ws9H2)v4Dd2Sp* zBT-KYM;sj*ZcpOnz_nJ!-{ofW@ed4kJm7br>l3{ZLc$T+MPjerMFw5nMx+h+fo7!* z144lMv}dy-Es;z?b7y;68rz2DyyHO!vfTl2oC?3vrcBe zl1Q;@+Wy{6c5`fEe(Q?0&SpG&h%u<~)PcI-^DqB5f!8!CzM`e^lN7Co4UYnc9C2oU*8C_cD?ZDk zb&|!D7>2${ zqa()_1fh2pz-TL&Uvle}UAHHLVff-zmK+UCCcJ77=}($3>Gm3VpeinSTH-i#7n32n zjx2;pNZn5%TS;g7w}0&UD`ibZn>N(1rKzG9i%vd)lk?QPnIEx7?l_!;UY+(?#*VE-g0~1AGJixQ|JHfSK}@idSGD z>V{Nbd_)nIUm(LlDJ6CJc{_}DBj#B3(Tb|8Ubx0>_e-{Hz5Si2lyiKA z?AyG&jsxFncAips)TNX?&e1F&x}M1^`kd_i(b_x_RA;~YppwsZot3(+mAmd9+kjnepfeQ$o9o&q=M6WW`E-Q0livi&isE1MaH(c%;{vTJ&H#f)CX3a=`zc zAr%_OV@(RC;i}E|8OlX^`+f~DS5@upiK;hn*NoKk-e2%%-xKk)@pAFO%`-O)7pxzJ)?E~N9K z&N=-`=rnNTF{LD1-<+waFdYfDDib){&5`eUIXZdfrJqra^4ZOj^=2oKK+fcLU62eO z$y#vv@U+l^x+4bZIyuw3#Gv=%7-Xf_u3YVNn~+kx=WM&(PMj$dI0B`0Xlc?7^^IRSLeE47HS?ikFpyKm*CDCR3GNx5qmy&6i5yu`)LY}cX_-#zHU?Uf}dycz=vAj zZ4L!G8%5P*hcLo|XnuiFZ*r;u>r z+2;2Bn=!$i-5()4I1R2l6-K;?*#6TrhkrfMls^}$5J(cBNQo)mFQ&;r|3myt?AiVA z!RY_KOnXK#=yHgmuO(Vl>|9;lk4$AsdpIUvav*}!Sz5E1ob0$g+1H)KpDi28k zRdU4{r$LE7ErxQxGOMkB+Ogy&%~dPvY|Y#wC?fcDA-ZfDIppi{`;k`A(-M?%DpM)a zWG|hin9WYMYBBj<)9cN5Gy&VS%o&mN^K9SjP4vmH+Iic|T~}0t`cZ#4){C0nqZSM2 zp|+&w)FHo)-|S;~p+1@R=&~ra-^};}?RE9{jQ$RPqWZc5-`YU!%!f>`Q==DO-zrxR zc=Xy=hwRpert690pBYRo$t7HFk_QudMH)qvFJo8@V3-U1pvAu@lfbl!n3#3lnQo{Z z$y$;ipKS17m3~ylpZCAK0LnPhOfR(3aXm7Z3tf8m1KyFRo-TO5#pv^h%PrrxK56&M zH~Ge7cjkt1L^|BV#S`-JQrKfl+^YnwkuvQmiXGE%^_QA% zi(5rA9&gZ4NzpMcZ>BOo{<$gI%@|rMabSGGEH2*csE2c}L0Ex%c6jl{p4;`lw=V$_ z?Bi!+DVg*Gv=z=RAQ_Xd! zZ{X0SX0ZQVAIiU&zmtkR`6o>=F;hM74|_fH7ka!Q?f6Nvl8GgnC0E8HvTJ8DdLf}p z{ZPr8sqLYt+#4QTaD*O=8b(a*)xk7~{gRo7NR8i(;E00pzY4Vrp@9^b;t;vmMD)9! zSy<#MPB=hE6_HtaY$oFvOOUuN2IEG%i0#jmtzud8&X)e%8ee%!|J4^^orlgvwV`u1 znpFHl=|$fviEm7}1V3n6en>^)qNktE+6g3kU7xL7dd2QPkEGkvtYqY?<>A?QpM*p4 z*TA`dtu?{RnMB%KzM}o+ zl@o|A9hAd8?Hg9jpYLFd9c^FNd3~5+FC;uMcEEP&3G1om07cS7bSG`Hz+ya4e2)nX zfOUfVr{m9`U2`3ui!EN0-lPs72M3aJYMIjEd>0!}BJuDqn?%)^34?hT_+8w53uC%3 zc!h2*4*>piYeZU`W-8|~DgSvVU2xuh?+$8RLdM*Cv!M(jy?VEb2Jk)YEXB4#w2fbDhMi)d!BY{0l12~40R@jC{Nj%tD}88Oo{Ql!sFM|Vdy5+Tqa zek$x4!=h2BRA#1Zq}2xBanQxyU6Mvbc+b!^pwGp@`lJDZAMDfT4RWUQ(mr{lHur_4ZR#RMOEJPr(L# zzSfPRx&%{;+hF-jHcj=8!60N-f}ouw#Ago1%_K@zm!{48n``VuO6XA__f8@Fk&=Yu z&rg5e2$x*GX&stx4b9PS5P{5eWRWB6dq3oCog-AcU>O{H^(*c^W1jVACuJVe&y-=JPv9Ih2QjYjkE+c-kZPFa+b<_*2*OA*dd&P3HH zd`$!2GJ$aazk7$Iki_>4n&HJ`R*3OY)m+tJgxwG<^)P_j1w+(`i8GK65${+Z%H#4n zwKLLUc=+(c$&9b4DF+#t3Zbd${ib1Iinr}x_;il^E4$K7ItI>SnQw{*5}M^$4w*E4EPmy|Gi{?@;^oq^}HT@@56IT+B3I# zqx=dv${ntEWrJUlmoicPzDS@Qmv}d0=#lQ%Dh}XH$^L+0#YFhd1COnQXSYZ{AalDB z&@)WY+#0kf2SgAON&oWPi?G9t zTO~(@9wyWGRTcW*wuW$e3|f*;HTd;0gf|nAJLHw=UsFa5SzrMuA{!~1Z$~M0hhX`k zoavEbVF+^#V31*eIk)5bU!UoW)P_?hkK2KcaJX!0QhFaMr+Dqla+As{ARkR$FW@ZZ z5lTrZJ9M60Qk3K`x0>pwO9n?`Zan!KA}_JJ_d>V{DDSQ^Tl$C zZaiaARkhQGsMb<>3AW@T$^gR&-<9k&G_zL?EUCViL`$9Of1<8+e%Tp_T<$iL_piQO zAIxcnQ6}ZQA$J=o`rPOD85BtRlKAxp7UoQZ_-EY(gvKcfq(cYRemi!_ly39V<9vGc zuRxS}(Bdg`bO?mo?oocuS60f_i=BF@?=PbFU)R71>VRpl)tLrSkc}Vz?E3<3^mxdD zb9-(MO`?}H4e7WcuJKRW+uE)T(UdF)oxB&HR6DtaJ<#`RJ1Od0seBomGhT~MNJc>O zJB@}(PBBe3QSG+sto2&N(u;WNJS^Mk!)bgkNJ@HzO)wH_l$@%3&>pbJ12 zYlHc%4mglGsyTR25T1Qkv7h~YOS{ah5klsNZVeAuihYBl>}#f~Vk*9=cKq`a@FBXu zIb8AO5}8Zntl4QhO4Vi*(s$8dbHxgKqlKNx z+Bn(J~}?xSl^1)rQT! z$>25f~dRP zu`x;!(*LyKd&Q*tuSe!-plyS-p^>X^Cii4hsma@|iD&D=X>B%!Eufrz zxiKT%Yi8YDqxyv&BIvzN?JEh)JeZSRG1*%gL<}C{??26;m5o3+7bLRBk4G;!jp~0i zdb#+YtTIhh+oiIZRzG{y$!@-3)gwkjV~K8QpJQy z$$oVdo<>JUCje`j(v*GAfbP4zw!hg`hI`JLfN9NbH^B=h`I8jh?INhKxq_D8$Y5#5 zF=14*_i27KOa@A*>1W+vAVTpuTsLd$rKG24L}l1_l99;#TkI?Jo${C6CLkhu%_2zF zFfHfli9R@(;C0f|m3%m&1b6YB#sGZKOGBrr*6i!G{ey7ovVuV(Ve3I^KL}KZs_hJ* ztz`bd)V+8;1VyJyOhjZoSbn0pB`>n0a6TaN43K838-{sOiXA1Y~C|y z35$$e0R9^yf`)(0Gr)`y?H<6dhC{RyT6&-yfQ(~nKJq>f^nf5efsyD|1NLuF z{UhpQ_{)!In75<`O}HE{&b%@)qi&#I1otiGz~)ErAfO&zE}p|bMa1R6VFA$BUx%>O zvSJ(h>MZpl>#5q$DhniWadC*p6}(3}Vc`jf>J0dLaB7)@Y|#Vv6|?pSva-e<9R5_i zhUts~)`CC$Ky@>LOD;&Jv9p=CZf0ZY72wL!J_-CH(p|1pq@KS~m!D>Y`ayjY4{6t7 zLUIKbE-1eiG_pPSR@4v@6(D0ps@Xv^QE}z$GfqTwz9a})p;)I(dAi=M!-Nrj>N}wF zr3Gwc^T;>9SSkdkak~@Fgwbzhj6+`^Z7L_Q zY89&IN04=+U(k{8k>i!>SLJ{j?W;3d;Fo0*4*mH1%}2Bp?9% zFunn4L;pK&GY|??tPnhGy&VB`V|bdfx=&~b{$PWY00cvFi5B`b_Ul7OtAOhv#}A?m zfo7szLFX!>^6%;bBL-P3tTSomiFJ2iMM{I_!t-xYLGV60TA&Kz9{?ycOgdp7E^1`I zgC-oz9*Xp4a2~j1%LKiPk&6a8ef1&R3 zf4h5vK*L@Ju6iD9ZBstAD_>wu2zhK!fHBnGTKiGZrCc-X+-(AaFHjQifCtQ{G)bB* zAy}Z$_7COA-T>jC@5HT`u2*eyU)J4kv|(M*EjP!8Wkzt%0PT`6qMTg=Ha6^626iR_ zEZ^^Nsqj1)w?e!gfG8(!*9WU~b-aRUCg4&GoL0ylNrE=+2&7R^YO7apTm9lTe=fvx z8l}LJEe9dcGqFI)S(hn$j|}-o8hP@Bh)V@r#$-S0UA+P=Lp~hVIdsTtgUc)Yd9M6h z+W&iP_l?uQg9Yu#Fm2?6UK|_(SHt!M(XPO*MFiP*z$yXQuEdnI%t!z22k1GU@dbWC zN*YKOVUg{>lsT}1?s2Bn98@pho$*F7KSwT_9ORyvRg0jMM#vj*utnVB&_C)Ayfv5W zu?!msF};A#9?`1gIP<53OcpHBpi5>zbHPBnf3J@R?p~(AF!zY^shC_xMvw||jK_=a zR?y7Dyz3dboxm0tTFx=)jb{PtvVk)E%I@-Shz|nn0GQcb_MJkFgDvtBc%V7zMQ6Pd zi2cnQ3Lz;lBZ7@kd+GBJM4CSLTX;uJKmVw8G6Sa&8E*>sYH%fu1Vt-iS_U2xLVhQ_ z0L_8>7&pirp(iH;bT1<3XgaYVhq-XX20DR4V5+L2OKoZ1DOR-7<|D%39PYp;1Y729sqL}KpLTJ6*RMS&&Vr^7o#>D1>f;l z;3Tl=ya%qy~o}K~X zzk&Slwf*4_dP8MWSIcFc;K+bN`Ylr;6S$2(@)U?cQ6H^bu>1H@NnRd|8}+MSu>9=B z-bnS$uZEMf2pUO*2nke(OJrByR~beQ0r)In69CH4w$0Oa%L*r`$CdgV?hVrgcEI{2 zVbjKiws5Q<17QpR{u(-BlMiex|Mg7Zt&nbq2VII2_Nf>Qz#$UPtQPdqsDTH30$|Hr zmJ&=g_8d@7B64hnaD}}0`EW<5^*t{4(2k|Y)=PYQC211Rm`q%h>L$ot+FmF#0aqOk zMzvCXtrXtpir`P@XLA#DrZ6sm@4$+)E5FOsgjYL5u4qp0Y*l~a+hU%PUFVz z1hy8l3Oy&mG-$6DC+3LY=hI`?Og^y}n}<6t4-b(7idn5uaIrTjS1q>_cDL}r-Z@as z^}t*W+Kqe=PMKaICGpJ$1s{ADYhH4~cWhgCVITgdf@=@26{R8dF5b`~csOV)_B!h-@-MxvtJ>*V0OW8>9cl<;XqMI33MRoPM)0%a{+G9IGn;YeE4 z2y|cl$uRmsPa1&yB3Rr5H5o0Z8zRjqyQDoVJ({I@p({33aKQ-<4k5J0`nur0Y@3-7 z>sXgY&%`k6DtL5WbA#en#kDw=Fi@F1@ZK{JcUS<8Wgmc!upRN?`c3kxC~NkHY|Ugp z9GEPIwOnw%-X0|;u?B0vqi|wesxu-BHtlD#vxFq96d_%7Hpfz<5z1ft?|wTsWxam5 zVY2isnb%=ynw8}CePcxEYF+i8%U}M%nDIY8Shb3G^>Um4Fw}5#(UG-4m=r#x?sqvuYWJfY2_5z>^4)24Gm@-p|Khy@SyDf{t(Ke)fN$ zVdeKk-L#k>>{5~o69eOca0|An0u82bIYu*>3oQj)5<5hv z2j`(28w~w7t;3F1iZ>_?0VZRU$;pyL zOe=43o`)+8H8ajxmJ@_uUXfMfO4YdYz@A6skaGTXv*obY4VobED`2d!8US;K{sKQo zFh>HffDYK@j$N$6bv-b+d&hPBK(6Hy8x=eg+5RF^2DLK0j{VL3oyewvq47o%ST({V zLPn|OOF%H}seGTq4aAyDS6P)tK}p`^uT|#mVElcB$4|D`c$p4g4Xyr3zAg9ZVEIX! zNC4+pSrRyWo*nP%Raz5TR*V<4Ov3@PKEVejcVkSq@8eQ^J*5tK&0ca|>^nOXAscf& zTCUBkDbup;{rZ{rNu^HNOxaTj@OzN~L)c($^us63y}2vSb-K;Ibu%MtBu6)?{RQ7J zmQwX9iqOf-w*+vp;hembWR>aK>iCwdbm6M_(fB^tNEK-mKpBDtdT-UC3}$V8N%vty z+g`G54e-W2`bMmL#Uv2g841p1IyOv`a1zPtniE#rPb%m4Cj78za`~|W=of{c<4gD` zs`-kf&!7i*TSk%urZC_%fjGXw^O!|kscP6h^V*E+f1tm(&a2Nc2o>u4C-A3>o@z>z zlZO4lV%%6eaPvl9e!deljrLQub0ef3&xZ=Q|5erWe5=G-ZnyzbAN!a?i{%VIV>~s4 zvvR-Xj0YY&sT{#ksOmRkZUSzDprG!zZK2#D!Qg+jc`T%$PIx4cd0bXF^7lHcc7?2_ zHvaHS!=_Nun9xsKSmvb}fL1KoNEkJFCxDSI$|}Q)aZGk~#_4G5S%&vt7ML(BRguYp zh<~JHjK!!LjVfk2V}9C%%M_P~kj(mMj6qk6b!6uE?EslXiy);|vR6S|m|&O@RXCE8 zc8G?CcewcKvYK+dcAAs*k;%E1%7<31Glq zorBQ2U_XYlYU89U2Mk;{Ig7S+wa)O#?}6tw$zRGOcHY`P)l>d0B0o~KNb{`HmCyl~ zI+(jV-bacM3olZ#6mNE_ZYo;io3R?ZT2Ao5+CUPU&KvlVLok>q%kM<)EPOU2O(Sa_ zawQ|%>uGl?3w6SKJEC2m&xDnxj-D^@_m+Q4=u5I5%M-2-aAcN-sfzU_Rj*99OcIw` z-MheB`>f^9rxmZ@Q~r|9{AkC85qkDmLfhqd-b-j&S{E_ zn}m@<0mql=OHz1MXA3r=lBz%Cl@#-2R-FSJoRg z{rOKzZCN6imM1P}5j-&%b? zQ>@b8-}2mGC)q!_!WeLde`D#p`QHzlf_rOjn9W>KcQnK;*E-#-dG$pDJ~gy$U+$NK zloY?=JdxVR5k5?lRfXmG-2qDc0XV7u^1bNYjtoz`nEu9;>DRIH_P*l-aeNYtg1+Qk zv2mtKQrXsv>jCf`etk&RyRfNQa200OF6Z4%{Lr@Q3g7PYq@5t;8}>}MX&=(DMR&C- zOWYQti+EIuP877{k=X`xhU^UZ@d)e^}nQ+Ptw1vYIMDg zT{+#Op<3M`ON?>_$%mdgiukQX^6&HO&@=;JJYSW4?PzB*bLH??+qaaOc%{df4+@lL z_dUc-e;#qeJYn9cuFmm-z3oxc<9tOeuib=Yuk-brMH*$?K0u#_&y#Jvjmpbse6Uyd zyV9@lfexq9?0!z5G{f;W}XKS*Peg(4k!L1VaRqO17OOPo% zg^M93+(_r4!99r3Z6x=J-pX059g4_N%%|nx3)yT=>G{bw$)c0Z1K=-yjC+CW_)eiF z4@^rtZZunt#6)g;P6a=@W%@686+Jm9S@gn=Gebf;tF?RfnZp%5i(MjO`<>OUP3MDQ zC(($|!23~IZMoBzJ3bXm{HQ-!dVQmsAJtzyeM3Q0?npvJq;1Pc+!g&^sZJ4>LNslN z>CMiInU62VFWFdn6rw1_f?TXr25XpGM4G&9|%qYI0UV*2|xmKH3Ka9J_-VSZ) zNu@KEMA28<=|6fu@^zr$4YyaPVRH&!f~yPpsk=j$WktFF@_pa!b)LPGD-#k^A?o>k z+ap0*By4J^J2PjJpNaCBbw2atb}7@dv!~@DNLC)kgC)*qJ9}kbo6$)u6k72U`{bW( zCoR#?s$Lkkr0}ncY_~FH<_@ju?F|WwDvtL40ZweM$KwFY!-FU0`aFUGOT0Ilk5LwD z9u>1)nLXX|R@24Q*topT4>p83CMuUB9Ri?48(aQP8yH-@w$W4=7Sux$rKr99w|E|I zPhQ|zdkj}y@G9IXx}2(YdIeJxM_`FWc~z>-YC8JPM0ol}mOeg#nCE z$y`E-W`XHq@vnyYzm)%<3$V_A@M7kh&JCTN-H%V1)yjDzTT)-OTDPYq%2lPf9nDWt zyHtmhlFU08cA0RMpB_E`?HxdScl2CFQGNbtS($qF(CUxXYw`-p_xKpXx5B;(rD&tM z*1!Bf|0@DT8eokpb@gC#T)|XI^iz5q*|1ot&fN|ntcIXPiI)4!iB7h}@Io#JCZIVvWx#0c?4FWFJeFGbr{AT^~K`a zX}w98{N8vvK89q;+_x*md_Zd{A~V9P5F!OP^^w0-x-~X;#>%E=zpXCd1}uoB)o5Sv z{9KnuL17_fCL&F!T3wf^JzexU`PMW4=}lM&s2?ss2j(G+XOw4&ZB z%UcU3Mn$z`GPB~q5a<_gN?P?YCVUW>tl{V-f}z=N(Iqm%qYgNG3&57=KDxW)%egn4 zY||-IC43VNI7~405?LttWVZI&z@QPI=Vw3I;1Ow-8sA7z3~^?AuOgLWv#;+dYTul) z&9E)-G47di*Sgb8y{WdeX8E_p8BQLnPLezW;u6>jYNeKT%2X20r#w&HeJcDE)dT}J zc=zuLbXo2a7&S4%=RbLDn60QzsPzH;?OQ^_s`0H_F^?(C%U6$y2nb#VAKnrIs5Mx> zl#!QL6ZaF^rLGz-7M2MtTDW}3{nwHy)rKEazyA&$M8NdFxV%a9VY`6kQJ;XLM^rJX zIHb8=%WW(q;jEo+U!5L#k7~{@e9ToZ+Fyv*&v%J5cArN=44se zuq;Gcd;E)8D9!HjsLAw%Cdp&78(Kdp`MF4W^{1)lyD#*fDxxCd|IokC?i0It{T$&2 zQi{0e0njQw?f$*GMlN^TCfX`y@`;V&Pf88{`e}Ps&El_BzxvvZS`z7utAr_U4`j~G zA3uQq-@oiyYm_)n0+og}_R{{HId zera;Dxuv;kx#peUCnh|?=^F<|&Z~(p;EU@#BfV);l~(nWS;6DX4@G~kWCT{-VF()Y z;g6RnMVK4kA&D9Lhq(Cz4%`XXkM=8UFtCInix&_QR(>}%j44NBqyL7LY+9ptIa z|0{Uhr#5VZCmV6gYH_C{?R1}{ZHDaO<+3sDMW-8)edmIEgQ_hrv=W?Yr=-vv0Socq za7I;>3YKvf{wC88lRxl-08t_!B3Isq*P&i1=whjqtshOM)S3-bPvABSr{gQ+pY&Cy zPOj$|zheCN`}3WoAqC6#Av2t5xz^z*>&giUKjS)vYZu167W$=yn#G3EBMtuNVA!*T z2JeYMT>N*zg$r18A{{K?^G({UoU}Zs;rKry6YT&IRqA5vS8aCRZOfoLIP4>fen=tW z`;vwD_cCm^?`h%>rOxm$@hE#1RK%tA6?t%|T=gk?Dc|GSCq=ehKTs`K5_;Xj9Z!_s zYx>zdYh=xV*u}mk)tQuad&ky{?BGOXFW`UyhxEz0ek#<*XO`R`QQ74gN@m^Q4qda z5Zoh~9pl-aUQOzA+bmUA04)g-m0nn;&i#T(>1e&0zmGER?yz1B4BWdb7@QxuG+1Y6 z)|@7u93!3{lEcjFFmx5<$aEZQ+nt{tii&s&zMm!N)d^c#yZ`=YqdV?qvv@o?w_Blh z?yV8qk^C96o4b93*Koa-oIZAfY2>aI+2!}OcSAp!p{8kc#r!O=HIT!jZhz;LIqxit zjfI;h)nSb*N0;B1_^4nAmXunxF9X$cwb0b4RW}S~|W1U^j7QL~_$^K)sQtqMYHJ!@z^)_yp66bx#a^d+|;alQVG3qHw zr7sZm>@;yd_>l~nqOyqO*HvfK^PXDL;=su^eN<; zagp~_>T;1qGb?JdQi8MdijMK@cq<+AQxVODDxy+W-aCxyGg zX!ffHTp+Cw=xxqM7sXYx=~+H`NQKX%t<|2UoKRx6V`IPWOT zMgFSXw|}+WvgWP5ve|rX4Vj=Px>oTBJslloE;m+EUpQb8CR~=&ammRm*Y*lEJ$|3u zR?pbKr@!Ik^A#0vz* zk`cJXFH-Pc!H#4|pBAZBt@LD3jAu_LKHOjCx41$6YWuRRbkv&bVwFH{)aoK&QmIrs zSNra!5I!^)&g!)8wwQ}-@dH|^<1hFjCm{sz1(?kt_`>l3$Uk*qumdK|c>r-3E5tw& zPFtW~!zPP&x!>Zz@xuzcqep?)|InLV2IzF}*un!*jkP$g4qi_Yp-AjGh!eTjXM={P zCr;nDV|P(DV!`lJ{B%tLxmhKCobJgUYEUiVLk|t6Rrp!z{!+iRhp<8K@aK<6($d2F6@4;o=GK_ldeoP-A>mZ zxmT`A`1%cnG?b~0$$}AbJRcAH+$X8pkepI>{s!g-2>K5}MIBezV8Ayr>H8Fy%caR zG{Ty&1O&Lg5nBdEMjqgC1EmEf$h)iP2QbA(d{_aQQ-k4ESqDo75Eh$N#QVRJ8rYY7 zK$THPp@NkQ9+iyDtHnv##tLNh+9mhHX z&xQem?gN{B#Ew095gh|1-sEFeljr>RXi!w-lT{bqg;0^p!CLaI$N?F+O3t5+51GGb z8f?%hGi)&iD@P!tvBFp1J?4A_fj9_CX5ND`j!yVsSjSVU&$oPv;o@M2y?nVvvzREz zn>y4jFL259wh(+A>+Bw=h0s|K7rxc8+Xa{7t)qpQ3J7cBu0>uxCOY~jn2iDk#_)3i z3x|EP>5%hAOL8kTc;(tFGKL!xY4U$-UFRqy*x$9yE@yVFgv8STN`!!qAU_{nPS68p zgd}_`NWtJ%F7T*%IpcN8fxkKaEiu}b8xtc^cgFzA0aDc7^GW<{a)At_Yc*h_*44G_ z-R}}e5aERh^g95$k_DY|9)oc8KD*!8a#Y&0#}&U zOUA~owX#N~^$BicLN*uxf_$PJ(0>SIhzTiAjEyCL*o!fhr>RPt}4?FPKxAS&8Q^AnKEWm*!FDDl-PS3J1q$qj| z`E1PfqJ=m@>YgeyZOgIK8B(U*rL>wN~~v^b}CPAaDtY1y;L>9J;0a zoagRufhj>qs27&kE~ClH67W0jrGDa|byb>>UqpAe6c8~8G)is($c(rKLsiUFnFZT~ zUYH24fRGn}@mv34MIHZo+2NQcDX2yFk7=8Om;$hT{a4j?ZCs0=UO}p4&~x9{7EG<@ z=H|Tq@*cqy4&j8r^b*KiM0Zvj&XNErG6y7)_rXiQhDJKG(9=ujV{G}5)Y^_z>AN-MjYIDsy}5&&RPKYhOjsw zsj2beWKDcpoA^vCScn225OI~7FMiRWHv&(0BmxaQs0oh>dhcJf!_PnxnN%dsdEwL{ z6$nR)?L%6*+_%6oMob{#*g!Y#H2sYDWFgrHU&L=20tN$41;&pBaC<@AS{ngeM=<*P=eyxd879D(rWJehKLlqHY;BeS zd?!vM#%ese;tyc>^WTj^i0MD%3;?Mb@ll0+dPm&1b|CJ_X#_CdxBz@doZU06Obh=9 zpA>)u#J^_$Ma?9_ngCAXT(rP%8gX$dFl7d~<3FQ)hysC+IB$6i3#VQc40eIb9Ryg0 zx~?+K77?I?=CfY{!J_lQa@D^tN04~%1F#-wg_e^>sDb+i;B^jwz2Xw)aZNez;^Y75 zutmTG5^)%B^6|*LRx}pkL_?x!5Ew;-usMM>VPzOrOt!v4%&1%af zoy8-N!*S>6a_i4+`Y?Z6AZ7SAz>5-5L?}JF-N?1agtcFWgzB%(_@|k zn+a0%lyp^Sw$KiV!pG6QvOhW-r#IeW)x?UHTNo;4zk)n7h|S6ZBB{TYxC$yS;7dZ6YjMsoptam^39ZvkWs|Nb9b)!mJ7@rFMdr6R#bYuM;$nGnbKy`-!;g1ry2 z+~DKDynX@Hn^_Pb;ct{IyLCx&-=r9r-5hMLElqL_q zOW-CVF$MnP0??tD!4AZw5`70JUuN|p`1V2vlxR0uee8R8Y7znP;W(M*YuNz&lVKbDpRU`dN%9=*C5E3;z#&hB@_{0Cjz}{^sI^`gcB7_A1ge7YL8R03-$~Iq|*vh@32xsqu3nVW& z9wg-xcwMYh;L?-M7BxV5A z+)$Q)m3~v`rfmR{cm(`Bv?~36;JRYLm{rdJN!@_@;B~TE-~~LoGuBo2>PtT`IYd~F zaLj?Bb0ob2QrP@c9fiTs0X_qy1aV?=0|BipKC$0&0pv2~NB|x^4pc029_|;vxPX!^ z3B03Z$nlyvRDhiijt9>mM?pL${d;%!EC774c2C?g#(}>14#*Z7WyWGqkY!*6pH<&S z$N^9pW#AulTmhO^_&evCl^Id_|GSu!8YICI#aY8XO93)f+`D)gMMWM+hXK=k!`oQp zik&a`=}IhM^K|deN%s_Yo8$68(2=6K3_8$i1|IN(i<1zW4ufL+)+(#9x3_T1<%I|o zdLUyhg=_tu322croWcV&5@fdhvUBfVv{aCXu7ExH7EqR*&rM>2gFhs4V2d(EDA(0yy4-n42ohr*qBg!^&0OE*X*5% z8i&o(hnl6|iF1@t^w3@mco;xfUmyGm*q&@vYy4m4T(fUt(RY(X9M&sHp(NEfJ@aR# z?FFVI1+AY_fEyTy}5EozRi?nnNRP^n_KFGJWgS> zOuzT|0n^deXt>T(N1zZP$Uf9jIQ4f|`Imtz>2RspLT4QEyLtv2eBkW<=adFLf=~bM8<2~g^;iVfVcO(8{lwlhxzad zFeIUsCcX9_nF#7W^nc(_N+|ms!~fy?k={IoINb*S8w-re1u{iH;XUrGo^7<^8KQ#a zN)~^H>;laO&COP8IeP4ox8Iro7`xIrQ~vS(y%3RX^&%{M?4|P><9zRYXVJrdS6Y-_ z&9fowuG^fJ=dVkZ(k@7scpp&37`T4RL^pGk$I4Vmmh_BG1fIt0*jSS?Lm!aIe$cCU zjW8^Ls&vB)Yr`R}UnQE4JQ_@S;V5LHdKZK?P`NrZ{`ruLS~*4WYrpy2uE&>!?bx*V zZ%-Jeih(~_lcj5|iOa*=Y z6qVCCAeAmc8)6RhC}Toegf+bxm>cEofd4A)OF84&`h=Tt-3GCW zXe-=cfcRd;6*PNsE+Fx~3n_m82edtgn25~p`tm(LEjkqETV?@w{Y@zpCf4AQi&`{n z$pF7*@Z5*H$=|WE%^|x@P)S0U_y~x!Acs-^sPbOK?XS$tvYcwE9B!TeaP!M7^&Wcq zDHGM1?`a}FjE9?{Yh$3!%7woS*Bz{DSQ`TlyBcPAfau)j`~&AZbiyRM?i*7I9mQ1u z$0B4Z6s?+U(PSY;$=HX3-hE(Zb8~YeyvpT$*S5B{=c6C)z**C~Khgx|GU_=>vWiKi zG{8Ulvf!kVV}8eG%%S(MR*CbuH^LxB+6&l(IlBl0X2gaM?)LAYNX%blW&ZT-^uR#B zdiCYdTy0lxa6}dj@fGsY#Ft+rub^GS>;8K^l}anoBC0d%(lvtbR791;)!R?oCiC=2 zTmiM=m7;^v9R4sA1`FJ$LmSF@ZouV*=;4$L0AOte{uN;F57pocly!h;VVniGIrT=o=_E7v&SJ`DP@v`d@lrp%?B`Y3Th^yrxnP(zW!Rz( z6$NRVAqvLS1fjMlf#e`xeY>4lC5%k=VW7prz*>0G*viMadwPk-=Q|8kb{aRMwflPW zBgy#Ayfj%!%kcbO=UzV)`*bReq6f@Rans%on+Id&&?8OQDazQ$Aa`UnnR}70`JH(9 z%a>mQ&W-p}6V_A5atEz9y-N#oI>HGd9-N0O@97tIP4+C zuLk1r8_zIr;?(rXp18b@X=-p?{R(XoyyavvU8JQ>iC|IGmeP27J^BWE9TLSG zol;FNc=Wq&bc*UGM2vz!U@cVmXXC!KE)P%lC-YfnA?n%D+~CPYS}~6Oi zau}-pKF@qqUsb+S#uT~4E1tQ-O-Z#L_+b4z+eZLXiaUlE_lh($i}d+)*0mZvoe)E7 z(K!(g{mR)N+0u3X>A!x>u;>+2sL4joB+iJ5%ruOogliYjv5N)`G#g6Bvb?j^3FvyE z>}TSitmP&Pc< z4tgwXfd#MS=KKF4qcsSzW3_7sItBd4g`1%6!^CPu<`*S zCV_BuaUV>~a+q-(ns?BcVyKta$BY5Vn^E&*j*!x~VFhMwo&9}?`9bbeka7gtQSnUk zGl)ro63?h3?eepK6(m;k2eq5z>CAmRJ>l56DFO;eQKqLnc7V6~tC*9zaUTa%^^^I#xB+vCnPS6X3y&($w_5!gR(=)Z(_tQ3t>$>G z?0HLq+_`*fa@_U#Tq}@9E@pmyK`9&fkkZP6q;&i3kv?E~?seZn_g5fAfIE=5uo3$_^DVc{z6WM^XI_ zEh7FnXK2h>KH2Z_)UWmE?KRJ{K#_N@=UR<5p7*qE@laB&NwyNEOX&j7D)hXLLzrsq ztwo7HQp*1f6mu)tx+I@^1wa3l#U}gLv9V2oM0+O%ZZIxP(quwN>yh`HyP?R-EVEjZ zzs>;#6HFms)I%8Y&{0p_l82DMq!#P)ips%tn91eEGK)WzH`jd7Jekq{_{Pj)T^F?^ zisau^^__<4&cO-{r8H+Yks60qP3>NfH3_qY@8+X+%I$_)J=GjD^UDPVpJpkph2mQ6 z-%fQBHlk4g)xwB?}`^-vWn=iO3|3g_{8;anLMy^W2H?%^tH{o%j9!3W2Cs~!w9 z0f&ni10{;3z$R4J*8du`OugJwS60r(5^XCNy;#RYCAmp0sb#^?dM~^2Wb}ID@dddy zhtJ)7^&YTBQ(mj4JRU$XFemiRq;s(*C|2svV20c3>gsmG`HYN9IFGX~ttdo2V}W_M z4YOP0pARA+^Mop0!}h{coKC^Is$O{f_H9xguZi@3g704Ut(uP=aKzuby?fH~)a1Bp z=9AqFwmJCZQuD_-^Co|s_HjCLWz?`wZjH!yfKjtzK6zw*N>`@QmpzfqLo)j+@59Aq zTiruH+PfZ%xv})k$2$*r^^MkXGE)3}+|^?+vk%q8XU_I>lC?zM3r z_Vhc4154qdn=&Q4t?SO&gMZ)EY}qX})xV4DicvNDoE1y*V)~3vV2U^0f!|lTt|&_E z(ZEh`YM<^|W)fFw$q(zwcS;sh5^F3}$-AN>BTG;FEx(YF$vl6)$}kcR^Gq;zq7Eyy zYMseZvlC10w*=L~6BuZdn@7shSX+ai<>2v&8nueLUZPs@FfIiT1*FHkY;9u}NI+#K zNgLbqi+S(2soR--eKPcRD{a@?VPBZY{p@Acd&~sI=(^(KkN^CyVftX24kXdt<34!J zlBO)u^SbKpCruqQR<_d+BN{b*U#ip*#fCTOMO<1gm;VZ4V+FmBX3L_4NDI{85K$2I zj_+xHUtG-6E)qofUICVZer~p`61z?GYe_RM%L=QkQplTGch=aw9_fJ-f>xy+nSb)L zYzqSe1LB62;uRS{uWLM#4u^0#gu=kU%~OF=)aC;pbA0av&&A32H{62p&F9xmOFt71 z74tE4$WlyXN)~(+!{Wt!R-vEV;)q?&ZdNrKo8gVZvu$ZN{d^`hU>?Hp$ z{C4`&o7;>|PEOx4#9;e+DXisampC<80CIg9z_WedS2_QqL14U%+wi*kQyS%hp@(i& z$?FEq3$wqcD{amzGJ4!HcenQ!leXIv6d5ouyc&59vGqHvq)XM+)YWA)D{i?Rg2}h3 zLDf>n*zae%HEZL|iz4{+8J~CW2UmRyi$AoFsl*H&&%|8$Wmi43 zPk#Ay2dw^(p!zK+XfEJ^8i}v1dY^n`6a*6%F#4JT#}!)9H?!sR%*^j1oQIx@=N>(# z50Q!P_^QJ6CVO{#v3!U?Pb!k0g6O09luh4 zU~Q&t(b=@L=-|cNQ&Wf)_FTyhMZ)GG{`R1F1L5kgeQbCGLyjYqz1Z6MUTvEDKYWpZ zee_s*1+XnedGS*g^eME~iK0cfx^9jnWhzq@eARpnzJt`whm4cWmx;MO*U7l7$p$z) z-&k^UI0>(>xQch59So`#jnJ>pv>gYzh(5R^wQo9Yo!EXTr*&6Rp>*(*%cSMcA?0oG ze%twXCJSc0CLfFGe~`6zuXXOu2VAsG-xO7J-Mw{md`#D8KR`zl*l)A=)Qk~TDe?CH zn16daOU*q6ocW2$T(<`NZ$A4o-~64aD1|{hiuED=XLrCbO?*NEfp7RL6Y!3L+&prK zx)0u{AxEzfhPJvWqt$aEfBJAA zho-;+%b7m2fyQ9$zE~^L*$d-OPu} zsQBDaF@wgc&Xl3Wyy9Xa>8!Wzl=bD#$0ADPVpOkM7Q75whs zS61$!ginuG&#`cLax|F(ti*RO%i}DPi;ES(dk6N?(DA4F^O{<(vk`#JF>%QiVK+{R z`eELj@wg!neW!DEIL?sU5zEO=_>=Saq!N`_#+NTNJI>{L&E|we@GfQUd9lkyc0^UZ ze@(UR=Tx6IC3>N6oPJ4?UhitPTXR>iQi2ew%s+SHJ0npsI*kJ>gwpTaW;iOtp7+dV z>$sf%Qh0IXiwE6N>$!(g=c+4IX7>il$b52aY&b~9HnvIrEURhjD=mK%Q)MQB>V_6M z{_P#1blqZSz}wWgkSME?)0;!&y%}aVfJlh?+YY!(H_U!zaU_s}`F`szm&p~lT}ycf z^`W#m40d{I8n$J2yTgPq*);C(CEB=(ivx9I{*wsgJ;MzJ)jOdoa`m+&g}aDFK7*iC2V#YoJt&C&^?IrNtRve_wkfiprxAq~EJ~okQ=$c|Y{>n@?0(%f(+*!LUo6 zq1!T36XoMU@Iuzo3W4}|KqivD%?+%(BN>QtZyG|3{Z7a1AC65(l>g)YLxSV$ch1bh zLMup*TQH;$QiKbwWQTfmW@g3}X&R`{;E?d#iO^n8uI%to3A4CAqjXkZ>_M_39Hv{_ z`?)z&GM+N@P&na>HT(NpSBb+1?V9@pcT;$>8fwpIe~|sr3;!_E{}W~Uf}agXA@KK1 zCj4mSg5{{3etYSAELb?(A0iCckwq6ICG~dNo&*P@LpB61j@G&|Mzz(jK8tOc9)hEb zxOg*Qc}n>VGBUE48yiV-xeU#If?x~^?J|Tm3qg)IqCbOSdX5XJ;l*p(mm@Z^*{WHC z*1>z|Nel~}G0Q338nw>dSWfNpw4hF)Q@DQQyJ!kSyJ4DhH5j_$gam=?&xbEM6Ry$_ zlLD|cAt|YwLiA|zgUtf3wT-Ao|Hfa_b@I@sJc^;1pB`I6#l|`+^nr606$~=W08N~7 zpR~)_#@NqM6Pp7fnRA^Cu57DCf3VYnkl){6tgBi#LA+9@XLU!!Qt4HE669su)l7qE z{DEM=MWar@>Be+J-FyTa=(vs%u{7J7=YL(OdhZd`l6K^u4t{Cl;mI#*%xft zo&j!O66m4)mU!1N+!t6zZAJ;DE5q)wsj64Y7b3xu{`?!#nP6xR8fiLD&`^ZHljn$> z@elp8@LaTI*6o{CLe9erH1g=g5o*p>HLZ3)yI9Hp5bZ+7a-5NBr_rGV>l^tq*}aRa zjdhOV54{-%#7_S)+;;#R9zeN7pUtKufK#xqV*QoPo$x-`-)DeJ5xCCixhe(qrChiC z9W$=kJ=#B$b$FAYBqAV~ePM0w(bwk*qpc!tm5-OpdCnk`>06_}w}UlDKCKg536`cP^)pzN9kGt38$4*IIngg`n=?S;by zKG6NR&_Azrl~VjV7rWn|IcDJIs%1R+-siK=3A9#K+ zli&d4;nvf(eMSgjm55avpnrf9-Tii_*PQ3`>|%h%GbbL4lj+JR+vxm>sXvrA6Ie;f zqcI=5@s%Xr&#vT3g~z3MiixWM`JvxIV7u}&{{~Egi7AU`cLYcP0qBaM1{bkdFo?S+ z_AoB1vNHbuXel7@N!*TGSg)fS-`I*9Pat4FIsnqB}A7Qv{NgUQ9G5*CaKnyeO$g zuEEeX$mR~x(v5XcyucA=?Xw5gHPai$3V~POKX(qc#5Af@gNFAgh=7g za_(+atPnU`&QB5m2pX+#SXK{wHf9bEi-pc7AC6b(4%Vmpf_sJvKNNl;BZ<2ABTPRR zTDF~np4huHZOVFj*rbaV-~v(Yd&t)`@58;n#A4{TKN1`o>cb(cr>%VpQmmO^yZ|96 z-fkn7h%yoa(*czV1q?^PQ>iP{&2{;^5&R}IA|hfko_{uyUuR}sax=HbJwD@+&W?pL zp_!P10o!#{V5;?XtAE$hWNIKt8O3TOu>$tiC{RII|z_S2BeFxv-a0WeVsbn z$HOZLPFUI6C2Ov{AYc!?cHO(_93zPFIde+CC5QtArW~(+cX zeFrJ<2<{8$xG&t`pVU7oFE2;z8X!XLo`l3qi5tS50k=(4s3A|jvt2AlgJ;v|XCUhV zTHXPm4qG3^#jHt#Ie8}jza)kHC;`D-akWvs(@(o9SDEy^h^Z2G!9Msw_xXs z9{e(c+;(JM1AINJfsDocB;$IMPxgv{0__ZIsBD9&CZBxo7l|C5GGhdvfhbm={<g(EaG54$$&mZ`wX0wQnq;!?l)f)@z_!~+H#`9?|AfqbM= zqg2~v%*f;Fd{mC)4^>>SZi1?PKIUQ!YAtGj`Ja^A?d++1N^YR;>Vn0a${Oo?gb)9C_HVGQYO9 z-2rqGQeg>y!uNd%`{rU*Y@M8IvRwknLkItmA2wBBSMFKG2|ZM_+z@@bF4%ZnRNCnS zZ}88A1){^D6029BlqKMGk_JYJ8E6sM*^$SGZd?HGo#N51i<`jKd~ds(b2Zr zN0pQyF%k0G05&1Uqpdx|>v;L{W&Hz2+6R$9|KKlYAM+aaelYMr5;BAl*QVz~uK^Kq z;(hc5#wo~h2Wy3|swBgyawBoD7l5-YYiyjsMTCJCI3@({P+$Xtz^&$1Rz6jnh}9D~ zTfnk-&-wd9)^p@;TmhLvFp^;=mqs3agsGMmDd;03j20y% zB+5qfp&LVR7u-8Mc|Dkuw+!V0KSw~Ki;IgKZuBQ@s(=_zd9Ri3ZA=@;E7K5orbCta z?Yr9_AYxN`#+;7?=Lf}D&SbxHAmp&_Hu4j*G-NLvOAvdy2ym}3D>tDqH z4(wL=&E@4h$l37Q@6f2XudhizDIx*~pITh$;ln^KT=XkQ;5^vxJOC=eAX$+2P@y&n zCH{3d?qm}!mIgBK=YeBRqav8fin#v+=_8QT8ugPNzQS|@YXKms>OLX45(|Y8Cc21W z9)bts(H7p0w$bCHp?SHp;|%k4M%cetjc)+I0h>v1W+}UC1(a9ta8uLLVnC<6G7F(@ zix5Rd%gwFE`#S46SpKtp`c3WOe(8aLJVgy50$m}4O^5l{w5D3g(20+}OV z>VbpQ|QuhDpi35P_ z@&Bvtz2mX$-}rx(L?IDLW`rawBO=MXk`b~JWrvheW>kc%ima?q$5%f@89qL-}`ZQKf1YG&g(qi<9Hv(^LV`?W$JVEvxtEK3C)z!(q*Y0Z2ti3 z%;Axw;iz6kl;?0l2j`^xziF1KCjcp~Q!wCum~g876o1qi*qpaK$gIFh zg%IEYQ27ail($zB6&r6%dO}tUa$FdDSk=5y*gqR9lG3za3GN3NrJ~?x;1D!3JFAeR zk4hdfk-@=04dq4C&k0EVyn_aNZ>3ksk4EwZm52iwUI~;Bxaq_NdwY9j=RY1JuuxXk zkHCIn5%Yst)Of9d6E=>O2$-OBHPrRA502QDU{DD!?5y1Kol$4HMn~}g-%XVawnA6A z3Gq7&+6iw1YG#qAq+b(YotlV0&=jk~p_N}olo;P%9VEf>?I#*CF_p11-=)Bsb&OcF zn8Q>E7j$AZdDh2`lgb`$m8V^Hy};eTqW(3$h|RJQ_nuHS!OmM<1Pf)VHa|vpwZY^CeSHC@5%|YtAbMv@5z_-{>Koc5)J>@Y~{7 ztDVmGjpwLD)YZNc0`Y_64>amHWe-N&CfmlVyFbG9N~qDjy2$tKKV3~zCu&@78l-nV ziccij8Xo6LNpYR-4pZ>UwXC^)r`p4`vKBH`9#h3V?pQd%atFJsk;hc0@Y7LVYVOXF z-S}eR`g4z#wi?fX=R(Sjc-m5v)~_yCbkf>BrfBp3qBbR^aE`bN9BznclAUL`k{&+4 z_}z{9q+6jlI#L}-oRkjyQOQYTU)8Gn>58Y-*wTcy!S%;`6D(0O6rWaX10B zphJKii;ord$kh40pF>n`eC>r+p8L$DfZZIe5S0^r#%HS&dsN@L&FAsj-T9BcR}beq z`ttnhEYG(Ad|jCOqxLv)GhL(>|;ES>-DPoN(OS1Tk)jMcQ-En&U-JtdGM#bxc1 zN?6?O`ah?l2Q&(fqS~*OH&H0Tq2qHhUX|mPfBQqa6rOM0=L!L?nW<Qsnyl1umrgog^(ui+)e>cXIcgcJE1Njrl&bmgC67;^^=K=>bOOh(%oG0pK z#U{^*9TQ`D!%j$O!Ej|9{3sn;2Crc{sDH$SL z#m*yeJOqJtDGK7AeC=jxKH zp%>afUXEc5?ft}HvIt^abbeTMWhtHm`I`8@XTDD_U7|M*i@qXdQg6eNXE$>^;Q90C zSm-HGHH5${72`2=AEw-WNLeeQ$3uitezx z@x$BuS7qk2+y*kcLZdj56{hH;7rzcwS3Z4udk4GwZ6NmN^z=s0O9OHg!wg2~bZ5Zv z+AC+X^`#?c%WhCe#-Eoh@_m|CuWH(`bm8?mBct9+V@!;Ufc5V-S<;`T6Q@zkfAJ#V zfMe+$a5Yp-R6<_C!NL4OLcEf%qk0tc)_Q1_QijfY3Uu6<^cwgaJST^+ZR%)sdAsJP(;=r{Vo{PNM$(=#QudQL=4 zMhL7H6hz=7BPbQJU!0b&Y0uic*L<=1&gKLiTfqeiOG~3g@&byz5q#P+ZAlqtp6>)} z92(mE^DV5{I_#XfzF}oT*8j$m=T>vCR(a{)H(SRhQoC)LC2k&cjM z=bdiP?MI?Md~Nd*vpt?D)bEHoPl)nnQgd-ygO0wZ(-BV1K))0NGw^9%*t}E+RtJA; zq&4cbJWEMDC$ODAEyX&yc#Hm2`umgT zvdjwi@4J%V>8h5Q$XTkLsn_V}cJ&3*{`5|xn69^Jib*a$n(1kOKKcnM56bRyELq)5K4L^+w9y={ zD3l&~B#?UK%j^h3^9lu4AB4n&(j-D2Q+XCH+c)CnGsiJ`MiH>kMG#XsnbgqMR&9DE z9_Od@PEDtQho&E^Huc9(u83sG8`fQo%o`c5NEa)*ruy1p?(MHM|84zu<4Wz1 z;aj9H`HU9YbZLPLT$d*#ky7*<>5E8?uV1Ni`B;8UX1)CNrLQ#HhXn**N}Q4No7u;a zcj@Pe&06`Inx@BTXDcrA)UUdYzi#TWkTe)}l`)##xbQJnGKr79DrDHeb-Y=)o0CMp zyQMTPS(DXboJ|T1zQT5#QC4wJAJXaQXnw9NnYU%?y*GB2^%IqEvbqcJM~kADEFYal zchi)8(gD}3tgqjFh)RQjbx4tP?;cHsZ>E>9#De%1iV-u-rK2RMv(Q|tluZ69wGncG zFYNo!26^rQmbN$PHlkL)MI5WIh_9?jW7r?Rxl9+C%TZU8#-B>si&K{-Lx#$B(}MGb*Q6sgiu-1w=n4fpIM+_^P7$7GLx=!wzPo1-)oWv)FSQ{ zC2NY3-*i^^a!Dk`r?-RMb1IJ0i|!udSUhO{eLn6oKa<_is5ACL>|k1ap=(P_QP6#E?sf4I$2W0pRRgs{DLt=TXYGkF*YoPhr8duq zXUVO@Ba_YLZTcNzxil!WZp%@r|9oNEy8mswv@7SG?2m;GeQptXzQ=DT!w9`dFIw0m zvGt*1$Rtx7EZK55BQrnpR#gJoAW*|}_kP@9DKEJ{ zs^+;xGBENXnc4T$yI+!@XjLhi$W=tqPdRd zJti}wk?T_`Sh5rnqr3c>f&JNpw%th|8JdCbbt{L{V+BGIIdK(l{R>vznPkGA2<6l* z|7~FSVtMFAut52a?ObNhOrgM1e)Bs?CV4Oai7%S`9CyI6JSuo6L$uv7 z`Y zRzS81Z;rg0$>NV9V(()*s=~Ye z7Dk2%5{B8dt>ZCWxgX0!m#>hTk8-tZsWz)|OHUl(7s%rkYfLWX=T3J~pY6OtDY>kp zZ&d%YU*|MUm1{7~A-TN0&vovc$#^>zO=>>;?#HxZ#W>>)B09D6<;+sY_h>8posM-#y&+b+bu@;nnX{tSAbqhY z@LM2$Z|^WACj?Qajvz8rm4hQS*1m>VEU)hg_A(>Yl8aN<~BWy***^ zK?9C_mnU{7Xv*E^A)T#QH_et{LOoW7!z@8l3jZx{SQ>eoUvHVDF@aTOrgJj?#P4UU zCqn(9ly3Q>D-EfiTJsErX^!i&3N2P`JZG}(OAGH3#e?SPqePCc>egzo=K1R@2ZF1r zs?cbmMNZ2oPF2Jrp**qc;YL7JPp@f&KQ7|PJT*qUX0*+uh`3%uXhQD4K}`4&FspRlk^}XJ0Hb} z6#7o@A{O3n?%c*4^6bpM!?)K)g{#u977pP>PMtNoHrRX9ZwyQtNi9|n8MjGp$}3c@ z{#zdWykPm^oT=wH7q3?NBUQezyoyEls~3H(ua|6Idl1O`w_?b+!R&ZuQ8?|t^ZS#^ z|C~(H7+mZy>Bx{)t?JNrt)k0d?~Ie_(o@rmJ)1yUy?>Lf;$f5%h3_WWSGV7%K^Z9D z+wS_iKP*app9LkgIe;&IAwhr+kHHpz{I^i09e&m4F&t%Z__#rxqMOzsdEvmuALBso zZpU9s{IF8DbMeo{o=q}8n-kTqz2mz+bZxTK1G8^xZuvgkkgOVQg%pT?^Uu-5-7&h3 z&aZ5GBu}5_Zft4IzF}Fmd@npA;^5w$EP^f?5b(!HNJC;5$#NWe08`9ElK)egiw*kD zd7kl=W#lw zcVw4mwPcq4&4PnVsnNnn_PTt*f%Yax^Lv9V-l~h@L%mhSeGb>p$q49L zDW2+>^`2#~1%$PR#nF_v7~V>$wL`0IwG^Uzl@ynUO#9)q1qM^s(j|7xBPUsjHAskLeYO0oQ-kVeqk zYkRbviyW`Mq;r9oZBNQE2?+`B;xEewsX}*W`QT?``1*x41U>|z$U$5Q;t(1U-Z9Rm7JR|xNqNi=TpQy+Pw~@ zJpruR)Y4MtScvv2TlUVKXw@V+?cro#V!vPS$aid>+9{`R3o$=15FDCIH+L({?E~w$ zHu2o%=U1-ixMLhIy*6ilZk1$Hn@H-I^=J0poDeJMb+ELu;v&)GkVX^jG~z}h9dZwe zR&-oa_znA3*;%=izRZ5TXDD4EYcX4tPp&ZxDGd2u%#z~n-v{LhAhqhr>ch*BqZwc*21 zQPFVAOC3N?E8?`m_3Qk@kIo^k-PtyV4ETMpQ$`_%SlKc%v!8*Lij8(knvp%zW>?<% z^Qo1|g;C=jsRa?{!69wf74|&pVBQ*rd*@tm>`Gr1!=Dh!i(`|M4b>BJr0G9XWh3Dy zSS)QmT8f=BHPuv8qa;d7x&-(G;)*Dc7TI>(MM-%lkpeh#=FE@w{9US_c8NrF2^ZG2 zW!;2T?3g;!Fb7>t=qkrMyULkUl?^Xv95^@DHiX*_Z~R*j-mz|Gy1DW-d0^EmdA-u! z*Mn|x-l9Lq$9t_q0LjX^km4i!V&`>DOf>>y=^n?-=0~Amgrqhl%+X|J-zdD6nxC6v zmUJLD+l=)eIapA;W+H`{#8H#UO@pnu`|Ze$i4C8uc;DP>)f<(*&-|*pD>h$v`TkAZ zmz5T9io1tqsy=h~U^Qp=#Pd;;+Z z1jl!UD%oiaUQgplyby4ao_iJu5hOK;%GIOD$dU86Pz{kHWMDQoR%xQ^@{m=ry}=?N zRJXcR-L&%H#(dktRLs(P9PP$8%h9$E8`or3VRDPRq>8XGJ7B{h9n&& z71bWLOd=Hte4mi!8uernr$SWL6UzL)XY!=NyjyF0lNgQ)f$Uz6dbRHd1<^U}-L4U^w&tz! zAh9O6O$q~^MKDb;O}nj^M>ZQ%5iSrV zVEs)xE@u3sM)i?g+gAnfCs5PWv_?(`S7=J92(b9#&T2s3GbpDcf%b$PE&KgmZPZoE zmQj3d*_1RlYRR&@ZI_4EOJY4X*G)y~v$C>!%Ut*>+@@c=cwcd(I3pv2Fm{9;%gA?& zwRIZYyj`ZoHGO&2p*k53uiAyflvNLr%sZtfORe9E$iSNF>DV=>d=TIi$}>AJQ$7hu zfg0QwIKaTegg$~noC!YBpO`28GgdCy6eb7V{`LJ z^aaP^@DqQYzIxT3b=4WNr-T&;l3K{$(-*voMx-@|;Tx^0jJu{EuOS z8kqfeFK;*pl+SG2Wr*rMls&{?deafN^H*MTn5b-PagS*;+GYv(B;eC0dZsr8bk#MK zj^$%QdUg_$_Vv%VuJX}T$#8IFOGsoJZwN&c2B#-`r`GNmGFv1O)z%C>F?i+?N&A!2(NeD%X_42YyN({5Nzi;iwsBShC}FWPwPn47Fe;HQiYV? z$4;%2ny9e*^}rd|ys#Hx;;h{dULeE=sL@3M(vIi~1ABpdwfJGIC(FMJi?dDE_i*PW z*F4K`8{(k54VjI%uOe5%CY-rBoX)B3d?=gIh6mI&E^zX~{FYS)U(5d3$vEdukVy)s zrEfoZ!U7IuW@)KmaB%R*g&L-idj$U!+1AtXTG8Oe;0^iO+LY1+&4ieoaL-TF0*q(S zlZ`}^*{xYodwHX#w^SpgW8?9^w$@6C6Ak&WUmAmM2H`gIoof%V5T0uPjKtFD#Kin? zFeB^nSpSSScQ*`ZpDU(2+Pcczy?c6QVPT%f;!1WReNuUkVJ2vGZC#78bOu%FBKa+W zE$=0ILWiQS=w4y#VJTLb>M9=}9i4#$Zfb`us+Uqh!NGIJ7hgN{)}iyiPqo)^h=JsW`7m142vB-bu z#2e+G*oWim+ofNv7u^OF&Yl(Y@$oUu8ibD<;ZZ|aNdTKj-S*!K|IYj}Xg5N00F~}@ zL}dq!oKQ8;(a})@C4nUjIr!o0GT@EstxLLu7Y60YjBZ+pvvf=@B!%*ciemK%MzQW0 zqC6CC^)h``7CSI8MV!7X6&YW>C`NYeQEY4@c!ScZ*M0D{f6`OJ0-q!>ywD%Xx9@R; z(hO>;HFhP#;CKZD9A~CxH&ddarBC&Ma)%MGBrn(t{lC+L$(SN&lGxlM^9yAMu{Qp< zz19l4B73tkGby3S3dDjaTAzlK$|+8|wOXZdTsx6)vo`&@!6fd(a?w430F7X*#w87v zjT=z2Sy@>@*&(^*_+~XxC%Z* zLpl(2Y$D3fQ0!=IX<4wl2)5xPD$6jf@#_iGua)=1k}qo0%1W>}{~;b@-Shrb3=rB+ z1cAjlBk=CsJ3+H5R%|+KZv6_{50_+L9Xocc7wi?5mKPw5OtlX4&zzJO&R%0(zQ9@f zn?@M~DV7ETKY%X-J#ZQFyT-`x09Xi9@iWe0qB#g-JoyRY59DcVa4o3{X#xGl2DzsrvC?jEx1z=sG%17)P6|9xz$ zoz)P_p9fDx`5)5)J(EdlrApK3F2fr_F}vbh0&w9M+P0FRxdPPAGgL!h4HrVO2UWj) z>=P)sU4kISX~KSLmF?x}b1`CVeOtmH>j9TI9(nodrZEGiwUZz)pc|7!R3`t2a)3TQ zdFx+0R8Ic)q+yZvv%l;ZYGwydoah52rlvNOnU!n4GB*Yenu~P{v~w-%{Hcl@dUfy) z-w5Ch+r^cR)a`%=Eg&gHjH;R}aIAD391p<68#|6AQ_<2As!TAS3)1G_O2(_1&>xw!RFB;-g!O0CY7!@<3h;1OVEVc`b=v2@Tj2wIPdl9Cft4d|msPoA8?Z_hUrbolmW zKP+*esizvw$^~o~a9xU?KyRrNH%g1**S;mds0e+R8t(4LQOEbPb zoq$P%HVQWsM*xivT|fS%=n4Z?Z6Hg4soo)R0NHG5aAqi;C!uh@=fDAVAD@%hp$2D=LySHOFxjfypl-_jt*xb(Ufs*+$1&6QmVSpWX@) zkRO0X9S6<;5rrB|D)u+%=xi}FGeb)jvi7^7S@aZoU0)m|C9i!8ZL#KtD=qM3h$!m0 zsR686$0`+Xavb4P0XJqCFdsgA7?y5eIPleHfHFb!fsBE=`9WMP>W)~ruudF; zNyy#1TX9bV^|Ri=c@8rLIwXjdYRvN=#>NKW7mAC6zS>KeSRo8Q^E?9FU~otX5^p@m zjz!|>4oy!#FwL`psUB8kIz~q2D_0JCE&hhB4{j(b+q}4;kPAZ92h4!p`SbA0(*!#L zDiWXzq7%?HM2|K;15m!+l4~3?iQxzUArnK$uYfiJheXf7fGq&+bc8D+csCVDAHiic zHdYP43^$Pgn4!=@sADH5b70v&Bqzs)M}oy@2Q6!jrPv-OCKc4XVW$G+R2(4?x$#O# z#k99;V@>&jUy8;;aTaN(@8lSIxGr#&U#flO@%Uf85+UFutQpu{P<|n<3rGq4aYx6; zonbWyy-6HSP~;<&+F;cMh6#D4-RQW0FbJZsgNF`n_p3$ta0yRKPhX!NmjWOapC6AN zpC5n09?pQTUcSr)FmDHdO6Rp@C;V0oZEZS`H;@$4)zu~Bo`5_O)x=8E-8JxP!!za* z6bwb39MX;8I0QObB!81}?<;E0Lq0JSs+OsgYburi78;f(FU3dVAdHJ8PD@=t2D*pav2LUF0vD*pRLLAZI}yJ!otKx4mlXt zRPOW)XQ<6iC!*zGFB20z4o4&s6)_>6_r$Q!kde_)l9Uwmpf}8{hGY~T43r^2_%2=`@w(z{(YaGZo_#OUORkZVi6xcoWYcsO!7nY0K}`2 za7+T&hjCcL3j_~PQc@BuH#hefsBzQ`rMb8iC^qscE5fc8IQ~7paX~89V(Qn|t5Kp~R4zZ36ER#m zW$@MUv7?xjq>`u#_qotnE?8wTq|tkCvlBO`-owDb9k7pu^LCXsb#3~?+gvXxn=B86 zIt+9>+E=7IPEGqbopwof;gEAX{>}4G!r;W!_|1jtn+v`d2TdxTIAe_Rkn(z(F%2Uu z`S%_q1M4}!(*#4s1TuFB14UQ@w=u{uR*oQ43#o1s8#XCADyqXlGLok)Sze2bAdpEB zCEq-cY!P7z6JvkSc}e6|ad8w+8PvwM4gswsMIb&iLBvX$Ljyl2*&j&t@btE~*I;*v z7#$ko+;Saz2u~ASbRUu}6SnR=>pt?$A3hux5vjq$Iwmil3?c4=q;KfKDKZoU!N}3u z)6)R9bC&2c5sMo|w4{~R(TLuJh*|dp8X6iH0JCy%Ol+*LUXhGnX+1Ihkf*P&&j?LE zh%#mY4GIbhj&^FvCqB{A)TGtIUZu_d7Rd@nxE&&b^9H7dZPWuxd&IN02@7RqEJvL3 zfNo&{SoQB$7EcqlEHUh`@CmeWbCXh6SI6;mDUv4{fFetnO44zsyI6l9qk}UTX1X`# zcx+@OBB-^8JRT4hD=aOI1tv~N5PEcKNXLMY(^oP9pvIAQTX4r*Xc(5CqWTU6}2zo(|GEG)Q7 zaE7rJ|A6Njf{41m!cEvBpBYNG9|8g>ATyRHi(3BbS>uqls=2*w!vh54K$rX^f6$dj0yfv#o6q$F0A6@O3kfF~;{JPTxRqW&=b+ zYk)gcG@~Csp20BSA%Sw9Cms|C;V%ONE&u*`esgMIONfmfBH+;eeiLFSJyP>0*2TUl zYcn&B-EiOq5{5I-qbAD;ke>W8u*9COS`A0br!|3RYx42&^19EBlJJyHE_~MIX$oZb z3_>9P2D(YYCZ#o4K^)N&!c%6`#*Rh;c4=pS==hkR4GCiCq&Y08;&EsDq5Dx$QQ?8E z5KWj^KA&j7_`yMF78jOMKdhEmPwaUZl8``3?Ck9P{p;63vc)9~kivoj>|vw`T$9k2 z8Au9olVA<~7`rBq2hilLLs(UG?U~5ZU%WUjElnc({o@BG>CcyZKQedxvIt8@N1>^k zCrEQZXUJ;^5jh?sUETWayOQW^TET8_gr_yWuSUp21>~cK?3pGV+YpWRjeL6C9_bh(?x}yfKjNox` zcGl^61g*EnWbQ*XcYI63UESOmPW_tqnn-k`CsS2bjZ@M;eb+vV&JQy~__(0Ar0kUGVD$5UBe?7P-!DfT?q{^-%8 zMSWAhr>7@?245-c)oHN7&QxTavj(*b{<-SeYd2J3`ilmsy=-i3IMXU0XH`MJqRfdC zSPt6z`a)2JC*QgS>5EGa4%ASzR6+~Dztz>tC4C(o9d|IN{w^)0Wn@sHTauZDg@BBM za&v_~#!Ky%laqUymlxPDQoFo-{QK;285tRDfgL?Pfmk1)54#7C6F+iVU40kK7%36SyS1Eib91i{4MTD?Ej@jQeNXPazNzX(!xT9`$}7(=M~U1sjQ(vgYfAR z?#$P(Ps&#fOiV(-?fdcY^6_1rZii?W_ZstOq=~K;t?wGeVHDpK}wfFZY{3Ah^yPN14B&&I zyF0b2ihX2c1X-U`xFx?d9Wiz>I54V2B_!@)gr%jVY(c$l|9;=8NLlO(gaZI9%kl9A z1O#5eOpBPG*47j!lXs)B9jh#yH-7y7t%QS}r>EzTt4v3Kf2g5g0RCNEyovK1{PMOR z(a)|qTGD^lT{isAoh{4jJ~;bR)6&*i7p7!o?E|eXiX1!US6i!q5eChL%h#{d-Me@1$FE;o$*>~S zPTfqyjl#pl^uVX{@32+6c1@Vj+=aZ}vs~`0SFdhfXN!xESM>Fje-a<>J1?VSV6Y>v z2RpCy$B!Q&`d8yv!p%&Lk4VhKW5*cM($a`U2Dyp4VG$e|Fc8@!lu-CZbe1nZ_P#VzyUXYc3NCrhjeE75#F9n+ve)d7^7UdUCvW+36^41 z5g9g24ENvquE}Gj@?d%)8u6L0#6b#ech#$3ec2}3zP&e-?%DiPSuN2zcx`^^eHqhQ zwN$cw-o@$Tn;#`N;%;pm8~>*|)l)37Wk|kd!t?z~^7y}{$(aWUlN`4ae6Qv96ejsx zi{I=qnU+~jYvuA?@R&C%4wH9Dn3UVM-o2tcx~ah*926APm|Xu<{to^U#J?A%)!s{d=U(dn{YU;Ee6z;t_k(0gC(Mpil2l^I P@DE8@Qz`fKrMv$JNz<_8 literal 0 HcmV?d00001 diff --git a/Docs/index.md b/Docs/index.md index 49370fbcf..a7e682caf 100644 --- a/Docs/index.md +++ b/Docs/index.md @@ -21,7 +21,7 @@ * [General Structure](benchmark_structure.md) * [Creating Your Benchmark](benchmark_creating.md) * [Computed Performance Metrics](benchmark_metrics.md) - +

Advanced topics

* [CARLA settings](carla_settings.md) @@ -41,3 +41,4 @@ * [How to add assets](how_to_add_assets.md) * [CARLA design](carla_design.md) * [CarlaServer documentation](carla_server.md) + * [Build system](build_system.md) diff --git a/Doxyfile b/Doxyfile index 3940101b1..36409b425 100644 --- a/Doxyfile +++ b/Doxyfile @@ -11,7 +11,7 @@ CASE_SENSE_NAMES = YES SORT_BRIEF_DOCS = YES WARN_IF_UNDOCUMENTED = NO WARN_LOGFILE = Doxygen/warnings.log -INPUT = Unreal/CarlaUE4/Source Unreal/CarlaUE4/Plugins/Carla/Source Util/CarlaServer/source +INPUT = Unreal/CarlaUE4/Source Unreal/CarlaUE4/Plugins/Carla/Source LibCarla/source FILE_PATTERNS = *.cpp *.h *.hpp *.cc RECURSIVE = YES SOURCE_BROWSER = YES @@ -26,7 +26,7 @@ FORMULA_FONTSIZE = 12 GENERATE_LATEX = NO MACRO_EXPANSION = YES EXPAND_ONLY_PREDEF = YES -INCLUDE_PATH = Unreal/CarlaUE4/Source Unreal/CarlaUE4/Plugins/Carla/Source Util/CarlaServer/source Util/CarlaServer/include +INCLUDE_PATH = Unreal/CarlaUE4/Source Unreal/CarlaUE4/Plugins/Carla/Source LibCarla/source INCLUDE_FILE_PATTERNS = *.h *.hpp HIDE_UNDOC_RELATIONS = NO HAVE_DOT = YES diff --git a/Makefile b/Makefile index 1afd6ab56..5faab3686 100644 --- a/Makefile +++ b/Makefile @@ -1,104 +1,6 @@ -INSTALL_FOLDER=$(CURDIR)/Unreal/CarlaUE4/Plugins/Carla/CarlaServer -PYTHON_CLIENT_FOLDER=$(CURDIR)/PythonClient/test -BASE_BUILD_FOLDER=$(CURDIR)/Util/Build/carlaserver-build -MY_CMAKE_FOLDER=$(CURDIR)/Util/cmake -MY_CMAKE_FLAGS=-B"$(BUILD_FOLDER)" -DCMAKE_INSTALL_PREFIX="$(INSTALL_FOLDER)" - +include Util/BuildTools/Vars.mk ifeq ($(OS),Windows_NT) -BUILD_RULE=build_windows -CLEAN_RULE=clean_windows -CALL_CMAKE_RULE=call_cmake_windows -PROTOC_COMPILE=cmd.exe /k "cd Util & call Protoc.bat & exit" -PROTOC_CLEAN=cmd.exe /k "cd Util & call Protoc.bat --clean & exit" +include Util/BuildTools/Windows.mk else -BUILD_RULE=build_linux -CLEAN_RULE=clean_linux -CALL_CMAKE_RULE=call_cmake_linux -PROTOC_COMPILE=./Util/Protoc.sh -PROTOC_CLEAN=./Util/Protoc.sh --clean +include Util/BuildTools/Linux.mk endif - -default: release - -### Build ###################################################################### - -debug: BUILD_FOLDER=$(BASE_BUILD_FOLDER)/debug -debug: MY_CMAKE_FLAGS+=-DCMAKE_BUILD_TYPE=Debug -debug: $(BUILD_RULE) - -release: BUILD_FOLDER=$(BASE_BUILD_FOLDER)/release -release: MY_CMAKE_FLAGS+=-DCMAKE_BUILD_TYPE=Release -release: $(BUILD_RULE) - -vsproject: BUILD_FOLDER=$(BASE_BUILD_FOLDER)/visualstudio -vsproject: MY_CMAKE_FLAGS+=-DCMAKE_BUILD_TYPE=Release -vsproject: MY_CMAKE_FLAGS+=-G "Visual Studio 14 2015 Win64" -vsproject: call_cmake - -vsproject15: BUILD_FOLDER=$(BASE_BUILD_FOLDER)/visualstudio -vsproject15: MY_CMAKE_FLAGS+=-DCMAKE_BUILD_TYPE=Release -vsproject15: MY_CMAKE_FLAGS+=-G "Visual Studio 15 2017 Win64" -vsproject15: call_cmake - -build_linux: MY_CMAKE_FLAGS+=-G "Ninja" -build_linux: call_cmake - @cd $(BUILD_FOLDER) && ninja && ninja install - -build_windows: MY_CMAKE_FLAGS+=-G "NMake Makefiles" -build_windows: call_cmake - @cd $(BUILD_FOLDER) && nmake && nmake install - -call_cmake: protobuf $(CALL_CMAKE_RULE) - @cd $(BUILD_FOLDER) && cmake $(MY_CMAKE_FLAGS) "$(MY_CMAKE_FOLDER)" - -protobuf: - @$(PROTOC_COMPILE) - -call_cmake_linux: - @mkdir -p $(BUILD_FOLDER) - -call_cmake_windows: - -@mkdir "$(BUILD_FOLDER)" - -### Docs ####################################################################### - -docs: doxygen - -doxygen: - @doxygen - @echo "Documentation index at ./Doxygen/html/index.html" - -### Clean ###################################################################### - -clean: $(CLEAN_RULE) - @$(PROTOC_CLEAN) - -clean_linux: - @rm -Rf $(BASE_BUILD_FOLDER) $(INSTALL_FOLDER) Doxygen - -clean_windows: - -@rd /s /q "$(BASE_BUILD_FOLDER)" "$(INSTALL_FOLDER)" Doxygen - -### Test ####################################################################### - -check: debug launch_test_clients run_test_debug kill_test_clients - -check_release: release launch_test_clients run_test_release kill_test_clients - -run_test_debug: - @-LD_LIBRARY_PATH=$(INSTALL_FOLDER)/shared $(INSTALL_FOLDER)/bin/test_carlaserverd --gtest_shuffle $(GTEST_ARGS) - -run_test_release: - @-LD_LIBRARY_PATH=$(INSTALL_FOLDER)/shared $(INSTALL_FOLDER)/bin/test_carlaserver --gtest_shuffle $(GTEST_ARGS) - -launch_test_clients: - @echo "Launch echo client" - @python3 $(PYTHON_CLIENT_FOLDER)/test_client.py --echo -v -p 4000 --log echo_client.log & echo $$! > echo_client.pid - @echo "Launch carla client" - @python3 $(PYTHON_CLIENT_FOLDER)/test_client.py -v -p 2000 --log carla_client.log & echo $$! > carla_client.pid - -kill_test_clients: - @echo "Kill echo client" - @kill `cat echo_client.pid` && rm echo_client.pid - @echo "Kill carla client" - @kill `cat carla_client.pid` && rm carla_client.pid diff --git a/Rebuild.sh b/Rebuild.sh deleted file mode 100755 index 879e79483..000000000 --- a/Rebuild.sh +++ /dev/null @@ -1,121 +0,0 @@ -#!/bin/bash - -################################################################################ -# Updates CARLA content. -################################################################################ - -set -e - -DOC_STRING="Update CARLA content to the latest version, to be run after 'git pull'." - -USAGE_STRING="Usage: $0 [-h|--help] [--no-editor]" - -# ============================================================================== -# -- Parse arguments ----------------------------------------------------------- -# ============================================================================== - -LAUNCH_UE4_EDITOR=true - -OPTS=`getopt -o h --long help,no-editor -n 'parse-options' -- "$@"` - -if [ $? != 0 ] ; then echo "$USAGE_STRING" ; exit 2 ; fi - -eval set -- "$OPTS" - -while true; do - case "$1" in - --no-editor ) - LAUNCH_UE4_EDITOR=false; - shift ;; - -h | --help ) - echo "$DOC_STRING" - echo "$USAGE_STRING" - exit 1 - ;; - * ) - break ;; - esac -done - -# ============================================================================== -# -- Set up environment -------------------------------------------------------- -# ============================================================================== - -SCRIPT_DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )" -pushd "$SCRIPT_DIR" >/dev/null - -UNREAL_PROJECT_FOLDER=./Unreal/CarlaUE4 -UE4_INTERMEDIATE_FOLDERS="Binaries Build Intermediate DerivedDataCache" - -function fatal_error { - echo -e "\033[0;31mERROR: $1\033[0m" - exit 1 -} - -function log { - echo -e "\033[0;33m$1\033[0m" -} - -if [ ! -d "${UE4_ROOT}" ]; then - fatal_error "UE4_ROOT is not defined, or points to a non-existant directory, please set this environment variable." -else - echo "Using Unreal Engine at '$UE4_ROOT'" -fi - -# ============================================================================== -# -- Make CarlaServer ---------------------------------------------------------- -# ============================================================================== - -log "Making CarlaServer..." -make clean && make debug && make release - -# ============================================================================== -# -- Clean up intermediate Unreal files ---------------------------------------- -# ============================================================================== - -pushd "$UNREAL_PROJECT_FOLDER" >/dev/null - -pushd "Plugins/Carla" >/dev/null - -log "Cleaning up CARLA Plugin..." -rm -Rf ${UE4_INTERMEDIATE_FOLDERS} - -popd > /dev/null - -log "Cleaning up CARLAUE4..." -rm -Rf ${UE4_INTERMEDIATE_FOLDERS} - -popd >/dev/null - -# ============================================================================== -# -- Build and launch Unreal project ------------------------------------------- -# ============================================================================== - -pushd "$UNREAL_PROJECT_FOLDER" >/dev/null - -# This command usually fails but normally we can continue anyway. -set +e -log "Generate Unreal project files..." -${UE4_ROOT}/GenerateProjectFiles.sh -project="${PWD}/CarlaUE4.uproject" -game -engine -makefiles -set -e - -log "Build CarlaUE4 project..." -make CarlaUE4Editor - -if $LAUNCH_UE4_EDITOR ; then - log "Launching UE4Editor..." - ${UE4_ROOT}/Engine/Binaries/Linux/UE4Editor "${PWD}/CarlaUE4.uproject" -else - echo "" - echo "****************" - echo "*** Success! ***" - echo "****************" -fi - -popd >/dev/null - -# ============================================================================== -# -- ...and we are done -------------------------------------------------------- -# ============================================================================== - -popd >/dev/null diff --git a/Setup.sh b/Setup.sh deleted file mode 100755 index 9a6a29e0d..000000000 --- a/Setup.sh +++ /dev/null @@ -1,227 +0,0 @@ -#! /bin/bash - -################################################################################ -# CARLA Setup.sh -# -# This script sets up the environment and dependencies for compiling CARLA on -# Linux. -# -# 1) Download CARLA Content if necessary. -# 2) Download and compile libc++. -# 3) Download other third-party libraries and compile them with libc++. -# -# Thanks to the people at https://github.com/Microsoft/AirSim for providing the -# important parts of this script. -################################################################################ - -set -e - -DOC_STRING="Download and compile CARLA content and dependencies." - -USAGE_STRING="Usage: $0 [-h|--help] [-s|--skip-download] [--jobs=N]" - -# ============================================================================== -# -- Parse arguments ----------------------------------------------------------- -# ============================================================================== - -UPDATE_SCRIPT_FLAGS= -NUMBER_OF_ASYNC_JOBS=1 - -OPTS=`getopt -o hs --long help,skip-download,jobs:: -n 'parse-options' -- "$@"` - -if [ $? != 0 ] ; then echo "$USAGE_STRING" ; exit 2 ; fi - -eval set -- "$OPTS" - -while true; do - case "$1" in - -s | --skip-download ) - UPDATE_SCRIPT_FLAGS=--skip-download; - shift ;; - --jobs) - case "$2" in - "") NUMBER_OF_ASYNC_JOBS=4 ; shift 2 ;; - *) NUMBER_OF_ASYNC_JOBS=$2 ; shift 2 ;; - esac ;; - -h | --help ) - echo "$DOC_STRING" - echo "$USAGE_STRING" - exit 1 - ;; - * ) - break ;; - esac -done - -# ============================================================================== -# -- Set up environment -------------------------------------------------------- -# ============================================================================== - -SCRIPT_DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )" -pushd "$SCRIPT_DIR" >/dev/null - -# Require clang 3.9 -command -v clang++-3.9 >/dev/null 2>&1 || { - echo >&2 "clang 3.9 is required, but it's not installed."; - echo >&2 "make sure you build Unreal Engine with clang 3.9 too."; - exit 1; -} - -mkdir -p Util/Build -pushd Util/Build >/dev/null - -# ============================================================================== -# -- Get and compile libc++ ---------------------------------------------------- -# ============================================================================== - -# Get libc++ source -if [[ ! -d "llvm-source" ]]; then - echo "Retrieving libc++..." - git clone --depth=1 -b release_39 https://github.com/llvm-mirror/llvm.git llvm-source - git clone --depth=1 -b release_39 https://github.com/llvm-mirror/libcxx.git llvm-source/projects/libcxx - git clone --depth=1 -b release_39 https://github.com/llvm-mirror/libcxxabi.git llvm-source/projects/libcxxabi -else - echo "Folder llvm-source already exists, skipping git clone..." -fi - -# Build libc++ -rm -rf llvm-build -mkdir -p llvm-build - -pushd llvm-build >/dev/null - -export C_COMPILER=clang-3.9 -export COMPILER=clang++-3.9 - -cmake -DCMAKE_C_COMPILER=${C_COMPILER} -DCMAKE_CXX_COMPILER=${COMPILER} \ - -DLIBCXX_ENABLE_EXPERIMENTAL_LIBRARY=OFF -DLIBCXX_INSTALL_EXPERIMENTAL_LIBRARY=OFF \ - -DCMAKE_BUILD_TYPE=RelWithDebInfo -DCMAKE_INSTALL_PREFIX="../llvm-install" \ - ../llvm-source - -make -j $NUMBER_OF_ASYNC_JOBS cxx - -#install libc++ locally in llvm-install folder -make -j $NUMBER_OF_ASYNC_JOBS install-libcxx install-libcxxabi - -popd >/dev/null - -# ============================================================================== -# -- Get Boost and compile it with libc++ -------------------------------------- -# ============================================================================== - -# Get boost source -if [[ ! -d "boost-source" ]]; then - echo "Retrieving boost..." - wget https://dl.bintray.com/boostorg/release/1.64.0/source/boost_1_64_0.tar.gz - tar -xvzf boost_1_64_0.tar.gz - rm boost_1_64_0.tar.gz - mv boost_1_64_0 boost-source -else - echo "Folder boost-source already exists, skipping download..." -fi - -pushd boost-source >/dev/null - -BOOST_TOOLSET="clang-3.9" -BOOST_CFLAGS="-fPIC -std=c++1y -stdlib=libc++ -I../llvm-install/include/c++/v1" -BOOST_LFLAGS="-stdlib=libc++ -L../llvm-install/lib" - -./bootstrap.sh \ - --with-toolset=clang \ - --prefix=../boost-install \ - --with-libraries=system -./b2 clean -./b2 toolset="${BOOST_TOOLSET}" cxxflags="${BOOST_CFLAGS}" linkflags="${BOOST_LFLAGS}" --prefix="../boost-install" -j $NUMBER_OF_ASYNC_JOBS stage release -./b2 install toolset="${BOOST_TOOLSET}" cxxflags="${BOOST_CFLAGS}" linkflags="${BOOST_LFLAGS}" --prefix="../boost-install" -j $NUMBER_OF_ASYNC_JOBS - -popd >/dev/null - -# ============================================================================== -# -- Get Protobuf and compile it with libc++ ----------------------------------- -# ============================================================================== - -# Get protobuf source -if [[ ! -d "protobuf-source" ]]; then - echo "Retrieving protobuf..." - git clone --depth=1 -b v3.3.0 --recurse-submodules https://github.com/google/protobuf.git protobuf-source -else - echo "Folder protobuf-source already exists, skipping git clone..." -fi - -pushd protobuf-source >/dev/null - -export LD_LIBRARY_PATH="$LD_LIBRARY_PATH:$PWD/../llvm-install/lib/" - -./autogen.sh -./configure \ - CC="clang-3.9" \ - CXX="clang++-3.9" \ - CXXFLAGS="-fPIC -stdlib=libc++ -I$PWD/../llvm-install/include/c++/v1" \ - LDFLAGS="-stdlib=libc++ -L$PWD/../llvm-install/lib/" \ - --prefix="$PWD/../protobuf-install" \ - --disable-shared -make -j $NUMBER_OF_ASYNC_JOBS -make -j $NUMBER_OF_ASYNC_JOBS install - -popd >/dev/null - -# ============================================================================== -# -- Get GTest and compile it with libc++ -------------------------------------- -# ============================================================================== - -# Get googletest source -if [[ ! -d "googletest-source" ]]; then - echo "Retrieving googletest..." - git clone --depth=1 -b release-1.8.0 https://github.com/google/googletest.git googletest-source -else - echo "Folder googletest-source already exists, skipping git clone..." -fi - -pushd googletest-source >/dev/null - -cmake -H. -B./build \ - -DCMAKE_C_COMPILER=${C_COMPILER} -DCMAKE_CXX_COMPILER=${COMPILER} \ - -DCMAKE_CXX_FLAGS="-stdlib=libc++ -I$PWD/../llvm-install/include/c++/v1 -Wl,-L$PWD/../llvm-install/lib" \ - -DCMAKE_INSTALL_PREFIX="../googletest-install" \ - -G "Ninja" - -pushd build >/dev/null -ninja -ninja install -popd >/dev/null - -popd >/dev/null - -# ============================================================================== -# -- Other CARLA files --------------------------------------------------------- -# ============================================================================== - -popd >/dev/null - -CARLA_SETTINGS_FILE="./Unreal/CarlaUE4/Config/CarlaSettings.ini" - -if [[ ! -f $CARLA_SETTINGS_FILE ]]; then - echo "Copying CarlaSettings.ini..." - sed -e 's/UseNetworking=true/UseNetworking=false/' ./Docs/Example.CarlaSettings.ini > $CARLA_SETTINGS_FILE -fi - -./Util/Protoc.sh - -# ============================================================================== -# -- Update CARLA Content ------------------------------------------------------ -# ============================================================================== - -echo -./Update.sh $UPDATE_SCRIPT_FLAGS - -# ============================================================================== -# -- ...and we are done -------------------------------------------------------- -# ============================================================================== - -popd >/dev/null - -set +x -echo "" -echo "****************" -echo "*** Success! ***" -echo "****************" diff --git a/Unreal/CarlaUE4/.gitignore b/Unreal/CarlaUE4/.gitignore index 32c3e361e..a8b3ead2a 100644 --- a/Unreal/CarlaUE4/.gitignore +++ b/Unreal/CarlaUE4/.gitignore @@ -7,6 +7,7 @@ Saved Plugins/Carla/Binaries Plugins/Carla/Build Plugins/Carla/CarlaServer +Plugins/Carla/CarlaDependencies Plugins/Carla/Debug Plugins/Carla/DerivedDataCache Plugins/Carla/Intermediate diff --git a/Unreal/CarlaUE4/CarlaUE4.uproject b/Unreal/CarlaUE4/CarlaUE4.uproject index 22c8354fb..c7b4426fb 100644 --- a/Unreal/CarlaUE4/CarlaUE4.uproject +++ b/Unreal/CarlaUE4/CarlaUE4.uproject @@ -1,6 +1,6 @@ { "FileVersion": 3, - "EngineAssociation": "4.18", + "EngineAssociation": "4.19", "Category": "", "Description": "", "Modules": [ diff --git a/Unreal/CarlaUE4/Config/DefaultGame.ini b/Unreal/CarlaUE4/Config/DefaultGame.ini index 8bb2e6084..72d4d8855 100644 --- a/Unreal/CarlaUE4/Config/DefaultGame.ini +++ b/Unreal/CarlaUE4/Config/DefaultGame.ini @@ -3,7 +3,7 @@ ProjectID=675BF8694238308FA9368292CC440350 ProjectName=CARLA UE4 CompanyName=CVC CopyrightNotice="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 ." -ProjectVersion=0.8.4 +ProjectVersion=0.9.0 [/Script/UnrealEd.ProjectPackagingSettings] BuildConfiguration=PPBC_Development diff --git a/Unreal/CarlaUE4/Plugins/Carla/Carla.uplugin b/Unreal/CarlaUE4/Plugins/Carla/Carla.uplugin index 5db0a836f..83ccb0f10 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Carla.uplugin +++ b/Unreal/CarlaUE4/Plugins/Carla/Carla.uplugin @@ -1,7 +1,7 @@ { "FileVersion": 3, "Version": 1, - "VersionName": "0.8.4", + "VersionName": "0.9.0", "FriendlyName": "CARLA", "Description": "Open-source simulator for autonomous driving research.", "Category": "Science", diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Carla.Build.cs b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Carla.Build.cs index 16bc6715f..f9c74b603 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Carla.Build.cs +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Carla.Build.cs @@ -1,5 +1,6 @@ // Copyright 1998-2017 Epic Games, Inc. All Rights Reserved. +using System; using System.IO; using UnrealBuildTool; @@ -78,17 +79,7 @@ public class Carla : ModuleRules private void AddCarlaServerDependency(ReadOnlyTargetRules Target) { - string CarlaServerInstallPath = Path.GetFullPath(Path.Combine(ModuleDirectory, "../../CarlaServer")); - - string CarlaServerLib; - if (UseDebugLibs(Target)) - { - CarlaServerLib = "carlaserverd"; - } - else - { - CarlaServerLib = "carlaserver"; - } + string LibCarlaInstallPath = Path.GetFullPath(Path.Combine(ModuleDirectory, "../../CarlaDependencies")); ADelegate GetLibName = (string BaseName) => { if (IsWindows(Target)) @@ -104,23 +95,17 @@ public class Carla : ModuleRules // Link dependencies. if (IsWindows(Target)) { - // Auto-links boost libraries in folder. - PublicLibraryPaths.Add(Path.Combine(CarlaServerInstallPath, "lib")); - - PublicAdditionalLibraries.Add(Path.Combine(CarlaServerInstallPath, "lib", GetLibName("libprotobuf"))); - PublicAdditionalLibraries.Add(Path.Combine(CarlaServerInstallPath, "lib", GetLibName(CarlaServerLib))); + throw new NotImplementedException(); } else { - PublicAdditionalLibraries.Add(Path.Combine(CarlaServerInstallPath, "lib", GetLibName("c++abi"))); - PublicAdditionalLibraries.Add(Path.Combine(CarlaServerInstallPath, "lib", GetLibName("boost_system"))); - PublicAdditionalLibraries.Add(Path.Combine(CarlaServerInstallPath, "lib", GetLibName("protobuf"))); - PublicAdditionalLibraries.Add(Path.Combine(CarlaServerInstallPath, "lib", GetLibName(CarlaServerLib))); + PublicAdditionalLibraries.Add(Path.Combine(LibCarlaInstallPath, "lib", GetLibName("c++abi"))); + PublicAdditionalLibraries.Add(Path.Combine(LibCarlaInstallPath, "lib", GetLibName("rpc"))); } // Include path. - string CarlaServerIncludePath = Path.Combine(CarlaServerInstallPath, "include"); - PublicIncludePaths.Add(CarlaServerIncludePath); - PrivateIncludePaths.Add(CarlaServerIncludePath); + string LibCarlaIncludePath = Path.Combine(LibCarlaInstallPath, "include"); + PublicIncludePaths.Add(LibCarlaIncludePath); + PrivateIncludePaths.Add(LibCarlaIncludePath); } } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaEncoder.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaEncoder.cpp index 77578cae0..751a9a44e 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaEncoder.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaEncoder.cpp @@ -4,6 +4,8 @@ // This work is licensed under the terms of the MIT license. // For a copy, see . +#ifdef CARLA_COMPILE_CARLASERVER_LEGACY + #include "Carla.h" #include "CarlaEncoder.h" @@ -221,3 +223,5 @@ void FCarlaEncoder::Visit(const UWalkerAgentComponent &Agent) ::Encode(Agent.GetBoundingBoxTransform(), Data.bounding_box.transform); ::Encode(Agent.GetBoundingBoxExtent() * TO_METERS, Data.bounding_box.extent); } + +#endif // CARLA_COMPILE_CARLASERVER_LEGACY diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaEncoder.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaEncoder.h index 0c523029c..659d32658 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaEncoder.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaEncoder.h @@ -6,6 +6,8 @@ #pragma once +#ifdef CARLA_COMPILE_CARLASERVER_LEGACY + #include "Agent/AgentComponentVisitor.h" #include "Sensor/SensorDataView.h" @@ -74,3 +76,5 @@ private: carla_agent &Data; }; + +#endif // CARLA_COMPILE_CARLASERVER_LEGACY diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp index 8488d31a6..879274281 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp @@ -9,12 +9,15 @@ #include "Server/CarlaEncoder.h" -#include +#ifdef CARLA_COMPILE_CARLASERVER_LEGACY +# include +#endif // CARLA_COMPILE_CARLASERVER_LEGACY // ============================================================================= // -- Static local methods ----------------------------------------------------- // ============================================================================= +#ifdef CARLA_COMPILE_CARLASERVER_LEGACY static FCarlaServer::ErrorCode ParseErrorCode(const uint32 ErrorCode) { if (ErrorCode == CARLA_SERVER_SUCCESS) { @@ -25,6 +28,7 @@ static FCarlaServer::ErrorCode ParseErrorCode(const uint32 ErrorCode) return FCarlaServer::Error; } } +#endif // CARLA_COMPILE_CARLASERVER_LEGACY static int32 GetTimeOut(uint32 TimeOut, const bool bBlocking) { @@ -38,7 +42,12 @@ static int32 GetTimeOut(uint32 TimeOut, const bool bBlocking) FCarlaServer::FCarlaServer(const uint32 InWorldPort, const uint32 InTimeOut) : WorldPort(InWorldPort), TimeOut(InTimeOut), - Server(carla_make_server()) { +#ifdef CARLA_COMPILE_CARLASERVER_LEGACY + Server(carla_make_server()) +#else + Server(nullptr) +#endif // CARLA_COMPILE_CARLASERVER_LEGACY +{ check(Server != nullptr); } @@ -47,17 +56,26 @@ FCarlaServer::~FCarlaServer() #ifdef CARLA_SERVER_EXTRA_LOG UE_LOG(LogCarlaServer, Warning, TEXT("Destroying CarlaServer")); #endif // CARLA_SERVER_EXTRA_LOG +#ifdef CARLA_COMPILE_CARLASERVER_LEGACY carla_free_server(Server); +#endif // CARLA_COMPILE_CARLASERVER_LEGACY } FCarlaServer::ErrorCode FCarlaServer::Connect() { +#ifdef CARLA_COMPILE_CARLASERVER_LEGACY UE_LOG(LogCarlaServer, Log, TEXT("Waiting for the client to connect...")); return ParseErrorCode(carla_server_connect(Server, WorldPort, TimeOut)); +#else + UE_LOG(LogCarlaServer, Error, TEXT("CarlaServer no longer supported!!")); + return ErrorCode::Error; +#endif // CARLA_COMPILE_CARLASERVER_LEGACY } FCarlaServer::ErrorCode FCarlaServer::ReadNewEpisode(FString &IniFile, const bool bBlocking) { +#ifdef CARLA_COMPILE_CARLASERVER_LEGACY + carla_request_new_episode values; auto ec = ParseErrorCode(carla_read_request_new_episode(Server, values, GetTimeOut(TimeOut, bBlocking))); if (Success == ec) { @@ -68,6 +86,10 @@ FCarlaServer::ErrorCode FCarlaServer::ReadNewEpisode(FString &IniFile, const boo #endif // CARLA_SERVER_EXTRA_LOG } return ec; + +#else + return ErrorCode::Error; +#endif // CARLA_COMPILE_CARLASERVER_LEGACY } FCarlaServer::ErrorCode FCarlaServer::SendSceneDescription( @@ -76,6 +98,8 @@ FCarlaServer::ErrorCode FCarlaServer::SendSceneDescription( const TArray &SensorDescriptions, const bool bBlocking) { +#ifdef CARLA_COMPILE_CARLASERVER_LEGACY + carla_scene_description scene; // Encode map name. const auto MapNameBuffer = FCarlaEncoder::Encode(MapName); @@ -95,10 +119,16 @@ FCarlaServer::ErrorCode FCarlaServer::SendSceneDescription( UE_LOG(LogCarlaServer, Log, TEXT("Sending %d available start positions"), scene.number_of_player_start_spots); UE_LOG(LogCarlaServer, Log, TEXT("Sending %d sensor descriptions"), scene.number_of_sensors); return ParseErrorCode(carla_write_scene_description(Server, scene, GetTimeOut(TimeOut, bBlocking))); + +#else + return ErrorCode::Error; +#endif // CARLA_COMPILE_CARLASERVER_LEGACY } FCarlaServer::ErrorCode FCarlaServer::ReadEpisodeStart(uint32 &StartPositionIndex, const bool bBlocking) { +#ifdef CARLA_COMPILE_CARLASERVER_LEGACY + carla_episode_start values; auto ec = ParseErrorCode(carla_read_episode_start(Server, values, GetTimeOut(TimeOut, bBlocking))); if (Success == ec) { @@ -106,17 +136,29 @@ FCarlaServer::ErrorCode FCarlaServer::ReadEpisodeStart(uint32 &StartPositionInde UE_LOG(LogCarlaServer, Log, TEXT("Episode start received: { StartIndex = %d }"), StartPositionIndex); } return ec; + +#else + return ErrorCode::Error; +#endif // CARLA_COMPILE_CARLASERVER_LEGACY } FCarlaServer::ErrorCode FCarlaServer::SendEpisodeReady(const bool bBlocking) { +#ifdef CARLA_COMPILE_CARLASERVER_LEGACY + UE_LOG(LogCarlaServer, Log, TEXT("Ready to play, notifying client")); const carla_episode_ready values = {true}; return ParseErrorCode(carla_write_episode_ready(Server, values, GetTimeOut(TimeOut, bBlocking))); + +#else + return ErrorCode::Error; +#endif // CARLA_COMPILE_CARLASERVER_LEGACY } FCarlaServer::ErrorCode FCarlaServer::ReadControl(FVehicleControl &Control, const bool bBlocking) { +#ifdef CARLA_COMPILE_CARLASERVER_LEGACY + carla_control values; auto ec = ParseErrorCode(carla_read_control(Server, values, GetTimeOut(TimeOut, bBlocking))); if (Success == ec) { @@ -137,13 +179,23 @@ FCarlaServer::ErrorCode FCarlaServer::ReadControl(FVehicleControl &Control, cons UE_LOG(LogCarlaServer, Warning, TEXT("No control received from the client this frame!")); } return ec; + +#else + return ErrorCode::Error; +#endif // CARLA_COMPILE_CARLASERVER_LEGACY } FCarlaServer::ErrorCode FCarlaServer::SendSensorData(const FSensorDataView &Data) { +#ifdef CARLA_COMPILE_CARLASERVER_LEGACY + carla_sensor_data values; FCarlaEncoder::Encode(Data, values); return ParseErrorCode(carla_write_sensor_data(Server, values)); + +#else + return ErrorCode::Error; +#endif // CARLA_COMPILE_CARLASERVER_LEGACY } FCarlaServer::ErrorCode FCarlaServer::SendMeasurements( @@ -151,6 +203,8 @@ FCarlaServer::ErrorCode FCarlaServer::SendMeasurements( const TArray &Agents, const bool bSendNonPlayerAgentsInfo) { +#ifdef CARLA_COMPILE_CARLASERVER_LEGACY + // Encode measurements. carla_measurements values; FCarlaEncoder::Encode(PlayerState, values); @@ -166,4 +220,8 @@ FCarlaServer::ErrorCode FCarlaServer::SendMeasurements( UE_LOG(LogCarlaServer, Log, TEXT("Sending data of %d agents"), values.number_of_non_player_agents); #endif // CARLA_SERVER_EXTRA_LOG return ParseErrorCode(carla_write_measurements(Server, values)); + +#else + return ErrorCode::Error; +#endif // CARLA_COMPILE_CARLASERVER_LEGACY } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/RPCServer.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/RPCServer.cpp new file mode 100644 index 000000000..5871ec9aa --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/RPCServer.cpp @@ -0,0 +1,91 @@ +// 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 . + +#include "Carla.h" +#include "Server.h" + +#include +#include +#include +#include +#include +#include +#include +#include + +static FVehicleControl MakeControl(const carla::rpc::VehicleControl &cControl) +{ + FVehicleControl Control; + Control.Throttle = cControl.throttle; + Control.Steer = cControl.steer; + Control.Brake = cControl.brake; + Control.bHandBrake = cControl.hand_brake; + Control.bReverse = cControl.reverse; + return Control; +} + +class FRPCServer::Pimpl +{ +public: + Pimpl(uint16_t port) : Server(port) {} + carla::rpc::Server Server; +}; + +FRPCServer::FRPCServer() : _Pimpl(nullptr) {} + +FRPCServer::~FRPCServer() {} + +void FRPCServer::Initialize(AServer &Server, uint16_t Port) +{ + UE_LOG(LogTemp, Error, TEXT("Initializing rpc-server at port %d"), Port); + + _Pimpl = std::make_unique(Port); + + namespace cr = carla::rpc; + + auto &srv = _Pimpl->Server; + + srv.BindAsync("ping", []() { return true; }); + + srv.BindAsync("version", []() { return std::string(carla::version()); }); + + srv.BindAsync("get_blueprints", []() { + return std::vector{ + cr::ActorBlueprint{"vehicle.mustang.red"}, + cr::ActorBlueprint{"vehicle.mustang.also_red"}, + cr::ActorBlueprint{"vehicle.mustang.still_red"} + }; + }); + + srv.BindSync("spawn_actor", [&]( + const cr::ActorBlueprint &blueprint, + const cr::Transform &transform) { + auto id = Server.SpawnAgent(transform); + return cr::Actor{static_cast(id), blueprint}; + }); + + srv.BindSync("apply_control_to_actor", [&]( + const cr::Actor &actor, + const cr::VehicleControl &control) { + Server.ApplyControl(actor.id, MakeControl(control)); + }); +} + +void FRPCServer::Run() +{ + _Pimpl->Server.AsyncRun(4); +} + +void FRPCServer::RunSome() +{ + using namespace std::chrono_literals; + _Pimpl->Server.SyncRunFor(20ms); +} + +void FRPCServer::Stop() +{ + _Pimpl->Server.Stop(); +} diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/RPCServer.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/RPCServer.h new file mode 100644 index 000000000..2ec8c71b6 --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/RPCServer.h @@ -0,0 +1,35 @@ +// 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 . + +#pragma once + +#include "CoreMinimal.h" + +#include + +class AServer; + +class FRPCServer +{ +public: + + FRPCServer(); + + ~FRPCServer(); + + void Initialize(AServer &Server, uint16_t Port = 8080u); + + void Run(); + + void RunSome(); + + void Stop(); + +private: + + class Pimpl; + std::unique_ptr _Pimpl; +}; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/Server.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/Server.cpp new file mode 100644 index 000000000..2a1ab6d95 --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/Server.cpp @@ -0,0 +1,72 @@ +// 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 . + +#include "Carla.h" +#include "Server.h" + + +// Sets default values +AServer::AServer() +{ + // Set this actor to call Tick() every frame. You can turn this off to improve performance if you don't need it. + PrimaryActorTick.bCanEverTick = true; + +} + +// Called when the game starts or when spawned +void AServer::BeginPlay() +{ + Super::BeginPlay(); + + _Server.Initialize(*this); + _Server.Run(); +} + +void AServer::EndPlay(EEndPlayReason::Type EndPlayReason) +{ + _Server.Stop(); +} + +// Called every frame +void AServer::Tick(float DeltaTime) +{ + Super::Tick(DeltaTime); + + _Server.RunSome(); +} + +int32 AServer::SpawnAgent(const FTransform &Transform) +{ + check(IsInGameThread()); + UE_LOG(LogTemp, Warning, TEXT("Spawning vehicle at %s"), *Transform.ToString()); + + static int32 COUNT = 0u; + ++COUNT; + + ACarlaWheeledVehicle *Vehicle; + SpawnVehicle(Transform, Vehicle); + if ((Vehicle != nullptr) && !Vehicle->IsPendingKill()) + { + // Vehicle->AIControllerClass = AWheeledVehicleAIController::StaticClass(); + Vehicle->SpawnDefaultController(); + _Agents.Add(COUNT, Vehicle); + return COUNT; + } + return -1; +} + +bool AServer::ApplyControl(int32 AgentId, const FVehicleControl &Control) +{ + UE_LOG(LogTemp, Log, TEXT("Applying control to vehicle %d: throttle = %f, steer = %f"), AgentId, Control.Throttle, Control.Steer); + if (!_Agents.Contains(AgentId)) + { + UE_LOG(LogTemp, Error, TEXT("Vehicle %d does not exist!"), AgentId); + return false; + } + auto *Vehicle = _Agents[AgentId]; + Vehicle->ApplyVehicleControl(Control); + return true; +} diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/Server.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/Server.h new file mode 100644 index 000000000..e8cd23755 --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/Server.h @@ -0,0 +1,52 @@ +// 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 . + +#pragma once + +#include "Vehicle/CarlaWheeledVehicle.h" +#include "CoreMinimal.h" +#include "GameFramework/Actor.h" +#include "RPCServer.h" +#include "Vehicle/VehicleControl.h" +#include +#include +#include +#include "Server.generated.h" + +UCLASS() +class CARLA_API AServer : public AActor +{ + GENERATED_BODY() + +public: + // Sets default values for this actor's properties + AServer(); + +protected: + // Called when the game starts or when spawned + virtual void BeginPlay() override; + virtual void EndPlay(EEndPlayReason::Type EndPlayReason) override; + +public: + // Called every frame + virtual void Tick(float DeltaTime) override; + + UFUNCTION(BlueprintCallable) + int32 SpawnAgent(const FTransform &Transform); + + UFUNCTION(BlueprintCallable) + bool ApplyControl(int32 AgentId, const FVehicleControl &Control); + + UFUNCTION(BlueprintImplementableEvent) + void SpawnVehicle(const FTransform &SpawnTransform, ACarlaWheeledVehicle *&SpawnedCharacter); + +private: + + FRPCServer _Server; + + UPROPERTY(VisibleAnywhere) + TMap _Agents; +}; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerAIController.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerAIController.cpp index 31f8aa246..69f0279f0 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerAIController.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerAIController.cpp @@ -155,7 +155,7 @@ AWalkerAIController::AWalkerAIController(const FObjectInitializer& ObjectInitial SightConfiguration->DetectionByAffiliation.bDetectEnemies = true; SightConfiguration->DetectionByAffiliation.bDetectNeutrals = true; SightConfiguration->DetectionByAffiliation.bDetectFriendlies = true; - + Perception->ConfigureSense(*SightConfiguration); Perception->SetDominantSense(SightConfiguration->GetSenseImplementation()); Perception->OnPerceptionUpdated.AddDynamic(this, &AWalkerAIController::SenseActors); @@ -163,7 +163,6 @@ AWalkerAIController::AWalkerAIController(const FObjectInitializer& ObjectInitial TimeInState=0.0f; } - void AWalkerAIController::Possess(APawn *aPawn) { Super::Possess(aPawn); @@ -175,12 +174,12 @@ void AWalkerAIController::Tick(float DeltaSeconds) { Super::Tick(DeltaSeconds); TimeInState+=DeltaSeconds; - if (Status != EWalkerStatus::RunOver) + if (Status != EWalkerStatus::RunOver) { - switch (GetMoveStatus()) + switch (GetMoveStatus()) { default: break; - case EPathFollowingStatus::Idle: + case EPathFollowingStatus::Idle: //case EPathFollowingStatus::Waiting: //<-- incomplete path LOG_AI_WALKER(Warning, "is stuck!"); ChangeStatus(EWalkerStatus::Stuck); @@ -191,7 +190,7 @@ void AWalkerAIController::Tick(float DeltaSeconds) TryResumeMovement(); } break; - + }; } } @@ -208,7 +207,7 @@ FPathFollowingRequestResult AWalkerAIController::MoveTo( ; #endif // CARLA_AI_WALKERS_EXTRA_LOG - + ChangeStatus(EWalkerStatus::Moving); return Super::MoveTo(MoveRequest, OutPath); } @@ -221,13 +220,12 @@ void AWalkerAIController::OnMoveCompleted( #ifdef CARLA_AI_WALKERS_EXTRA_LOG UE_LOG(LogCarla, Log, TEXT("Walker %s completed move at (%s)"), *GetPawn()->GetName(), - *GetPawn()->GetActorLocation().ToString()) -; + *GetPawn()->GetActorLocation().ToString()); #endif // CARLA_AI_WALKERS_EXTRA_LOG ChangeStatus(EWalkerStatus::MoveCompleted); } -void AWalkerAIController::SenseActors(TArray Actors) +void AWalkerAIController::SenseActors(const TArray &Actors) { const auto *aPawn = GetPawn(); if ((Status == EWalkerStatus::Moving) && diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerAIController.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerAIController.h index 986d22fde..5db79ee81 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerAIController.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerAIController.h @@ -35,16 +35,17 @@ public: virtual void Tick(float DeltaSeconds) override; - + virtual FPathFollowingRequestResult MoveTo( const FAIMoveRequest& MoveRequest, FNavPathSharedPtr* OutPath = nullptr) override; - virtual void OnMoveCompleted(FAIRequestID RequestID, const FPathFollowingResult &Result) override; - + virtual void OnMoveCompleted( + FAIRequestID RequestID, + const FPathFollowingResult &Result) override; UFUNCTION(BlueprintCallable) - void SenseActors(TArray Actors); + void SenseActors(const TArray &Actors); EWalkerStatus GetWalkerStatus() const { @@ -58,19 +59,27 @@ public: float GetTimeInState() const { return TimeInState; } private: + void ChangeStatus(EWalkerStatus status); + void TryResumeMovement(); - + void TryPauseMovement(bool bItWasRunOver = false); UFUNCTION() - void OnPawnTookDamage(AActor *DamagedActor, float Damage, const UDamageType *DamageType, AController *InstigatedBy, AActor *DamageCauser); + void OnPawnTookDamage( + AActor *DamagedActor, + float Damage, + const UDamageType *DamageType, + AController *InstigatedBy, + AActor *DamageCauser); UPROPERTY(Category = "Walker AI Controller", VisibleAnywhere) UAISenseConfig_Sight *SightConfiguration; UPROPERTY(VisibleAnywhere) EWalkerStatus Status = EWalkerStatus::Unknown; + /** Continous time in the same EWalkerStatus */ float TimeInState=0.0f; }; diff --git a/Util/BuildTools/BuildCarlaUE4.sh b/Util/BuildTools/BuildCarlaUE4.sh new file mode 100755 index 000000000..950aed19f --- /dev/null +++ b/Util/BuildTools/BuildCarlaUE4.sh @@ -0,0 +1,147 @@ +#! /bin/bash + +# ============================================================================== +# -- Set up environment -------------------------------------------------------- +# ============================================================================== + +source $(dirname "$0")/Environment.sh + +if [ ! -d "${UE4_ROOT}" ]; then + fatal_error "UE4_ROOT is not defined, or points to a non-existant directory, please set this environment variable." +else + log "Using Unreal Engine at '$UE4_ROOT'" +fi + +# ============================================================================== +# -- Parse arguments ----------------------------------------------------------- +# ============================================================================== + +DOC_STRING="Build and launch CarlaUE4." + +USAGE_STRING="Usage: $0 [-h|--help] [--build] [--rebuild] [--launch] [--clean] [--hard-clean]" + +REMOVE_INTERMEDIATE=false +HARD_CLEAN=false +BUILD_CARLAUE4=false +LAUNCH_UE4_EDITOR=false + +OPTS=`getopt -o h --long help,build,rebuild,launch,clean,hard-clean -n 'parse-options' -- "$@"` + +if [ $? != 0 ] ; then echo "$USAGE_STRING" ; exit 2 ; fi + +eval set -- "$OPTS" + +while true; do + case "$1" in + --build ) + BUILD_CARLAUE4=true; + shift ;; + --rebuild ) + REMOVE_INTERMEDIATE=true; + BUILD_CARLAUE4=true; + shift ;; + --launch ) + LAUNCH_UE4_EDITOR=true; + shift ;; + --clean ) + REMOVE_INTERMEDIATE=true; + shift ;; + --hard-clean ) + REMOVE_INTERMEDIATE=true; + HARD_CLEAN=true; + shift ;; + -h | --help ) + echo "$DOC_STRING" + echo "$USAGE_STRING" + exit 1 + ;; + * ) + break ;; + esac +done + +if ! { ${REMOVE_INTERMEDIATE} || ${BUILD_CARLAUE4} || ${LAUNCH_UE4_EDITOR}; }; then + fatal_error "Nothing selected to be done." +fi + +pushd "${CARLAUE4_ROOT_FOLDER}" >/dev/null + +# ============================================================================== +# -- Clean CarlaUE4 ------------------------------------------------------------ +# ============================================================================== + +if ${REMOVE_INTERMEDIATE} ; then + + log "Cleaning intermediate files and folders." + + UE4_INTERMEDIATE_FOLDERS="Binaries Build Intermediate DerivedDataCache" + + rm -Rf ${UE4_INTERMEDIATE_FOLDERS} + + pushd "${CARLAUE4_PLUGIN_ROOT_FOLDER}" >/dev/null + + rm -Rf ${UE4_INTERMEDIATE_FOLDERS} + + popd >/dev/null + +fi + +if ${HARD_CLEAN} ; then + + if [ ! -f Makefile ]; then + fatal_error "The project wasn't built before!" + fi + + log "Doing a \"hard\" clean of the Unreal Engine project." + + make CarlaUE4Editor ARGS=-clean + +fi + +if ${REMOVE_INTERMEDIATE} ; then + + rm -f Makefile + +fi + +# ============================================================================== +# -- Build CarlaUE4 ------------------------------------------------------------ +# ============================================================================== + +if ${BUILD_CARLAUE4} ; then + + if [ ! -f Makefile ]; then + + # This command fails sometimes but normally we can continue anyway. + set +e + log "Generate Unreal project files." + ${UE4_ROOT}/GenerateProjectFiles.sh -project="${PWD}/CarlaUE4.uproject" -game -engine -makefiles + set -e + + fi + + log "Build CarlaUE4 project." + make CarlaUE4Editor + +fi + +# ============================================================================== +# -- Launch UE4Editor ---------------------------------------------------------- +# ============================================================================== + +if ${LAUNCH_UE4_EDITOR} ; then + + log "Launching UE4Editor..." + ${UE4_ROOT}/Engine/Binaries/Linux/UE4Editor "${PWD}/CarlaUE4.uproject" + +else + + log "Success!" + +fi + +# ============================================================================== +# -- ...and we are done -------------------------------------------------------- +# ============================================================================== + +popd >/dev/null diff --git a/Util/BuildTools/BuildLibCarla.sh b/Util/BuildTools/BuildLibCarla.sh new file mode 100755 index 000000000..49b73fcb3 --- /dev/null +++ b/Util/BuildTools/BuildLibCarla.sh @@ -0,0 +1,131 @@ +#! /bin/bash + +source $(dirname "$0")/Environment.sh + +# ============================================================================== +# -- Parse arguments ----------------------------------------------------------- +# ============================================================================== + +DOC_STRING="Build LibCarla." + +USAGE_STRING="Usage: $0 [-h|--help] [--rebuild] [--server] [--client] [--clean]" + +REMOVE_INTERMEDIATE=false +BUILD_SERVER=false +BUILD_CLIENT=false + +OPTS=`getopt -o h --long help,rebuild,server,client,clean -n 'parse-options' -- "$@"` + +if [ $? != 0 ] ; then echo "$USAGE_STRING" ; exit 2 ; fi + +eval set -- "$OPTS" + +while true; do + case "$1" in + --rebuild ) + REMOVE_INTERMEDIATE=true; + BUILD_SERVER=true; + BUILD_CLIENT=true; + shift ;; + --server ) + BUILD_SERVER=true; + shift ;; + --client ) + BUILD_CLIENT=true; + shift ;; + --clean ) + REMOVE_INTERMEDIATE=true; + shift ;; + -h | --help ) + echo "$DOC_STRING" + echo "$USAGE_STRING" + exit 1 + ;; + * ) + break ;; + esac +done + +if ! { ${REMOVE_INTERMEDIATE} || ${BUILD_SERVER} || ${BUILD_CLIENT}; }; then + fatal_error "Nothing selected to be done." +fi + +# ============================================================================== +# -- Clean intermediate files -------------------------------------------------- +# ============================================================================== + +if ${REMOVE_INTERMEDIATE} ; then + + log "Cleaning intermediate files and folders." + + rm -Rf ${LIBCARLA_BUILD_SERVER_FOLDER} ${LIBCARLA_BUILD_CLIENT_FOLDER} + rm -Rf ${LIBCARLA_INSTALL_SERVER_FOLDER} ${LIBCARLA_INSTALL_CLIENT_FOLDER} + rm -f ${LIBCARLA_ROOT_FOLDER}/source/carla/Version.h + +fi + +# ============================================================================== +# -- Build Server configuration ------------------------------------------------ +# ============================================================================== + +if ${BUILD_SERVER} ; then + + log "Building LibCarla \"Server\" configuration." + + mkdir -p ${LIBCARLA_BUILD_SERVER_FOLDER} + pushd "${LIBCARLA_BUILD_SERVER_FOLDER}" >/dev/null + + if [ ! -f "build.ninja" ]; then + + cmake \ + -G "Ninja" \ + -DCMAKE_BUILD_TYPE=Server \ + -DCMAKE_TOOLCHAIN_FILE=${LIBCPP_TOOLCHAIN_FILE} \ + -DCMAKE_INSTALL_PREFIX=${LIBCARLA_INSTALL_SERVER_FOLDER} \ + ${CARLA_ROOT_FOLDER} + + fi + + ninja + + ninja install | grep -v "Up-to-date:" + + popd >/dev/null + +fi + +# ============================================================================== +# -- Build Client configuration ------------------------------------------------ +# ============================================================================== + +if ${BUILD_CLIENT} ; then + + log "Building LibCarla \"Client\" configuration." + + mkdir -p ${LIBCARLA_BUILD_CLIENT_FOLDER} + pushd "${LIBCARLA_BUILD_CLIENT_FOLDER}" >/dev/null + + if [ ! -f "build.ninja" ]; then + + cmake \ + -G "Ninja" \ + -DCMAKE_BUILD_TYPE=Client \ + -DCMAKE_TOOLCHAIN_FILE=${LIBSTDCPP_TOOLCHAIN_FILE} \ + -DCMAKE_INSTALL_PREFIX=${LIBCARLA_INSTALL_CLIENT_FOLDER} \ + ${CARLA_ROOT_FOLDER} + + fi + + ninja + + ninja install | grep -v "Up-to-date:" + + popd >/dev/null + +fi + +# ============================================================================== +# -- ...and we are done -------------------------------------------------------- +# ============================================================================== + +log "Success!" diff --git a/Util/BuildTools/BuildPythonAPI.sh b/Util/BuildTools/BuildPythonAPI.sh new file mode 100755 index 000000000..89671c58a --- /dev/null +++ b/Util/BuildTools/BuildPythonAPI.sh @@ -0,0 +1,99 @@ +#! /bin/bash + +source $(dirname "$0")/Environment.sh + +export CC=clang-5.0 +export CXX=clang++-5.0 + +# ============================================================================== +# -- Parse arguments ----------------------------------------------------------- +# ============================================================================== + +DOC_STRING="Build and package CARLA Python API." + +USAGE_STRING="Usage: $0 [-h|--help] [--rebuild] [--py2] [--py3] [--clean]" + +REMOVE_INTERMEDIATE=false +BUILD_FOR_PYTHON2=false +BUILD_FOR_PYTHON3=false + +OPTS=`getopt -o h --long help,rebuild,py2,py3,clean -n 'parse-options' -- "$@"` + +if [ $? != 0 ] ; then echo "$USAGE_STRING" ; exit 2 ; fi + +eval set -- "$OPTS" + +while true; do + case "$1" in + --rebuild ) + REMOVE_INTERMEDIATE=true; + BUILD_FOR_PYTHON2=true; + BUILD_FOR_PYTHON3=true; + shift ;; + --py2 ) + BUILD_FOR_PYTHON2=true; + shift ;; + --py3 ) + BUILD_FOR_PYTHON3=true; + shift ;; + --clean ) + REMOVE_INTERMEDIATE=true; + shift ;; + -h | --help ) + echo "$DOC_STRING" + echo "$USAGE_STRING" + exit 1 + ;; + * ) + break ;; + esac +done + +if ! { ${REMOVE_INTERMEDIATE} || ${BUILD_FOR_PYTHON2} || ${BUILD_FOR_PYTHON3}; }; then + fatal_error "Nothing selected to be done." +fi + +pushd "${CARLA_PYTHONAPI_ROOT_FOLDER}" >/dev/null + +# ============================================================================== +# -- Clean intermediate files -------------------------------------------------- +# ============================================================================== + +if ${REMOVE_INTERMEDIATE} ; then + + log "Cleaning intermediate files and folders." + + rm -Rf build dist carla.egg-info source/carla.egg-info + + find source -name "*.so" -delete + find source -name "__pycache__" -type d -exec rm -r "{}" \; + +fi + +# ============================================================================== +# -- Build API ----------------------------------------------------------------- +# ============================================================================== + +if ${BUILD_FOR_PYTHON2} ; then + + log "Building Python API for Python 2." + + /usr/bin/env python2 setup.py bdist_egg + +fi + +if ${BUILD_FOR_PYTHON3} ; then + + log "Building Python API for Python 3." + + /usr/bin/env python3 setup.py bdist_egg + +fi + +# ============================================================================== +# -- ...and we are done -------------------------------------------------------- +# ============================================================================== + +popd >/dev/null + +log "Success!" diff --git a/Util/BuildTools/Check.sh b/Util/BuildTools/Check.sh new file mode 100755 index 000000000..db3609226 --- /dev/null +++ b/Util/BuildTools/Check.sh @@ -0,0 +1,131 @@ +#! /bin/bash + +source $(dirname "$0")/Environment.sh + +# ============================================================================== +# -- Parse arguments ----------------------------------------------------------- +# ============================================================================== + +DOC_STRING="Run unit tests." + +USAGE_STRING=$(cat <<- END +Usage: $0 [-h|--help] [--gdb] [--gtest_args=ARGS] + +Then either ran all the tests + + [--all] + +Or choose one or more of the following + + [--libcarla-release] [--libcarla-debug] + [--python-api-2] [--python-api-3] + [--benchmark] +END +) + +GDB= +GTEST_ARGS= +LIBCARLA_RELEASE=false +LIBCARLA_DEBUG=false +PYTHON_API_2=false +PYTHON_API_3=false + +OPTS=`getopt -o h --long help,gdb,gtest_args:,all,libcarla-release,libcarla-debug,python-api-2,python-api-3,benchmark -n 'parse-options' -- "$@"` + +if [ $? != 0 ] ; then echo "$USAGE_STRING" ; exit 2 ; fi + +eval set -- "$OPTS" + +while true; do + case "$1" in + --gdb ) + GDB="gdb --args"; + shift ;; + --gtest_args ) + GTEST_ARGS="$2"; + shift ;; + --all ) + LIBCARLA_RELEASE=true; + LIBCARLA_DEBUG=true; + PYTHON_API_2=true; + PYTHON_API_3=true; + shift ;; + --libcarla-release ) + LIBCARLA_RELEASE=true; + shift ;; + --libcarla-debug ) + LIBCARLA_DEBUG=true; + shift ;; + --python-api-2 ) + PYTHON_API_2=true; + shift ;; + --python-api-3 ) + PYTHON_API_3=true; + shift ;; + --benchmark ) + LIBCARLA_RELEASE=true; + GTEST_ARGS="--gtest_filter=benchmark*"; + shift ;; + -h | --help ) + echo "$DOC_STRING" + echo -e "$USAGE_STRING" + exit 1 + ;; + * ) + break ;; + esac +done + +if ! { ${LIBCARLA_RELEASE} || ${LIBCARLA_DEBUG} || ${PYTHON_API_2} || ${PYTHON_API_3}; }; then + fatal_error "Nothing selected to be done." +fi + +# ============================================================================== +# -- Run LibCarla tests -------------------------------------------------------- +# ============================================================================== + +if ${LIBCARLA_DEBUG} ; then + + log "Running LibCarla unit tests debug." + + LD_LIBRARY_PATH=${LIBCARLA_INSTALL_SERVER_FOLDER}/lib ${GDB} ${LIBCARLA_INSTALL_SERVER_FOLDER}/test/libcarla_test_debug ${GTEST_ARGS} + +fi + +if ${LIBCARLA_RELEASE} ; then + + log "Running LibCarla unit tests release." + + LD_LIBRARY_PATH=${LIBCARLA_INSTALL_SERVER_FOLDER}/lib ${GDB} ${LIBCARLA_INSTALL_SERVER_FOLDER}/test/libcarla_test_release ${GTEST_ARGS} + +fi + +# ============================================================================== +# -- Run Python API tests ------------------------------------------------------ +# ============================================================================== + +pushd "${CARLA_PYTHONAPI_ROOT_FOLDER}/test" >/dev/null + +if ${PYTHON_API_2} ; then + + log "Running Python API for Python 2 unit tests." + + /usr/bin/env python2 -m nose2 + +fi + +if ${PYTHON_API_3} ; then + + log "Running Python API for Python 3 unit tests." + + /usr/bin/env python3 -m nose2 + +fi + +popd >/dev/null + +# ============================================================================== +# -- ...and we are done -------------------------------------------------------- +# ============================================================================== + +log "Success!" diff --git a/Util/BuildTools/Environment.sh b/Util/BuildTools/Environment.sh new file mode 100644 index 000000000..03a334009 --- /dev/null +++ b/Util/BuildTools/Environment.sh @@ -0,0 +1,47 @@ +#! /bin/bash + +# Sets the environment for other shell scripts. + +set -e + +CURDIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )/../.." && pwd )" +source $(dirname "$0")/Vars.mk +unset CURDIR + +if [ -n "${CARLA_BUILD_NO_COLOR}" ]; then + + function log { + echo "`basename "$0"`: $1" + } + + function fatal_error { + echo -e >&2 "`basename "$0"`: ERROR: $1" + exit 2 + } + +else + + function log { + echo -e "\033[1;35m`basename "$0"`: $1\033[0m" + } + + function fatal_error { + echo -e >&2 "\033[0;31m`basename "$0"`: ERROR: $1\033[0m" + exit 2 + } + +fi + +function get_carla_version { + git describe --tags --dirty --always +} + +function copy_if_changed { + mkdir -p $(dirname $2) + rsync -cI --out-format="%n" $1 $2 +} + +function move_if_changed { + copy_if_changed $1 $2 + rm -f $1 +} diff --git a/Util/BuildTools/Linux.mk b/Util/BuildTools/Linux.mk new file mode 100644 index 000000000..a1100969e --- /dev/null +++ b/Util/BuildTools/Linux.mk @@ -0,0 +1,57 @@ +ARGS=--all + +default: help + +help: + @less ${CARLA_BUILD_TOOLS_FOLDER}/Linux.mk.help + +launch: LibCarla + @${CARLA_BUILD_TOOLS_FOLDER}/BuildCarlaUE4.sh --build --launch + +launch-only: + @${CARLA_BUILD_TOOLS_FOLDER}/BuildCarlaUE4.sh --launch + +package: CarlaUE4Editor PythonAPI + @${CARLA_BUILD_TOOLS_FOLDER}/Package.sh + +docs: + @doxygen + @echo "Documentation index at ./Doxygen/html/index.html" + +clean: + @${CARLA_BUILD_TOOLS_FOLDER}/BuildCarlaUE4.sh --clean + @${CARLA_BUILD_TOOLS_FOLDER}/BuildPythonAPI.sh --clean + @${CARLA_BUILD_TOOLS_FOLDER}/BuildLibCarla.sh --clean + +rebuild: setup + @${CARLA_BUILD_TOOLS_FOLDER}/BuildLibCarla.sh --rebuild + @${CARLA_BUILD_TOOLS_FOLDER}/BuildPythonAPI.sh --rebuild + @${CARLA_BUILD_TOOLS_FOLDER}/BuildCarlaUE4.sh --rebuild + +hard-clean: clean + @rm -Rf ${CARLA_BUILD_FOLDER} + @${CARLA_BUILD_TOOLS_FOLDER}/BuildCarlaUE4.sh --hard-clean + +check: PythonAPI + @${CARLA_BUILD_TOOLS_FOLDER}/Check.sh $(ARGS) + +benchmark: LibCarla + @${CARLA_BUILD_TOOLS_FOLDER}/Check.sh --benchmark + @cat profiler.csv + +CarlaUE4Editor: LibCarla + @${CARLA_BUILD_TOOLS_FOLDER}/BuildCarlaUE4.sh --build + +.PHONY: PythonAPI +PythonAPI: LibCarla + @${CARLA_BUILD_TOOLS_FOLDER}/BuildPythonAPI.sh --py2 --py3 + +.PHONY: LibCarla +LibCarla: setup + @${CARLA_BUILD_TOOLS_FOLDER}/BuildLibCarla.sh --server --client + +setup: + @${CARLA_BUILD_TOOLS_FOLDER}/Setup.sh + +pretty: + @${CARLA_BUILD_TOOLS_FOLDER}/Prettify.sh $(ARGS) diff --git a/Util/BuildTools/Linux.mk.help b/Util/BuildTools/Linux.mk.help new file mode 100644 index 000000000..28f4d7627 --- /dev/null +++ b/Util/BuildTools/Linux.mk.help @@ -0,0 +1,77 @@ +Welcome to CARLA Simulator! +=========================== + +This Makefile will help you building the different CARLA utilities. + +Use the following commands: + + help: + + Display this help message. + + launch: + + Compile CarlaUE4 project and launch it in Unreal Engine's Editor. + + launch-only: + + Launch CarlaUE4 project in Unreal Engine's Editor, but skip building + step (assume the project is already built). + + package: + + Makes a packaged version of CARLA ready for distribution. + + docs: + + Build CARLA Doxygen documentation. + + clean: + + Remove intermediate build files. + + rebuild: + + Remove intermediate build files and rebuild the whole project. + + hard-clean: + + Remove intermediate build files and dependencies, and force a + recompilation of Unreal Engine's pre-compiled headers. Useful for + fixing "version.h has been modified since the precompiled header" + errors. Beware, recompilation takes a long time! + + +There are also some lower level commands for building individual modules helpful +for developers: + + check: + + Run unit test suites for LibCarla and PythonAPI. + + benchmark: + + Run the benchmark tests for LibCarla. + + CarlaUE4Editor: + + Build CarlaUE4 project, but do not launch the editor. + + PythonAPI: + + Build and package the Python API module for Python 2 and 3. + + LibCarla: + + Build the LibCarla library, both "Server" and "Client" configurations. + + setup: + + Run the setup step only. + + pretty: + + Prettify code files. Run uncrustify on C++ files or AutoPEP8 on Python + files. To prettify a single file, use: make pretty ARGS=-f/path/to/file. + + diff --git a/Package.sh b/Util/BuildTools/Package.sh similarity index 59% rename from Package.sh rename to Util/BuildTools/Package.sh index 155fd65d9..92155640d 100755 --- a/Package.sh +++ b/Util/BuildTools/Package.sh @@ -1,20 +1,15 @@ #! /bin/bash -################################################################################ -# Packages a CARLA build. -################################################################################ - -set -e - -DOC_STRING="Makes a packaged version of CARLA for distribution. -Please make sure to run Rebuild.sh before!" - -USAGE_STRING="Usage: $0 [-h|--help] [--no-packaging] [--no-zip] [--clean-intermediate]" +source $(dirname "$0")/Environment.sh # ============================================================================== # -- Parse arguments ----------------------------------------------------------- # ============================================================================== +DOC_STRING="Makes a packaged version of CARLA for distribution." + +USAGE_STRING="Usage: $0 [-h|--help] [--no-packaging] [--no-zip] [--clean-intermediate]" + DO_PACKAGE=true DO_COPY_FILES=true DO_TARBALL=true @@ -47,39 +42,21 @@ while true; do esac done -# ============================================================================== -# -- Set up environment -------------------------------------------------------- -# ============================================================================== - -SCRIPT_DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )" -pushd "$SCRIPT_DIR" >/dev/null - -REPOSITORY_TAG=`git describe --tags --dirty --always` - -echo "Packaging version '$REPOSITORY_TAG'." - -UNREAL_PROJECT_FOLDER=${PWD}/Unreal/CarlaUE4 -DIST_FOLDER=${PWD}/Dist -BUILD_FOLDER=${DIST_FOLDER}/${REPOSITORY_TAG} - -function fatal_error { - echo -e "\033[0;31mERROR: $1\033[0m" - exit 1 -} - -function log { - echo -e "\033[0;33m$1\033[0m" -} - # ============================================================================== # -- Package project ----------------------------------------------------------- # ============================================================================== +REPOSITORY_TAG=$(get_carla_version) + +BUILD_FOLDER=${CARLA_DIST_FOLDER}/${REPOSITORY_TAG} + +log "Packaging version '$REPOSITORY_TAG'." + if $DO_PACKAGE ; then - pushd "$UNREAL_PROJECT_FOLDER" >/dev/null + pushd "${CARLAUE4_ROOT_FOLDER}" >/dev/null - log "Packaging the project..." + log "Packaging the project." if [ ! -d "${UE4_ROOT}" ]; then fatal_error "UE4_ROOT is not defined, or points to a non-existant directory, please set this environment variable." @@ -105,34 +82,25 @@ if [[ ! -d ${BUILD_FOLDER}/LinuxNoEditor ]] ; then fi # ============================================================================== -# -- Copy files (Python server, README, etc) ----------------------------------- +# -- Copy files (Python API, README, etc) -------------------------------------- # ============================================================================== if $DO_COPY_FILES ; then DESTINATION=${BUILD_FOLDER}/LinuxNoEditor - log "Copying extra files..." + log "Adding extra files to package." - cp -v ./LICENSE ${DESTINATION}/LICENSE - cp -v ./CHANGELOG.md ${DESTINATION}/CHANGELOG - cp -v ./Docs/release_readme.md ${DESTINATION}/README - cp -v ./Docs/Example.CarlaSettings.ini ${DESTINATION}/Example.CarlaSettings.ini - cp -v ./Util/Docker/Release.Dockerfile ${DESTINATION}/Dockerfile + pushd ${CARLA_ROOT_FOLDER} >/dev/null - rsync -vhr --delete --delete-excluded \ - --exclude "*.egg-info" \ - --exclude "*.log" \ - --exclude "*.pyc" \ - --exclude ".*" \ - --exclude ".tags*" \ - --exclude "__pycache__" \ - --exclude "_benchmarks_results*" \ - --exclude "_images*" \ - --exclude "_out*" \ - PythonClient/ ${DESTINATION}/PythonClient + copy_if_changed "./LICENSE" "${DESTINATION}/LICENSE" + copy_if_changed "./CHANGELOG.md" "${DESTINATION}/CHANGELOG" + copy_if_changed "./Docs/release_readme.md" "${DESTINATION}/README" + copy_if_changed "./Docs/Example.CarlaSettings.ini" "${DESTINATION}/Example.CarlaSettings.ini" + copy_if_changed "./Util/Docker/Release.Dockerfile" "${DESTINATION}/Dockerfile" + copy_if_changed "./PythonAPI/dist/*.egg" "${DESTINATION}/PythonAPI" - echo + popd >/dev/null fi @@ -142,12 +110,12 @@ fi if $DO_TARBALL ; then - DESTINATION=${DIST_FOLDER}/CARLA_${REPOSITORY_TAG}.tar.gz + DESTINATION=${CARLA_DIST_FOLDER}/CARLA_${REPOSITORY_TAG}.tar.gz SOURCE=${BUILD_FOLDER}/LinuxNoEditor - pushd "$SOURCE" >/dev/null + pushd "${SOURCE}" >/dev/null - log "Packaging build..." + log "Packaging build." rm -f ./Manifest_NonUFSFiles_Linux.txt rm -Rf ./CarlaUE4/Saved @@ -165,7 +133,7 @@ fi if $DO_CLEAN_INTERMEDIATE ; then - log "Removing intermediate build..." + log "Removing intermediate build." rm -Rf ${BUILD_FOLDER} @@ -176,16 +144,10 @@ fi # ============================================================================== if $DO_TARBALL ; then - FINAL_PACKAGE=Dist/CARLA_${REPOSITORY_TAG}.tar.gz + FINAL_PACKAGE=${CARLA_DIST_FOLDER}/CARLA_${REPOSITORY_TAG}.tar.gz else - FINAL_PACKAGE=Dist/${REPOSITORY_TAG} + FINAL_PACKAGE=${BUILD_FOLDER} fi -echo -echo "Packaged version created at ${FINAL_PACKAGE}" -echo -echo "****************" -echo "*** Success! ***" -echo "****************" - -popd >/dev/null +log "Packaged version created at ${FINAL_PACKAGE}" +log "Success!" diff --git a/Util/BuildTools/Prettify.sh b/Util/BuildTools/Prettify.sh new file mode 100755 index 000000000..631e6e909 --- /dev/null +++ b/Util/BuildTools/Prettify.sh @@ -0,0 +1,137 @@ +#! /bin/bash + +# ============================================================================== +# -- Set up environment -------------------------------------------------------- +# ============================================================================== + +source $(dirname "$0")/Environment.sh + +# ============================================================================== +# -- Parse arguments ----------------------------------------------------------- +# ============================================================================== + +DOC_STRING="Prettify code files." + +USAGE_STRING="Usage: $0 [-h|--help] [--all] [-f path|--file=path]" + +PRETTIFY_ALL=false +PRETTIFY_FILE=false + +OPTS=`getopt -o hf: --long help,all,file: -n 'parse-options' -- "$@"` + +if [ $? != 0 ] ; then echo "$USAGE_STRING" ; exit 2 ; fi + +eval set -- "$OPTS" + +while true; do + case "$1" in + --all ) + PRETTIFY_ALL=true; + shift ;; + -f | --file ) + PRETTIFY_FILE="$2"; + shift ;; + -h | --help ) + echo "$DOC_STRING" + echo "$USAGE_STRING" + exit 1 + ;; + * ) + break ;; + esac +done + +if ! { ${PRETTIFY_ALL} || [ -n "${PRETTIFY_FILE}" ]; } ; then + fatal_error "Nothing selected to be done." +fi + +if ${PRETTIFY_ALL} ; then + PRETTIFY_FILE=false +elif [[ ! -f ${PRETTIFY_FILE} ]] ; then + pwd + fatal_error "\"${PRETTIFY_FILE}\" no such file." +fi + +# ============================================================================== +# -- Get latest version of uncrustify ------------------------------------------ +# ============================================================================== + +mkdir -p ${CARLA_BUILD_FOLDER} +pushd ${CARLA_BUILD_FOLDER} >/dev/null + +UNCRUSTIFY_BASENAME=uncrustify-0.67 + +UNCRUSTIFY=${PWD}/${UNCRUSTIFY_BASENAME}-install/bin/uncrustify + +if [[ -d "${UNCRUSTIFY_BASENAME}-install" ]] ; then + log "${UNCRUSTIFY_BASENAME} already installed." +else + rm -Rf ${UNCRUSTIFY_BASENAME}-source ${UNCRUSTIFY_BASENAME}-build + + log "Retrieving Uncrustify." + + git clone --depth=1 -b uncrustify-0.67 https://github.com/uncrustify/uncrustify.git ${UNCRUSTIFY_BASENAME}-source + + log "Building Uncrustify." + + mkdir -p ${UNCRUSTIFY_BASENAME}-build + + pushd ${UNCRUSTIFY_BASENAME}-build >/dev/null + + cmake -G "Ninja" \ + -DCMAKE_BUILD_TYPE=Release \ + -DCMAKE_INSTALL_PREFIX="../${UNCRUSTIFY_BASENAME}-install" \ + ../${UNCRUSTIFY_BASENAME}-source + + ninja + + ninja install + + popd >/dev/null + + rm -Rf ${UNCRUSTIFY_BASENAME}-source ${UNCRUSTIFY_BASENAME}-build + +fi + +command -v ${UNCRUSTIFY} >/dev/null 2>&1 || { + fatal_error "Failed to install Uncrustify!"; +} + +popd >/dev/null + +command -v autopep8 >/dev/null 2>&1 || { + log "Installing autopep8 for this user." + pip3 install --user autopep8 +} + +# ============================================================================== +# -- Run uncrustify and/or autopep8 -------------------------------------------- +# ============================================================================== + +UNCRUSTIFY_CONFIG=${CARLA_BUILD_TOOLS_FOLDER}/uncrustify.cfg +UNCRUSTIFY_COMMAND="${UNCRUSTIFY} -c ${UNCRUSTIFY_CONFIG} --no-backup --replace" + +AUTOPEP8_COMMAND="autopep8 --jobs 0 --in-place -a" + +if ${PRETTIFY_ALL} ; then + + find ${CARLA_ROOT_FOLDER} -iregex '.*\.\(py\)$' -exec ${AUTOPEP8_COMMAND} {} + + # find ${LIBCARLA_ROOT_FOLDER} -iregex '.*\.\(h\|cpp\)$' -exec ${UNCRUSTIFY_COMMAND} {} \; + +elif [[ -f ${PRETTIFY_FILE} ]] ; then + + if [[ ${PRETTIFY_FILE} == *.py ]] ; then + log "autopep8 ${PRETTIFY_FILE}" + ${AUTOPEP8_COMMAND} ${PRETTIFY_FILE} + else + log "uncrustify ${PRETTIFY_FILE}" + ${UNCRUSTIFY_COMMAND} ${PRETTIFY_FILE} + fi + +fi + +# ============================================================================== +# -- ...and we are done -------------------------------------------------------- +# ============================================================================== + +log "Success!" diff --git a/Util/BuildTools/Setup.sh b/Util/BuildTools/Setup.sh new file mode 100755 index 000000000..214e7daf0 --- /dev/null +++ b/Util/BuildTools/Setup.sh @@ -0,0 +1,267 @@ +#! /bin/bash + +# ============================================================================== +# -- Set up environment -------------------------------------------------------- +# ============================================================================== + +command -v /usr/bin/clang++-5.0 >/dev/null 2>&1 || { + echo >&2 "clang 5.0 is required, but it's not installed."; + echo >&2 "make sure you build Unreal Engine with clang 5.0 too."; + exit 1; +} + +export CC=/usr/bin/clang-5.0 +export CXX=/usr/bin/clang++-5.0 + +source $(dirname "$0")/Environment.sh + +mkdir -p ${CARLA_BUILD_FOLDER} +pushd ${CARLA_BUILD_FOLDER} >/dev/null + +# ============================================================================== +# -- Get and compile libc++ ---------------------------------------------------- +# ============================================================================== + +LLVM_BASENAME=llvm-5.0 + +LLVM_INCLUDE=${PWD}/${LLVM_BASENAME}-install/include/c++/v1 +LLVM_LIBPATH=${PWD}/${LLVM_BASENAME}-install/lib + +if [[ -d "${LLVM_BASENAME}-install" ]] ; then + log "${LLVM_BASENAME} already installed." +else + rm -Rf ${LLVM_BASENAME}-source ${LLVM_BASENAME}-build + + log "Retrieving libc++." + + git clone --depth=1 -b release_50 https://github.com/llvm-mirror/llvm.git ${LLVM_BASENAME}-source + git clone --depth=1 -b release_50 https://github.com/llvm-mirror/libcxx.git ${LLVM_BASENAME}-source/projects/libcxx + git clone --depth=1 -b release_50 https://github.com/llvm-mirror/libcxxabi.git ${LLVM_BASENAME}-source/projects/libcxxabi + + log "Compiling libc++." + + mkdir -p ${LLVM_BASENAME}-build + + pushd ${LLVM_BASENAME}-build >/dev/null + + cmake -G "Ninja" \ + -DLIBCXX_ENABLE_EXPERIMENTAL_LIBRARY=OFF -DLIBCXX_INSTALL_EXPERIMENTAL_LIBRARY=OFF \ + -DCMAKE_BUILD_TYPE=RelWithDebInfo -DCMAKE_INSTALL_PREFIX="../${LLVM_BASENAME}-install" \ + ../${LLVM_BASENAME}-source + + ninja cxx + + ninja install-libcxx + + ninja install-libcxxabi + + popd >/dev/null + + # Workaround, it seems LLVM 5.0 does not install these files. + cp -v ${LLVM_BASENAME}-build/include/c++/v1/cxxabi.h ${LLVM_INCLUDE} + cp -v ${LLVM_BASENAME}-build/include/c++/v1/__cxxabi_config.h ${LLVM_INCLUDE} + + rm -Rf ${LLVM_BASENAME}-source ${LLVM_BASENAME}-build + +fi + +unset LLVM_BASENAME + +# ============================================================================== +# -- Get boost includes -------------------------------------------------------- +# ============================================================================== + +BOOST_BASENAME=boost-1.67.0 + +BOOST_INCLUDE=${PWD}/${BOOST_BASENAME}-install/include + +if [[ -d "${BOOST_BASENAME}-install" ]] ; then + log "${BOOST_BASENAME} already installed." +else + + log "Retrieving boost." + wget https://dl.bintray.com/boostorg/release/1.67.0/source/boost_1_67_0.tar.gz + log "Extracting boost." + tar -xzf boost_1_67_0.tar.gz + rm boost_1_67_0.tar.gz + mkdir -p ${BOOST_BASENAME}-install/include + mv boost_1_67_0/boost ${BOOST_BASENAME}-install/include/ + rm -Rf boost_1_67_0 + +fi + +unset BOOST_BASENAME + +# ============================================================================== +# -- Get rpclib and compile it with libc++ and libstdc++ ----------------------- +# ============================================================================== + +RPCLIB_BASENAME=rpclib-2.2.1 + +RPCLIB_LIBCXX_INCLUDE=${PWD}/${RPCLIB_BASENAME}-libcxx-install/include +RPCLIB_LIBCXX_LIBPATH=${PWD}/${RPCLIB_BASENAME}-libcxx-install/lib +RPCLIB_LIBSTDCXX_INCLUDE=${PWD}/${RPCLIB_BASENAME}-libstdcxx-install/include +RPCLIB_LIBSTDCXX_LIBPATH=${PWD}/${RPCLIB_BASENAME}-libstdcxx-install/lib + +if [[ -d "${RPCLIB_BASENAME}-libcxx-install" && -d "${RPCLIB_BASENAME}-libstdcxx-install" ]] ; then + log "${RPCLIB_BASENAME} already installed." +else + rm -Rf \ + ${RPCLIB_BASENAME}-source \ + ${RPCLIB_BASENAME}-libcxx-build ${RPCLIB_BASENAME}-libstdcxx-build \ + ${RPCLIB_BASENAME}-libcxx-install ${RPCLIB_BASENAME}-libstdcxx-install + + log "Retrieving rpclib." + + git clone --depth=1 -b v2.2.1 https://github.com/rpclib/rpclib.git ${RPCLIB_BASENAME}-source + + log "Building rpclib with libc++." + + mkdir -p ${RPCLIB_BASENAME}-libcxx-build + + pushd ${RPCLIB_BASENAME}-libcxx-build >/dev/null + + cmake -G "Ninja" \ + -DCMAKE_CXX_FLAGS="-fPIC -std=c++17 -stdlib=libc++ -I${LLVM_INCLUDE} -Wl,-L${LLVM_LIBPATH}" \ + -DCMAKE_INSTALL_PREFIX="../${RPCLIB_BASENAME}-libcxx-install" \ + ../${RPCLIB_BASENAME}-source + + ninja + + ninja install + + popd >/dev/null + + log "Building rpclib with libstdc++." + + mkdir -p ${RPCLIB_BASENAME}-libstdcxx-build + + pushd ${RPCLIB_BASENAME}-libstdcxx-build >/dev/null + + cmake -G "Ninja" \ + -DCMAKE_CXX_FLAGS="-fPIC -std=c++17" \ + -DCMAKE_INSTALL_PREFIX="../${RPCLIB_BASENAME}-libstdcxx-install" \ + ../${RPCLIB_BASENAME}-source + + ninja + + ninja install + + popd >/dev/null + + rm -Rf ${RPCLIB_BASENAME}-source ${RPCLIB_BASENAME}-libcxx-build ${RPCLIB_BASENAME}-libstdcxx-build + +fi + +unset RPCLIB_BASENAME + +# ============================================================================== +# -- Get GTest and compile it with libc++ -------------------------------------- +# ============================================================================== + +GTEST_BASENAME=googletest-1.8.0 + +GTEST_INCLUDE=${PWD}/${GTEST_BASENAME}-install/include +GTEST_LIBPATH=${PWD}/${GTEST_BASENAME}-install/lib + +if [[ -d "${GTEST_BASENAME}-install" ]] ; then + log "${GTEST_BASENAME} already installed." +else + rm -Rf ${GTEST_BASENAME}-source ${GTEST_BASENAME}-build + + log "Retrieving Google Test." + + git clone --depth=1 -b release-1.8.0 https://github.com/google/googletest.git ${GTEST_BASENAME}-source + + log "Building Google Test." + + mkdir -p ${GTEST_BASENAME}-build + + pushd ${GTEST_BASENAME}-build >/dev/null + + cmake -G "Ninja" \ + -DCMAKE_CXX_FLAGS="-std=c++17 -stdlib=libc++ -I${LLVM_INCLUDE} -Wl,-L${LLVM_LIBPATH}" \ + -DCMAKE_INSTALL_PREFIX="../${GTEST_BASENAME}-install" \ + ../${GTEST_BASENAME}-source + + ninja + + ninja install + + popd >/dev/null + + rm -Rf ${GTEST_BASENAME}-source ${GTEST_BASENAME}-build + +fi + +# ============================================================================== +# -- Generate CMake toolchains and config -------------------------------------- +# ============================================================================== + +log "Generating CMake configuration files." + +# -- LIBSTDCPP_TOOLCHAIN_FILE -------------------------------------------------- + +cat >${LIBSTDCPP_TOOLCHAIN_FILE}.gen <>${LIBCPP_TOOLCHAIN_FILE}.gen <${CMAKE_CONFIG_FILE}.gen </dev/null + +log "Success!" diff --git a/Util/BuildTools/Vars.mk b/Util/BuildTools/Vars.mk new file mode 100644 index 000000000..997f4ab8e --- /dev/null +++ b/Util/BuildTools/Vars.mk @@ -0,0 +1,22 @@ +# Here CURDIR is assumed to be the root folder of the project. + +CARLA_ROOT_FOLDER=${CURDIR} +CARLA_BUILD_FOLDER=${CURDIR}/Build +CARLA_DIST_FOLDER=${CURDIR}/Dist +CARLA_BUILD_TOOLS_FOLDER=${CURDIR}/Util/BuildTools + +CARLAUE4_ROOT_FOLDER=${CURDIR}/Unreal/CarlaUE4 +CARLAUE4_PLUGIN_ROOT_FOLDER=${CURDIR}/Unreal/CarlaUE4/Plugins/Carla +CARLA_PYTHONAPI_ROOT_FOLDER=${CURDIR}/PythonAPI + +LIBCARLA_ROOT_FOLDER=${CURDIR}/LibCarla +LIBCARLA_BUILD_SERVER_FOLDER=${CARLA_BUILD_FOLDER}/libcarla-server-build +LIBCARLA_BUILD_CLIENT_FOLDER=${CARLA_BUILD_FOLDER}/libcarla-client-build +LIBCARLA_INSTALL_SERVER_FOLDER=${CARLAUE4_PLUGIN_ROOT_FOLDER}/CarlaDependencies +LIBCARLA_INSTALL_CLIENT_FOLDER=${CARLA_PYTHONAPI_ROOT_FOLDER}/dependencies + +CARLAUE4_PLUGIN_DEPS_FOLDER=${CARLAUE4_PLUGIN_ROOT_FOLDER}/CarlaDependencies + +LIBSTDCPP_TOOLCHAIN_FILE=${CARLA_BUILD_FOLDER}/LibStdCppToolChain.cmake +LIBCPP_TOOLCHAIN_FILE=${CARLA_BUILD_FOLDER}/LibCppToolChain.cmake +CMAKE_CONFIG_FILE=${CARLA_BUILD_FOLDER}/CMakeLists.txt.in diff --git a/Util/BuildTools/Windows.mk b/Util/BuildTools/Windows.mk new file mode 100644 index 000000000..6fdd66328 --- /dev/null +++ b/Util/BuildTools/Windows.mk @@ -0,0 +1,2 @@ +default: + @echo "Not implemented!" diff --git a/Util/BuildTools/uncrustify.cfg b/Util/BuildTools/uncrustify.cfg new file mode 100644 index 000000000..926933119 --- /dev/null +++ b/Util/BuildTools/uncrustify.cfg @@ -0,0 +1,2239 @@ +# Uncrustify-0.67 + +# +# General options +# + +# The type of line endings. Default=Auto. +newlines = auto # auto/lf/crlf/cr + +# The original size of tabs in the input. Default=8. +input_tab_size = 2 # unsigned number + +# The size of tabs in the output (only used if align_with_tabs=true). Default=8. +output_tab_size = 2 # unsigned number + +# The ASCII value of the string escape char, usually 92 (\) or 94 (^). (Pawn). +string_escape_char = 92 # unsigned number + +# Alternate string escape char for Pawn. Only works right before the quote char. +string_escape_char2 = 0 # unsigned number + +# Replace tab characters found in string literals with the escape sequence \t instead. +string_replace_tab_chars = true # false/true + +# Allow interpreting '>=' and '>>=' as part of a template in 'void f(list>=val);'. +# If True, 'assert(x<0 && y>=3)' will be broken. Default=False +# Improvements to template detection may make this option obsolete. +tok_split_gte = false # false/true + +# Override the default ' *INDENT-OFF*' in comments for disabling processing of part of the file. +disable_processing_cmt = "" # string + +# Override the default ' *INDENT-ON*' in comments for enabling processing of part of the file. +enable_processing_cmt = "" # string + +# Enable parsing of digraphs. Default=False. +enable_digraphs = false # false/true + +# Control what to do with the UTF-8 BOM (recommend 'remove'). +utf8_bom = ignore # ignore/add/remove/force + +# If the file contains bytes with values between 128 and 255, but is not UTF-8, then output as UTF-8. +utf8_byte = false # false/true + +# Force the output encoding to UTF-8. +utf8_force = false # false/true + +# +# Spacing options +# + +# Add or remove space around arithmetic operator '+', '-', '/', '*', etc +# also '>>>' '<<' '>>' '%' '|'. +sp_arith = add # ignore/add/remove/force + +# Add or remove space around arithmetic operator '+' and '-'. Overrides sp_arith +sp_arith_additive = add # ignore/add/remove/force + +# Add or remove space around assignment operator '=', '+=', etc. +sp_assign = add # ignore/add/remove/force + +# Add or remove space around '=' in C++11 lambda capture specifications. Overrides sp_assign. +sp_cpp_lambda_assign = remove # ignore/add/remove/force + +# Add or remove space after the capture specification in C++11 lambda. +sp_cpp_lambda_paren = ignore # ignore/add/remove/force + +# Add or remove space around assignment operator '=' in a prototype. +sp_assign_default = ignore # ignore/add/remove/force + +# Add or remove space before assignment operator '=', '+=', etc. Overrides sp_assign. +sp_before_assign = ignore # ignore/add/remove/force + +# Add or remove space after assignment operator '=', '+=', etc. Overrides sp_assign. +sp_after_assign = ignore # ignore/add/remove/force + +# Add or remove space in 'NS_ENUM ('. +sp_enum_paren = ignore # ignore/add/remove/force + +# Add or remove space around assignment '=' in enum. +sp_enum_assign = add # ignore/add/remove/force + +# Add or remove space before assignment '=' in enum. Overrides sp_enum_assign. +sp_enum_before_assign = ignore # ignore/add/remove/force + +# Add or remove space after assignment '=' in enum. Overrides sp_enum_assign. +sp_enum_after_assign = ignore # ignore/add/remove/force + +# Add or remove space around assignment ':' in enum. +sp_enum_colon = ignore # ignore/add/remove/force + +# Add or remove space around preprocessor '##' concatenation operator. Default=Add. +sp_pp_concat = add # ignore/add/remove/force + +# Add or remove space after preprocessor '#' stringify operator. Also affects the '#@' charizing operator. +sp_pp_stringify = add # ignore/add/remove/force + +# Add or remove space before preprocessor '#' stringify operator as in '#define x(y) L#y'. +sp_before_pp_stringify = ignore # ignore/add/remove/force + +# Add or remove space around boolean operators '&&' and '||'. +sp_bool = force # ignore/add/remove/force + +# Add or remove space around compare operator '<', '>', '==', etc. +sp_compare = add # ignore/add/remove/force + +# Add or remove space inside '(' and ')'. +sp_inside_paren = remove # ignore/add/remove/force + +# Add or remove space between nested parens: '((' vs ') )'. +sp_paren_paren = remove # ignore/add/remove/force + +# Add or remove space between back-to-back parens: ')(' vs ') ('. +sp_cparen_oparen = ignore # ignore/add/remove/force + +# Whether to balance spaces inside nested parens. +sp_balance_nested_parens = false # false/true + +# Add or remove space between ')' and '{'. +sp_paren_brace = force # ignore/add/remove/force + +# Add or remove space before pointer star '*'. +sp_before_ptr_star = force # ignore/add/remove/force + +# Add or remove space before pointer star '*' that isn't followed by a variable name +# If set to 'ignore', sp_before_ptr_star is used instead. +sp_before_unnamed_ptr_star = force # ignore/add/remove/force + +# Add or remove space between pointer stars '*'. +sp_between_ptr_star = remove # ignore/add/remove/force + +# Add or remove space after pointer star '*', if followed by a word. +sp_after_ptr_star = remove # ignore/add/remove/force + +# Add or remove space after pointer caret '^', if followed by a word. +sp_after_ptr_block_caret = ignore # ignore/add/remove/force + +# Add or remove space after pointer star '*', if followed by a qualifier. +sp_after_ptr_star_qualifier = ignore # ignore/add/remove/force + +# Add or remove space after a pointer star '*', if followed by a func proto/def. +sp_after_ptr_star_func = ignore # ignore/add/remove/force + +# Add or remove space after a pointer star '*', if followed by an open paren (function types). +sp_ptr_star_paren = ignore # ignore/add/remove/force + +# Add or remove space before a pointer star '*', if followed by a func proto/def. +sp_before_ptr_star_func = force # ignore/add/remove/force + +# Add or remove space before a reference sign '&'. +sp_before_byref = force # ignore/add/remove/force + +# Add or remove space before a reference sign '&' that isn't followed by a variable name. +# If set to 'ignore', sp_before_byref is used instead. +sp_before_unnamed_byref = force # ignore/add/remove/force + +# Add or remove space after reference sign '&', if followed by a word. +sp_after_byref = remove # ignore/add/remove/force + +# Add or remove space after a reference sign '&', if followed by a func proto/def. +sp_after_byref_func = remove # ignore/add/remove/force + +# Add or remove space before a reference sign '&', if followed by a func proto/def. +sp_before_byref_func = force # ignore/add/remove/force + +# Add or remove space between type and word. Default=Force. +sp_after_type = force # ignore/add/remove/force + +# Add or remove space before the paren in the D constructs 'template Foo(' and 'class Foo('. +sp_before_template_paren = ignore # ignore/add/remove/force + +# Add or remove space in 'template <' vs 'template<'. +# If set to ignore, sp_before_angle is used. +sp_template_angle = force # ignore/add/remove/force + +# Add or remove space before '<>'. +sp_before_angle = remove # ignore/add/remove/force + +# Add or remove space inside '<' and '>'. +sp_inside_angle = remove # ignore/add/remove/force + +# Add or remove space between '<>' and ':'. +sp_angle_colon = ignore # ignore/add/remove/force + +# Add or remove space after '<>'. +sp_after_angle = ignore # ignore/add/remove/force + +# Add or remove space between '<>' and '(' as found in 'new List(foo);'. +sp_angle_paren = remove # ignore/add/remove/force + +# Add or remove space between '<>' and '()' as found in 'new List();'. +sp_angle_paren_empty = remove # ignore/add/remove/force + +# Add or remove space between '<>' and a word as in 'List m;' or 'template static ...'. +sp_angle_word = force # ignore/add/remove/force + +# Add or remove space between '>' and '>' in '>>' (template stuff). Default=Add. +sp_angle_shift = remove # ignore/add/remove/force + +# Permit removal of the space between '>>' in 'foo >' (C++11 only). Default=False. +# sp_angle_shift cannot remove the space without this option. +sp_permit_cpp11_shift = true # false/true + +# Add or remove space before '(' of 'if', 'for', 'switch', 'while', etc. +sp_before_sparen = force # ignore/add/remove/force + +# Add or remove space inside if-condition '(' and ')'. +sp_inside_sparen = remove # ignore/add/remove/force + +# Add or remove space before if-condition ')'. Overrides sp_inside_sparen. +sp_inside_sparen_close = ignore # ignore/add/remove/force + +# Add or remove space after if-condition '('. Overrides sp_inside_sparen. +sp_inside_sparen_open = ignore # ignore/add/remove/force + +# Add or remove space after ')' of 'if', 'for', 'switch', and 'while', etc. +sp_after_sparen = force # ignore/add/remove/force + +# Add or remove space between ')' and '{' of 'if', 'for', 'switch', and 'while', etc. +sp_sparen_brace = force # ignore/add/remove/force + +# Add or remove space between 'invariant' and '(' in the D language. +sp_invariant_paren = ignore # ignore/add/remove/force + +# Add or remove space after the ')' in 'invariant (C) c' in the D language. +sp_after_invariant_paren = ignore # ignore/add/remove/force + +# Add or remove space before empty statement ';' on 'if', 'for' and 'while'. +sp_special_semi = ignore # ignore/add/remove/force + +# Add or remove space before ';'. Default=Remove. +sp_before_semi = remove # ignore/add/remove/force + +# Add or remove space before ';' in non-empty 'for' statements. +sp_before_semi_for = ignore # ignore/add/remove/force + +# Add or remove space before a semicolon of an empty part of a for statement. +sp_before_semi_for_empty = ignore # ignore/add/remove/force + +# Add or remove space after ';', except when followed by a comment. Default=Add. +sp_after_semi = add # ignore/add/remove/force + +# Add or remove space after ';' in non-empty 'for' statements. Default=Force. +sp_after_semi_for = force # ignore/add/remove/force + +# Add or remove space after the final semicolon of an empty part of a for statement: for ( ; ; ). +sp_after_semi_for_empty = ignore # ignore/add/remove/force + +# Add or remove space before '[' (except '[]'). +sp_before_square = remove # ignore/add/remove/force + +# Add or remove space before '[]'. +sp_before_squares = remove # ignore/add/remove/force + +# Add or remove space before structured bindings. Only for C++17. +sp_cpp_before_struct_binding = ignore # ignore/add/remove/force + +# Add or remove space inside a non-empty '[' and ']'. +sp_inside_square = remove # ignore/add/remove/force + +# Add or remove space inside a non-empty OC boxed array '@[' and ']'. +# If set to ignore, sp_inside_square is used. +sp_inside_square_oc_array = ignore # ignore/add/remove/force + +# Add or remove space after ',', 'a,b' vs 'a, b'. +sp_after_comma = add # ignore/add/remove/force + +# Add or remove space before ','. Default=Remove. +sp_before_comma = remove # ignore/add/remove/force + +# Add or remove space between ',' and ']' in multidimensional array type 'int[,,]'. Only for C#. +sp_after_mdatype_commas = ignore # ignore/add/remove/force + +# Add or remove space between '[' and ',' in multidimensional array type 'int[,,]'. Only for C#. +sp_before_mdatype_commas = ignore # ignore/add/remove/force + +# Add or remove space between ',' in multidimensional array type 'int[,,]'. Only for C#. +sp_between_mdatype_commas = ignore # ignore/add/remove/force + +# Add or remove space between an open paren and comma: '(,' vs '( ,'. Default=Force. +sp_paren_comma = force # ignore/add/remove/force + +# Add or remove space before the variadic '...' when preceded by a non-punctuator. +sp_before_ellipsis = ignore # ignore/add/remove/force + +# Add or remove space after class ':'. +sp_after_class_colon = ignore # ignore/add/remove/force + +# Add or remove space before class ':'. +sp_before_class_colon = ignore # ignore/add/remove/force + +# Add or remove space after class constructor ':'. +sp_after_constr_colon = ignore # ignore/add/remove/force + +# Add or remove space before class constructor ':'. +sp_before_constr_colon = ignore # ignore/add/remove/force + +# Add or remove space before case ':'. Default=Remove. +sp_before_case_colon = remove # ignore/add/remove/force + +# Add or remove space between 'operator' and operator sign. +sp_after_operator = remove # ignore/add/remove/force + +# Add or remove space between the operator symbol and the open paren, as in 'operator ++('. +sp_after_operator_sym = remove # ignore/add/remove/force + +# Overrides sp_after_operator_sym when the operator has no arguments, as in 'operator *()'. +sp_after_operator_sym_empty = ignore # ignore/add/remove/force + +# Add or remove space after C/D cast, i.e. 'cast(int)a' vs 'cast(int) a' or '(int)a' vs '(int) a'. +sp_after_cast = force # ignore/add/remove/force + +# Add or remove spaces inside cast parens. +sp_inside_paren_cast = remove # ignore/add/remove/force + +# Add or remove space between the type and open paren in a C++ cast, i.e. 'int(exp)' vs 'int (exp)'. +sp_cpp_cast_paren = remove # ignore/add/remove/force + +# Add or remove space between 'sizeof' and '('. +sp_sizeof_paren = remove # ignore/add/remove/force + +# Add or remove space after the tag keyword (Pawn). +sp_after_tag = ignore # ignore/add/remove/force + +# Add or remove space inside enum '{' and '}'. +sp_inside_braces_enum = force # ignore/add/remove/force + +# Add or remove space inside struct/union '{' and '}'. +sp_inside_braces_struct = force # ignore/add/remove/force + +# Add or remove space inside OC boxed dictionary @'{' and '}' +sp_inside_braces_oc_dict = ignore # ignore/add/remove/force + +# Add or remove space after open brace in an unnamed temporary direct-list-initialization. +sp_after_type_brace_init_lst_open = ignore # ignore/add/remove/force + +# Add or remove space before close brace in an unnamed temporary direct-list-initialization. +sp_before_type_brace_init_lst_close = ignore # ignore/add/remove/force + +# Add or remove space inside an unnamed temporary direct-list-initialization. +sp_inside_type_brace_init_lst = ignore # ignore/add/remove/force + +# Add or remove space inside '{' and '}'. +sp_inside_braces = ignore # ignore/add/remove/force + +# Add or remove space inside '{}'. +sp_inside_braces_empty = remove # ignore/add/remove/force + +# Add or remove space between return type and function name +# A minimum of 1 is forced except for pointer return types. +sp_type_func = force # ignore/add/remove/force + +# Add or remove space between type and open brace of an unnamed temporary direct-list-initialization. +sp_type_brace_init_lst = ignore # ignore/add/remove/force + +# Add or remove space between function name and '(' on function declaration. +sp_func_proto_paren = remove # ignore/add/remove/force + +# Add or remove space between function name and '()' on function declaration without parameters. +sp_func_proto_paren_empty = remove # ignore/add/remove/force + +# Add or remove space between function name and '(' on function definition. +sp_func_def_paren = remove # ignore/add/remove/force + +# Add or remove space between function name and '()' on function definition without parameters. +sp_func_def_paren_empty = remove # ignore/add/remove/force + +# Add or remove space inside empty function '()'. +sp_inside_fparens = remove # ignore/add/remove/force + +# Add or remove space inside function '(' and ')'. +sp_inside_fparen = remove # ignore/add/remove/force + +# Add or remove space inside the first parens in the function type: 'void (*x)(...)'. +sp_inside_tparen = ignore # ignore/add/remove/force + +# Add or remove between the parens in the function type: 'void (*x)(...)'. +sp_after_tparen_close = ignore # ignore/add/remove/force + +# Add or remove space between ']' and '(' when part of a function call. +sp_square_fparen = remove # ignore/add/remove/force + +# Add or remove space between ')' and '{' of function. +sp_fparen_brace = force # ignore/add/remove/force + +# Add or remove space between ')' and '{' of function call in object initialization. Overrides sp_fparen_brace. +sp_fparen_brace_initializer = ignore # ignore/add/remove/force + +# Java: Add or remove space between ')' and '{{' of double brace initializer. +sp_fparen_dbrace = ignore # ignore/add/remove/force + +# Add or remove space between function name and '(' on function calls. +sp_func_call_paren = remove # ignore/add/remove/force + +# Add or remove space between function name and '()' on function calls without parameters. +# If set to 'ignore' (the default), sp_func_call_paren is used. +sp_func_call_paren_empty = ignore # ignore/add/remove/force + +# Add or remove space between the user function name and '(' on function calls +# You need to set a keyword to be a user function, like this: 'set func_call_user _' in the config file. +sp_func_call_user_paren = ignore # ignore/add/remove/force + +# Add or remove space inside user function '(' and ')' +# You need to set a keyword to be a user function, like this: 'set func_call_user _' in the config file. +sp_func_call_user_inside_fparen = ignore # ignore/add/remove/force + +# Add or remove space between nested parens with user functions: '((' vs ') )'You need to set a keyword to be a user function, like this: 'set func_call_user _' in the config file. +sp_func_call_user_paren_paren = ignore # ignore/add/remove/force + +# Add or remove space between a constructor/destructor and the open paren. +sp_func_class_paren = remove # ignore/add/remove/force + +# Add or remove space between a constructor without parameters or destructor and '()'. +sp_func_class_paren_empty = remove # ignore/add/remove/force + +# Add or remove space between 'return' and '('. +sp_return_paren = force # ignore/add/remove/force + +# Add or remove space between '__attribute__' and '('. +sp_attribute_paren = remove # ignore/add/remove/force + +# Add or remove space between 'defined' and '(' in '#if defined (FOO)'. +sp_defined_paren = remove # ignore/add/remove/force + +# Add or remove space between 'throw' and '(' in 'throw (something)'. +sp_throw_paren = ignore # ignore/add/remove/force + +# Add or remove space between 'throw' and anything other than '(' as in '@throw [...];'. +sp_after_throw = ignore # ignore/add/remove/force + +# Add or remove space between 'catch' and '(' in 'catch (something) { }' +# If set to ignore, sp_before_sparen is used. +sp_catch_paren = force # ignore/add/remove/force + +# Add or remove space between '@catch' and '(' in '@catch (something) { }' +# If set to ignore, sp_catch_paren is used. +sp_oc_catch_paren = ignore # ignore/add/remove/force + +# Add or remove space between 'version' and '(' in 'version (something) { }' (D language) +# If set to ignore, sp_before_sparen is used. +sp_version_paren = ignore # ignore/add/remove/force + +# Add or remove space between 'scope' and '(' in 'scope (something) { }' (D language) +# If set to ignore, sp_before_sparen is used. +sp_scope_paren = ignore # ignore/add/remove/force + +# Add or remove space between 'super' and '(' in 'super (something)'. Default=Remove. +sp_super_paren = remove # ignore/add/remove/force + +# Add or remove space between 'this' and '(' in 'this (something)'. Default=Remove. +sp_this_paren = remove # ignore/add/remove/force + +# Add or remove space between macro and value. +sp_macro = force # ignore/add/remove/force + +# Add or remove space between macro function ')' and value. +sp_macro_func = force # ignore/add/remove/force + +# Add or remove space between 'else' and '{' if on the same line. +sp_else_brace = force # ignore/add/remove/force + +# Add or remove space between '}' and 'else' if on the same line. +sp_brace_else = force # ignore/add/remove/force + +# Add or remove space between '}' and the name of a typedef on the same line. +sp_brace_typedef = force # ignore/add/remove/force + +# Add or remove space between 'catch' and '{' if on the same line. +sp_catch_brace = force # ignore/add/remove/force + +# Add or remove space between '@catch' and '{' if on the same line. +# If set to ignore, sp_catch_brace is used. +sp_oc_catch_brace = force # ignore/add/remove/force + +# Add or remove space between '}' and 'catch' if on the same line. +sp_brace_catch = force # ignore/add/remove/force + +# Add or remove space between '}' and '@catch' if on the same line. +# If set to ignore, sp_brace_catch is used. +sp_oc_brace_catch = force # ignore/add/remove/force + +# Add or remove space between 'finally' and '{' if on the same line. +sp_finally_brace = force # ignore/add/remove/force + +# Add or remove space between '}' and 'finally' if on the same line. +sp_brace_finally = force # ignore/add/remove/force + +# Add or remove space between 'try' and '{' if on the same line. +sp_try_brace = force # ignore/add/remove/force + +# Add or remove space between get/set and '{' if on the same line. +sp_getset_brace = force # ignore/add/remove/force + +# Add or remove space between a variable and '{' for C++ uniform initialization. Default=Add. +sp_word_brace = add # ignore/add/remove/force + +# Add or remove space between a variable and '{' for a namespace. Default=Add. +sp_word_brace_ns = add # ignore/add/remove/force + +# Add or remove space before the '::' operator. +sp_before_dc = remove # ignore/add/remove/force + +# Add or remove space after the '::' operator. +sp_after_dc = remove # ignore/add/remove/force + +# Add or remove around the D named array initializer ':' operator. +sp_d_array_colon = ignore # ignore/add/remove/force + +# Add or remove space after the '!' (not) operator. Default=Remove. +sp_not = remove # ignore/add/remove/force + +# Add or remove space after the '~' (invert) operator. Default=Remove. +sp_inv = remove # ignore/add/remove/force + +# Add or remove space after the '&' (address-of) operator. Default=Remove +# This does not affect the spacing after a '&' that is part of a type. +sp_addr = remove # ignore/add/remove/force + +# Add or remove space around the '.' or '->' operators. Default=Remove. +sp_member = remove # ignore/add/remove/force + +# Add or remove space after the '*' (dereference) operator. Default=Remove +# This does not affect the spacing after a '*' that is part of a type. +sp_deref = remove # ignore/add/remove/force + +# Add or remove space after '+' or '-', as in 'x = -5' or 'y = +7'. Default=Remove. +sp_sign = remove # ignore/add/remove/force + +# Add or remove space before or after '++' and '--', as in '(--x)' or 'y++;'. Default=Remove. +sp_incdec = remove # ignore/add/remove/force + +# Add or remove space before a backslash-newline at the end of a line. Default=Add. +sp_before_nl_cont = force # ignore/add/remove/force + +# Add or remove space after the scope '+' or '-', as in '-(void) foo;' or '+(int) bar;'. +sp_after_oc_scope = remove # ignore/add/remove/force + +# Add or remove space after the colon in message specs +# '-(int) f:(int) x;' vs '-(int) f: (int) x;'. +sp_after_oc_colon = force # ignore/add/remove/force + +# Add or remove space before the colon in message specs +# '-(int) f: (int) x;' vs '-(int) f : (int) x;'. +sp_before_oc_colon = remove # ignore/add/remove/force + +# Add or remove space after the colon in immutable dictionary expression +# 'NSDictionary *test = @{@"foo" :@"bar"};'. +sp_after_oc_dict_colon = ignore # ignore/add/remove/force + +# Add or remove space before the colon in immutable dictionary expression +# 'NSDictionary *test = @{@"foo" :@"bar"};'. +sp_before_oc_dict_colon = ignore # ignore/add/remove/force + +# Add or remove space after the colon in message specs +# '[object setValue:1];' vs '[object setValue: 1];'. +sp_after_send_oc_colon = ignore # ignore/add/remove/force + +# Add or remove space before the colon in message specs +# '[object setValue:1];' vs '[object setValue :1];'. +sp_before_send_oc_colon = ignore # ignore/add/remove/force + +# Add or remove space after the (type) in message specs +# '-(int)f: (int) x;' vs '-(int)f: (int)x;'. +sp_after_oc_type = ignore # ignore/add/remove/force + +# Add or remove space after the first (type) in message specs +# '-(int) f:(int)x;' vs '-(int)f:(int)x;'. +sp_after_oc_return_type = ignore # ignore/add/remove/force + +# Add or remove space between '@selector' and '(' +# '@selector(msgName)' vs '@selector (msgName)' +# Also applies to @protocol() constructs. +sp_after_oc_at_sel = ignore # ignore/add/remove/force + +# Add or remove space between '@selector(x)' and the following word +# '@selector(foo) a:' vs '@selector(foo)a:'. +sp_after_oc_at_sel_parens = ignore # ignore/add/remove/force + +# Add or remove space inside '@selector' parens +# '@selector(foo)' vs '@selector( foo )' +# Also applies to @protocol() constructs. +sp_inside_oc_at_sel_parens = ignore # ignore/add/remove/force + +# Add or remove space before a block pointer caret +# '^int (int arg){...}' vs. ' ^int (int arg){...}'. +sp_before_oc_block_caret = ignore # ignore/add/remove/force + +# Add or remove space after a block pointer caret +# '^int (int arg){...}' vs. '^ int (int arg){...}'. +sp_after_oc_block_caret = ignore # ignore/add/remove/force + +# Add or remove space between the receiver and selector in a message. +# '[receiver selector ...]'. +sp_after_oc_msg_receiver = ignore # ignore/add/remove/force + +# Add or remove space after @property. +sp_after_oc_property = ignore # ignore/add/remove/force + +# Add or remove space between '@synchronized' and the parenthesis +# '@synchronized(foo)' vs '@synchronized (foo)'. +sp_after_oc_synchronized = ignore # ignore/add/remove/force + +# Add or remove space around the ':' in 'b ? t : f'. +sp_cond_colon = force # ignore/add/remove/force + +# Add or remove space before the ':' in 'b ? t : f'. Overrides sp_cond_colon. +sp_cond_colon_before = ignore # ignore/add/remove/force + +# Add or remove space after the ':' in 'b ? t : f'. Overrides sp_cond_colon. +sp_cond_colon_after = ignore # ignore/add/remove/force + +# Add or remove space around the '?' in 'b ? t : f'. +sp_cond_question = force # ignore/add/remove/force + +# Add or remove space before the '?' in 'b ? t : f'. Overrides sp_cond_question. +sp_cond_question_before = ignore # ignore/add/remove/force + +# Add or remove space after the '?' in 'b ? t : f'. Overrides sp_cond_question. +sp_cond_question_after = ignore # ignore/add/remove/force + +# In the abbreviated ternary form (a ?: b), add/remove space between ? and :.'. Overrides all other sp_cond_* options. +sp_cond_ternary_short = ignore # ignore/add/remove/force + +# Fix the spacing between 'case' and the label. Only 'ignore' and 'force' make sense here. +sp_case_label = force # ignore/add/remove/force + +# Control the space around the D '..' operator. +sp_range = ignore # ignore/add/remove/force + +# Control the spacing after ':' in 'for (TYPE VAR : EXPR)'. Only JAVA. +sp_after_for_colon = ignore # ignore/add/remove/force + +# Control the spacing before ':' in 'for (TYPE VAR : EXPR)'. Only JAVA. +sp_before_for_colon = ignore # ignore/add/remove/force + +# Control the spacing in 'extern (C)' (D). +sp_extern_paren = ignore # ignore/add/remove/force + +# Control the space after the opening of a C++ comment '// A' vs '//A'. +sp_cmt_cpp_start = add # ignore/add/remove/force + +# True: If space is added with sp_cmt_cpp_start, do it after doxygen sequences like '///', '///<', '//!' and '//!<'. +sp_cmt_cpp_doxygen = true # false/true + +# True: If space is added with sp_cmt_cpp_start, do it after Qt translator or meta-data comments like '//:', '//=', and '//~'. +sp_cmt_cpp_qttr = false # false/true + +# Controls the spaces between #else or #endif and a trailing comment. +sp_endif_cmt = ignore # ignore/add/remove/force + +# Controls the spaces after 'new', 'delete' and 'delete[]'. +sp_after_new = force # ignore/add/remove/force + +# Controls the spaces between new and '(' in 'new()'. +sp_between_new_paren = remove # ignore/add/remove/force + +# Controls the spaces between ')' and 'type' in 'new(foo) BAR'. +sp_after_newop_paren = ignore # ignore/add/remove/force + +# Controls the spaces inside paren of the new operator: 'new(foo) BAR'. +sp_inside_newop_paren = ignore # ignore/add/remove/force + +# Controls the space after open paren of the new operator: 'new(foo) BAR'. +# Overrides sp_inside_newop_paren. +sp_inside_newop_paren_open = ignore # ignore/add/remove/force + +# Controls the space before close paren of the new operator: 'new(foo) BAR'. +# Overrides sp_inside_newop_paren. +sp_inside_newop_paren_close = ignore # ignore/add/remove/force + +# Controls the spaces before a trailing or embedded comment. +sp_before_tr_emb_cmt = add # ignore/add/remove/force + +# Number of spaces before a trailing or embedded comment. +sp_num_before_tr_emb_cmt = 0 # unsigned number + +# Control space between a Java annotation and the open paren. +sp_annotation_paren = ignore # ignore/add/remove/force + +# If True, vbrace tokens are dropped to the previous token and skipped. +sp_skip_vbrace_tokens = false # false/true + +# Controls the space after 'noexcept'. +sp_after_noexcept = force # ignore/add/remove/force + +# If True, a is inserted after #define. +force_tab_after_define = false # false/true + +# +# Indenting +# + +# The number of columns to indent per level. +# Usually 2, 3, 4, or 8. Default=8. +indent_columns = 2 # unsigned number + +# The continuation indent. If non-zero, this overrides the indent of '(' and '=' continuation indents. +# For FreeBSD, this is set to 4. Negative value is absolute and not increased for each '(' level. +indent_continue = 4 # number + +# Indent empty lines - lines which contain only spaces before newline character +indent_single_newlines = false # false/true + +# The continuation indent for func_*_param if they are true. +# If non-zero, this overrides the indent. +indent_param = 0 # unsigned number + +# How to use tabs when indenting code +# 0=spaces only +# 1=indent with tabs to brace level, align with spaces (default) +# 2=indent and align with tabs, using spaces when not on a tabstop +indent_with_tabs = 0 # unsigned number + +# Comments that are not a brace level are indented with tabs on a tabstop. +# Requires indent_with_tabs=2. If false, will use spaces. +indent_cmt_with_tabs = false # false/true + +# Whether to indent strings broken by '\' so that they line up. +indent_align_string = true # false/true + +# The number of spaces to indent multi-line XML strings. +# Requires indent_align_string=True. +indent_xml_string = 0 # unsigned number + +# Spaces to indent '{' from level. +indent_brace = 0 # unsigned number + +# Whether braces are indented to the body level. +indent_braces = false # false/true + +# Disabled indenting function braces if indent_braces is True. +indent_braces_no_func = false # false/true + +# Disabled indenting class braces if indent_braces is True. +indent_braces_no_class = false # false/true + +# Disabled indenting struct braces if indent_braces is True. +indent_braces_no_struct = false # false/true + +# Indent based on the size of the brace parent, i.e. 'if' => 3 spaces, 'for' => 4 spaces, etc. +indent_brace_parent = false # false/true + +# Indent based on the paren open instead of the brace open in '({\n', default is to indent by brace. +indent_paren_open_brace = false # false/true + +# indent a C# delegate by another level, default is to not indent by another level. +indent_cs_delegate_brace = false # false/true + +# indent a C# delegate(To hanndle delegates with no brace) by another level. default: false +indent_cs_delegate_body = false # false/true + +# Whether the 'namespace' body is indented. +indent_namespace = true # false/true + +# Only indent one namespace and no sub-namespaces. +# Requires indent_namespace=True. +indent_namespace_single_indent = true # false/true + +# The number of spaces to indent a namespace block. +indent_namespace_level = 2 # unsigned number + +# If the body of the namespace is longer than this number, it won't be indented. +# Requires indent_namespace=True. Default=0 (no limit) +indent_namespace_limit = 0 # unsigned number + +# Whether the 'extern "C"' body is indented. +indent_extern = true # false/true + +# Whether the 'class' body is indented. +indent_class = true # false/true + +# Whether to indent the stuff after a leading base class colon. +indent_class_colon = true # false/true + +# Indent based on a class colon instead of the stuff after the colon. +# Requires indent_class_colon=True. Default=False. +indent_class_on_colon = false # false/true + +# Whether to indent the stuff after a leading class initializer colon. +indent_constr_colon = true # false/true + +# Virtual indent from the ':' for member initializers. Default=2. +indent_ctor_init_leading = 2 # unsigned number + +# Additional indent for constructor initializer list. +# Negative values decrease indent down to the first column. Default=0. +indent_ctor_init = 0 # number + +# False=treat 'else\nif' as 'else if' for indenting purposes +# True=indent the 'if' one level. +indent_else_if = false # false/true + +# Amount to indent variable declarations after a open brace. neg=relative, pos=absolute. +indent_var_def_blk = 0 # number + +# Indent continued variable declarations instead of aligning. +indent_var_def_cont = false # false/true + +# Indent continued shift expressions ('<<' and '>>') instead of aligning. +# Turn align_left_shift off when enabling this. +indent_shift = false # false/true + +# True: force indentation of function definition to start in column 1 +# False: use the default behavior. +indent_func_def_force_col1 = false # false/true + +# True: indent continued function call parameters one indent level +# False: align parameters under the open paren. +indent_func_call_param = true # false/true + +# Same as indent_func_call_param, but for function defs. +indent_func_def_param = true # false/true + +# Same as indent_func_call_param, but for function protos. +indent_func_proto_param = true # false/true + +# Same as indent_func_call_param, but for class declarations. +indent_func_class_param = true # false/true + +# Same as indent_func_call_param, but for class variable constructors. +indent_func_ctor_var_param = true # false/true + +# Same as indent_func_call_param, but for templates. +indent_template_param = true # false/true + +# Double the indent for indent_func_xxx_param options. +# Use both values of the options indent_columns and indent_param. +indent_func_param_double = true # false/true + +# Indentation column for standalone 'const' function decl/proto qualifier. +indent_func_const = 0 # unsigned number + +# Indentation column for standalone 'throw' function decl/proto qualifier. +indent_func_throw = 0 # unsigned number + +# The number of spaces to indent a continued '->' or '.' +# Usually set to 0, 1, or indent_columns. +indent_member = 4 # unsigned number + +# setting to true will indent lines broken at '.' or '->' by a single indent +# UO_indent_member option will not be effective if this is set to true. +indent_member_single = false # false/true + +# Spaces to indent single line ('//') comments on lines before code. +indent_sing_line_comments = 0 # unsigned number + +# If set, will indent trailing single line ('//') comments relative +# to the code instead of trying to keep the same absolute column. +indent_relative_single_line_comments = false # false/true + +# Spaces to indent 'case' from 'switch' +# Usually 0 or indent_columns. +indent_switch_case = 2 # unsigned number + +# Whether to indent preprocessor statements inside of switch statements. +indent_switch_pp = true # false/true + +# Spaces to shift the 'case' line, without affecting any other lines +# Usually 0. +indent_case_shift = 0 # unsigned number + +# Spaces to indent '{' from 'case'. +# By default, the brace will appear under the 'c' in case. +# Usually set to 0 or indent_columns. +# negative value are OK. +indent_case_brace = 0 # number + +# Whether to indent comments found in first column. +indent_col1_comment = false # false/true + +# How to indent goto labels +# >0: absolute column where 1 is the leftmost column +# <=0: subtract from brace indent +# Default=1 +indent_label = 1 # number + +# Same as indent_label, but for access specifiers that are followed by a colon. Default=1 +indent_access_spec = 3 # number + +# Indent the code after an access specifier by one level. +# If set, this option forces 'indent_access_spec=0'. +indent_access_spec_body = false # false/true + +# If an open paren is followed by a newline, indent the next line so that it lines up after the open paren (not recommended). +indent_paren_nl = false # false/true + +# Controls the indent of a close paren after a newline. +# 0: Indent to body level +# 1: Align under the open paren +# 2: Indent to the brace level +indent_paren_close = 0 # unsigned number + +# Controls the indent of the open paren of a function definition, if on it's own line.If True, indents the open paren +indent_paren_after_func_def = false # false/true + +# Controls the indent of the open paren of a function declaration, if on it's own line.If True, indents the open paren +indent_paren_after_func_decl = false # false/true + +# Controls the indent of the open paren of a function call, if on it's own line.If True, indents the open paren +indent_paren_after_func_call = false # false/true + +# Controls the indent of a comma when inside a paren.If True, aligns under the open paren. +indent_comma_paren = false # false/true + +# Controls the indent of a BOOL operator when inside a paren.If True, aligns under the open paren. +indent_bool_paren = false # false/true + +# Controls the indent of a semicolon when inside a for paren.If True, aligns under the open for paren. +indent_semicolon_for_paren = false # false/true + +# If 'indent_bool_paren' is True, controls the indent of the first expression. If True, aligns the first expression to the following ones. +indent_first_bool_expr = false # false/true + +# If 'indent_semicolon_for_paren' is True, controls the indent of the first expression. If True, aligns the first expression to the following ones. +indent_first_for_expr = false # false/true + +# If an open square is followed by a newline, indent the next line so that it lines up after the open square (not recommended). +indent_square_nl = false # false/true + +# Don't change the relative indent of ESQL/C 'EXEC SQL' bodies. +indent_preserve_sql = false # false/true + +# Align continued statements at the '='. Default=True +# If False or the '=' is followed by a newline, the next line is indent one tab. +indent_align_assign = false # false/true + +# Align continued statements at the '('. Default=True +# If FALSE or the '(' is not followed by a newline, the next line indent is one tab. +indent_align_paren = true # false/true + +# Indent OC blocks at brace level instead of usual rules. +indent_oc_block = false # false/true + +# Indent OC blocks in a message relative to the parameter name. +# 0=use indent_oc_block rules, 1+=spaces to indent +indent_oc_block_msg = 0 # unsigned number + +# Minimum indent for subsequent parameters +indent_oc_msg_colon = 0 # unsigned number + +# If True, prioritize aligning with initial colon (and stripping spaces from lines, if necessary). +# Default=True. +indent_oc_msg_prioritize_first_colon = true # false/true + +# If indent_oc_block_msg and this option are on, blocks will be indented the way that Xcode does by default (from keyword if the parameter is on its own line; otherwise, from the previous indentation level). +indent_oc_block_msg_xcode_style = false # false/true + +# If indent_oc_block_msg and this option are on, blocks will be indented from where the brace is relative to a msg keyword. +indent_oc_block_msg_from_keyword = false # false/true + +# If indent_oc_block_msg and this option are on, blocks will be indented from where the brace is relative to a msg colon. +indent_oc_block_msg_from_colon = false # false/true + +# If indent_oc_block_msg and this option are on, blocks will be indented from where the block caret is. +indent_oc_block_msg_from_caret = false # false/true + +# If indent_oc_block_msg and this option are on, blocks will be indented from where the brace is. +indent_oc_block_msg_from_brace = false # false/true + +# When indenting after virtual brace open and newline add further spaces to reach this min. indent. +indent_min_vbrace_open = 0 # unsigned number + +# True: When identing after virtual brace open and newline add further spaces after regular indent to reach next tabstop. +indent_vbrace_open_on_tabstop = false # false/true + +# If True, a brace followed by another token (not a newline) will indent all contained lines to match the token.Default=True. +indent_token_after_brace = true # false/true + +# If True, cpp lambda body will be indentedDefault=False. +indent_cpp_lambda_body = false # false/true + +# indent (or not) an using block if no braces are used. Only for C#.Default=True. +indent_using_block = true # false/true + +# indent the continuation of ternary operator. +# 0: (Default) off +# 1: When the `if_false` is a continuation, indent it under `if_false` +# 2: When the `:` is a continuation, indent it under `?` +indent_ternary_operator = 0 # unsigned number + +# If true, the indentation of the chunks after a `return new` sequence will be set at return indentation column. +indent_off_after_return_new = false # false/true + +# If true, the tokens after return are indented with regular single indentation.By default (false) the indentation is after the return token. +indent_single_after_return = false # false/true + +# If true, ignore indent and align for asm blocks as they have their own indentation. +indent_ignore_asm_block = false # false/true + +# +# Newline adding and removing options +# + +# Whether to collapse empty blocks between '{' and '}'. +nl_collapse_empty_body = true # false/true + +# Don't split one-line braced assignments - 'foo_t f = { 1, 2 };'. +nl_assign_leave_one_liners = true # false/true + +# Don't split one-line braced statements inside a class xx { } body. +nl_class_leave_one_liners = false # false/true + +# Don't split one-line enums: 'enum foo { BAR = 15 };' +nl_enum_leave_one_liners = false # false/true + +# Don't split one-line get or set functions. +nl_getset_leave_one_liners = false # false/true + +# Don't split one-line get or set functions. +nl_cs_property_leave_one_liners = false # false/true + +# Don't split one-line function definitions - 'int foo() { return 0; }'. +nl_func_leave_one_liners = false # false/true + +# Don't split one-line C++11 lambdas - '[]() { return 0; }'. +nl_cpp_lambda_leave_one_liners = true # false/true + +# Don't split one-line if/else statements - 'if(a) b++;'. +nl_if_leave_one_liners = false # false/true + +# Don't split one-line while statements - 'while(a) b++;'. +nl_while_leave_one_liners = false # false/true + +# Don't split one-line OC messages. +nl_oc_msg_leave_one_liner = false # false/true + +# Add or remove newline between Objective-C block signature and '{'. +nl_oc_block_brace = ignore # ignore/add/remove/force + +# Add or remove newline between @interface and '{'. +nl_oc_interface_brace = ignore # ignore/add/remove/force + +# Add or remove newline between @implementation and '{'. +nl_oc_implementation_brace = ignore # ignore/add/remove/force + +# Add or remove newlines at the start of the file. +nl_start_of_file = remove # ignore/add/remove/force + +# The number of newlines at the start of the file (only used if nl_start_of_file is 'add' or 'force'. +nl_start_of_file_min = 0 # unsigned number + +# Add or remove newline at the end of the file. +nl_end_of_file = force # ignore/add/remove/force + +# The number of newlines at the end of the file (only used if nl_end_of_file is 'add' or 'force'). +nl_end_of_file_min = 1 # unsigned number + +# Add or remove newline between '=' and '{'. +nl_assign_brace = ignore # ignore/add/remove/force + +# Add or remove newline between '=' and '[' (D only). +nl_assign_square = ignore # ignore/add/remove/force + +# Add or remove newline between '[]' and '{'. +nl_tsquare_brace = ignore # ignore/add/remove/force + +# Add or remove newline after '= [' (D only). Will also affect the newline before the ']'. +nl_after_square_assign = ignore # ignore/add/remove/force + +# The number of blank lines after a block of variable definitions at the top of a function body +# 0 = No change (default). +nl_func_var_def_blk = 0 # unsigned number + +# The number of newlines before a block of typedefs +# 0 = No change (default) +# is overridden by the option 'nl_after_access_spec'. +nl_typedef_blk_start = 0 # unsigned number + +# The number of newlines after a block of typedefs +# 0 = No change (default). +nl_typedef_blk_end = 0 # unsigned number + +# The maximum consecutive newlines within a block of typedefs +# 0 = No change (default). +nl_typedef_blk_in = 0 # unsigned number + +# The number of newlines before a block of variable definitions not at the top of a function body +# 0 = No change (default) +# is overridden by the option 'nl_after_access_spec'. +nl_var_def_blk_start = 0 # unsigned number + +# The number of newlines after a block of variable definitions not at the top of a function body +# 0 = No change (default). +nl_var_def_blk_end = 0 # unsigned number + +# The maximum consecutive newlines within a block of variable definitions +# 0 = No change (default). +nl_var_def_blk_in = 0 # unsigned number + +# Add or remove newline between a function call's ')' and '{', as in: +# list_for_each(item, &list) { }. +nl_fcall_brace = remove # ignore/add/remove/force + +# Add or remove newline between 'enum' and '{'. +nl_enum_brace = remove # ignore/add/remove/force + +# Add or remove newline between 'enum' and 'class'. +nl_enum_class = remove # ignore/add/remove/force + +# Add or remove newline between 'enum class' and the identifier. +nl_enum_class_identifier = remove # ignore/add/remove/force + +# Add or remove newline between 'enum class' type and ':'. +nl_enum_identifier_colon = remove # ignore/add/remove/force + +# Add or remove newline between 'enum class identifier :' and 'type' and/or 'type'. +nl_enum_colon_type = remove # ignore/add/remove/force + +# Add or remove newline between 'struct and '{'. +nl_struct_brace = remove # ignore/add/remove/force + +# Add or remove newline between 'union' and '{'. +nl_union_brace = remove # ignore/add/remove/force + +# Add or remove newline between 'if' and '{'. +nl_if_brace = remove # ignore/add/remove/force + +# Add or remove newline between '}' and 'else'. +nl_brace_else = remove # ignore/add/remove/force + +# Add or remove newline between 'else if' and '{' +# If set to ignore, nl_if_brace is used instead. +nl_elseif_brace = remove # ignore/add/remove/force + +# Add or remove newline between 'else' and '{'. +nl_else_brace = remove # ignore/add/remove/force + +# Add or remove newline between 'else' and 'if'. +nl_else_if = remove # ignore/add/remove/force + +# Add or remove newline before 'if'/'else if' closing parenthesis. +nl_before_if_closing_paren = remove # ignore/add/remove/force + +# Add or remove newline between '}' and 'finally'. +nl_brace_finally = remove # ignore/add/remove/force + +# Add or remove newline between 'finally' and '{'. +nl_finally_brace = remove # ignore/add/remove/force + +# Add or remove newline between 'try' and '{'. +nl_try_brace = remove # ignore/add/remove/force + +# Add or remove newline between get/set and '{'. +nl_getset_brace = remove # ignore/add/remove/force + +# Add or remove newline between 'for' and '{'. +nl_for_brace = remove # ignore/add/remove/force + +# Add or remove newline between 'catch' and '{'. +nl_catch_brace = remove # ignore/add/remove/force + +# Add or remove newline between '@catch' and '{'. +# If set to ignore, nl_catch_brace is used. +nl_oc_catch_brace = remove # ignore/add/remove/force + +# Add or remove newline between '}' and 'catch'. +nl_brace_catch = remove # ignore/add/remove/force + +# Add or remove newline between '}' and 'catch'. +# If set to ignore, nl_brace_catch is used. +nl_oc_brace_catch = remove # ignore/add/remove/force + +# Add or remove newline between '}' and ']'. +nl_brace_square = remove # ignore/add/remove/force + +# Add or remove newline between '}' and ')' in a function invocation. +nl_brace_fparen = remove # ignore/add/remove/force + +# Add or remove newline between 'while' and '{'. +nl_while_brace = remove # ignore/add/remove/force + +# Add or remove newline between 'scope (x)' and '{' (D). +nl_scope_brace = remove # ignore/add/remove/force + +# Add or remove newline between 'unittest' and '{' (D). +nl_unittest_brace = remove # ignore/add/remove/force + +# Add or remove newline between 'version (x)' and '{' (D). +nl_version_brace = remove # ignore/add/remove/force + +# Add or remove newline between 'using' and '{'. +nl_using_brace = remove # ignore/add/remove/force + +# Add or remove newline between two open or close braces. +# Due to general newline/brace handling, REMOVE may not work. +nl_brace_brace = ignore # ignore/add/remove/force + +# Add or remove newline between 'do' and '{'. +nl_do_brace = remove # ignore/add/remove/force + +# Add or remove newline between '}' and 'while' of 'do' statement. +nl_brace_while = remove # ignore/add/remove/force + +# Add or remove newline between 'switch' and '{'. +nl_switch_brace = remove # ignore/add/remove/force + +# Add or remove newline between 'synchronized' and '{'. +nl_synchronized_brace = remove # ignore/add/remove/force + +# Add a newline between ')' and '{' if the ')' is on a different line than the if/for/etc. +# Overrides nl_for_brace, nl_if_brace, nl_switch_brace, nl_while_switch and nl_catch_brace. +nl_multi_line_cond = false # false/true + +# Force a newline in a define after the macro name for multi-line defines. +nl_multi_line_define = false # false/true + +# Whether to put a newline before 'case' statement, not after the first 'case'. +nl_before_case = false # false/true + +# Add or remove newline between ')' and 'throw'. +nl_before_throw = ignore # ignore/add/remove/force + +# Whether to put a newline after 'case' statement. +nl_after_case = false # false/true + +# Add or remove a newline between a case ':' and '{'. Overrides nl_after_case. +nl_case_colon_brace = remove # ignore/add/remove/force + +# Newline between namespace and {. +nl_namespace_brace = remove # ignore/add/remove/force + +# Add or remove newline between 'template<>' and whatever follows. +nl_template_class = ignore # ignore/add/remove/force + +# Add or remove newline between 'class' and '{'. +nl_class_brace = remove # ignore/add/remove/force + +# Add or remove newline before/after each ',' in the base class list, +# (tied to pos_class_comma). +nl_class_init_args = add # ignore/add/remove/force + +# Add or remove newline after each ',' in the constructor member initialization. +# Related to nl_constr_colon, pos_constr_colon and pos_constr_comma. +nl_constr_init_args = add # ignore/add/remove/force + +# Add or remove newline before first element, after comma, and after last element in enum. +nl_enum_own_lines = add # ignore/add/remove/force + +# Add or remove newline between return type and function name in a function definition. +nl_func_type_name = ignore # ignore/add/remove/force + +# Add or remove newline between return type and function name inside a class {} +# Uses nl_func_type_name or nl_func_proto_type_name if set to ignore. +nl_func_type_name_class = ignore # ignore/add/remove/force + +# Add or remove newline between class specification and '::' in 'void A::f() { }' +# Only appears in separate member implementation (does not appear with in-line implmementation). +nl_func_class_scope = ignore # ignore/add/remove/force + +# Add or remove newline between function scope and name +# Controls the newline after '::' in 'void A::f() { }'. +nl_func_scope_name = ignore # ignore/add/remove/force + +# Add or remove newline between return type and function name in a prototype. +nl_func_proto_type_name = remove # ignore/add/remove/force + +# Add or remove newline between a function name and the opening '(' in the declaration. +nl_func_paren = remove # ignore/add/remove/force + +# Overrides nl_func_paren for functions with no parameters. +nl_func_paren_empty = remove # ignore/add/remove/force + +# Add or remove newline between a function name and the opening '(' in the definition. +nl_func_def_paren = remove # ignore/add/remove/force + +# Overrides nl_func_def_paren for functions with no parameters. +nl_func_def_paren_empty = remove # ignore/add/remove/force + +# Add or remove newline between a function name and the opening '(' in the call +nl_func_call_paren = remove # ignore/add/remove/force + +# Overrides nl_func_call_paren for functions with no parameters. +nl_func_call_paren_empty = remove # ignore/add/remove/force + +# Add or remove newline after '(' in a function declaration. +nl_func_decl_start = ignore # ignore/add/remove/force + +# Add or remove newline after '(' in a function definition. +nl_func_def_start = ignore # ignore/add/remove/force + +# Overrides nl_func_decl_start when there is only one parameter. +nl_func_decl_start_single = ignore # ignore/add/remove/force + +# Overrides nl_func_def_start when there is only one parameter. +nl_func_def_start_single = ignore # ignore/add/remove/force + +# Whether to add newline after '(' in a function declaration if '(' and ')' are in different lines. +nl_func_decl_start_multi_line = true # false/true + +# Whether to add newline after '(' in a function definition if '(' and ')' are in different lines. +nl_func_def_start_multi_line = true # false/true + +# Add or remove newline after each ',' in a function declaration. +nl_func_decl_args = ignore # ignore/add/remove/force + +# Add or remove newline after each ',' in a function definition. +nl_func_def_args = ignore # ignore/add/remove/force + +# Whether to add newline after each ',' in a function declaration if '(' and ')' are in different lines. +nl_func_decl_args_multi_line = true # false/true + +# Whether to add newline after each ',' in a function definition if '(' and ')' are in different lines. +nl_func_def_args_multi_line = true # false/true + +# Add or remove newline before the ')' in a function declaration. +nl_func_decl_end = remove # ignore/add/remove/force + +# Add or remove newline before the ')' in a function definition. +nl_func_def_end = remove # ignore/add/remove/force + +# Overrides nl_func_decl_end when there is only one parameter. +nl_func_decl_end_single = ignore # ignore/add/remove/force + +# Overrides nl_func_def_end when there is only one parameter. +nl_func_def_end_single = ignore # ignore/add/remove/force + +# Whether to add newline before ')' in a function declaration if '(' and ')' are in different lines. +nl_func_decl_end_multi_line = false # false/true + +# Whether to add newline before ')' in a function definition if '(' and ')' are in different lines. +nl_func_def_end_multi_line = false # false/true + +# Add or remove newline between '()' in a function declaration. +nl_func_decl_empty = remove # ignore/add/remove/force + +# Add or remove newline between '()' in a function definition. +nl_func_def_empty = remove # ignore/add/remove/force + +# Add or remove newline between '()' in a function call. +nl_func_call_empty = remove # ignore/add/remove/force + +# Whether to add newline after '(' in a function call if '(' and ')' are in different lines. +nl_func_call_start_multi_line = false # false/true + +# Whether to add newline after each ',' in a function call if '(' and ')' are in different lines. +nl_func_call_args_multi_line = false # false/true + +# Whether to add newline before ')' in a function call if '(' and ')' are in different lines. +nl_func_call_end_multi_line = false # false/true + +# Whether to put each OC message parameter on a separate line +# See nl_oc_msg_leave_one_liner. +nl_oc_msg_args = false # false/true + +# Add or remove newline between function signature and '{'. +nl_fdef_brace = remove # ignore/add/remove/force + +# Add or remove newline between C++11 lambda signature and '{'. +nl_cpp_ldef_brace = remove # ignore/add/remove/force + +# Add or remove a newline between the return keyword and return expression. +nl_return_expr = ignore # ignore/add/remove/force + +# Whether to put a newline after semicolons, except in 'for' statements. +nl_after_semicolon = true # false/true + +# Java: Control the newline between the ')' and '{{' of the double brace initializer. +nl_paren_dbrace_open = ignore # ignore/add/remove/force + +# Whether to put a newline after the type in an unnamed temporary direct-list-initialization. +nl_type_brace_init_lst = ignore # ignore/add/remove/force + +# Whether to put a newline after open brace in an unnamed temporary direct-list-initialization. +nl_type_brace_init_lst_open = ignore # ignore/add/remove/force + +# Whether to put a newline before close brace in an unnamed temporary direct-list-initialization. +nl_type_brace_init_lst_close = ignore # ignore/add/remove/force + +# Whether to put a newline after brace open. +# This also adds a newline before the matching brace close. +nl_after_brace_open = false # false/true + +# If nl_after_brace_open and nl_after_brace_open_cmt are True, a newline is +# placed between the open brace and a trailing single-line comment. +nl_after_brace_open_cmt = false # false/true + +# Whether to put a newline after a virtual brace open with a non-empty body. +# These occur in un-braced if/while/do/for statement bodies. +nl_after_vbrace_open = false # false/true + +# Whether to put a newline after a virtual brace open with an empty body. +# These occur in un-braced if/while/do/for statement bodies. +nl_after_vbrace_open_empty = false # false/true + +# Whether to put a newline after a brace close. +# Does not apply if followed by a necessary ';'. +nl_after_brace_close = false # false/true + +# Whether to put a newline after a virtual brace close. +# Would add a newline before return in: 'if (foo) a++; return;'. +nl_after_vbrace_close = false # false/true + +# Control the newline between the close brace and 'b' in: 'struct { int a; } b;' +# Affects enums, unions and structures. If set to ignore, uses nl_after_brace_close. +nl_brace_struct_var = ignore # ignore/add/remove/force + +# Whether to alter newlines in '#define' macros. +nl_define_macro = false # false/true + +# Whether to alter newlines between consecutive paren closes, +# The number of closing paren in a line will depend on respective open paren lines +nl_squeeze_paren_close = false # false/true + +# Whether to remove blanks after '#ifxx' and '#elxx', or before '#elxx' and '#endif'. Does not affect top-level #ifdefs. +nl_squeeze_ifdef = false # false/true + +# Makes the nl_squeeze_ifdef option affect the top-level #ifdefs as well. +nl_squeeze_ifdef_top_level = false # false/true + +# Add or remove blank line before 'if'. +nl_before_if = ignore # ignore/add/remove/force + +# Add or remove blank line after 'if' statement. +# Add/Force work only if the next token is not a closing brace. +nl_after_if = ignore # ignore/add/remove/force + +# Add or remove blank line before 'for'. +nl_before_for = ignore # ignore/add/remove/force + +# Add or remove blank line after 'for' statement. +nl_after_for = ignore # ignore/add/remove/force + +# Add or remove blank line before 'while'. +nl_before_while = ignore # ignore/add/remove/force + +# Add or remove blank line after 'while' statement. +nl_after_while = ignore # ignore/add/remove/force + +# Add or remove blank line before 'switch'. +nl_before_switch = ignore # ignore/add/remove/force + +# Add or remove blank line after 'switch' statement. +nl_after_switch = ignore # ignore/add/remove/force + +# Add or remove blank line before 'synchronized'. +nl_before_synchronized = ignore # ignore/add/remove/force + +# Add or remove blank line after 'synchronized' statement. +nl_after_synchronized = ignore # ignore/add/remove/force + +# Add or remove blank line before 'do'. +nl_before_do = ignore # ignore/add/remove/force + +# Add or remove blank line after 'do/while' statement. +nl_after_do = ignore # ignore/add/remove/force + +# Whether to double-space commented-entries in struct/union/enum. +nl_ds_struct_enum_cmt = false # false/true + +# force nl before } of a struct/union/enum +# (lower priority than 'eat_blanks_before_close_brace'). +nl_ds_struct_enum_close_brace = false # false/true + +# Add or remove blank line before 'func_class_def'. +nl_before_func_class_def = 0 # unsigned number + +# Add or remove blank line before 'func_class_proto'. +nl_before_func_class_proto = 0 # unsigned number + +# Add or remove a newline before/after a class colon, +# (tied to pos_class_colon). +nl_class_colon = ignore # ignore/add/remove/force + +# Add or remove a newline around a class constructor colon. +# Related to nl_constr_init_args, pos_constr_colon and pos_constr_comma. +nl_constr_colon = ignore # ignore/add/remove/force + +# If true turns two liner namespace to one liner,else will make then four liners +nl_namespace_two_to_one_liner = false # false/true + +# Change simple unbraced if statements into a one-liner +# 'if(b)\n i++;' => 'if(b) i++;'. +nl_create_if_one_liner = false # false/true + +# Change simple unbraced for statements into a one-liner +# 'for (i=0;i<5;i++)\n foo(i);' => 'for (i=0;i<5;i++) foo(i);'. +nl_create_for_one_liner = false # false/true + +# Change simple unbraced while statements into a one-liner +# 'while (i<5)\n foo(i++);' => 'while (i<5) foo(i++);'. +nl_create_while_one_liner = false # false/true + +# Change simple 4,3,2 liner function def statements into a one-liner +nl_create_func_def_one_liner = false # false/true + +# Change a one-liner if statement into simple unbraced if +# 'if(b) i++;' => 'if(b)\n i++;'. +nl_split_if_one_liner = false # false/true + +# Change a one-liner for statement into simple unbraced for +# 'for (i=0;<5;i++) foo(i);' => 'for (i=0;<5;i++)\n foo(i);'. +nl_split_for_one_liner = false # false/true + +# Change a one-liner while statement into simple unbraced while +# 'while (i<5) foo(i++);' => 'while (i<5)\n foo(i++);'. +nl_split_while_one_liner = false # false/true + +# +# Blank line options +# + +# The maximum consecutive newlines (3 = 2 blank lines). +nl_max = 2 # unsigned number + +# The maximum consecutive newlines in function. +nl_max_blank_in_func = 0 # unsigned number + +# The number of newlines after a function prototype, if followed by another function prototype. +nl_after_func_proto = 2 # unsigned number + +# The number of newlines after a function prototype, if not followed by another function prototype. +nl_after_func_proto_group = 0 # unsigned number + +# The number of newlines after a function class prototype, if followed by another function class prototype. +nl_after_func_class_proto = 0 # unsigned number + +# The number of newlines after a function class prototype, if not followed by another function class prototype. +nl_after_func_class_proto_group = 0 # unsigned number + +# The number of newlines before a multi-line function def body. +nl_before_func_body_def = 0 # unsigned number + +# The number of newlines before a multi-line function prototype body. +nl_before_func_body_proto = 0 # unsigned number + +# The number of newlines after '}' of a multi-line function body. +nl_after_func_body = 0 # unsigned number + +# The number of newlines after '}' of a multi-line function body in a class declaration. +nl_after_func_body_class = 0 # unsigned number + +# The number of newlines after '}' of a single line function body. +nl_after_func_body_one_liner = 0 # unsigned number + +# The minimum number of newlines before a multi-line comment. +# Doesn't apply if after a brace open or another multi-line comment. +nl_before_block_comment = 0 # unsigned number + +# The minimum number of newlines before a single-line C comment. +# Doesn't apply if after a brace open or other single-line C comments. +nl_before_c_comment = 0 # unsigned number + +# The minimum number of newlines before a CPP comment. +# Doesn't apply if after a brace open or other CPP comments. +nl_before_cpp_comment = 0 # unsigned number + +# Whether to force a newline after a multi-line comment. +nl_after_multiline_comment = false # false/true + +# Whether to force a newline after a label's colon. +nl_after_label_colon = false # false/true + +# The number of newlines after '}' or ';' of a struct/enum/union definition. +nl_after_struct = 2 # unsigned number + +# The number of newlines before a class definition. +nl_before_class = 0 # unsigned number + +# The number of newlines after '}' or ';' of a class definition. +nl_after_class = 2 # unsigned number + +# The number of newlines before a 'private:', 'public:', 'protected:', 'signals:', or 'slots:' label. +# Will not change the newline count if after a brace open. +# 0 = No change. +nl_before_access_spec = 2 # unsigned number + +# The number of newlines after a 'private:', 'public:', 'protected:', 'signals:' or 'slots:' label. +# 0 = No change. +# Overrides 'nl_typedef_blk_start' and 'nl_var_def_blk_start'. +nl_after_access_spec = 2 # unsigned number + +# The number of newlines between a function def and the function comment. +# 0 = No change. +nl_comment_func_def = 0 # unsigned number + +# The number of newlines after a try-catch-finally block that isn't followed by a brace close. +# 0 = No change. +nl_after_try_catch_finally = 0 # unsigned number + +# The number of newlines before and after a property, indexer or event decl. +# 0 = No change. +nl_around_cs_property = 0 # unsigned number + +# The number of newlines between the get/set/add/remove handlers in C#. +# 0 = No change. +nl_between_get_set = 0 # unsigned number + +# Add or remove newline between C# property and the '{'. +nl_property_brace = ignore # ignore/add/remove/force + +# Whether to remove blank lines after '{'. +eat_blanks_after_open_brace = false # false/true + +# Whether to remove blank lines before '}'. +eat_blanks_before_close_brace = false # false/true + +# How aggressively to remove extra newlines not in preproc. +# 0: No change +# 1: Remove most newlines not handled by other config +# 2: Remove all newlines and reformat completely by config +nl_remove_extra_newlines = 0 # unsigned number + +# Whether to put a blank line before 'return' statements, unless after an open brace. +nl_before_return = false # false/true + +# Whether to put a blank line after 'return' statements, unless followed by a close brace. +nl_after_return = false # false/true + +# Whether to put a newline after a Java annotation statement. +# Only affects annotations that are after a newline. +nl_after_annotation = ignore # ignore/add/remove/force + +# Controls the newline between two annotations. +nl_between_annotation = ignore # ignore/add/remove/force + +# +# Positioning options +# + +# The position of arithmetic operators in wrapped expressions. +pos_arith = trail # ignore/join/lead/lead_break/lead_force/trail/trail_break/trail_force + +# The position of assignment in wrapped expressions. +# Do not affect '=' followed by '{'. +pos_assign = trail # ignore/join/lead/lead_break/lead_force/trail/trail_break/trail_force + +# The position of boolean operators in wrapped expressions. +pos_bool = trail # ignore/join/lead/lead_break/lead_force/trail/trail_break/trail_force + +# The position of comparison operators in wrapped expressions. +pos_compare = ignore # ignore/join/lead/lead_break/lead_force/trail/trail_break/trail_force + +# The position of conditional (b ? t : f) operators in wrapped expressions. +pos_conditional = ignore # ignore/join/lead/lead_break/lead_force/trail/trail_break/trail_force + +# The position of the comma in wrapped expressions. +pos_comma = trail # ignore/join/lead/lead_break/lead_force/trail/trail_break/trail_force + +# The position of the comma in enum entries. +pos_enum_comma = trail # ignore/join/lead/lead_break/lead_force/trail/trail_break/trail_force + +# The position of the comma in the base class list if there are more than one line, +# (tied to nl_class_init_args). +pos_class_comma = trail # ignore/join/lead/lead_break/lead_force/trail/trail_break/trail_force + +# The position of the comma in the constructor initialization list. +# Related to nl_constr_colon, nl_constr_init_args and pos_constr_colon. +pos_constr_comma = trail # ignore/join/lead/lead_break/lead_force/trail/trail_break/trail_force + +# The position of trailing/leading class colon, between class and base class list +# (tied to nl_class_colon). +pos_class_colon = lead # ignore/join/lead/lead_break/lead_force/trail/trail_break/trail_force + +# The position of colons between constructor and member initialization, +# (tied to nl_constr_colon). +# Related to nl_constr_colon, nl_constr_init_args and pos_constr_comma. +pos_constr_colon = lead # ignore/join/lead/lead_break/lead_force/trail/trail_break/trail_force + +# +# Line Splitting options +# + +# Try to limit code width to N number of columns +code_width = 110 # unsigned number + +# Whether to fully split long 'for' statements at semi-colons. +ls_for_split_full = true # false/true + +# Whether to fully split long function protos/calls at commas. +ls_func_split_full = true # false/true + +# Whether to split lines as close to code_width as possible and ignore some groupings. +ls_code_width = false # false/true + +# +# Code alignment (not left column spaces/tabs) +# + +# Whether to keep non-indenting tabs. +align_keep_tabs = false # false/true + +# Whether to use tabs for aligning. +align_with_tabs = false # false/true + +# Whether to bump out to the next tab when aligning. +align_on_tabstop = true # false/true + +# Whether to right-align numbers. +align_number_right = true # false/true + +# Whether to keep whitespace not required for alignment. +align_keep_extra_space = true # false/true + +# Align variable definitions in prototypes and functions. +align_func_params = false # false/true + +# The span for aligning parameter definitions in function on parameter name (0=don't align). +align_func_params_span = 0 # unsigned number + +# The threshold for aligning function parameter definitions (0=no limit). +align_func_params_thresh = 0 # unsigned number + +# The gap for aligning function parameter definitions. +align_func_params_gap = 0 # unsigned number + +# Align parameters in single-line functions that have the same name. +# The function names must already be aligned with each other. +align_same_func_call_params = false # false/true + +# The span for aligning variable definitions (0=don't align) +align_var_def_span = 0 # unsigned number + +# How to align the star in variable definitions. +# 0=Part of the type 'void * foo;' +# 1=Part of the variable 'void *foo;' +# 2=Dangling 'void *foo;' +align_var_def_star_style = 0 # unsigned number + +# How to align the '&' in variable definitions. +# 0=Part of the type +# 1=Part of the variable +# 2=Dangling +align_var_def_amp_style = 0 # unsigned number + +# The threshold for aligning variable definitions (0=no limit) +align_var_def_thresh = 0 # unsigned number + +# The gap for aligning variable definitions. +align_var_def_gap = 0 # unsigned number + +# Whether to align the colon in struct bit fields. +align_var_def_colon = false # false/true + +# align variable defs gap for bit colons. +align_var_def_colon_gap = 0 # unsigned number + +# Whether to align any attribute after the variable name. +align_var_def_attribute = false # false/true + +# Whether to align inline struct/enum/union variable definitions. +align_var_def_inline = false # false/true + +# The span for aligning on '=' in assignments (0=don't align) +align_assign_span = 0 # unsigned number + +# The threshold for aligning on '=' in assignments (0=no limit) +align_assign_thresh = 0 # unsigned number + +# The span for aligning on '=' in enums (0=don't align) +align_enum_equ_span = 1 # unsigned number + +# The threshold for aligning on '=' in enums (0=no limit) +align_enum_equ_thresh = 0 # unsigned number + +# The span for aligning class (0=don't align) +align_var_class_span = 0 # unsigned number + +# The threshold for aligning class member definitions (0=no limit). +align_var_class_thresh = 0 # unsigned number + +# The gap for aligning class member definitions. +align_var_class_gap = 0 # unsigned number + +# The span for aligning struct/union (0=don't align) +align_var_struct_span = 0 # unsigned number + +# The threshold for aligning struct/union member definitions (0=no limit) +align_var_struct_thresh = 0 # unsigned number + +# The gap for aligning struct/union member definitions. +align_var_struct_gap = 0 # unsigned number + +# The span for aligning struct initializer values (0=don't align) +align_struct_init_span = 0 # unsigned number + +# The minimum space between the type and the synonym of a typedef. +align_typedef_gap = 0 # unsigned number + +# The span for aligning single-line typedefs (0=don't align). +align_typedef_span = 0 # unsigned number + +# How to align typedef'd functions with other typedefs +# 0: Don't mix them at all +# 1: align the open paren with the types +# 2: align the function type name with the other type names +align_typedef_func = 0 # unsigned number + +# Controls the positioning of the '*' in typedefs. Just try it. +# 0: Align on typedef type, ignore '*' +# 1: The '*' is part of type name: typedef int *pint; +# 2: The '*' is part of the type, but dangling: typedef int *pint; +align_typedef_star_style = 0 # unsigned number + +# Controls the positioning of the '&' in typedefs. Just try it. +# 0: Align on typedef type, ignore '&' +# 1: The '&' is part of type name: typedef int &pint; +# 2: The '&' is part of the type, but dangling: typedef int &pint; +align_typedef_amp_style = 0 # unsigned number + +# The span for aligning comments that end lines (0=don't align) +align_right_cmt_span = 0 # unsigned number + +# If aligning comments, mix with comments after '}' and #endif with less than 3 spaces before the comment. +align_right_cmt_mix = false # false/true + +# If a trailing comment is more than this number of columns away from the text it follows, +# it will qualify for being aligned. This has to be > 0 to do anything. +align_right_cmt_gap = 0 # unsigned number + +# Align trailing comment at or beyond column N; 'pulls in' comments as a bonus side effect (0=ignore) +align_right_cmt_at_col = 0 # unsigned number + +# The span for aligning function prototypes (0=don't align). +align_func_proto_span = 0 # unsigned number + +# Minimum gap between the return type and the function name. +align_func_proto_gap = 0 # unsigned number + +# Align function protos on the 'operator' keyword instead of what follows. +align_on_operator = false # false/true + +# Whether to mix aligning prototype and variable declarations. +# If True, align_var_def_XXX options are used instead of align_func_proto_XXX options. +align_mix_var_proto = false # false/true + +# Align single-line functions with function prototypes, uses align_func_proto_span. +align_single_line_func = false # false/true + +# Aligning the open brace of single-line functions. +# Requires align_single_line_func=True, uses align_func_proto_span. +align_single_line_brace = false # false/true + +# Gap for align_single_line_brace. +align_single_line_brace_gap = 0 # unsigned number + +# The span for aligning ObjC msg spec (0=don't align) +align_oc_msg_spec_span = 0 # unsigned number + +# Whether to align macros wrapped with a backslash and a newline. +# This will not work right if the macro contains a multi-line comment. +align_nl_cont = true # false/true + +# # Align macro functions and variables together. +align_pp_define_together = false # false/true + +# The minimum space between label and value of a preprocessor define. +align_pp_define_gap = 1 # unsigned number + +# The span for aligning on '#define' bodies (0=don't align, other=number of lines including comments between blocks) +align_pp_define_span = 1 # unsigned number + +# Align lines that start with '<<' with previous '<<'. Default=True. +align_left_shift = true # false/true + +# Align text after asm volatile () colons. +align_asm_colon = false # false/true + +# Span for aligning parameters in an Obj-C message call on the ':' (0=don't align) +align_oc_msg_colon_span = 0 # unsigned number + +# If True, always align with the first parameter, even if it is too short. +align_oc_msg_colon_first = false # false/true + +# Aligning parameters in an Obj-C '+' or '-' declaration on the ':'. +align_oc_decl_colon = false # false/true + +# +# Comment modifications +# + +# Try to wrap comments at cmt_width columns +cmt_width = 80 # unsigned number + +# Set the comment reflow mode (Default=0) +# 0: no reflowing (apart from the line wrapping due to cmt_width) +# 1: no touching at all +# 2: full reflow +cmt_reflow_mode = 0 # unsigned number + +# Whether to convert all tabs to spaces in comments. Default is to leave tabs inside comments alone, unless used for indenting. +cmt_convert_tab_to_spaces = true # false/true + +# If False, disable all multi-line comment changes, including cmt_width. keyword substitution and leading chars. +# Default=True. +cmt_indent_multi = true # false/true + +# Whether to group c-comments that look like they are in a block. +cmt_c_group = false # false/true + +# Whether to put an empty '/*' on the first line of the combined c-comment. +cmt_c_nl_start = false # false/true + +# Whether to put a newline before the closing '*/' of the combined c-comment. +cmt_c_nl_end = false # false/true + +# Whether to group cpp-comments that look like they are in a block. +cmt_cpp_group = false # false/true + +# Whether to put an empty '/*' on the first line of the combined cpp-comment. +cmt_cpp_nl_start = false # false/true + +# Whether to put a newline before the closing '*/' of the combined cpp-comment. +cmt_cpp_nl_end = false # false/true + +# Whether to change cpp-comments into c-comments. +cmt_cpp_to_c = false # false/true + +# Whether to put a star on subsequent comment lines. +cmt_star_cont = false # false/true + +# The number of spaces to insert at the start of subsequent comment lines. +cmt_sp_before_star_cont = 0 # unsigned number + +# The number of spaces to insert after the star on subsequent comment lines. +cmt_sp_after_star_cont = 0 # number + +# For multi-line comments with a '*' lead, remove leading spaces if the first and last lines of +# the comment are the same length. Default=True. +cmt_multi_check_last = true # false/true + +# For multi-line comments with a '*' lead, remove leading spaces if the first and last lines of +# the comment are the same length AND if the length is bigger as the first_len minimum. Default=4 +cmt_multi_first_len_minimum = 4 # unsigned number + +# The filename that contains text to insert at the head of a file if the file doesn't start with a C/C++ comment. +# Will substitute $(filename) with the current file's name. +cmt_insert_file_header = "" # string + +# The filename that contains text to insert at the end of a file if the file doesn't end with a C/C++ comment. +# Will substitute $(filename) with the current file's name. +cmt_insert_file_footer = "" # string + +# The filename that contains text to insert before a function implementation if the function isn't preceded with a C/C++ comment. +# Will substitute $(function) with the function name and $(javaparam) with the javadoc @param and @return stuff. +# Will also substitute $(fclass) with the class name: void CFoo::Bar() { ... }. +cmt_insert_func_header = "" # string + +# The filename that contains text to insert before a class if the class isn't preceded with a C/C++ comment. +# Will substitute $(class) with the class name. +cmt_insert_class_header = "" # string + +# The filename that contains text to insert before a Obj-C message specification if the method isn't preceded with a C/C++ comment. +# Will substitute $(message) with the function name and $(javaparam) with the javadoc @param and @return stuff. +cmt_insert_oc_msg_header = "" # string + +# If a preprocessor is encountered when stepping backwards from a function name, then +# this option decides whether the comment should be inserted. +# Affects cmt_insert_oc_msg_header, cmt_insert_func_header and cmt_insert_class_header. +cmt_insert_before_preproc = false # false/true + +# If a function is declared inline to a class definition, then +# this option decides whether the comment should be inserted. +# Affects cmt_insert_func_header. +cmt_insert_before_inlines = true # false/true + +# If the function is a constructor/destructor, then +# this option decides whether the comment should be inserted. +# Affects cmt_insert_func_header. +cmt_insert_before_ctor_dtor = false # false/true + +# +# Code modifying options (non-whitespace) +# + +# Add or remove braces on single-line 'do' statement. +mod_full_brace_do = add # ignore/add/remove/force + +# Add or remove braces on single-line 'for' statement. +mod_full_brace_for = add # ignore/add/remove/force + +# Add or remove braces on single-line function definitions. (Pawn). +mod_full_brace_function = add # ignore/add/remove/force + +# Add or remove braces on single-line 'if' statement. Will not remove the braces if they contain an 'else'. +mod_full_brace_if = add # ignore/add/remove/force + +# Make all if/elseif/else statements in a chain be braced or not. Overrides mod_full_brace_if. +# If any must be braced, they are all braced. If all can be unbraced, then the braces are removed. +mod_full_brace_if_chain = false # false/true + +# Make all if/elseif/else statements with at least one 'else' or 'else if' fully braced. +# If mod_full_brace_if_chain is used together with this option, all if-else chains will get braces, +# and simple 'if' statements will lose them (if possible). +mod_full_brace_if_chain_only = false # false/true + +# Don't remove braces around statements that span N newlines +mod_full_brace_nl = 0 # unsigned number + +# Blocks removal of braces if the parenthesis of if/for/while/.. span multiple lines. +mod_full_brace_nl_block_rem_mlcond = false # false/true + +# Add or remove braces on single-line 'while' statement. +mod_full_brace_while = add # ignore/add/remove/force + +# Add or remove braces on single-line 'using ()' statement. +mod_full_brace_using = ignore # ignore/add/remove/force + +# Add or remove unnecessary paren on 'return' statement. +mod_paren_on_return = ignore # ignore/add/remove/force + +# Whether to change optional semicolons to real semicolons. +mod_pawn_semicolon = false # false/true + +# Add parens on 'while' and 'if' statement around bools. +mod_full_paren_if_bool = false # false/true + +# Whether to remove superfluous semicolons. +mod_remove_extra_semicolon = true # false/true + +# If a function body exceeds the specified number of newlines and doesn't have a comment after +# the close brace, a comment will be added. +mod_add_long_function_closebrace_comment = 0 # unsigned number + +# If a namespace body exceeds the specified number of newlines and doesn't have a comment after +# the close brace, a comment will be added. +mod_add_long_namespace_closebrace_comment = 0 # unsigned number + +# If a class body exceeds the specified number of newlines and doesn't have a comment after +# the close brace, a comment will be added. +mod_add_long_class_closebrace_comment = 0 # unsigned number + +# If a switch body exceeds the specified number of newlines and doesn't have a comment after +# the close brace, a comment will be added. +mod_add_long_switch_closebrace_comment = 0 # unsigned number + +# If an #ifdef body exceeds the specified number of newlines and doesn't have a comment after +# the #endif, a comment will be added. +mod_add_long_ifdef_endif_comment = 0 # unsigned number + +# If an #ifdef or #else body exceeds the specified number of newlines and doesn't have a comment after +# the #else, a comment will be added. +mod_add_long_ifdef_else_comment = 0 # unsigned number + +# If True, will sort consecutive single-line 'import' statements [Java, D]. +mod_sort_import = false # false/true + +# If True, will sort consecutive single-line 'using' statements [C#]. +mod_sort_using = false # false/true + +# If True, will sort consecutive single-line '#include' statements [C/C++] and '#import' statements [Obj-C] +# This is generally a bad idea, as it may break your code. +mod_sort_include = false # false/true + +# If True, it will move a 'break' that appears after a fully braced 'case' before the close brace. +mod_move_case_break = true # false/true + +# Will add or remove the braces around a fully braced case statement. +# Will only remove the braces if there are no variable declarations in the block. +mod_case_brace = ignore # ignore/add/remove/force + +# If True, it will remove a void 'return;' that appears as the last statement in a function. +mod_remove_empty_return = true # false/true + +# If True, it will organize the properties (Obj-C). +mod_sort_oc_properties = false # false/true + +# Determines weight of class property modifier (Obj-C). +mod_sort_oc_property_class_weight = 0 # number + +# Determines weight of atomic, nonatomic (Obj-C). +mod_sort_oc_property_thread_safe_weight = 0 # number + +# Determines weight of readwrite (Obj-C). +mod_sort_oc_property_readwrite_weight = 0 # number + +# Determines weight of reference type (retain, copy, assign, weak, strong) (Obj-C). +mod_sort_oc_property_reference_weight = 0 # number + +# Determines weight of getter type (getter=) (Obj-C). +mod_sort_oc_property_getter_weight = 0 # number + +# Determines weight of setter type (setter=) (Obj-C). +mod_sort_oc_property_setter_weight = 0 # number + +# Determines weight of nullability type (nullable, nonnull, null_unspecified, null_resettable) (Obj-C). +mod_sort_oc_property_nullability_weight = 0 # number + +# +# Preprocessor options +# + +# Control indent of preprocessors inside #if blocks at brace level 0 (file-level). +pp_indent = force # ignore/add/remove/force + +# Whether to indent #if/#else/#endif at the brace level (True) or from column 1 (False). +pp_indent_at_level = false # false/true + +# Specifies the number of columns to indent preprocessors per level at brace level 0 (file-level). +# If pp_indent_at_level=False, specifies the number of columns to indent preprocessors per level at brace level > 0 (function-level). +# Default=1. +pp_indent_count = 0 # unsigned number + +# Add or remove space after # based on pp_level of #if blocks. +pp_space = ignore # ignore/add/remove/force + +# Sets the number of spaces added with pp_space. +pp_space_count = 0 # unsigned number + +# The indent for #region and #endregion in C# and '#pragma region' in C/C++. +pp_indent_region = 0 # number + +# Whether to indent the code between #region and #endregion. +pp_region_indent_code = false # false/true + +# If pp_indent_at_level=True, sets the indent for #if, #else and #endif when not at file-level. +# 0: indent preprocessors using output_tab_size. +# >0: column at which all preprocessors will be indented. +pp_indent_if = 0 # number + +# Control whether to indent the code between #if, #else and #endif. +pp_if_indent_code = false # false/true + +# Whether to indent '#define' at the brace level (True) or from column 1 (false). +pp_define_at_level = false # false/true + +# Whether to ignore the '#define' body while formatting. +pp_ignore_define_body = false # false/true + +# Whether to indent case statements between #if, #else, and #endif. +# Only applies to the indent of the preprocesser that the case statements directly inside of. +pp_indent_case = true # false/true + +# Whether to indent whole function definitions between #if, #else, and #endif. +# Only applies to the indent of the preprocesser that the function definition is directly inside of. +pp_indent_func_def = true # false/true + +# Whether to indent extern C blocks between #if, #else, and #endif. +# Only applies to the indent of the preprocesser that the extern block is directly inside of. +pp_indent_extern = true # false/true + +# Whether to indent braces directly inside #if, #else, and #endif. +# Only applies to the indent of the preprocesser that the braces are directly inside of. +pp_indent_brace = true # false/true + +# +# Sort includes options +# + +# The regex for include category with priority 0. +include_category_0 = "" # string + +# The regex for include category with priority 1. +include_category_1 = "" # string + +# The regex for include category with priority 2. +include_category_2 = "" # string + +# +# Use or Do not Use options +# + +# True: indent_func_call_param will be used (default) +# False: indent_func_call_param will NOT be used. +use_indent_func_call_param = true # false/true + +# The value of the indentation for a continuation line is calculate differently if the statement is: +# a declaration: your case with QString fileName ... +# an assignment: your case with pSettings = new QSettings( ... +# At the second case the indentation value might be used twice: +# at the assignment +# at the function call (if present) +# To prevent the double use of the indentation value, use this option with the value 'True'. +# True: indent_continue will be used only once +# False: indent_continue will be used every time (default). +use_indent_continue_only_once = false # false/true + +# the value might be used twice: +# at the assignment +# at the opening brace +# To prevent the double use of the indentation value, use this option with the value 'True'. +# True: indentation will be used only once +# False: indentation will be used every time (default). +indent_cpp_lambda_only_once = true # false/true + +# SIGNAL/SLOT Qt macros have special formatting options. See options_for_QT.cpp for details. +# Default=True. +use_options_overriding_for_qt_macros = true # false/true + +# +# Warn levels - 1: error, 2: warning (default), 3: note +# + +# Warning is given if doing tab-to-\t replacement and we have found one in a C# verbatim string literal. +warn_level_tabs_found_in_verbatim_string_literals = 2 # unsigned number + +# Meaning of the settings: +# Ignore - do not do any changes +# Add - makes sure there is 1 or more space/brace/newline/etc +# Force - makes sure there is exactly 1 space/brace/newline/etc, +# behaves like Add in some contexts +# Remove - removes space/brace/newline/etc +# +# +# - Token(s) can be treated as specific type(s) with the 'set' option: +# `set tokenType tokenString [tokenString...]` +# +# Example: +# `set BOOL __AND__ __OR__` +# +# tokenTypes are defined in src/token_enum.h, use them without the +# 'CT_' prefix: 'CT_BOOL' -> 'BOOL' +# +# +# - Token(s) can be treated as type(s) with the 'type' option. +# `type tokenString [tokenString...]` +# +# Example: +# `type int c_uint_8 Rectangle` +# +# This can also be achieved with `set TYPE int c_uint_8 Rectangle` +# +# +# To embed whitespace in tokenStrings use the '\' escape character, or quote +# the tokenStrings. These quotes are supported: "'` +# +# +# - Support for the auto detection of languages through the file ending can be +# added using the 'file_ext' command. +# `file_ext langType langString [langString..]` +# +# Example: +# `file_ext CPP .ch .cxx .cpp.in` +# +# langTypes are defined in uncrusify_types.h in the lang_flag_e enum, use +# them without the 'LANG_' prefix: 'LANG_CPP' -> 'CPP' +# +# +# - Custom macro-based indentation can be set up using 'macro-open', +# 'macro-else' and 'macro-close'. +# `(macro-open | macro-else | macro-close) tokenString` +# +# Example: +# `macro-open BEGIN_TEMPLATE_MESSAGE_MAP` +# `macro-open BEGIN_MESSAGE_MAP` +# `macro-close END_MESSAGE_MAP` +# +# +# option(s) with 'not default' value: 0 +# diff --git a/Util/CARLA.sublime-project b/Util/CARLA.sublime-project new file mode 100644 index 000000000..aa8975f8c --- /dev/null +++ b/Util/CARLA.sublime-project @@ -0,0 +1,138 @@ +{ + "folders": + [ + { + "path": "..", + "file_exclude_patterns": + [ + "*.VC.db", + "*.VC.opendb", + "*.gdb_history", + "*.kdev4", + "*.pri", + "*.pro", + "*.py[cod]", + "*.sln", + "*.stackdump", + "*.sublime-workspace", + "*.uasset", + "*.umap", + "*.workspace", + "*CodeCompletionFolders.txt", + "*CodeLitePreProcessor.txt", + ".tags*", + "core" + ], + "folder_exclude_patterns": + [ + ".clang", + ".codelite", + ".kdev4", + ".vs", + ".vscode", + "Binaries", + "DerivedDataCache", + "Dist", + "Doxygen", + "Intermediate", + "PythonAPI/build", + "PythonAPI/dependencies", + "PythonAPI/dist", + "Saved", + "Unreal/CarlaUE4/Content*", + "Unreal/CarlaUE4/Plugins/Carla/CarlaDependencies", + "__pycache__", + "_site" + ], + } + ], + "settings": + { + "ensure_newline_at_eof_on_save": true, + "tab_size": 2, + "translate_tabs_to_spaces": true, + "trim_trailing_white_space_on_save": true + }, + "build_systems": + [ + { + "name": "CARLA - make CarlaUE4Editor", + "working_dir": "${project_path}/..", + "file_regex": "(Unreal\\/CarlaUE4\\/[^:]*):([0-9]+):?([0-9]+)?:? (.*)$", + "syntax": "Packages/Makefile/Make Output.sublime-syntax", + "linux": + { + "shell_cmd": "CARLA_BUILD_NO_COLOR=true make CarlaUE4Editor" + } + }, + { + "name": "CARLA - make LibCarla", + "working_dir": "${project_path}/..", + "file_regex": "^../../([^:]*):([0-9]+):?([0-9]+)?:? (.*)$", + "syntax": "Packages/Makefile/Make Output.sublime-syntax", + "linux": + { + "shell_cmd": "CARLA_BUILD_NO_COLOR=true make LibCarla" + } + }, + { + "name": "CARLA - make PythonAPI", + "working_dir": "${project_path}/..", + "file_regex": "^../../([^:]*):([0-9]+):?([0-9]+)?:? (.*)$", + "syntax": "Packages/Makefile/Make Output.sublime-syntax", + "linux": + { + "shell_cmd": "CARLA_BUILD_NO_COLOR=true make PythonAPI" + } + }, + { + "name": "CARLA - make check", + "working_dir": "${project_path}/..", + "file_regex": "^../../([^:]*):([0-9]+):?([0-9]+)?:? (.*)$", + "syntax": "Packages/Makefile/Make Output.sublime-syntax", + "linux": + { + "shell_cmd": "CARLA_BUILD_NO_COLOR=true make check" + } + }, + { + "name": "CARLA - make check LibCarla", + "working_dir": "${project_path}/..", + "file_regex": "^../../([^:]*):([0-9]+):?([0-9]+)?:? (.*)$", + "syntax": "Packages/Makefile/Make Output.sublime-syntax", + "linux": + { + "shell_cmd": "CARLA_BUILD_NO_COLOR=true make check ARGS=\"--carlalib-debug\"" + } + }, + { + "name": "CARLA - make check LibCarla (launch GDB)", + "working_dir": "${project_path}/..", + "file_regex": "^../../([^:]*):([0-9]+):?([0-9]+)?:? (.*)$", + "syntax": "Packages/Makefile/Make Output.sublime-syntax", + "linux": + { + "shell_cmd": "gnome-terminal --maximize -e 'make check ARGS=\"--gdb --carlalib-debug\"'" + } + }, + { + "name": "CARLA - make clean", + "working_dir": "${project_path}/..", + "syntax": "Packages/Makefile/Make Output.sublime-syntax", + "linux": + { + "shell_cmd": "CARLA_BUILD_NO_COLOR=true make clean" + } + }, + { + "name": "CARLA - Prettify this file", + "working_dir": "${project_path}/..", + "file_regex": "^([^:]*):([0-9]+):?([0-9]+)?:? (.*)$", + "syntax": "Packages/Makefile/Make Output.sublime-syntax", + "linux": + { + "shell_cmd": "CARLA_BUILD_NO_COLOR=true make pretty ARGS=-f${file}" + } + } + ] +} diff --git a/mkdocs.yml b/mkdocs.yml index 964c8132d..3a366e59b 100644 --- a/mkdocs.yml +++ b/mkdocs.yml @@ -35,6 +35,7 @@ pages: - 'How to add assets': 'how_to_add_assets.md' - 'CARLA design': 'carla_design.md' - 'CarlaServer documentation': 'carla_server.md' + - 'Build system': 'build_system.md' - Appendix: - 'Driving Benchmark Sample Results Town01': 'benchmark_basic_results_town01.md' - 'Driving Benchmark Sample Results Town02': 'benchmark_basic_results_town02.md' From 90b58429bb748939d6180fbee7b699a5f357c9d6 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Fri, 6 Jul 2018 13:14:48 +0200 Subject: [PATCH 05/71] Update Jenkins pipeline --- Jenkinsfile | 34 ++++++++++++++++--- LibCarla/source/compiler/disable-ue4-macros.h | 10 ++++++ LibCarla/source/test/test.h | 2 +- 3 files changed, 40 insertions(+), 6 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index c16ff0fdd..4c8e1b0d2 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -2,7 +2,7 @@ pipeline { agent any environment { - UE4_ROOT = '/var/lib/jenkins/UnrealEngine_4.18' + UE4_ROOT = '/var/lib/jenkins/UnrealEngine_4.19' } options { @@ -13,19 +13,43 @@ pipeline { stage('Setup') { steps { - sh './Setup.sh --jobs=12' + sh 'make setup' } } - stage('Build') { + stage('Download Content') { steps { - sh './Rebuild.sh --no-editor' + sh './Update.sh' + } + } + + stage('LibCarla') { + steps { + sh 'make LibCarla' + } + } + + stage('PythonAPI') { + steps { + sh 'make PythonAPI' + } + } + + stage('Unit Tests') { + steps { + sh 'make check' + } + } + + stage('CarlaUE4Editor') { + steps { + sh 'make CarlaUE4Editor' } } stage('Package') { steps { - sh './Package.sh --clean-intermediate' + sh 'make package' } } diff --git a/LibCarla/source/compiler/disable-ue4-macros.h b/LibCarla/source/compiler/disable-ue4-macros.h index 6d3f61a0d..4a95f7757 100644 --- a/LibCarla/source/compiler/disable-ue4-macros.h +++ b/LibCarla/source/compiler/disable-ue4-macros.h @@ -16,3 +16,13 @@ #ifndef BOOST_COROUTINES_NO_DEPRECATION_WARNING # define BOOST_COROUTINES_NO_DEPRECATION_WARNING #endif // BOOST_COROUTINES_NO_DEPRECATION_WARNING + +#ifndef BOOST_NO_EXCEPTIONS +# define BOOST_NO_EXCEPTIONS +#endif // BOOST_NO_EXCEPTIONS + +namespace boost { + + static inline void throw_exception(const std::exception &) {} + +} // namespace boost diff --git a/LibCarla/source/test/test.h b/LibCarla/source/test/test.h index eb185bc0d..487182fac 100644 --- a/LibCarla/source/test/test.h +++ b/LibCarla/source/test/test.h @@ -21,6 +21,6 @@ #include #include -constexpr uint16_t TESTING_PORT = 8080u; +constexpr uint16_t TESTING_PORT = 2000u; using namespace std::chrono_literals; From 113dc4b6b8c35198cbae3f0ab69e66a5dce114cc Mon Sep 17 00:00:00 2001 From: nsubiron Date: Fri, 6 Jul 2018 18:14:38 +0200 Subject: [PATCH 06/71] Report test results as XML for Jenkins --- Jenkinsfile | 3 ++- PythonAPI/test/unittest.cfg | 4 ++++ Util/BuildTools/Check.sh | 42 +++++++++++++++++++++++++++++++------ Util/BuildTools/Vars.mk | 1 + 4 files changed, 43 insertions(+), 7 deletions(-) create mode 100644 PythonAPI/test/unittest.cfg diff --git a/Jenkinsfile b/Jenkinsfile index 4c8e1b0d2..73e9a75f8 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -37,7 +37,7 @@ pipeline { stage('Unit Tests') { steps { - sh 'make check' + sh 'make check ARGS="--all --xml"' } } @@ -58,6 +58,7 @@ pipeline { post { always { + junit 'Build/test-results/*.xml' archiveArtifacts 'Dist/*.tar.gz' deleteDir() } diff --git a/PythonAPI/test/unittest.cfg b/PythonAPI/test/unittest.cfg new file mode 100644 index 000000000..4bdfb4b1e --- /dev/null +++ b/PythonAPI/test/unittest.cfg @@ -0,0 +1,4 @@ +[unittest] +plugins = nose2.plugins.junitxml +[junit-xml] +path = test-results.xml diff --git a/Util/BuildTools/Check.sh b/Util/BuildTools/Check.sh index db3609226..c31b8420a 100755 --- a/Util/BuildTools/Check.sh +++ b/Util/BuildTools/Check.sh @@ -9,7 +9,7 @@ source $(dirname "$0")/Environment.sh DOC_STRING="Run unit tests." USAGE_STRING=$(cat <<- END -Usage: $0 [-h|--help] [--gdb] [--gtest_args=ARGS] +Usage: $0 [-h|--help] [--gdb] [--xml] [--gtest_args=ARGS] Then either ran all the tests @@ -24,13 +24,14 @@ END ) GDB= +XML_OUTPUT=false GTEST_ARGS= LIBCARLA_RELEASE=false LIBCARLA_DEBUG=false PYTHON_API_2=false PYTHON_API_3=false -OPTS=`getopt -o h --long help,gdb,gtest_args:,all,libcarla-release,libcarla-debug,python-api-2,python-api-3,benchmark -n 'parse-options' -- "$@"` +OPTS=`getopt -o h --long help,gdb,xml,gtest_args:,all,libcarla-release,libcarla-debug,python-api-2,python-api-3,benchmark -n 'parse-options' -- "$@"` if [ $? != 0 ] ; then echo "$USAGE_STRING" ; exit 2 ; fi @@ -41,6 +42,9 @@ while true; do --gdb ) GDB="gdb --args"; shift ;; + --xml ) + XML_OUTPUT=true; + shift ;; --gtest_args ) GTEST_ARGS="$2"; shift ;; @@ -86,17 +90,29 @@ fi if ${LIBCARLA_DEBUG} ; then + if ${XML_OUTPUT} ; then + EXTRA_ARGS="--gtest_output=xml:${CARLA_TEST_RESULTS_FOLDER}/libcarla-debug.xml" + else + EXTRA_ARGS= + fi + log "Running LibCarla unit tests debug." - LD_LIBRARY_PATH=${LIBCARLA_INSTALL_SERVER_FOLDER}/lib ${GDB} ${LIBCARLA_INSTALL_SERVER_FOLDER}/test/libcarla_test_debug ${GTEST_ARGS} + LD_LIBRARY_PATH=${LIBCARLA_INSTALL_SERVER_FOLDER}/lib ${GDB} ${LIBCARLA_INSTALL_SERVER_FOLDER}/test/libcarla_test_debug ${GTEST_ARGS} ${EXTRA_ARGS} fi if ${LIBCARLA_RELEASE} ; then + if ${XML_OUTPUT} ; then + EXTRA_ARGS="--gtest_output=xml:${CARLA_TEST_RESULTS_FOLDER}/libcarla-release.xml" + else + EXTRA_ARGS= + fi + log "Running LibCarla unit tests release." - LD_LIBRARY_PATH=${LIBCARLA_INSTALL_SERVER_FOLDER}/lib ${GDB} ${LIBCARLA_INSTALL_SERVER_FOLDER}/test/libcarla_test_release ${GTEST_ARGS} + LD_LIBRARY_PATH=${LIBCARLA_INSTALL_SERVER_FOLDER}/lib ${GDB} ${LIBCARLA_INSTALL_SERVER_FOLDER}/test/libcarla_test_release ${GTEST_ARGS} ${EXTRA_ARGS} fi @@ -106,11 +122,21 @@ fi pushd "${CARLA_PYTHONAPI_ROOT_FOLDER}/test" >/dev/null +if ${XML_OUTPUT} ; then + EXTRA_ARGS="-X" +else + EXTRA_ARGS= +fi + if ${PYTHON_API_2} ; then log "Running Python API for Python 2 unit tests." - /usr/bin/env python2 -m nose2 + /usr/bin/env python2 -m nose2 ${EXTRA_ARGS} + + if ${XML_OUTPUT} ; then + mv test-results.xml ${CARLA_TEST_RESULTS_FOLDER}/python-api-2.xml + fi fi @@ -118,7 +144,11 @@ if ${PYTHON_API_3} ; then log "Running Python API for Python 3 unit tests." - /usr/bin/env python3 -m nose2 + /usr/bin/env python3 -m nose2 ${EXTRA_ARGS} + + if ${XML_OUTPUT} ; then + mv test-results.xml ${CARLA_TEST_RESULTS_FOLDER}/python-api-3.xml + fi fi diff --git a/Util/BuildTools/Vars.mk b/Util/BuildTools/Vars.mk index 997f4ab8e..c01c6b79e 100644 --- a/Util/BuildTools/Vars.mk +++ b/Util/BuildTools/Vars.mk @@ -4,6 +4,7 @@ CARLA_ROOT_FOLDER=${CURDIR} CARLA_BUILD_FOLDER=${CURDIR}/Build CARLA_DIST_FOLDER=${CURDIR}/Dist CARLA_BUILD_TOOLS_FOLDER=${CURDIR}/Util/BuildTools +CARLA_TEST_RESULTS_FOLDER=${CARLA_BUILD_FOLDER}/test-results CARLAUE4_ROOT_FOLDER=${CURDIR}/Unreal/CarlaUE4 CARLAUE4_PLUGIN_ROOT_FOLDER=${CURDIR}/Unreal/CarlaUE4/Plugins/Carla From b4885db53ea2c7f3d856b5528c53f160d4eb3d77 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Fri, 6 Jul 2018 18:58:51 +0200 Subject: [PATCH 07/71] Archive profiler generated data in Jenkins build --- Jenkinsfile | 1 + 1 file changed, 1 insertion(+) diff --git a/Jenkinsfile b/Jenkinsfile index 73e9a75f8..a8d85281c 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -59,6 +59,7 @@ pipeline { always { junit 'Build/test-results/*.xml' + archiveArtifacts 'profiler.csv' archiveArtifacts 'Dist/*.tar.gz' deleteDir() } From e930133ebb251761bff9e96f0b8ccba95064f562 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Tue, 10 Jul 2018 12:54:57 +0200 Subject: [PATCH 08/71] Add unit tests to travis build --- .travis.yml | 61 +++++++++++++++++++++++++++++++++-------------------- 1 file changed, 38 insertions(+), 23 deletions(-) diff --git a/.travis.yml b/.travis.yml index 3a2830407..a6b9b8880 100644 --- a/.travis.yml +++ b/.travis.yml @@ -1,35 +1,50 @@ -language: python +language: cpp +compiler: clang os: linux -dist: trusty # xenial is not yet supported. - -env: TEST="Pylint" -python: - - "3.5" - - "3.6" - - "2.7" -install: - - pip install -r PythonClient/requirements.txt - - pip install pylint -script: - - pylint --disable=R,C --rcfile=PythonClient/.pylintrc PythonClient/carla PythonClient/*.py +dist: trusty +sudo: false matrix: include: - # CppCheck does not support C++17. - # - env: TEST="CppCheck" - # install: true - # addons: - # apt: - # packages: - # - cppcheck - # script: - # - cppcheck . -iBuild -i.pb.cc --error-exitcode=1 --enable=warning --inline-suppr --quiet + - env: TEST="Unit Tests" + addons: + apt: + sources: + - ubuntu-toolchain-r-test + - llvm-toolchain-trusty-5.0 + packages: + - g++-7 # we need this one for the libstdc++. + - clang-5.0 + - ninja-build + - python + - python-pip + - python3 + - python3-pip + - libboost-python-dev + install: + - pip2 install --user setuptools nose2 + - pip3 install --user setuptools nose2 + - make setup + script: + - make check ARGS="--all --gtest_args=--gtest_filter=-*_mt" + + - env: TEST="Pylint 2" + addons: + apt: + packages: + - python + - python-pip + install: + - pip2 install --user -r PythonClient/requirements.txt + - pip2 install --user pylint + script: + - pylint --disable=R,C --rcfile=PythonClient/.pylintrc PythonClient/carla PythonClient/*.py - env: TEST="MkDocs" install: - - pip install mkdocs + - pip install --user mkdocs script: - mkdocs build --verbose --clean --strict --site-dir _site From 83e16d065f30f382ed9ea0fb270b9800a6ac67e7 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Tue, 10 Jul 2018 16:26:05 +0200 Subject: [PATCH 09/71] Refactor Jenkins pipeline --- Jenkinsfile | 35 +++++++++++++---------------------- 1 file changed, 13 insertions(+), 22 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index a8d85281c..e8b7ae9bc 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -6,7 +6,7 @@ pipeline { } options { - buildDiscarder(logRotator(numToKeepStr: '6', artifactNumToKeepStr: '6')) + buildDiscarder(logRotator(numToKeepStr: '3', artifactNumToKeepStr: '3')) } stages { @@ -14,24 +14,15 @@ pipeline { stage('Setup') { steps { sh 'make setup' - } - } - - stage('Download Content') { - steps { sh './Update.sh' } } - stage('LibCarla') { + stage('Build') { steps { sh 'make LibCarla' - } - } - - stage('PythonAPI') { - steps { sh 'make PythonAPI' + sh 'make CarlaUE4Editor' } } @@ -39,11 +30,11 @@ pipeline { steps { sh 'make check ARGS="--all --xml"' } - } - - stage('CarlaUE4Editor') { - steps { - sh 'make CarlaUE4Editor' + post { + always { + junit 'Build/test-results/*.xml' + archiveArtifacts 'profiler.csv' + } } } @@ -51,18 +42,18 @@ pipeline { steps { sh 'make package' } + post { + always { + archiveArtifacts 'Dist/*.tar.gz' + } + } } } post { - always { - junit 'Build/test-results/*.xml' - archiveArtifacts 'profiler.csv' - archiveArtifacts 'Dist/*.tar.gz' deleteDir() } - } } From b7a13d08d69ebcdd64ff69331b64a8edfc74e178 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Thu, 12 Jul 2018 18:23:34 +0200 Subject: [PATCH 10/71] Refactor streaming library --- LibCarla/cmake/server/CMakeLists.txt | 26 +++ LibCarla/cmake/test/CMakeLists.txt | 2 + LibCarla/source/carla/NonCopyable.h | 3 +- LibCarla/source/carla/StopWatch.h | 5 +- .../low_level/tcp/Timeout.h => Time.h} | 27 ++- LibCarla/source/carla/streaming/Client.h | 8 +- LibCarla/source/carla/streaming/Message.h | 13 +- LibCarla/source/carla/streaming/Server.h | 10 +- LibCarla/source/carla/streaming/Stream.h | 16 +- .../carla/streaming/detail/Dispatcher.cpp | 42 +++++ .../carla/streaming/detail/Dispatcher.h | 49 +++++ .../carla/streaming/detail/HashableClient.h | 48 +++++ .../streaming/{low_level => detail}/Session.h | 6 +- .../{low_level => detail}/StreamState.h | 19 +- .../source/carla/streaming/detail/Token.cpp | 36 ++++ .../streaming/{low_level => detail}/Token.h | 49 ++--- .../streaming/{low_level => detail}/Types.h | 4 +- .../tcp/Client.h => detail/tcp/Client.cpp} | 164 ++++++----------- .../carla/streaming/detail/tcp/Client.h | 76 ++++++++ .../carla/streaming/detail/tcp/Server.cpp | 47 +++++ .../carla/streaming/detail/tcp/Server.h | 56 ++++++ .../streaming/detail/tcp/ServerSession.cpp | 119 ++++++++++++ .../streaming/detail/tcp/ServerSession.h | 82 +++++++++ .../source/carla/streaming/low_level/Client.h | 14 +- .../carla/streaming/low_level/Dispatcher.h | 68 ------- .../source/carla/streaming/low_level/Server.h | 11 +- .../carla/streaming/low_level/tcp/Server.h | 76 -------- .../streaming/low_level/tcp/ServerSession.h | 173 ------------------ LibCarla/source/compiler/disable-ue4-macros.h | 14 +- .../source/test/test_benchmark_streaming.cpp | 2 +- LibCarla/source/test/test_rpc.cpp | 2 +- .../source/test/test_streaming_low_level.cpp | 5 +- .../test/test_streaming_low_level_tcp.cpp | 9 +- .../Plugins/Carla/Source/Carla/Carla.Build.cs | 8 + Util/BuildTools/Setup.sh | 5 +- 35 files changed, 746 insertions(+), 548 deletions(-) rename LibCarla/source/carla/{streaming/low_level/tcp/Timeout.h => Time.h} (58%) create mode 100644 LibCarla/source/carla/streaming/detail/Dispatcher.cpp create mode 100644 LibCarla/source/carla/streaming/detail/Dispatcher.h create mode 100644 LibCarla/source/carla/streaming/detail/HashableClient.h rename LibCarla/source/carla/streaming/{low_level => detail}/Session.h (77%) rename LibCarla/source/carla/streaming/{low_level => detail}/StreamState.h (81%) create mode 100644 LibCarla/source/carla/streaming/detail/Token.cpp rename LibCarla/source/carla/streaming/{low_level => detail}/Token.h (67%) rename LibCarla/source/carla/streaming/{low_level => detail}/Types.h (89%) rename LibCarla/source/carla/streaming/{low_level/tcp/Client.h => detail/tcp/Client.cpp} (57%) create mode 100644 LibCarla/source/carla/streaming/detail/tcp/Client.h create mode 100644 LibCarla/source/carla/streaming/detail/tcp/Server.cpp create mode 100644 LibCarla/source/carla/streaming/detail/tcp/Server.h create mode 100644 LibCarla/source/carla/streaming/detail/tcp/ServerSession.cpp create mode 100644 LibCarla/source/carla/streaming/detail/tcp/ServerSession.h delete mode 100644 LibCarla/source/carla/streaming/low_level/Dispatcher.h delete mode 100644 LibCarla/source/carla/streaming/low_level/tcp/Server.h delete mode 100644 LibCarla/source/carla/streaming/low_level/tcp/ServerSession.h diff --git a/LibCarla/cmake/server/CMakeLists.txt b/LibCarla/cmake/server/CMakeLists.txt index 5af82c109..56a1bbac7 100644 --- a/LibCarla/cmake/server/CMakeLists.txt +++ b/LibCarla/cmake/server/CMakeLists.txt @@ -23,3 +23,29 @@ file(GLOB libcarla_carla_streaming_headers "${libcarla_source_path}/carla/stream install(FILES ${libcarla_carla_streaming_headers} DESTINATION include/carla/streaming) install(DIRECTORY "${BOOST_INCLUDE_PATH}/boost" DESTINATION include) + +# carla_server library. + +file(GLOB_RECURSE libcarla_server_sources + "${libcarla_source_path}/carla/rpc/*.h" + "${libcarla_source_path}/carla/rpc/*.cpp" + "${libcarla_source_path}/carla/streaming/*.h" + "${libcarla_source_path}/carla/streaming/*.cpp") + +# Create targets for debug and release in the same build type. +foreach(target carla_server_debug carla_server) + add_library(${target} STATIC ${libcarla_server_sources}) + + target_include_directories(${target} PRIVATE + "${BOOST_INCLUDE_PATH}" + "${RPCLIB_INCLUDE_PATH}") + + install(TARGETS ${target} DESTINATION lib) +endforeach(target) + +# Specific options for debug. +set_target_properties(carla_server_debug PROPERTIES COMPILE_FLAGS ${CMAKE_CXX_FLAGS_DEBUG}) +target_compile_definitions(carla_server_debug PUBLIC -DBOOST_ASIO_ENABLE_BUFFER_DEBUGGING) + +# Specific options for release. +set_target_properties(carla_server PROPERTIES COMPILE_FLAGS ${CMAKE_CXX_FLAGS_RELEASE}) diff --git a/LibCarla/cmake/test/CMakeLists.txt b/LibCarla/cmake/test/CMakeLists.txt index 376d94879..47f6c8d3d 100644 --- a/LibCarla/cmake/test/CMakeLists.txt +++ b/LibCarla/cmake/test/CMakeLists.txt @@ -30,7 +30,9 @@ endforeach(target) # Specific options for debug. set_target_properties(libcarla_test_debug PROPERTIES COMPILE_FLAGS ${CMAKE_CXX_FLAGS_DEBUG}) +target_link_libraries(libcarla_test_debug "carla_server_debug") target_compile_definitions(libcarla_test_debug PUBLIC -DBOOST_ASIO_ENABLE_BUFFER_DEBUGGING) # Specific options for release. set_target_properties(libcarla_test_release PROPERTIES COMPILE_FLAGS ${CMAKE_CXX_FLAGS_RELEASE}) +target_link_libraries(libcarla_test_release "carla_server") diff --git a/LibCarla/source/carla/NonCopyable.h b/LibCarla/source/carla/NonCopyable.h index 41747bc41..e64d381c8 100644 --- a/LibCarla/source/carla/NonCopyable.h +++ b/LibCarla/source/carla/NonCopyable.h @@ -8,6 +8,7 @@ namespace carla { + /// Inherit (privately) to suppress copy-construction and copy-assignment. class NonCopyable { public: @@ -15,7 +16,7 @@ namespace carla { NonCopyable(const NonCopyable &) = delete; - void operator=(const NonCopyable &x) = delete; + void operator=(const NonCopyable &) = delete; }; } // namespace carla diff --git a/LibCarla/source/carla/StopWatch.h b/LibCarla/source/carla/StopWatch.h index db29b93d3..cd4376a5a 100644 --- a/LibCarla/source/carla/StopWatch.h +++ b/LibCarla/source/carla/StopWatch.h @@ -9,6 +9,7 @@ #include namespace carla { +namespace detail { template class StopWatchTmpl { @@ -51,6 +52,8 @@ namespace carla { bool _is_running; }; - using StopWatch = StopWatchTmpl; +} // namespace detail + + using StopWatch = detail::StopWatchTmpl; } // namespace carla diff --git a/LibCarla/source/carla/streaming/low_level/tcp/Timeout.h b/LibCarla/source/carla/Time.h similarity index 58% rename from LibCarla/source/carla/streaming/low_level/tcp/Timeout.h rename to LibCarla/source/carla/Time.h index 880eb7f31..74efb7423 100644 --- a/LibCarla/source/carla/streaming/low_level/tcp/Timeout.h +++ b/LibCarla/source/carla/Time.h @@ -11,33 +11,31 @@ #include namespace carla { -namespace streaming { -namespace low_level { -namespace tcp { - /// Positive time-out up to milliseconds resolution. - class timeout_type { + /// Positive time duration up to milliseconds resolution. Automatically casts + /// between std::chrono::duration and boost::posix_time::time_duration. + class time_duration { public: - static inline timeout_type seconds(size_t timeout) { + static inline time_duration seconds(size_t timeout) { return std::chrono::seconds(timeout); } - static inline timeout_type milliseconds(size_t timeout) { + static inline time_duration milliseconds(size_t timeout) { return std::chrono::milliseconds(timeout); } - constexpr timeout_type() : _milliseconds(0u) {} + constexpr time_duration() : _milliseconds(0u) {} template - timeout_type(std::chrono::duration duration) + time_duration(std::chrono::duration duration) : _milliseconds(std::chrono::duration_cast(duration).count()) {} - timeout_type(boost::posix_time::time_duration timeout) - : timeout_type(std::chrono::milliseconds(timeout.total_milliseconds())) {} + time_duration(boost::posix_time::time_duration timeout) + : time_duration(std::chrono::milliseconds(timeout.total_milliseconds())) {} - timeout_type(const timeout_type &) = default; - timeout_type &operator=(const timeout_type &) = default; + time_duration(const time_duration &) = default; + time_duration &operator=(const time_duration &) = default; boost::posix_time::time_duration to_posix_time() const { return boost::posix_time::milliseconds(_milliseconds); @@ -56,7 +54,4 @@ namespace tcp { size_t _milliseconds; }; -} // namespace tcp -} // namespace low_level -} // namespace streaming } // namespace carla diff --git a/LibCarla/source/carla/streaming/Client.h b/LibCarla/source/carla/streaming/Client.h index 3295c75b6..d6c9c1834 100644 --- a/LibCarla/source/carla/streaming/Client.h +++ b/LibCarla/source/carla/streaming/Client.h @@ -8,16 +8,16 @@ #include "carla/ThreadGroup.h" #include "carla/streaming/low_level/Client.h" -#include "carla/streaming/low_level/tcp/Client.h" +#include "carla/streaming/detail/tcp/Client.h" #include namespace carla { namespace streaming { - using stream_token = low_level::token_type; + using stream_token = detail::token_type; - /// With this client you can subscribe to multiple streams. + /// A client able to subscribe to multiple streams. class Client { public: @@ -45,7 +45,7 @@ namespace streaming { private: - using underlying_client = low_level::Client; + using underlying_client = low_level::Client; boost::asio::io_service _io_service; diff --git a/LibCarla/source/carla/streaming/Message.h b/LibCarla/source/carla/streaming/Message.h index 18c1c7f31..559d540bc 100644 --- a/LibCarla/source/carla/streaming/Message.h +++ b/LibCarla/source/carla/streaming/Message.h @@ -7,6 +7,7 @@ #pragma once #include "carla/Debug.h" +#include "carla/streaming/detail/Types.h" #include @@ -19,14 +20,6 @@ namespace carla { namespace streaming { -namespace low_level { -namespace tcp { - - class Client; /// @todo - -} // namespace low_level -} // namespace tcp - /// A message owns a buffer with raw data. class Message { @@ -38,7 +31,7 @@ namespace tcp { using value_type = unsigned char; - using size_type = uint32_t; + using size_type = detail::message_size_type; // ========================================================================= // -- Construction and assignment ------------------------------------------ @@ -131,8 +124,6 @@ namespace tcp { private: - friend class low_level::tcp::Client; /// @todo - size_type _size = 0u; std::unique_ptr _data = nullptr; diff --git a/LibCarla/source/carla/streaming/Server.h b/LibCarla/source/carla/streaming/Server.h index 039176e36..91ea98ea7 100644 --- a/LibCarla/source/carla/streaming/Server.h +++ b/LibCarla/source/carla/streaming/Server.h @@ -8,19 +8,19 @@ #include "carla/ThreadGroup.h" #include "carla/streaming/low_level/Server.h" -#include "carla/streaming/low_level/tcp/Server.h" +#include "carla/streaming/detail/tcp/Server.h" #include namespace carla { namespace streaming { + /// A streaming server. Each new stream has a token associated, this token can + /// be used by a client to subscribe to the stream. class Server { - using underlying_server = low_level::Server; + using underlying_server = low_level::Server; public: - using duration_type = underlying_server::duration_type; - explicit Server(uint16_t port) : _server(_io_service, port) {} @@ -31,7 +31,7 @@ namespace streaming { Stop(); } - void set_timeout(duration_type timeout) { + void set_timeout(time_duration timeout) { _server.set_timeout(timeout); } diff --git a/LibCarla/source/carla/streaming/Stream.h b/LibCarla/source/carla/streaming/Stream.h index e2a1821a4..d33940135 100644 --- a/LibCarla/source/carla/streaming/Stream.h +++ b/LibCarla/source/carla/streaming/Stream.h @@ -8,8 +8,8 @@ #include "carla/Debug.h" #include "carla/streaming/Message.h" -#include "carla/streaming/low_level/StreamState.h" -#include "carla/streaming/low_level/Token.h" +#include "carla/streaming/detail/StreamState.h" +#include "carla/streaming/detail/Token.h" #include @@ -18,13 +18,13 @@ namespace carla { namespace streaming { -namespace low_level { +namespace detail { class Dispatcher; -} // namespace low_level +} // namespace detail - using stream_token = low_level::token_type; + using stream_token = detail::token_type; class Stream { public: @@ -54,14 +54,14 @@ namespace low_level { private: - friend class low_level::Dispatcher; + friend class detail::Dispatcher; - Stream(std::shared_ptr state) + Stream(std::shared_ptr state) : _shared_state(std::move(state)) { DEBUG_ASSERT(_shared_state != nullptr); } - std::shared_ptr _shared_state; + std::shared_ptr _shared_state; }; } // namespace streaming diff --git a/LibCarla/source/carla/streaming/detail/Dispatcher.cpp b/LibCarla/source/carla/streaming/detail/Dispatcher.cpp new file mode 100644 index 000000000..f222243f8 --- /dev/null +++ b/LibCarla/source/carla/streaming/detail/Dispatcher.cpp @@ -0,0 +1,42 @@ +// 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 . + +#include "carla/streaming/detail/Dispatcher.h" + +#include "carla/Logging.h" + +#include + +namespace carla { +namespace streaming { +namespace detail { + + Stream Dispatcher::MakeStream() { + std::lock_guard lock(_mutex); + ++_cached_token._token.stream_id; // id zero only happens in overflow. + auto ptr = std::make_shared(_cached_token); + auto result = _stream_map.emplace(std::make_pair(_cached_token.get_stream_id(), ptr)); + if (!result.second) { + throw std::runtime_error("failed to create stream!"); + } + return ptr; + } + + void Dispatcher::RegisterSession(std::shared_ptr session) { + DEBUG_ASSERT(session != nullptr); + std::lock_guard lock(_mutex); + auto search = _stream_map.find(session->get_stream_id()); + if (search != _stream_map.end()) { + DEBUG_ASSERT(search->second != nullptr); + search->second->set_session(std::move(session)); + } else { + log_error("Invalid session: no stream available with id", session->get_stream_id()); + } + } + +} // namespace detail +} // namespace streaming +} // namespace carla diff --git a/LibCarla/source/carla/streaming/detail/Dispatcher.h b/LibCarla/source/carla/streaming/detail/Dispatcher.h new file mode 100644 index 000000000..0f485603f --- /dev/null +++ b/LibCarla/source/carla/streaming/detail/Dispatcher.h @@ -0,0 +1,49 @@ +// 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 . + +#pragma once + +#include "carla/streaming/Stream.h" +#include "carla/streaming/detail/Session.h" +#include "carla/streaming/detail/StreamState.h" +#include "carla/streaming/detail/Token.h" + +#include +#include +#include + +namespace carla { +namespace streaming { +namespace detail { + + /// Keeps the mapping between streams and sessions. + class Dispatcher { + public: + + template + explicit Dispatcher(const boost::asio::ip::basic_endpoint

&ep) + : _cached_token(0u, ep) {} + + Stream MakeStream(); + + void RegisterSession(std::shared_ptr session); + + private: + + // We use a mutex here, but we assume that sessions and streams won't be + // created too often. + std::mutex _mutex; + + token_type _cached_token; + + std::unordered_map< + stream_id_type, + std::shared_ptr> _stream_map; + }; + +} // namespace detail +} // namespace streaming +} // namespace carla diff --git a/LibCarla/source/carla/streaming/detail/HashableClient.h b/LibCarla/source/carla/streaming/detail/HashableClient.h new file mode 100644 index 000000000..beebbbf85 --- /dev/null +++ b/LibCarla/source/carla/streaming/detail/HashableClient.h @@ -0,0 +1,48 @@ +// 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 . + +#pragma once + +#include "carla/streaming/detail/Types.h" + +#include + +namespace carla { +namespace streaming { +namespace detail { + + /// A wrapper to put clients into std::unordered_set. + template + class HashableClient : public T { + public: + + template + HashableClient(Args && ... args) + : T(std::forward(args) ...) {} + + bool operator==(const HashableClient &rhs) const { + return T::GetStreamId() == rhs.GetStreamId(); + } + }; + +} // namespace detail +} // namespace streaming +} // namespace carla + +namespace std { + + // Injecting a hash function for our clients into std namespace so we can + // directly insert them into std::unordered_set. + template + struct hash> { + using argument_type = carla::streaming::detail::HashableClient; + using result_type = std::size_t; + result_type operator()(const argument_type &client) const noexcept { + return std::hash()(client.GetStreamId()); + } + }; + +} // namespace std diff --git a/LibCarla/source/carla/streaming/low_level/Session.h b/LibCarla/source/carla/streaming/detail/Session.h similarity index 77% rename from LibCarla/source/carla/streaming/low_level/Session.h rename to LibCarla/source/carla/streaming/detail/Session.h index 9acf14d36..6c30ffc03 100644 --- a/LibCarla/source/carla/streaming/low_level/Session.h +++ b/LibCarla/source/carla/streaming/detail/Session.h @@ -6,14 +6,14 @@ #pragma once -#include "carla/streaming/low_level/tcp/ServerSession.h" +#include "carla/streaming/detail/tcp/ServerSession.h" namespace carla { namespace streaming { -namespace low_level { +namespace detail { using Session = tcp::ServerSession; -} // namespace low_level +} // namespace detail } // namespace streaming } // namespace carla diff --git a/LibCarla/source/carla/streaming/low_level/StreamState.h b/LibCarla/source/carla/streaming/detail/StreamState.h similarity index 81% rename from LibCarla/source/carla/streaming/low_level/StreamState.h rename to LibCarla/source/carla/streaming/detail/StreamState.h index 852ae7b2b..8c427a6c7 100644 --- a/LibCarla/source/carla/streaming/low_level/StreamState.h +++ b/LibCarla/source/carla/streaming/detail/StreamState.h @@ -6,17 +6,16 @@ #pragma once +#include "carla/NonCopyable.h" #include "carla/streaming/Message.h" -#include "carla/streaming/low_level/Session.h" -#include "carla/streaming/low_level/Token.h" +#include "carla/streaming/detail/Session.h" +#include "carla/streaming/detail/Token.h" #include #include namespace carla { namespace streaming { -namespace low_level { - namespace detail { /// Handles the synchronization of the shared session. @@ -37,18 +36,16 @@ namespace detail { private: - mutable std::mutex _mutex; /// @todo it can be atomic + mutable std::mutex _mutex; /// @todo it can be atomic. std::shared_ptr _session; }; -} // namespace detail - /// Shared state among all the copies of a stream. Provides access to the - /// underlying UDP session if active. + /// underlying server session if active. class StreamState - : public detail::SessionHolder, - private boost::noncopyable { + : public SessionHolder, + private NonCopyable { public: explicit StreamState(const token_type &token) : _token(token) {} @@ -69,6 +66,6 @@ namespace detail { const token_type _token; }; -} // namespace low_level +} // namespace detail } // namespace streaming } // namespace carla diff --git a/LibCarla/source/carla/streaming/detail/Token.cpp b/LibCarla/source/carla/streaming/detail/Token.cpp new file mode 100644 index 000000000..2ac50c6e5 --- /dev/null +++ b/LibCarla/source/carla/streaming/detail/Token.cpp @@ -0,0 +1,36 @@ +// 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 . + +#include "carla/streaming/detail/Token.h" + +#include + +namespace carla { +namespace streaming { +namespace detail { + + void token_type::set_address(const boost::asio::ip::address &addr) { + if (addr.is_v4()) { + _token.address_type = token_data::address::ip_v4; + _token.address.v4 = addr.to_v4().to_bytes(); + } else if (addr.is_v6()) { + _token.address_type = token_data::address::ip_v6; + _token.address.v6 = addr.to_v6().to_bytes(); + } else { + throw std::invalid_argument("invalid ip address!"); + } + } + + boost::asio::ip::address token_type::get_address() const { + if (_token.address_type == token_data::address::ip_v4) { + return boost::asio::ip::address_v4(_token.address.v4); + } + return boost::asio::ip::address_v6(_token.address.v6); + } + +} // namespace detail +} // namespace streaming +} // namespace carla diff --git a/LibCarla/source/carla/streaming/low_level/Token.h b/LibCarla/source/carla/streaming/detail/Token.h similarity index 67% rename from LibCarla/source/carla/streaming/low_level/Token.h rename to LibCarla/source/carla/streaming/detail/Token.h index 0a9cef798..5dc70464e 100644 --- a/LibCarla/source/carla/streaming/low_level/Token.h +++ b/LibCarla/source/carla/streaming/detail/Token.h @@ -7,7 +7,7 @@ #pragma once #include "carla/Debug.h" -#include "carla/streaming/low_level/Types.h" +#include "carla/streaming/detail/Types.h" #include #include @@ -15,13 +15,11 @@ namespace carla { namespace streaming { -namespace low_level { - namespace detail { #pragma pack(push, 1) - struct token { + struct token_data { stream_id_type stream_id; uint16_t port; @@ -47,7 +45,7 @@ namespace detail { #pragma pack(pop) static_assert( - sizeof(token) == 24u, + sizeof(token_data) == 24u, "Size shouldn't be more than" " v6 address : 128" " + state : 16" @@ -56,8 +54,6 @@ namespace detail { " -----------------" " 192"); -} // namespace detail - /// Serializes a stream endpoint. Contains all the necessary information for a /// client to subscribe to a stream. class token_type { @@ -66,28 +62,13 @@ namespace detail { template static constexpr auto get_protocol() { return std::is_same::value ? - detail::token::protocol::tcp : - detail::token::protocol::udp; + token_data::protocol::tcp : + token_data::protocol::udp; } - void set_address(const boost::asio::ip::address &addr) { - if (addr.is_v4()) { - _token.address_type = detail::token::address::ip_v4; - _token.address.v4 = addr.to_v4().to_bytes(); - } else if (addr.is_v6()) { - _token.address_type = detail::token::address::ip_v6; - _token.address.v6 = addr.to_v6().to_bytes(); - } else { - throw std::invalid_argument("invalid ip address!"); - } - } + void set_address(const boost::asio::ip::address &addr); - boost::asio::ip::address get_address() const { - if (_token.address_type == detail::token::address::ip_v4) { - return boost::asio::ip::address_v4(_token.address.v4); - } - return boost::asio::ip::address_v6(_token.address.v6); - } + boost::asio::ip::address get_address() const; template boost::asio::ip::basic_endpoint

get_endpoint() const { @@ -120,24 +101,24 @@ namespace detail { } bool is_valid() const { - return ((_token.protocol != detail::token::protocol::not_set) && - (_token.address_type != detail::token::address::not_set)); + return ((_token.protocol != token_data::protocol::not_set) && + (_token.address_type != token_data::address::not_set)); } bool address_is_v4() const { - return _token.address_type == detail::token::address::ip_v4; + return _token.address_type == token_data::address::ip_v4; } bool address_is_v6() const { - return _token.address_type == detail::token::address::ip_v6; + return _token.address_type == token_data::address::ip_v6; } bool protocol_is_udp() const { - return _token.protocol == detail::token::protocol::udp; + return _token.protocol == token_data::protocol::udp; } bool protocol_is_tcp() const { - return _token.protocol == detail::token::protocol::tcp; + return _token.protocol == token_data::protocol::tcp; } boost::asio::ip::udp::endpoint to_udp_endpoint() const { @@ -156,9 +137,9 @@ namespace detail { friend class Dispatcher; - detail::token _token; + token_data _token; }; -} // namespace low_level +} // namespace detail } // namespace streaming } // namespace carla diff --git a/LibCarla/source/carla/streaming/low_level/Types.h b/LibCarla/source/carla/streaming/detail/Types.h similarity index 89% rename from LibCarla/source/carla/streaming/low_level/Types.h rename to LibCarla/source/carla/streaming/detail/Types.h index 1da5e93d7..273e78a49 100644 --- a/LibCarla/source/carla/streaming/low_level/Types.h +++ b/LibCarla/source/carla/streaming/detail/Types.h @@ -10,12 +10,12 @@ namespace carla { namespace streaming { -namespace low_level { +namespace detail { using stream_id_type = uint32_t; using message_size_type = uint32_t; -} // namespace low_level +} // namespace detail } // namespace streaming } // namespace carla diff --git a/LibCarla/source/carla/streaming/low_level/tcp/Client.h b/LibCarla/source/carla/streaming/detail/tcp/Client.cpp similarity index 57% rename from LibCarla/source/carla/streaming/low_level/tcp/Client.h rename to LibCarla/source/carla/streaming/detail/tcp/Client.cpp index 6adea93e1..454acfecd 100644 --- a/LibCarla/source/carla/streaming/low_level/tcp/Client.h +++ b/LibCarla/source/carla/streaming/detail/tcp/Client.cpp @@ -4,36 +4,30 @@ // This work is licensed under the terms of the MIT license. // For a copy, see . -#pragma once +#include "carla/streaming/detail/tcp/Client.h" #include "carla/Debug.h" #include "carla/Logging.h" -#include "carla/streaming/Message.h" -#include "carla/streaming/low_level/Types.h" -#include "carla/streaming/low_level/tcp/Timeout.h" +#include "carla/Time.h" #include -#include -#include -#include #include -#include #include -#include -#include -#include - namespace carla { namespace streaming { -namespace low_level { +namespace detail { namespace tcp { - class Encoder { + // =========================================================================== + // -- Decoder ---------------------------------------------------------------- + // =========================================================================== + + class Decoder { public: boost::asio::mutable_buffer header() { - return boost::asio::buffer(reinterpret_cast(&_size), sizeof(_size)); + return boost::asio::buffer(&_size, sizeof(_size)); } boost::asio::mutable_buffer body() { @@ -58,81 +52,37 @@ namespace tcp { std::shared_ptr _message; }; - /// @warning The client should not be destroyed before the @a io_service is - /// stopped. - class Client : private boost::noncopyable { - public: + // =========================================================================== + // -- Client ----------------------------------------------------------------- + // =========================================================================== - using endpoint = boost::asio::ip::tcp::endpoint; + Client::Client( + boost::asio::io_service &io_service, + endpoint ep, + stream_id_type stream_id, + callback_function_type callback) + : _endpoint(std::move(ep)), + _stream_id(stream_id), + _callback(std::move(callback)), + _socket(io_service), + _strand(io_service), + _connection_timer(io_service) { + Connect(); + } - template - Client( - boost::asio::io_service &io_service, - endpoint ep, - stream_id_type stream_id, - Functor &&callback) - : _endpoint(std::move(ep)), - _stream_id(stream_id), - _callback(std::forward(callback)), - _socket(io_service), - _strand(io_service), - _connection_timer(io_service) { - Connect(); - } + Client::~Client() { + Stop(); + } - ~Client() { - Stop(); - } - - stream_id_type get_id() const { - return _stream_id; - } - - bool operator==(const Client &rhs) const { - return get_id() == rhs.get_id(); - } - - void Stop() { - _connection_timer.cancel(); - _strand.post([this]() { - _done = true; - if (_socket.is_open()) { - _socket.close(); - } - }); - } - - private: - - /// @todo Stop inlining and make cpp files. - - inline void Connect(); - - inline void Reconnect() { - _connection_timer.expires_from_now(timeout_type::seconds(1u)); - _connection_timer.async_wait([this](boost::system::error_code ec) { - if (!ec) { - Connect(); - } - }); - } - - inline void ReadData(); - - const endpoint _endpoint; - - const stream_id_type _stream_id; - - std::function)> _callback; - - boost::asio::ip::tcp::socket _socket; - - boost::asio::io_service::strand _strand; - - boost::asio::deadline_timer _connection_timer; - - bool _done = false; - }; + void Client::Stop() { + _connection_timer.cancel(); + _strand.post([this]() { + _done = true; + if (_socket.is_open()) { + _socket.close(); + } + }); + } void Client::Connect() { _strand.post([this]() { @@ -151,9 +101,9 @@ namespace tcp { // Send the stream id to subscribe to the stream. log_debug("streaming client: sending stream id", _stream_id); boost::asio::async_write( - _socket, - boost::asio::buffer(&_stream_id, sizeof(_stream_id)), - _strand.wrap([=](error_code ec, size_t DEBUG_ONLY(bytes)) { + _socket, + boost::asio::buffer(&_stream_id, sizeof(_stream_id)), + _strand.wrap([=](error_code ec, size_t DEBUG_ONLY(bytes)) { if (!ec) { DEBUG_ASSERT_EQ(bytes, sizeof(_stream_id)); // If succeeded start reading data. @@ -175,6 +125,15 @@ namespace tcp { }); } + void Client::Reconnect() { + _connection_timer.expires_from_now(time_duration::seconds(1u)); + _connection_timer.async_wait([this](boost::system::error_code ec) { + if (!ec) { + Connect(); + } + }); + } + void Client::ReadData() { _strand.post([this]() { if (_done) { @@ -183,14 +142,15 @@ namespace tcp { log_debug("streaming client: Client::ReadData"); - auto encoder = std::make_shared(); + auto encoder = std::make_shared(); auto handle_read_data = [=](boost::system::error_code ec, size_t DEBUG_ONLY(bytes)) { DEBUG_ONLY(log_debug("streaming client: Client::ReadData.handle_read_data", bytes, "bytes")); if (!ec) { DEBUG_ASSERT_EQ(bytes, encoder->size()); DEBUG_ASSERT_NE(bytes, 0u); - // Move the buffer to the callback function and start reading the next + // Move the buffer to the callback function and start reading + // the next // piece of data. log_debug("streaming client: success reading data, calling the callback"); _socket.get_io_service().post([this, encoder]() { _callback(encoder->pop()); }); @@ -206,7 +166,8 @@ namespace tcp { DEBUG_ONLY(log_debug("streaming client: Client::ReadData.handle_read_header", bytes, "bytes")); if (!ec && (encoder->size() > 0u)) { DEBUG_ASSERT_EQ(bytes, sizeof(message_size_type)); - // Now that we know the size of the coming buffer, we can allocate + // Now that we know the size of the coming buffer, we can + // allocate // our buffer and start putting data into it. boost::asio::async_read( _socket, @@ -229,21 +190,6 @@ namespace tcp { } } // namespace tcp -} // namespace low_level +} // namespace detail } // namespace streaming } // namespace carla - -namespace std { - - // Injecting a hash function for our clients into std namespace so we can - // directly insert them into std::unordered_set. - template <> - struct hash { - using argument_type = carla::streaming::low_level::tcp::Client; - using result_type = std::size_t; - result_type operator()(const argument_type &client) const noexcept { - return std::hash()(client.get_id()); - } - }; - -} // namespace std diff --git a/LibCarla/source/carla/streaming/detail/tcp/Client.h b/LibCarla/source/carla/streaming/detail/tcp/Client.h new file mode 100644 index 000000000..625e69725 --- /dev/null +++ b/LibCarla/source/carla/streaming/detail/tcp/Client.h @@ -0,0 +1,76 @@ +// 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 . + +#pragma once + +#include "carla/NonCopyable.h" +#include "carla/streaming/Message.h" +#include "carla/streaming/detail/Types.h" + +#include +#include +#include +#include + +#include +#include + +namespace carla { +namespace streaming { +namespace detail { +namespace tcp { + + /// A client that connects to a single stream. + /// + /// @warning The client should not be destroyed before the @a io_service is + /// stopped. + class Client : private NonCopyable { + public: + + using endpoint = boost::asio::ip::tcp::endpoint; + using callback_function_type = std::function)>; + + Client( + boost::asio::io_service &io_service, + endpoint ep, + stream_id_type stream_id, + callback_function_type callback); + + ~Client(); + + stream_id_type GetStreamId() const { + return _stream_id; + } + + void Stop(); + + private: + + void Connect(); + + void Reconnect(); + + void ReadData(); + + const endpoint _endpoint; + + const stream_id_type _stream_id; + + callback_function_type _callback; + + boost::asio::ip::tcp::socket _socket; + + boost::asio::io_service::strand _strand; + + boost::asio::deadline_timer _connection_timer; + + bool _done = false; + }; + +} // namespace tcp +} // namespace detail +} // namespace streaming +} // namespace carla diff --git a/LibCarla/source/carla/streaming/detail/tcp/Server.cpp b/LibCarla/source/carla/streaming/detail/tcp/Server.cpp new file mode 100644 index 000000000..5a890dc10 --- /dev/null +++ b/LibCarla/source/carla/streaming/detail/tcp/Server.cpp @@ -0,0 +1,47 @@ +// 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 . + +#include "carla/streaming/detail/tcp/Server.h" + +#include "carla/Logging.h" + +#include + +namespace carla { +namespace streaming { +namespace detail { +namespace tcp { + + Server::Server(boost::asio::io_service &io_service, endpoint ep) + : _acceptor(io_service, std::move(ep)), + _timeout(time_duration::seconds(10u)) {} + + void Server::OpenSession( + const time_duration timeout, + ServerSession::callback_function_type callback) { + using boost::system::error_code; + + auto session = std::make_shared(_acceptor.get_io_service(), timeout); + + auto handle_query = [=](const error_code &ec) { + if (!ec) { + session->Open(callback); + } else { + log_error("tcp accept error:", ec.message()); + } + }; + + _acceptor.async_accept(session->_socket, [=](error_code ec) { + // Handle query and open a new session immediately. + _acceptor.get_io_service().post([=]() { handle_query(ec); }); + OpenSession(timeout, callback); + }); + } + +} // namespace tcp +} // namespace detail +} // namespace streaming +} // namespace carla diff --git a/LibCarla/source/carla/streaming/detail/tcp/Server.h b/LibCarla/source/carla/streaming/detail/tcp/Server.h new file mode 100644 index 000000000..693ce80d2 --- /dev/null +++ b/LibCarla/source/carla/streaming/detail/tcp/Server.h @@ -0,0 +1,56 @@ +// 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 . + +#pragma once + +#include "carla/NonCopyable.h" +#include "carla/Time.h" +#include "carla/streaming/detail/tcp/ServerSession.h" + +#include +#include + +#include + +namespace carla { +namespace streaming { +namespace detail { +namespace tcp { + + class Server : private NonCopyable { + public: + + using endpoint = boost::asio::ip::tcp::endpoint; + using protocol_type = endpoint::protocol_type; + + explicit Server(boost::asio::io_service &io_service, endpoint ep); + + /// Set session time-out. Applies only to newly created sessions. By default + /// the time-out is set to 10 seconds. + void set_timeout(time_duration timeout) { + _timeout = timeout; + } + + /// Start listening for connections, on each new connection @a callback is + /// called. + template + void Listen(Functor callback) { + _acceptor.get_io_service().post([=]() { OpenSession(_timeout, callback); }); + } + + private: + + void OpenSession(time_duration timeout, ServerSession::callback_function_type callback); + + boost::asio::ip::tcp::acceptor _acceptor; + + std::atomic _timeout; + }; + +} // namespace tcp +} // namespace detail +} // namespace streaming +} // namespace carla diff --git a/LibCarla/source/carla/streaming/detail/tcp/ServerSession.cpp b/LibCarla/source/carla/streaming/detail/tcp/ServerSession.cpp new file mode 100644 index 000000000..41b714596 --- /dev/null +++ b/LibCarla/source/carla/streaming/detail/tcp/ServerSession.cpp @@ -0,0 +1,119 @@ +// 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 . + +#include "carla/streaming/detail/tcp/ServerSession.h" + +#include "carla/Debug.h" +#include "carla/Logging.h" + +#include +#include + +#include + +namespace carla { +namespace streaming { +namespace detail { +namespace tcp { + + static std::atomic_size_t SESSION_COUNTER{0u}; + + ServerSession::ServerSession( + boost::asio::io_service &io_service, + const time_duration timeout) + : _session_id(SESSION_COUNTER++), + _socket(io_service), + _timeout(timeout), + _deadline(io_service), + _strand(io_service) {} + + ServerSession::~ServerSession() { + _deadline.cancel(); + } + + void ServerSession::Open(callback_function_type callback) { + StartTimer(); + auto self = shared_from_this(); // To keep myself alive. + _strand.post([=]() { + + auto handle_query = [this, self, cb=std::move(callback)]( + const boost::system::error_code &ec, + size_t DEBUG_ONLY(bytes_received)) { + DEBUG_ASSERT_EQ(bytes_received, sizeof(_stream_id)); + if (!ec) { + log_debug("session", _session_id, "for stream", _stream_id, " started"); + _socket.get_io_service().post([=]() { cb(self); }); + } else { + log_error("session", _session_id, ": error retrieving stream id :", ec.message()); + Close(); + } + }; + + // Read the stream id. + _deadline.expires_from_now(_timeout); + boost::asio::async_read( + _socket, + boost::asio::buffer(&_stream_id, sizeof(_stream_id)), + _strand.wrap(handle_query)); + }); + } + + void ServerSession::Write(std::shared_ptr message) { + auto self = shared_from_this(); + _strand.post([=]() { + + /// @todo has to be a better way of doing this... + if (_is_writing) { + // Repost and return; + Write(std::move(message)); + return; + } + _is_writing = true; + + auto handle_sent = [this, self, message](const boost::system::error_code &ec, size_t DEBUG_ONLY(bytes)) { + _is_writing = false; + if (ec) { + log_error("session", _session_id, ": error sending data :", ec.message()); + } else { + DEBUG_ONLY(log_debug("session", _session_id, ": successfully sent", bytes, "bytes")); + DEBUG_ASSERT_EQ(bytes, sizeof(message_size_type) + message->size()); + } + }; + + log_debug("session", _session_id, ": sending message of", message->size(), "bytes"); + + _deadline.expires_from_now(_timeout); + boost::asio::async_write( + _socket, + message->encode(), + _strand.wrap(handle_sent)); + }); + } + + void ServerSession::Close() { + _strand.post([this, self = shared_from_this()]() { + if (_socket.is_open()) { + _socket.close(); + } + log_debug("session", _session_id, "closed"); + }); + } + + void ServerSession::StartTimer() { + if (_deadline.expires_at() <= boost::asio::deadline_timer::traits_type::now()) { + log_debug("session", _session_id, "timed out"); + Close(); + } else { + _deadline.async_wait([self = shared_from_this()](boost::system::error_code) { + self->StartTimer(); + }); + } + } + +} // namespace tcp +} // namespace detail +} // namespace streaming +} // namespace carla diff --git a/LibCarla/source/carla/streaming/detail/tcp/ServerSession.h b/LibCarla/source/carla/streaming/detail/tcp/ServerSession.h new file mode 100644 index 000000000..f1b645b19 --- /dev/null +++ b/LibCarla/source/carla/streaming/detail/tcp/ServerSession.h @@ -0,0 +1,82 @@ +// 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 . + +#pragma once + +#include "carla/NonCopyable.h" +#include "carla/Time.h" +#include "carla/streaming/Message.h" +#include "carla/streaming/detail/Types.h" + +#include +#include +#include +#include + +#include +#include + +namespace carla { +namespace streaming { +namespace detail { +namespace tcp { + + /// A TCP server session. When a session opens, it reads from the socket a + /// stream id object and passes itself to the callback functor. The session + /// closes itself after @a timeout of inactivity is met. + class ServerSession + : public std::enable_shared_from_this, + private NonCopyable { + public: + + using socket_type = boost::asio::ip::tcp::socket; + using callback_function_type = std::function)>; + + explicit ServerSession(boost::asio::io_service &io_service, time_duration timeout); + + ~ServerSession(); + + /// Starts the session and calls @a callback after successfully reading the + /// stream id. + void Open(callback_function_type callback); + + /// @warning This function should only be called after the session is + /// opened. It is safe to call this function from within the @a callback. + stream_id_type get_stream_id() const { + return _stream_id; + } + + /// Writes some data to the socket. + void Write(std::shared_ptr message); + + /// Posts a job to close this session. + void Close(); + + private: + + void StartTimer(); + + friend class Server; + + const size_t _session_id; + + stream_id_type _stream_id = 0u; + + socket_type _socket; + + time_duration _timeout; + + boost::asio::deadline_timer _deadline; + + boost::asio::io_service::strand _strand; + + bool _is_writing = false; + }; + +} // namespace tcp +} // namespace detail +} // namespace streaming +} // namespace carla diff --git a/LibCarla/source/carla/streaming/low_level/Client.h b/LibCarla/source/carla/streaming/low_level/Client.h index c5234776e..deb9b4da1 100644 --- a/LibCarla/source/carla/streaming/low_level/Client.h +++ b/LibCarla/source/carla/streaming/low_level/Client.h @@ -6,7 +6,9 @@ #pragma once -#include "carla/streaming/low_level/Token.h" +#include "carla/streaming/detail/HashableClient.h" +#include "carla/streaming/detail/Token.h" +#include "carla/streaming/detail/tcp/Client.h" #include @@ -16,23 +18,25 @@ namespace carla { namespace streaming { namespace low_level { - /// Wrapper around low level clients. You can subscribe to multiple streams. + /// A client able to subscribe to multiple streams. Accepts an external + /// io_service. /// /// @warning The client should not be destroyed before the @a io_service is /// stopped. - /// @pre T has to be hashable. template class Client { public: - using underlying_client = T; + using underlying_client = detail::HashableClient; + + using token_type = carla::streaming::detail::token_type; template void Subscribe( boost::asio::io_service &io_service, const token_type &token, Functor &&callback) { - if (!token.protocol_is_tcp()) { + if (!token.protocol_is_tcp()) { /// @todo throw std::invalid_argument("invalid token, only TCP tokens supported"); } _clients.emplace( diff --git a/LibCarla/source/carla/streaming/low_level/Dispatcher.h b/LibCarla/source/carla/streaming/low_level/Dispatcher.h deleted file mode 100644 index a74622541..000000000 --- a/LibCarla/source/carla/streaming/low_level/Dispatcher.h +++ /dev/null @@ -1,68 +0,0 @@ -// 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 . - -#pragma once - -#include "carla/streaming/Stream.h" -#include "carla/streaming/low_level/Session.h" -#include "carla/streaming/low_level/StreamState.h" -#include "carla/streaming/low_level/Token.h" - -#include -#include -#include -#include - -namespace carla { -namespace streaming { -namespace low_level { - - class Dispatcher { - public: - - template - explicit Dispatcher(const boost::asio::ip::basic_endpoint

&ep) - : _cached_token(0u, ep) {} - - Stream MakeStream() { - std::lock_guard lock(_mutex); - ++_cached_token._token.stream_id; // id zero only happens in overflow. - auto ptr = std::make_shared(_cached_token); - auto result = _stream_map.emplace(std::make_pair(_cached_token.get_stream_id(), ptr)); - if (!result.second) { - throw std::runtime_error("failed to create stream!"); - } - return ptr; - } - - void RegisterSession(std::shared_ptr session) { - DEBUG_ASSERT(session != nullptr); - std::lock_guard lock(_mutex); - auto search = _stream_map.find(session->get_stream_id()); - if (search != _stream_map.end()) { - DEBUG_ASSERT(search->second != nullptr); - search->second->set_session(std::move(session)); - } else { - log_error("Invalid session: no stream available with id", session->get_stream_id()); - } - } - - private: - - // We use a mutex here, but we assume that sessions and streams won't be - // created too often. - std::mutex _mutex; - - token_type _cached_token; - - std::unordered_map< - stream_id_type, - std::shared_ptr> _stream_map; - }; - -} // namespace low_level -} // namespace streaming -} // namespace carla diff --git a/LibCarla/source/carla/streaming/low_level/Server.h b/LibCarla/source/carla/streaming/low_level/Server.h index 6b61df677..d93916868 100644 --- a/LibCarla/source/carla/streaming/low_level/Server.h +++ b/LibCarla/source/carla/streaming/low_level/Server.h @@ -6,7 +6,7 @@ #pragma once -#include "carla/streaming/low_level/Dispatcher.h" +#include "carla/streaming/detail/Dispatcher.h" #include "carla/streaming/Stream.h" #include @@ -15,14 +15,15 @@ namespace carla { namespace streaming { namespace low_level { - /// Wrapper around low level servers. + /// A low-level streaming server. Each new stream has a token associated, this + /// token can be used by a client to subscribe to the stream. This server + /// requires an external io_service running. template class Server { public: using underlying_server = T; - using duration_type = typename underlying_server::duration_type; using endpoint = typename underlying_server::endpoint; using protocol_type = typename underlying_server::protocol_type; @@ -40,7 +41,7 @@ namespace low_level { explicit Server(boost::asio::io_service &io_service, const std::string &address, uint16_t port) : Server(io_service, endpoint(boost::asio::ip::address::from_string(address), port)) {} - void set_timeout(duration_type timeout) { + void set_timeout(time_duration timeout) { _server.set_timeout(timeout); } @@ -52,7 +53,7 @@ namespace low_level { underlying_server _server; - Dispatcher _dispatcher; + detail::Dispatcher _dispatcher; }; } // namespace low_level diff --git a/LibCarla/source/carla/streaming/low_level/tcp/Server.h b/LibCarla/source/carla/streaming/low_level/tcp/Server.h deleted file mode 100644 index d87d101cf..000000000 --- a/LibCarla/source/carla/streaming/low_level/tcp/Server.h +++ /dev/null @@ -1,76 +0,0 @@ -// 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 . - -#pragma once - -#include "carla/streaming/low_level/tcp/ServerSession.h" - -#include -#include - -#include -#include -#include - -namespace carla { -namespace streaming { -namespace low_level { -namespace tcp { - - class Server : private boost::noncopyable { - public: - - using endpoint = boost::asio::ip::tcp::endpoint; - using protocol_type = endpoint::protocol_type; - using duration_type = ServerSession::duration_type; - - explicit Server(boost::asio::io_service &io_service, endpoint ep) - : _acceptor(io_service, std::move(ep)), - _timeout(duration_type::seconds(10u)) {} - - /// Set session time-out. Applies only to newly created sessions. - void set_timeout(duration_type timeout) { - _timeout = timeout; - } - - template - void Listen(Functor callback) { - log_info("starting streaming server at port", _acceptor.local_endpoint().port()); - _acceptor.get_io_service().post([=]() { OpenSession(_timeout, callback); }); - } - - private: - - template - void OpenSession(duration_type timeout, Functor callback) { - using boost::system::error_code; - - auto session = std::make_shared(_acceptor.get_io_service(), timeout); - - auto handle_query = [=](const error_code &ec) { - if (!ec) { - session->Open(callback); - } else { - log_error("tcp accept error:", ec.message()); - } - }; - - _acceptor.async_accept(session->_socket, [=](error_code ec) { - // Handle query and open a new session immediately. - _acceptor.get_io_service().post([=]() { handle_query(ec); }); - OpenSession(timeout, callback); - }); - } - - boost::asio::ip::tcp::acceptor _acceptor; - - std::atomic _timeout; - }; - -} // namespace tcp -} // namespace low_level -} // namespace streaming -} // namespace carla diff --git a/LibCarla/source/carla/streaming/low_level/tcp/ServerSession.h b/LibCarla/source/carla/streaming/low_level/tcp/ServerSession.h deleted file mode 100644 index 2d1d5a3eb..000000000 --- a/LibCarla/source/carla/streaming/low_level/tcp/ServerSession.h +++ /dev/null @@ -1,173 +0,0 @@ -// 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 . - -#pragma once - -#include "carla/Debug.h" -#include "carla/Logging.h" -#include "carla/streaming/Message.h" -#include "carla/streaming/low_level/Types.h" -#include "carla/streaming/low_level/tcp/Timeout.h" - -#include -#include -#include -#include -#include -#include - -#include -#include - -namespace carla { -namespace streaming { -namespace low_level { -namespace tcp { - -namespace detail { - - static std::atomic_size_t SESSION_COUNTER{0u}; - -} // namespace detail - - /// A TCP server session. When a session opens, it reads from the socket a - /// stream id object and passes itself to the callback functor. The session - /// closes itself after @a timeout of inactivity is met. - class ServerSession - : public std::enable_shared_from_this, - private boost::noncopyable { - public: - - using socket_type = boost::asio::ip::tcp::socket; - using duration_type = timeout_type; - - explicit ServerSession(boost::asio::io_service &io_service, duration_type timeout) - : _session_id(detail::SESSION_COUNTER++), - _socket(io_service), - _timeout(timeout), - _deadline(io_service), - _strand(io_service) {} - - ~ServerSession() { - _deadline.cancel(); - } - - /// Starts the session and calls @a callback after successfully reading the - /// stream id. - /// - /// @pre Callback function signature: - /// `void(std::shared_ptr)`. - template - void Open(Functor callback) { - StartTimer(); - auto self = shared_from_this(); // To keep myself alive. - _strand.post([=]() { - - auto handle_query = [this, self, callback]( - const boost::system::error_code &ec, - size_t DEBUG_ONLY(bytes_received)) { - DEBUG_ASSERT_EQ(bytes_received, sizeof(_stream_id)); - if (!ec) { - log_debug("session", _session_id, "for stream", _stream_id, " started"); - _socket.get_io_service().post([=]() { callback(self); }); - } else { - log_error("session", _session_id, ": error retrieving stream id :", ec.message()); - Close(); - } - }; - - // Read the stream id. - _deadline.expires_from_now(_timeout); - boost::asio::async_read( - _socket, - boost::asio::buffer(&_stream_id, sizeof(_stream_id)), - _strand.wrap(handle_query)); - }); - } - - stream_id_type get_stream_id() const { - // Note that the stream id isn't synchronized. This function should only be - // called from the @a callback function, and after that point the stream_id - // can't change. - return _stream_id; - } - - /// Writes some data to the socket. - void Write(std::shared_ptr message) { - auto self = shared_from_this(); - _strand.post([=]() { - - /// @todo has to be a better way of doing this... - if (_is_writing) { - // Repost and return; - Write(std::move(message)); - return; - } - _is_writing = true; - - auto handle_sent = [this, self, message](const boost::system::error_code &ec, size_t DEBUG_ONLY(bytes)) { - _is_writing = false; - if (ec) { - log_error("session", _session_id, ": error sending data :", ec.message()); - } else { - DEBUG_ONLY(log_debug("session", _session_id, ": successfully sent", bytes, "bytes")); - DEBUG_ASSERT_EQ(bytes, sizeof(message_size_type) + message->size()); - } - }; - - log_debug("session", _session_id, ": sending message of", message->size(), "bytes"); - - _deadline.expires_from_now(_timeout); - boost::asio::async_write( - _socket, - message->encode(), - _strand.wrap(handle_sent)); - }); - } - - void Close() { - _strand.post([this, self = shared_from_this()]() { - if (_socket.is_open()) { - _socket.close(); - } - log_debug("session", _session_id, "closed"); - }); - } - - private: - - void StartTimer() { - if (_deadline.expires_at() <= boost::asio::deadline_timer::traits_type::now()) { - log_debug("session", _session_id, "timed out"); - Close(); - } else { - _deadline.async_wait([self = shared_from_this()](boost::system::error_code) { - self->StartTimer(); - }); - } - } - - friend class Server; - - const size_t _session_id; - - stream_id_type _stream_id = 0u; - - socket_type _socket; - - duration_type _timeout; - - boost::asio::deadline_timer _deadline; - - boost::asio::io_service::strand _strand; - - bool _is_writing = false; - }; - -} // namespace tcp -} // namespace low_level -} // namespace streaming -} // namespace carla diff --git a/LibCarla/source/compiler/disable-ue4-macros.h b/LibCarla/source/compiler/disable-ue4-macros.h index 4a95f7757..abefba603 100644 --- a/LibCarla/source/compiler/disable-ue4-macros.h +++ b/LibCarla/source/compiler/disable-ue4-macros.h @@ -4,6 +4,12 @@ // This work is licensed under the terms of the MIT license. // For a copy, see . +#ifndef LIBCARLA_INCLUDED_DISABLE_UE4_MACROS_HEADER +# define LIBCARLA_INCLUDED_DISABLE_UE4_MACROS_HEADER +#else +# error disable-ue4-macros.h should only be included once! +#endif // LIBCARLA_INCLUDED_DISABLE_UE4_MACROS_HEADER + #pragma push_macro("check") #undef check @@ -13,16 +19,14 @@ # define BOOST_ERROR_CODE_HEADER_ONLY #endif // BOOST_ERROR_CODE_HEADER_ONLY -#ifndef BOOST_COROUTINES_NO_DEPRECATION_WARNING -# define BOOST_COROUTINES_NO_DEPRECATION_WARNING -#endif // BOOST_COROUTINES_NO_DEPRECATION_WARNING - #ifndef BOOST_NO_EXCEPTIONS # define BOOST_NO_EXCEPTIONS #endif // BOOST_NO_EXCEPTIONS namespace boost { - static inline void throw_exception(const std::exception &) {} + static inline void throw_exception(const std::exception &e) { + UE_LOG(LogCarla, Fatal, TEXT("Exception thronw on Boost libraries: %s"), UTF8_TO_TCHAR(e.what())); + } } // namespace boost diff --git a/LibCarla/source/test/test_benchmark_streaming.cpp b/LibCarla/source/test/test_benchmark_streaming.cpp index bfa40529d..fb05786dc 100644 --- a/LibCarla/source/test/test_benchmark_streaming.cpp +++ b/LibCarla/source/test/test_benchmark_streaming.cpp @@ -31,7 +31,7 @@ public: void AddStream() { Stream stream = _server.MakeStream(); - _client.Subscribe(stream.token(), [this](std::shared_ptr msg) { + _client.Subscribe(stream.token(), [this](std::shared_ptr DEBUG_ONLY(msg)) { DEBUG_ASSERT_EQ(msg->size(), _message.size()); DEBUG_ASSERT(*msg == _message); _client_callback.post([this]() { diff --git a/LibCarla/source/test/test_rpc.cpp b/LibCarla/source/test/test_rpc.cpp index 4f190ff17..e1d2c25d4 100644 --- a/LibCarla/source/test/test_rpc.cpp +++ b/LibCarla/source/test/test_rpc.cpp @@ -39,7 +39,7 @@ TEST(rpc, server_bind_sync_run_on_game_thread) { carla::ThreadGroup threads; threads.CreateThread([&]() { Client client("localhost", TESTING_PORT); - for (auto i = 0u; i < 300u; ++i) { + for (auto i = 0; i < 300; ++i) { auto result = client.call("do_the_thing", i, 1).as(); EXPECT_EQ(result, i + 1); } diff --git a/LibCarla/source/test/test_streaming_low_level.cpp b/LibCarla/source/test/test_streaming_low_level.cpp index 35ba19d8b..36b0d4094 100644 --- a/LibCarla/source/test/test_streaming_low_level.cpp +++ b/LibCarla/source/test/test_streaming_low_level.cpp @@ -9,13 +9,14 @@ #include #include #include -#include -#include +#include +#include #include TEST(streaming_low_level, sending_strings) { using namespace util::message; + using namespace carla::streaming::detail; using namespace carla::streaming::low_level; constexpr auto number_of_messages = 5'000u; diff --git a/LibCarla/source/test/test_streaming_low_level_tcp.cpp b/LibCarla/source/test/test_streaming_low_level_tcp.cpp index 95abcaa76..31d8fd153 100644 --- a/LibCarla/source/test/test_streaming_low_level_tcp.cpp +++ b/LibCarla/source/test/test_streaming_low_level_tcp.cpp @@ -7,15 +7,14 @@ #include "test.h" #include -#include -#include +#include +#include #include -TEST(streaming_low_level_tcp, small_message) { +TEST(streaming_detail_tcp, small_message) { using namespace util::message; - using namespace carla::streaming::low_level; - using shared_session = std::shared_ptr; + using namespace carla::streaming::detail; boost::asio::io_service io_service; tcp::Server::endpoint ep(boost::asio::ip::tcp::v4(), TESTING_PORT); diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Carla.Build.cs b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Carla.Build.cs index f9c74b603..acb900025 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Carla.Build.cs +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Carla.Build.cs @@ -101,6 +101,14 @@ public class Carla : ModuleRules { PublicAdditionalLibraries.Add(Path.Combine(LibCarlaInstallPath, "lib", GetLibName("c++abi"))); PublicAdditionalLibraries.Add(Path.Combine(LibCarlaInstallPath, "lib", GetLibName("rpc"))); + if (UseDebugLibs(Target)) + { + PublicAdditionalLibraries.Add(Path.Combine(LibCarlaInstallPath, "lib", GetLibName("carla_server_debug"))); + } + else + { + PublicAdditionalLibraries.Add(Path.Combine(LibCarlaInstallPath, "lib", GetLibName("carla_server"))); + } } // Include path. diff --git a/Util/BuildTools/Setup.sh b/Util/BuildTools/Setup.sh index 214e7daf0..66d86c1b4 100755 --- a/Util/BuildTools/Setup.sh +++ b/Util/BuildTools/Setup.sh @@ -209,7 +209,9 @@ set(CMAKE_C_COMPILER ${CC}) set(CMAKE_CXX_COMPILER ${CXX}) set(CMAKE_CXX_FLAGS "\${CMAKE_CXX_FLAGS} -std=c++17 -pthread -fPIC" CACHE STRING "" FORCE) -# set(CMAKE_CXX_FLAGS "\${CMAKE_CXX_FLAGS} -Werror -Wall -Wextra" CACHE STRING "" FORCE) +set(CMAKE_CXX_FLAGS "\${CMAKE_CXX_FLAGS} -Werror -Wall -Wextra" CACHE STRING "" FORCE) +# See https://bugs.llvm.org/show_bug.cgi?id=21629 +set(CMAKE_CXX_FLAGS "\${CMAKE_CXX_FLAGS} -Wno-missing-braces" CACHE STRING "" FORCE) EOL # -- LIBCPP_TOOLCHAIN_FILE ----------------------------------------------------- @@ -232,7 +234,6 @@ cat >${CMAKE_CONFIG_FILE}.gen < Date: Fri, 13 Jul 2018 12:39:23 +0200 Subject: [PATCH 11/71] Compile everything with C++14 standard --- Docs/build_system.md | 2 +- PythonAPI/setup.py | 4 ++-- Util/BuildTools/Setup.sh | 8 ++++---- 3 files changed, 7 insertions(+), 7 deletions(-) diff --git a/Docs/build_system.md b/Docs/build_system.md index a79226d23..edeaf19a8 100644 --- a/Docs/build_system.md +++ b/Docs/build_system.md @@ -11,7 +11,7 @@ process. ![modules](img/modules.png) -In Linux, we compile CARLA and all the dependencies with clang-5.0 and C++17 +In Linux, we compile CARLA and all the dependencies with clang-5.0 and C++14 standard. We however link against different runtime C++ libraries depending on where the code going to be used, since all the code that is going to be linked with Unreal Engine needs to be compiled using `libc++`. diff --git a/PythonAPI/setup.py b/PythonAPI/setup.py index 02af08a52..5251b6bb2 100644 --- a/PythonAPI/setup.py +++ b/PythonAPI/setup.py @@ -44,8 +44,8 @@ def get_libcarla_extensions(): 'dependencies/lib'], runtime_library_dirs=['/usr/local/lib/boost'], libraries=libraries, - extra_compile_args=['-fPIC', '-std=c++17'], - language='c++17', + extra_compile_args=['-fPIC', '-std=c++14'], + language='c++14', depends=depends) return [make_extension('carla.libcarla', glob.glob('source/libcarla/*.cpp'))] diff --git a/Util/BuildTools/Setup.sh b/Util/BuildTools/Setup.sh index 66d86c1b4..ea4157385 100755 --- a/Util/BuildTools/Setup.sh +++ b/Util/BuildTools/Setup.sh @@ -122,7 +122,7 @@ else pushd ${RPCLIB_BASENAME}-libcxx-build >/dev/null cmake -G "Ninja" \ - -DCMAKE_CXX_FLAGS="-fPIC -std=c++17 -stdlib=libc++ -I${LLVM_INCLUDE} -Wl,-L${LLVM_LIBPATH}" \ + -DCMAKE_CXX_FLAGS="-fPIC -std=c++14 -stdlib=libc++ -I${LLVM_INCLUDE} -Wl,-L${LLVM_LIBPATH}" \ -DCMAKE_INSTALL_PREFIX="../${RPCLIB_BASENAME}-libcxx-install" \ ../${RPCLIB_BASENAME}-source @@ -139,7 +139,7 @@ else pushd ${RPCLIB_BASENAME}-libstdcxx-build >/dev/null cmake -G "Ninja" \ - -DCMAKE_CXX_FLAGS="-fPIC -std=c++17" \ + -DCMAKE_CXX_FLAGS="-fPIC -std=c++14" \ -DCMAKE_INSTALL_PREFIX="../${RPCLIB_BASENAME}-libstdcxx-install" \ ../${RPCLIB_BASENAME}-source @@ -180,7 +180,7 @@ else pushd ${GTEST_BASENAME}-build >/dev/null cmake -G "Ninja" \ - -DCMAKE_CXX_FLAGS="-std=c++17 -stdlib=libc++ -I${LLVM_INCLUDE} -Wl,-L${LLVM_LIBPATH}" \ + -DCMAKE_CXX_FLAGS="-std=c++14 -stdlib=libc++ -I${LLVM_INCLUDE} -Wl,-L${LLVM_LIBPATH}" \ -DCMAKE_INSTALL_PREFIX="../${GTEST_BASENAME}-install" \ ../${GTEST_BASENAME}-source @@ -208,7 +208,7 @@ cat >${LIBSTDCPP_TOOLCHAIN_FILE}.gen < Date: Fri, 13 Jul 2018 21:58:22 +0200 Subject: [PATCH 12/71] Add actor descriptions and definitions --- .../Carla/Source/Carla/Actor/ActorAttribute.h | 64 ++++++++++ .../Actor/ActorBlueprintFunctionLibrary.cpp | 101 +++++++++++++++ .../Actor/ActorBlueprintFunctionLibrary.h | 29 +++++ .../Source/Carla/Actor/ActorDefinition.h | 42 +++++++ .../Source/Carla/Actor/ActorDescription.h | 31 +++++ .../Source/Carla/Actor/ActorRegistry.cpp | 29 +++++ .../Carla/Source/Carla/Actor/ActorRegistry.h | 116 ++++++++++++++++++ .../Source/Carla/Actor/ActorSpawnerBase.h | 34 +++++ .../Carla/Source/Carla/Actor/ActorView.h | 52 ++++++++ 9 files changed, 498 insertions(+) create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorAttribute.h create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.h create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDefinition.h create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDescription.h create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorRegistry.cpp create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorRegistry.h create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnerBase.h create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorView.h diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorAttribute.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorAttribute.h new file mode 100644 index 000000000..29fd477a7 --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorAttribute.h @@ -0,0 +1,64 @@ +// 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 . + +#pragma once + +#include "ActorAttribute.generated.h" + +/// List of valid types for actor attributes. +UENUM(BlueprintType) +enum class EActorAttributeType : uint8 +{ + Bool UMETA(DisplayName = "Bool"), + Int UMETA(DisplayName = "Integer"), + Float UMETA(DisplayName = "Float"), + String UMETA(DisplayName = "String"), + RGBColor UMETA(DisplayName = "RGB Color (comma separated)"), + + SIZE UMETA(Hidden), + INVALID UMETA(Hidden) +}; + +/// Definition of an actor variation. Variations represent attributes of the +/// actor that the user can modify in order to generate variations of the same +/// actor. +/// +/// A list of recommended values is given. If bRestrictToRecommended is true, +/// only recommended values are accepted as valid. +USTRUCT(BlueprintType) +struct CARLA_API FActorVariation +{ + GENERATED_BODY() + + UPROPERTY(EditAnywhere, BlueprintReadWrite) + FString Id; + + UPROPERTY(EditAnywhere, BlueprintReadWrite) + EActorAttributeType Type = EActorAttributeType::Int; + + UPROPERTY(EditAnywhere, BlueprintReadWrite) + TArray RecommendedValues; + + UPROPERTY(EditAnywhere, BlueprintReadWrite) + bool bRestrictToRecommended = false; +}; + +/// An actor attribute, may be an intrinsic (non-modifiable) attribute of the +/// actor or an user-defined actor variation. +USTRUCT(BlueprintType) +struct CARLA_API FActorAttribute +{ + GENERATED_BODY() + + UPROPERTY(EditAnywhere, BlueprintReadWrite) + FString Id; + + UPROPERTY(EditAnywhere, BlueprintReadWrite) + EActorAttributeType Type = EActorAttributeType::Int; + + UPROPERTY(EditAnywhere, BlueprintReadWrite) + FString Value; +}; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp new file mode 100644 index 000000000..d5af02d12 --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp @@ -0,0 +1,101 @@ +// 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 . + +#include "Carla.h" +#include "ActorBlueprintFunctionLibrary.h" + +#include + +/// @todo Improve all the check here. +namespace ActorDetail { + + /// Iterate every item and validate it with @a Validator. + template + static bool ForEach(const TArray &Array, F Validator) + { + bool result = true; + for (auto &&Item : Array) + { + result &= Validator(Item); + } + return result; + } + + static bool IsValid(const FString &String) + { + return !String.IsEmpty(); + } + + static bool IdIsValid(const FString &Id) + { + return IsValid(Id); + } + + static bool TagsAreValid(const FString &Tags) + { + return IsValid(Tags); + } + + static bool IsValid(const EActorAttributeType Type) + { + return Type < EActorAttributeType::SIZE; + } + + static bool ValueIsValid(const EActorAttributeType Type, const FString &Value) + { + return true; + } + + static bool IsValid(const FActorVariation &Variation) + { + return + IdIsValid(Variation.Id) && + IsValid(Variation.Type) && + ForEach(Variation.RecommendedValues, [&](auto &Value) { + return ValueIsValid(Variation.Type, Value); + }); + } + + static bool IsValid(const FActorAttribute &Attribute) + { + return + IdIsValid(Attribute.Id) && + IsValid(Attribute.Type) && + ValueIsValid(Attribute.Type, Attribute.Value); + } + + static bool IsValid(const FActorDefinition &Definition); + + template + static bool AreValid(const TArray &Array) + { + return ForEach(Array, [](const auto &Item){ return ActorDetail::IsValid(Item); }); + } + + static bool IsValid(const FActorDefinition &Definition) + { + return + IdIsValid(Definition.Id) && + TagsAreValid(Definition.Tags) && + AreValid(Definition.Variations) && + AreValid(Definition.Attributes); + } + +} // namespace ActorDetail + +bool UActorBlueprintFunctionLibrary::CheckActorDefinitions(const TArray &ActorDefinitions) +{ + return ActorDetail::AreValid(ActorDefinitions); +} + +void UActorBlueprintFunctionLibrary::ValidateActorDefinitions(TArray &ActorDefinitions) +{ + /// @todo + if (!CheckActorDefinitions(ActorDefinitions)) + { + ActorDefinitions.Empty(); // lol + } +} diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.h new file mode 100644 index 000000000..f90414195 --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.h @@ -0,0 +1,29 @@ +// 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 . + +#pragma once + +#include "Carla/Actor/ActorDefinition.h" + +#include "Kismet/BlueprintFunctionLibrary.h" + +#include "ActorBlueprintFunctionLibrary.generated.h" + +UCLASS() +class UActorBlueprintFunctionLibrary : public UBlueprintFunctionLibrary +{ + GENERATED_BODY() + + /// Return whether the list of actor definitions is valid. Prints all the + /// errors found. + UFUNCTION(Category = "Carla Actor", BlueprintCallable) + static bool CheckActorDefinitions(const TArray &ActorDefinitions); + + /// Modifies the list of actor definitions, fixing or removing invalid items. + UFUNCTION(Category = "Carla Actor", BlueprintCallable) + static void ValidateActorDefinitions(TArray &ActorDefinitions); +}; + diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDefinition.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDefinition.h new file mode 100644 index 000000000..316ab9297 --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDefinition.h @@ -0,0 +1,42 @@ +// 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 . + +#pragma once + +#include "Carla/Actor/ActorAttribute.h" + +#include "GameFramework/Actor.h" + +#include "ActorDefinition.generated.h" + +/// A definition of a Carla Actor with all the variation and attributes. +USTRUCT(BlueprintType) +struct FActorDefinition +{ + GENERATED_BODY() + + /// Display ID that identifies the actor. + UPROPERTY(EditAnywhere, BlueprintReadWrite) + FString Id; + + /// AActor class of the actor to be spawned. + UPROPERTY(EditAnywhere, BlueprintReadWrite) + TSubclassOf Class; + + /// A list of comma-separated tags. + UPROPERTY(EditAnywhere, BlueprintReadWrite) + FString Tags; + + /// Variations represent variables the user can modify to generate variations + /// of the actor. + UPROPERTY(EditAnywhere, BlueprintReadWrite) + TArray Variations; + + /// Attributes represent non-modifiable properties of the actor that might + /// help the user identifying and filtering actors. + UPROPERTY(EditAnywhere, BlueprintReadWrite) + TArray Attributes; +}; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDescription.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDescription.h new file mode 100644 index 000000000..623206c2b --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDescription.h @@ -0,0 +1,31 @@ +// 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 . + +#pragma once + +#include "Carla/Actor/ActorAttribute.h" + +#include "ActorDescription.generated.h" + +/// A description of a Carla Actor with all its variation. +USTRUCT(BlueprintType) +struct FActorDescription +{ + GENERATED_BODY() + + /// Display ID that identifies the actor. + UPROPERTY(EditAnywhere, BlueprintReadWrite) + FString Id; + + /// AActor class of the actor to be spawned. + UPROPERTY(EditAnywhere, BlueprintReadWrite) + TSubclassOf Class; + + /// User selected variations of the actor. Note that at this point are + /// represented by non-modifiable attributes. + UPROPERTY(EditAnywhere, BlueprintReadWrite) + TArray Variations; +}; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorRegistry.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorRegistry.cpp new file mode 100644 index 000000000..1ad356d5d --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorRegistry.cpp @@ -0,0 +1,29 @@ +// 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 . + +#pragma once + +#include "Carla.h" +#include "Carla/Actor/ActorRegistry.h" + +FActorView UActorRegistry::Register(AActor &Actor) +{ + static IdType ID_COUNTER = 0u; + auto Id = ++ID_COUNTER; + Actors.Emplace(Id, &Actor); + auto Result = ActorDatabase.emplace(Id, FActorView(Id, Actor)); + check(Result.second); + check(static_cast(Actors.Num()) == ActorDatabase.size()); + return Result.first->second; +} + +void UActorRegistry::Deregister(IdType Id) +{ + check(Contains(Id)); + ActorDatabase.erase(Id); + Actors.Remove(Id); + check(static_cast(Actors.Num()) == ActorDatabase.size()); +} diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorRegistry.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorRegistry.h new file mode 100644 index 000000000..e78642352 --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorRegistry.h @@ -0,0 +1,116 @@ +// 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 . + +#pragma once + +#include "Carla/Actor/ActorView.h" + +#include "Containers/Map.h" + +#include + +#include "ActorRegistry.generated.h" + +/// A registry of all the Carla actors. +UCLASS(BlueprintType, Blueprintable) +class CARLA_API UActorRegistry : public UObject +{ + GENERATED_BODY() + +private: + + using DatabaseType = std::unordered_map; + +public: + + using IdType = DatabaseType::key_type; + + // =========================================================================== + /// @name Actor registry functions + // =========================================================================== + /// @{ +public: + + /// Register the @a Actor in the database. A new ID will be assign to this + /// actor. + /// + /// @warning Undefined if an actor is registered more than once. + FActorView Register(AActor &Actor); + + void Deregister(IdType Id); + + FActorView Find(IdType Id) const + { + auto it = ActorDatabase.find(Id); + return it != ActorDatabase.end() ? it->second : FActorView(); + } + + /// @} + // =========================================================================== + /// @name Blueprint support + // =========================================================================== + /// @{ +public: + + // UPROPERTY(BlueprintCallable) + int32 Num() const + { + return Actors.Num(); + } + + // UPROPERTY(BlueprintCallable) + bool IsEmpty() const + { + return ActorDatabase.empty(); + } + + // UPROPERTY(BlueprintCallable) + bool Contains(IdType Id) const + { + return ActorDatabase.find(Id) != ActorDatabase.end(); + } + + // UPROPERTY(BlueprintCallable) + AActor *FindActor(IdType Id) const + { + auto PtrToPtr = Actors.Find(Id); + return PtrToPtr != nullptr ? *PtrToPtr : nullptr; + } + + /// @} + // =========================================================================== + /// @name Range iteration support + // =========================================================================== + /// @{ +public: + + using key_type = DatabaseType::key_type; + using mapped_type = DatabaseType::mapped_type; + using value_type = DatabaseType::value_type; + using const_iterator = DatabaseType::const_iterator; + + const_iterator begin() const noexcept + { + return ActorDatabase.begin(); + } + + const_iterator end() const noexcept + { + return ActorDatabase.end(); + } + + /// @} +private: + + // Because UPROPERTY doesn't understand aliases... + static_assert(sizeof(IdType) == sizeof(uint32), "Id type missmatch!"); + + // This one makes sure actors are not garbage collected. + UPROPERTY(VisibleAnywhere) + TMap Actors; + + DatabaseType ActorDatabase; +}; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnerBase.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnerBase.h new file mode 100644 index 000000000..231043fe8 --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnerBase.h @@ -0,0 +1,34 @@ +// 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 . + +#pragma once + +#include "Carla/Actor/ActorDefinition.h" +#include "Carla/Actor/ActorDescription.h" + +#include "Containers/Array.h" + +#include + +#include "ActorSpawnerBase.generated.h" + +/// Interface for the actor spawner. It is implemented in blueprints. +UCLASS(BlueprintType, Blueprintable) +class CARLA_API UActorSpawnerBase : public UObject +{ + GENERATED_BODY() + +public: + + UFUNCTION(BlueprintImplementableEvent) + TArray GenerateDefinitions(); + + UFUNCTION(BlueprintImplementableEvent) + void SpawnActor( + const FTransform &SpawnAtTransform, + const FActorDescription &ActorDescription, + AActor *&Actor); +}; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorView.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorView.h new file mode 100644 index 000000000..1cd49f6c7 --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorView.h @@ -0,0 +1,52 @@ +// 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 . + +#pragma once + +class AActor; + +/// An view over an actor and its properties. +class FActorView +{ +public: + + using IdType = uint32; + + FActorView() = default; + FActorView(const FActorView &) = default; + + bool IsValid() const + { + return TheActor != nullptr; + } + + IdType GetActorId() const + { + return Id; + } + + AActor *GetActor() + { + return TheActor; + } + + const AActor *GetActor() const + { + return TheActor; + } + +private: + + friend class UActorRegistry; + + FActorView(IdType ActorId, AActor &Actor) + : Id(ActorId), + TheActor(&Actor) {} + + IdType Id = 0u; + + AActor *TheActor = nullptr; +}; From 82de324b0f9d4f8c9099a753cc5d15c5b6f40b99 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Sun, 15 Jul 2018 18:52:17 +0200 Subject: [PATCH 13/71] Suppress clang warning --- LibCarla/source/compiler/disable-ue4-macros.h | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/LibCarla/source/compiler/disable-ue4-macros.h b/LibCarla/source/compiler/disable-ue4-macros.h index abefba603..8051a982b 100644 --- a/LibCarla/source/compiler/disable-ue4-macros.h +++ b/LibCarla/source/compiler/disable-ue4-macros.h @@ -23,6 +23,13 @@ # define BOOST_NO_EXCEPTIONS #endif // BOOST_NO_EXCEPTIONS +// Suppress clang warning. +#if defined(__clang__) +# ifndef __cpp_coroutines +# define __cpp_coroutines 0 +# endif // __cpp_coroutines +#endif // defined(__clang__) + namespace boost { static inline void throw_exception(const std::exception &e) { From 892acbbd3c50929c9800e6930733c68b7bbbac41 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Sun, 15 Jul 2018 18:57:21 +0200 Subject: [PATCH 14/71] Actor spawner needs to be an actor --- .../Plugins/Carla/Source/Carla/Actor/ActorSpawnerBase.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnerBase.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnerBase.h index 231043fe8..c336b00ef 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnerBase.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnerBase.h @@ -10,6 +10,7 @@ #include "Carla/Actor/ActorDescription.h" #include "Containers/Array.h" +#include "GameFramework/Actor.h" #include @@ -17,7 +18,7 @@ /// Interface for the actor spawner. It is implemented in blueprints. UCLASS(BlueprintType, Blueprintable) -class CARLA_API UActorSpawnerBase : public UObject +class CARLA_API AActorSpawnerBase : public AActor { GENERATED_BODY() From a8ebcbd5050155bbb60672d1ac4b9288b0778709 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Sun, 15 Jul 2018 18:58:06 +0200 Subject: [PATCH 15/71] Improve actor definition checks output --- .../Actor/ActorBlueprintFunctionLibrary.cpp | 143 ++++++++++++------ .../Actor/ActorBlueprintFunctionLibrary.h | 4 - .../Carla/Source/Carla/Util/ScopedStack.h | 32 ++++ 3 files changed, 127 insertions(+), 52 deletions(-) create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/ScopedStack.h diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp index d5af02d12..245c6aa67 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp @@ -5,97 +5,144 @@ // For a copy, see . #include "Carla.h" -#include "ActorBlueprintFunctionLibrary.h" +#include "Carla/Actor/ActorBlueprintFunctionLibrary.h" + +#include "Carla/Util/ScopedStack.h" #include +#include -/// @todo Improve all the check here. -namespace ActorDetail { +/// Checks validity of FActorDefinition. +class FActorDefinitionValidator { +public: - /// Iterate every item and validate it with @a Validator. - template - static bool ForEach(const TArray &Array, F Validator) + /// Iterate all actor definitions and properties and display messages on + /// error. + bool AreValid(const TArray &ActorDefinitions) { - bool result = true; - for (auto &&Item : Array) + return AreValid(TEXT("Actor Definition"), ActorDefinitions); + } + +private: + + /// If @a Predicate is false, print an error message. If possible the message + /// is printed too in the editor window. + template + bool OnScreenAssert(bool Predicate, const T &Format, ARGS && ... Args) const + { + if (!Predicate) { - result &= Validator(Item); + FString Message; + for (auto &String : Stack) + { + Message += String; + } + Message += TEXT(" "); + Message += FString::Printf(Format, std::forward(Args)...); + + UE_LOG(LogCarla, Error, TEXT("%s"), *Message); +#if WITH_EDITOR + if(GEngine) + { + GEngine->AddOnScreenDebugMessage(42, 15.0f, FColor::Red, Message); + } +#endif // WITH_EDITOR } - return result; + return Predicate; } - static bool IsValid(const FString &String) + template + FString GetDisplayId(const FString &Type, size_t Index, const T &Item) { - return !String.IsEmpty(); + return FString::Printf(TEXT("[%s %d : %s]"), *Type, Index, *Item.Id); } - static bool IdIsValid(const FString &Id) + FString GetDisplayId(const FString &Type, size_t Index, const FString &Item) { - return IsValid(Id); + return FString::Printf(TEXT("[%s %d : %s]"), *Type, Index, *Item); } - static bool TagsAreValid(const FString &Tags) + /// Applies @a Validator to each item in @a Array. Pushes a new context to the + /// stack for each item. + template + bool ForEach(const FString &Type, const TArray &Array, F Validator) { - return IsValid(Tags); + bool Result = true; + auto Counter = 0u; + for (const auto &Item : Array) + { + auto Scope = Stack.PushScope(GetDisplayId(Type, Counter, Item)); + Result &= Validator(Item); + ++Counter; + } + return Result; } - static bool IsValid(const EActorAttributeType Type) + /// Applies @a IsValid to each item in @a Array. Pushes a new context to the + /// stack for each item. + template + bool AreValid(const FString &Type, const TArray &Array) { - return Type < EActorAttributeType::SIZE; + return ForEach(Type, Array, [this](const auto &Item){ return IsValid(Item); }); } - static bool ValueIsValid(const EActorAttributeType Type, const FString &Value) + bool IsIdValid(const FString &Id) { + /// @todo Do more checks. + return OnScreenAssert(!Id.IsEmpty(), TEXT("Id cannot be empty")); + } + + bool AreTagsValid(const FString &Tags) + { + /// @todo Do more checks. + return OnScreenAssert(!Tags.IsEmpty(), TEXT("Tags cannot be empty")); + } + + bool IsValid(const EActorAttributeType Type) + { + /// @todo Do more checks. + return OnScreenAssert(Type < EActorAttributeType::SIZE, TEXT("Invalid Type")); + } + + bool ValueIsValid(const EActorAttributeType Type, const FString &Value) + { + /// @todo Do more checks. return true; } - static bool IsValid(const FActorVariation &Variation) + bool IsValid(const FActorVariation &Variation) { return - IdIsValid(Variation.Id) && + IsIdValid(Variation.Id) && IsValid(Variation.Type) && - ForEach(Variation.RecommendedValues, [&](auto &Value) { + ForEach(TEXT("Recommended Value"), Variation.RecommendedValues, [&](auto &Value) { return ValueIsValid(Variation.Type, Value); }); } - static bool IsValid(const FActorAttribute &Attribute) + bool IsValid(const FActorAttribute &Attribute) { return - IdIsValid(Attribute.Id) && + IsIdValid(Attribute.Id) && IsValid(Attribute.Type) && ValueIsValid(Attribute.Type, Attribute.Value); } - static bool IsValid(const FActorDefinition &Definition); - - template - static bool AreValid(const TArray &Array) - { - return ForEach(Array, [](const auto &Item){ return ActorDetail::IsValid(Item); }); - } - - static bool IsValid(const FActorDefinition &Definition) + bool IsValid(const FActorDefinition &ActorDefinition) { + /// @todo Validate Class and make sure IDs are not repeated. return - IdIsValid(Definition.Id) && - TagsAreValid(Definition.Tags) && - AreValid(Definition.Variations) && - AreValid(Definition.Attributes); + IsIdValid(ActorDefinition.Id) && + AreTagsValid(ActorDefinition.Tags) && + AreValid(TEXT("Variation"), ActorDefinition.Variations) && + AreValid(TEXT("Attribute"), ActorDefinition.Attributes); } -} // namespace ActorDetail + FScopedStack Stack; +}; bool UActorBlueprintFunctionLibrary::CheckActorDefinitions(const TArray &ActorDefinitions) { - return ActorDetail::AreValid(ActorDefinitions); -} - -void UActorBlueprintFunctionLibrary::ValidateActorDefinitions(TArray &ActorDefinitions) -{ - /// @todo - if (!CheckActorDefinitions(ActorDefinitions)) - { - ActorDefinitions.Empty(); // lol - } + FActorDefinitionValidator Validator; + return Validator.AreValid(ActorDefinitions); } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.h index f90414195..4c26418db 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.h @@ -21,9 +21,5 @@ class UActorBlueprintFunctionLibrary : public UBlueprintFunctionLibrary /// errors found. UFUNCTION(Category = "Carla Actor", BlueprintCallable) static bool CheckActorDefinitions(const TArray &ActorDefinitions); - - /// Modifies the list of actor definitions, fixing or removing invalid items. - UFUNCTION(Category = "Carla Actor", BlueprintCallable) - static void ValidateActorDefinitions(TArray &ActorDefinitions); }; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/ScopedStack.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/ScopedStack.h new file mode 100644 index 000000000..dab2c1d1d --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/ScopedStack.h @@ -0,0 +1,32 @@ +// 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 . + +#pragma once + +#include + +/// A stack to keep track of nested scopes. +template +class FScopedStack : private std::deque { + using Super = std::deque; +public: + + /// Push this scope into the stack. Automatically pops @a Value when the + /// returned object goes out of the scope. + template + auto PushScope(V &&Value) + { + Super::emplace_back(std::forward(Value)); + T *Pointer = &Super::back(); + auto Deleter = [this](const T *) { Super::pop_back(); }; + return std::unique_ptr(Pointer, Deleter); + } + + using Super::empty; + using Super::size; + using Super::begin; + using Super::end; +}; From 2a8b8e2e4f26625e3d49a12cebdb98bd50368e76 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Sun, 15 Jul 2018 21:01:22 +0200 Subject: [PATCH 16/71] Add actor dispatcher --- .../Actor/ActorBlueprintFunctionLibrary.cpp | 18 ++++- .../Actor/ActorBlueprintFunctionLibrary.h | 6 ++ .../Source/Carla/Actor/ActorDefinition.h | 3 + .../Source/Carla/Actor/ActorDescription.h | 3 + .../Source/Carla/Actor/ActorDispatcher.cpp | 61 +++++++++++++++ .../Source/Carla/Actor/ActorDispatcher.h | 74 +++++++++++++++++++ .../Source/Carla/Actor/ActorRegistry.cpp | 19 ++++- .../Carla/Source/Carla/Actor/ActorRegistry.h | 67 ++++++++--------- .../Carla/Source/Carla/Actor/ActorSpawner.h | 32 ++++++++ .../Source/Carla/Actor/ActorSpawnerBase.h | 35 --------- .../Carla/Actor/ActorSpawnerBlueprintBase.h | 50 +++++++++++++ .../Carla/Source/Carla/Actor/ActorView.h | 2 +- 12 files changed, 293 insertions(+), 77 deletions(-) create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.h create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawner.h delete mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnerBase.h create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnerBlueprintBase.h diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp index 245c6aa67..658f1ad0b 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp @@ -16,17 +16,25 @@ class FActorDefinitionValidator { public: - /// Iterate all actor definitions and properties and display messages on + /// Iterate all actor definitions and their properties and display messages on /// error. bool AreValid(const TArray &ActorDefinitions) { return AreValid(TEXT("Actor Definition"), ActorDefinitions); } + /// Validate @a ActorDefinition and display messages on error. + bool SingleIsValid(const FActorDefinition &Definition) + { + auto ScopeText = FString::Printf(TEXT("[Actor Definition : %s]"), *Definition.Id); + auto Scope = Stack.PushScope(ScopeText); + return IsValid(Definition); + } + private: /// If @a Predicate is false, print an error message. If possible the message - /// is printed too in the editor window. + /// is printed to the editor window. template bool OnScreenAssert(bool Predicate, const T &Format, ARGS && ... Args) const { @@ -141,6 +149,12 @@ private: FScopedStack Stack; }; +bool UActorBlueprintFunctionLibrary::CheckActorDefinition(const FActorDefinition &ActorDefinition) +{ + FActorDefinitionValidator Validator; + return Validator.SingleIsValid(ActorDefinition); +} + bool UActorBlueprintFunctionLibrary::CheckActorDefinitions(const TArray &ActorDefinitions) { FActorDefinitionValidator Validator; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.h index 4c26418db..bbdfb3d5b 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.h @@ -17,6 +17,12 @@ class UActorBlueprintFunctionLibrary : public UBlueprintFunctionLibrary { GENERATED_BODY() +public: + + /// Return whether the actor definition is valid. Prints all the errors found. + UFUNCTION(Category = "Carla Actor", BlueprintCallable) + static bool CheckActorDefinition(const FActorDefinition &ActorDefinitions); + /// Return whether the list of actor definitions is valid. Prints all the /// errors found. UFUNCTION(Category = "Carla Actor", BlueprintCallable) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDefinition.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDefinition.h index 316ab9297..e71a65902 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDefinition.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDefinition.h @@ -18,6 +18,9 @@ struct FActorDefinition { GENERATED_BODY() + /// Uniquely identifies the definition (no need to fill it). + uint32 UId = 0u; + /// Display ID that identifies the actor. UPROPERTY(EditAnywhere, BlueprintReadWrite) FString Id; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDescription.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDescription.h index 623206c2b..c37af65c7 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDescription.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDescription.h @@ -16,6 +16,9 @@ struct FActorDescription { GENERATED_BODY() + /// Uniquely identifies the definition. + uint32 UId = 0u; + /// Display ID that identifies the actor. UPROPERTY(EditAnywhere, BlueprintReadWrite) FString Id; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp new file mode 100644 index 000000000..f237ddc7a --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp @@ -0,0 +1,61 @@ +// 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 . + +#include "Carla.h" +#include "Carla/Actor/ActorDispatcher.h" + +#include "Carla/Actor/ActorBlueprintFunctionLibrary.h" +#include "Carla/Actor/ActorSpawner.h" + +void AActorDispatcher::Bind(FActorDefinition Definition, SpawnFunctionType Functor) +{ + if (UActorBlueprintFunctionLibrary::CheckActorDefinition(Definition)) + { + Definition.UId = static_cast(SpawnFunctions.Num()) + 1u; + Definitions.Emplace(Definition); + SpawnFunctions.Emplace(Functor); + } + else + { + UE_LOG(LogCarla, Warning, TEXT("Invalid definition ignored")); + } +} + +void AActorDispatcher::Bind(IActorSpawner &ActorSpawner) +{ + for (const auto &Definition : ActorSpawner.MakeDefinitions()) + { + Bind(Definition, [&](const FTransform &Transform, const FActorDescription &Description) { + return ActorSpawner.SpawnActor(Transform, Description); + }); + } +} + +AActor *AActorDispatcher::SpawnActor( + const FTransform &Transform, + const FActorDescription &Description) +{ + if ((Description.UId == 0) || (Description.UId > SpawnFunctions.Num())) + { + UE_LOG(LogCarla, Error, TEXT("Invalid ActorDescription \"%s\" (UId=%d)"), *Description.Id, Description.UId); + return nullptr; + } + auto *Actor = SpawnFunctions[Description.UId](Transform, Description); + if (Actor != nullptr) + { + Registry.Register(*Actor); + } + return Actor; +} + +void AActorDispatcher::DestroyActor(AActor *Actor) +{ + if (Actor != nullptr) + { + Registry.Deregister(Actor); + Actor->Destroy(); + } +} diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.h new file mode 100644 index 000000000..a45926113 --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.h @@ -0,0 +1,74 @@ +// 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 . + +#pragma once + +#include "Carla/Actor/ActorDefinition.h" +#include "Carla/Actor/ActorDescription.h" +#include "Carla/Actor/ActorRegistry.h" + +#include "Containers/Array.h" +#include "GameFramework/Actor.h" +#include "Templates/Function.h" + +#include "ActorDispatcher.generated.h" + +class IActorSpawner; + +/// Actor in charge of binding ActorDefinitions to spawn functions, as well as +/// keeping the registry of all the actors spawned. +UCLASS() +class CARLA_API AActorDispatcher : public AActor +{ + GENERATED_BODY() + +public: + + using SpawnFunctionType = TFunction; + + /// Bind a definition to a spawn function. When SpawnActor is called with a + /// matching description @a Functor is called. + /// + /// @warning Invalid definitions are ignored. + void Bind(FActorDefinition Definition, SpawnFunctionType SpawnFunction); + + /// Bind all the definitions of @a ActorSpawner to its spawn function. + /// + /// @warning Invalid definitions are ignored. + void Bind(IActorSpawner &ActorSpawner); + + /// Spawns an actor based on @a ActorDescription at @a Transform. To properly + /// despawn an actor created with this function call DestroyActor. + /// + /// Return nullptr on failure. + UFUNCTION(BlueprintCallable) + AActor *SpawnActor( + const FTransform &Transform, + const FActorDescription &ActorDescription); + + /// Destroys an actor, properly removing it from the registry. + UFUNCTION(BlueprintCallable) + void DestroyActor(AActor *Actor); + + UFUNCTION(BlueprintCallable) + const TArray &GetActorDefinitions() const + { + return Definitions; + } + + const FActorRegistry &GetActorRegistry() const + { + return Registry; + } + +private: + + TArray Definitions; + + TArray SpawnFunctions; + + FActorRegistry Registry; +}; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorRegistry.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorRegistry.cpp index 1ad356d5d..75499dec9 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorRegistry.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorRegistry.cpp @@ -9,21 +9,34 @@ #include "Carla.h" #include "Carla/Actor/ActorRegistry.h" -FActorView UActorRegistry::Register(AActor &Actor) +FActorView FActorRegistry::Register(AActor &Actor) { static IdType ID_COUNTER = 0u; - auto Id = ++ID_COUNTER; + const auto Id = ++ID_COUNTER; Actors.Emplace(Id, &Actor); + Ids.Emplace(&Actor, Id); auto Result = ActorDatabase.emplace(Id, FActorView(Id, Actor)); check(Result.second); check(static_cast(Actors.Num()) == ActorDatabase.size()); + check(static_cast(Ids.Num()) == ActorDatabase.size()); return Result.first->second; } -void UActorRegistry::Deregister(IdType Id) +void FActorRegistry::Deregister(IdType Id) { check(Contains(Id)); + AActor *Actor = FindActor(Id); + check(Actor != nullptr); ActorDatabase.erase(Id); Actors.Remove(Id); + Ids.Remove(Actor); check(static_cast(Actors.Num()) == ActorDatabase.size()); + check(static_cast(Ids.Num()) == ActorDatabase.size()); +} + +void FActorRegistry::Deregister(AActor *Actor) +{ + auto View = Find(Actor); + check(View.IsValid()); + Deregister(View.GetActorId()); } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorRegistry.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorRegistry.h index e78642352..8f6342723 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorRegistry.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorRegistry.h @@ -12,14 +12,9 @@ #include -#include "ActorRegistry.generated.h" - /// A registry of all the Carla actors. -UCLASS(BlueprintType, Blueprintable) -class CARLA_API UActorRegistry : public UObject +class FActorRegistry { - GENERATED_BODY() - private: using DatabaseType = std::unordered_map; @@ -42,42 +37,45 @@ public: void Deregister(IdType Id); + void Deregister(AActor *Actor); + + /// @} + // =========================================================================== + /// @name Look up functions + // =========================================================================== + /// @{ + + int32 Num() const + { + return Actors.Num(); + } + + bool IsEmpty() const + { + return ActorDatabase.empty(); + } + + bool Contains(uint32 Id) const + { + return ActorDatabase.find(Id) != ActorDatabase.end(); + } + FActorView Find(IdType Id) const { auto it = ActorDatabase.find(Id); return it != ActorDatabase.end() ? it->second : FActorView(); } - /// @} - // =========================================================================== - /// @name Blueprint support - // =========================================================================== - /// @{ -public: - - // UPROPERTY(BlueprintCallable) - int32 Num() const + FActorView Find(AActor *Actor) const { - return Actors.Num(); + auto PtrToId = Ids.Find(Actor); + return PtrToId != nullptr ? Find(*PtrToId) : FActorView(); } - // UPROPERTY(BlueprintCallable) - bool IsEmpty() const - { - return ActorDatabase.empty(); - } - - // UPROPERTY(BlueprintCallable) - bool Contains(IdType Id) const - { - return ActorDatabase.find(Id) != ActorDatabase.end(); - } - - // UPROPERTY(BlueprintCallable) AActor *FindActor(IdType Id) const { - auto PtrToPtr = Actors.Find(Id); - return PtrToPtr != nullptr ? *PtrToPtr : nullptr; + auto View = Find(Id); + return View.IsValid() ? View.GetActor() : nullptr; } /// @} @@ -105,12 +103,9 @@ public: /// @} private: - // Because UPROPERTY doesn't understand aliases... - static_assert(sizeof(IdType) == sizeof(uint32), "Id type missmatch!"); + TMap Actors; - // This one makes sure actors are not garbage collected. - UPROPERTY(VisibleAnywhere) - TMap Actors; + TMap Ids; DatabaseType ActorDatabase; }; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawner.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawner.h new file mode 100644 index 000000000..b7ac4c0e6 --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawner.h @@ -0,0 +1,32 @@ +// 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 . + +#pragma once + +#include "Carla/Actor/ActorDefinition.h" +#include "Carla/Actor/ActorDescription.h" + +#include "Containers/Array.h" +#include "GameFramework/Actor.h" + +/// Interface for Carla actor spawners. +class IActorSpawner +{ +public: + + virtual ~IActorSpawner() {} + + /// Retrieve the list of actor definitions that this class is able to spawn. + virtual TArray MakeDefinitions() = 0; + + /// Spawn an actor based on @a ActorDescription and @a Transform. + /// + /// @pre ActorDescription is expected to be derived from one of the + /// definitions retrieved with MakeDefinitions. + virtual AActor *SpawnActor( + const FTransform &SpawnAtTransform, + const FActorDescription &ActorDescription) = 0; +}; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnerBase.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnerBase.h deleted file mode 100644 index c336b00ef..000000000 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnerBase.h +++ /dev/null @@ -1,35 +0,0 @@ -// 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 . - -#pragma once - -#include "Carla/Actor/ActorDefinition.h" -#include "Carla/Actor/ActorDescription.h" - -#include "Containers/Array.h" -#include "GameFramework/Actor.h" - -#include - -#include "ActorSpawnerBase.generated.h" - -/// Interface for the actor spawner. It is implemented in blueprints. -UCLASS(BlueprintType, Blueprintable) -class CARLA_API AActorSpawnerBase : public AActor -{ - GENERATED_BODY() - -public: - - UFUNCTION(BlueprintImplementableEvent) - TArray GenerateDefinitions(); - - UFUNCTION(BlueprintImplementableEvent) - void SpawnActor( - const FTransform &SpawnAtTransform, - const FActorDescription &ActorDescription, - AActor *&Actor); -}; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnerBlueprintBase.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnerBlueprintBase.h new file mode 100644 index 000000000..89af52382 --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnerBlueprintBase.h @@ -0,0 +1,50 @@ +// 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 . + +#pragma once + +#include "Carla/Actor/ActorSpawner.h" + +#include "ActorSpawnerBlueprintBase.generated.h" + +/// Base class for Blueprints implementing IActorSpawner interface. +/// +/// Blueprints deriving from this class are expected to override +/// GenerateDefinitions and SpawnActor functions. +UCLASS(BlueprintType, Blueprintable) +class CARLA_API AActorSpawnerBlueprintBase + : public AActor, + public IActorSpawner +{ + GENERATED_BODY() + +public: + + virtual TArray MakeDefinitions() final + { + return GenerateDefinitions(); + } + + virtual AActor *SpawnActor( + const FTransform &SpawnAtTransform, + const FActorDescription &ActorDescription) final + { + AActor *Actor = nullptr; + SpawnActor(SpawnAtTransform, ActorDescription, Actor); + return Actor; + } + +protected: + + UFUNCTION(BlueprintImplementableEvent) + TArray GenerateDefinitions(); + + UFUNCTION(BlueprintImplementableEvent) + void SpawnActor( + const FTransform &SpawnAtTransform, + const FActorDescription &ActorDescription, + AActor *&Actor); +}; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorView.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorView.h index 1cd49f6c7..9eefd1deb 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorView.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorView.h @@ -40,7 +40,7 @@ public: private: - friend class UActorRegistry; + friend class FActorRegistry; FActorView(IdType ActorId, AActor &Actor) : Id(ActorId), From 45f661ff9e6077d2dcd5b401762df21cd06cb1fb Mon Sep 17 00:00:00 2001 From: nsubiron Date: Wed, 18 Jul 2018 18:05:21 +0200 Subject: [PATCH 17/71] Expose actor definitions and attributes on client side --- LibCarla/cmake/client/CMakeLists.txt | 6 +- LibCarla/source/carla/Iterator.h | 27 +++ LibCarla/source/carla/StringUtil.cpp | 25 +++ LibCarla/source/carla/StringUtil.h | 36 ++++ LibCarla/source/carla/client/Actor.h | 12 +- .../source/carla/client/ActorAttribute.cpp | 103 ++++++++++++ LibCarla/source/carla/client/ActorAttribute.h | 156 ++++++++++++++++++ .../source/carla/client/ActorBlueprint.cpp | 47 ++++-- LibCarla/source/carla/client/ActorBlueprint.h | 108 ++++++++++-- .../source/carla/client/BlueprintLibrary.h | 30 ++-- LibCarla/source/carla/client/Client.cpp | 2 +- LibCarla/source/carla/client/Client.h | 4 +- LibCarla/source/carla/client/Color.h | 32 ++++ LibCarla/source/carla/client/Memory.h | 2 +- LibCarla/source/carla/client/World.h | 2 +- LibCarla/source/carla/rpc/Actor.h | 6 +- LibCarla/source/carla/rpc/ActorAttribute.h | 96 +++++++++++ .../source/carla/rpc/ActorAttributeType.h | 29 ++++ LibCarla/source/carla/rpc/ActorBlueprint.h | 49 ------ LibCarla/source/carla/rpc/ActorDefinition.h | 52 ++++++ LibCarla/source/carla/rpc/ActorDescription.h | 48 ++++++ LibCarla/source/carla/rpc/String.h | 31 ++++ PythonAPI/source/libcarla/Actor.cpp | 12 +- PythonAPI/source/libcarla/Blueprint.cpp | 74 ++++++++- .../Carla/Source/Carla/Actor/ActorAttribute.h | 20 ++- .../Source/Carla/Actor/ActorDefinition.h | 4 - .../Source/Carla/Actor/ActorDescription.h | 6 +- .../Carla/Source/Carla/Server/RPCServer.cpp | 27 ++- 28 files changed, 892 insertions(+), 154 deletions(-) create mode 100644 LibCarla/source/carla/Iterator.h create mode 100644 LibCarla/source/carla/StringUtil.cpp create mode 100644 LibCarla/source/carla/StringUtil.h create mode 100644 LibCarla/source/carla/client/ActorAttribute.cpp create mode 100644 LibCarla/source/carla/client/ActorAttribute.h create mode 100644 LibCarla/source/carla/client/Color.h create mode 100644 LibCarla/source/carla/rpc/ActorAttribute.h create mode 100644 LibCarla/source/carla/rpc/ActorAttributeType.h delete mode 100644 LibCarla/source/carla/rpc/ActorBlueprint.h create mode 100644 LibCarla/source/carla/rpc/ActorDefinition.h create mode 100644 LibCarla/source/carla/rpc/ActorDescription.h create mode 100644 LibCarla/source/carla/rpc/String.h diff --git a/LibCarla/cmake/client/CMakeLists.txt b/LibCarla/cmake/client/CMakeLists.txt index 456788dbe..396fb61ce 100644 --- a/LibCarla/cmake/client/CMakeLists.txt +++ b/LibCarla/cmake/client/CMakeLists.txt @@ -5,13 +5,17 @@ project(libcarla-client) install(DIRECTORY "${RPCLIB_INCLUDE_PATH}/rpc" DESTINATION include) install(FILES "${RPCLIB_LIB_PATH}/librpc.a" DESTINATION lib) +file(GLOB libcarla_sources + "${libcarla_source_path}/carla/*.h" + "${libcarla_source_path}/carla/*.cpp") + file(GLOB_RECURSE libcarla_client_sources "${libcarla_source_path}/carla/client/*.h" "${libcarla_source_path}/carla/client/*.cpp") # Create targets for debug and release in the same build type. foreach(target carla_client_debug carla_client) - add_library(${target} STATIC ${libcarla_client_sources}) + add_library(${target} STATIC ${libcarla_client_sources} ${libcarla_sources}) target_include_directories(${target} PRIVATE "${BOOST_INCLUDE_PATH}" diff --git a/LibCarla/source/carla/Iterator.h b/LibCarla/source/carla/Iterator.h new file mode 100644 index 000000000..12af40458 --- /dev/null +++ b/LibCarla/source/carla/Iterator.h @@ -0,0 +1,27 @@ +// 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 . + +#pragma once + +#include + +namespace carla { +namespace iterator { + + /// Creates an iterator over the keys of a map. + template + static auto make_map_keys_iterator(It it) { + return boost::make_transform_iterator(it, [](auto &pair){ return pair.first; }); + } + + /// Creates an iterator over the values of a map. + template + static auto make_map_values_iterator(It it) { + return boost::make_transform_iterator(it, [](auto &pair){ return pair.second; }); + } + +} // namespace iterator +} // namespace carla diff --git a/LibCarla/source/carla/StringUtil.cpp b/LibCarla/source/carla/StringUtil.cpp new file mode 100644 index 000000000..6e1b56bcc --- /dev/null +++ b/LibCarla/source/carla/StringUtil.cpp @@ -0,0 +1,25 @@ +// 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 . + +#include "carla/StringUtil.h" + +#ifdef _WIN32 +# include +#else +# include +#endif // _WIN32 + +namespace carla { + + bool StringUtil::Match(const std::string &str, const std::string &test) { +#ifdef _WIN32 + return PathMatchSpecA(str.c_str(), test.c_str()); +#else + return 0 == fnmatch(test.c_str(), str.c_str(), 0); +#endif // _WIN32 + } + +} // namespace carla diff --git a/LibCarla/source/carla/StringUtil.h b/LibCarla/source/carla/StringUtil.h new file mode 100644 index 000000000..f8a9cedf4 --- /dev/null +++ b/LibCarla/source/carla/StringUtil.h @@ -0,0 +1,36 @@ +// 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 . + +#pragma once + +#include + +#include +#include + +namespace carla { + + class StringUtil { + public: + + static void ToLower(std::string &str) { + boost::algorithm::to_lower(str); + } + + static std::string ToLowerCopy(const std::string &str) { + return boost::algorithm::to_lower_copy(str); + } + + template + static void Split(Container &destination, const std::string &str, const std::string &separators) { + boost::split(destination, str, boost::is_any_of(separators)); + } + + /// Match @a str with the Unix shell-style @a wildcard_pattern. + static bool Match(const std::string &str, const std::string &wildcard_pattern); + }; + +} // namespace carla diff --git a/LibCarla/source/carla/client/Actor.h b/LibCarla/source/carla/client/Actor.h index 45fbfa590..9ac4b6cd8 100644 --- a/LibCarla/source/carla/client/Actor.h +++ b/LibCarla/source/carla/client/Actor.h @@ -30,13 +30,13 @@ namespace client { return _actor.id; } - const std::string &GetTypeId() const { - return _actor.blueprint.type_id; - } + // const std::string &GetTypeId() const { + // return _actor.blueprint.type_id; + // } - ActorBlueprint GetBlueprint() const { - return _actor.blueprint; - } + // ActorBlueprint GetBlueprint() const { + // return _actor.blueprint; + // } SharedPtr GetWorld() const { return _world; diff --git a/LibCarla/source/carla/client/ActorAttribute.cpp b/LibCarla/source/carla/client/ActorAttribute.cpp new file mode 100644 index 000000000..4b40f9cf7 --- /dev/null +++ b/LibCarla/source/carla/client/ActorAttribute.cpp @@ -0,0 +1,103 @@ +// 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 . + +#include "carla/client/ActorAttribute.h" + +#include "carla/StringUtil.h" + +namespace carla { +namespace client { + +#define LIBCARLA_THROW_INVALID_VALUE(message) throw InvalidAttributeValue(_attribute.id + ": " + message); +#define LIBCARLA_THROW_BAD_VALUE_CAST(type) \ + if (GetType() != rpc::ActorAttributeType:: type) { \ + throw BadAttributeCast(_attribute.id + ": bad attribute cast: cannot convert to " #type); \ + } + + void ActorAttribute::Set(std::string value) { + if (!_attribute.is_modifiable) { + LIBCARLA_THROW_INVALID_VALUE("read-only attribute"); + } + if (GetType() == rpc::ActorAttributeType::Bool) { + StringUtil::ToLower(value); + } + _attribute.value = std::move(value); + Validate(); + } + + template <> + bool ActorAttribute::As() const { + LIBCARLA_THROW_BAD_VALUE_CAST(Bool); + auto value = StringUtil::ToLowerCopy(_attribute.value); + if (value == "true") { + return true; + } else if (value == "false") { + return false; + } + LIBCARLA_THROW_INVALID_VALUE("invalid bool: " + _attribute.value); + } + + template<> + int ActorAttribute::As() const { + LIBCARLA_THROW_BAD_VALUE_CAST(Int); + return std::atoi(_attribute.value.c_str()); + } + + template<> + float ActorAttribute::As() const { + LIBCARLA_THROW_BAD_VALUE_CAST(Float); + double x = std::atof(_attribute.value.c_str()); + if ((x > std::numeric_limits::max()) || + (x < std::numeric_limits::lowest())) { + LIBCARLA_THROW_INVALID_VALUE("float overflow"); + } + return x; + } + + template <> + std::string ActorAttribute::As() const { + LIBCARLA_THROW_BAD_VALUE_CAST(String); + return _attribute.value; + } + + template <> + Color ActorAttribute::As() const { + LIBCARLA_THROW_BAD_VALUE_CAST(RGBColor); + + std::vector channels; + StringUtil::Split(channels, _attribute.value, ","); + if (channels.size() != 3u) { + LIBCARLA_THROW_INVALID_VALUE("colors must have 3 channels (R,G,B)"); + } + + auto to_int = [this](const std::string &str) { + int i = std::atoi(str.c_str()); + if (i > std::numeric_limits::max()) { + LIBCARLA_THROW_INVALID_VALUE("integer overflow in color channel"); + } + return static_cast(i); + }; + + return {to_int(channels[0u]), to_int(channels[1u]), to_int(channels[2u])}; + } + + void ActorAttribute::Validate() const { + switch (_attribute.type) { + case rpc::ActorAttributeType::Bool: As(); + case rpc::ActorAttributeType::Int: As(); + case rpc::ActorAttributeType::Float: As(); + case rpc::ActorAttributeType::String: As(); + case rpc::ActorAttributeType::RGBColor: As(); + default: + LIBCARLA_THROW_INVALID_VALUE("invalid value type"); + } + } + +#undef LIBCARLA_THROW_BAD_VALUE_CAST +#undef LIBCARLA_THROW_INVALID_VALUE + +} // namespace client +} // namespace carla diff --git a/LibCarla/source/carla/client/ActorAttribute.h b/LibCarla/source/carla/client/ActorAttribute.h new file mode 100644 index 000000000..4be38b897 --- /dev/null +++ b/LibCarla/source/carla/client/ActorAttribute.h @@ -0,0 +1,156 @@ +// 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 . + +#pragma once + +#include "carla/client/Color.h" +#include "carla/rpc/ActorAttribute.h" + +#include +#include +#include + +namespace carla { +namespace client { + + // =========================================================================== + // -- InvalidAttributeValue -------------------------------------------------- + // =========================================================================== + + /// Exception thrown when the value given to an ActorAttribute cannot be + /// converted to its type. + class InvalidAttributeValue : public std::invalid_argument { + public: + + InvalidAttributeValue(const std::string &what) : std::invalid_argument(what) {} + }; + + // =========================================================================== + // -- BadAttributeCast ------------------------------------------------------- + // =========================================================================== + + /// Exception thrown when the value of an ActorAttribute cannot be cast to the + /// requested type. + class BadAttributeCast : public std::logic_error { + public: + + BadAttributeCast(const std::string &what) : std::logic_error(what) {} + }; + + // =========================================================================== + // -- ActorAttribute --------------------------------------------------------- + // =========================================================================== + + /// An attribute of an ActorBlueprint. + class ActorAttribute { + public: + + ActorAttribute(rpc::ActorAttribute attribute) + : _attribute(std::move(attribute)) { + Validate(); + } + + /// Set the value of this attribute. + /// + /// @throw InvalidAttributeValue if attribute is not modifiable. + /// @throw InvalidAttributeValue if format does not match this type. + void Set(std::string value); + + bool IsModifiable() const { + return _attribute.is_modifiable; + } + + rpc::ActorAttributeType GetType() const { + return _attribute.type; + } + + /// Cast the value to the given type. + /// + /// @throw BadAttributeCast if the cast fails. + template + T As() const; + + /// Cast the value to the type specified by the enum + /// carla::rpc::ActorAttributeType. + /// + /// @throw BadAttributeCast if the cast fails. + template + auto As() const; + + template + bool operator==(const T &rhs) const; + + template + bool operator!=(const T &rhs) const { + return !(*this == rhs); + } + + /// Serialize this object as a carla::rpc::ActorAttributeValue. + operator rpc::ActorAttributeValue() const { + return _attribute; + } + + private: + + void Validate() const; + + rpc::ActorAttribute _attribute; + }; + + template <> + bool ActorAttribute::As() const; + + template <> + int ActorAttribute::As() const; + + template <> + float ActorAttribute::As() const; + + template <> + std::string ActorAttribute::As() const; + + template <> + Color ActorAttribute::As() const; + + template <> + inline auto ActorAttribute::As() const { + return As(); + } + + template <> + inline auto ActorAttribute::As() const { + return As(); + } + + template <> + inline auto ActorAttribute::As() const { + return As(); + } + + template <> + inline auto ActorAttribute::As() const { + return As(); + } + + template <> + inline auto ActorAttribute::As() const { + return As(); + } + + template + inline bool ActorAttribute::operator==(const T &rhs) const { + return As() == rhs; + } + + template <> + inline bool ActorAttribute::operator==(const ActorAttribute &rhs) const { + return + (_attribute.type == rhs._attribute.type) && + (_attribute.value == rhs._attribute.value); + } + +} // namespace client +} // namespace carla diff --git a/LibCarla/source/carla/client/ActorBlueprint.cpp b/LibCarla/source/carla/client/ActorBlueprint.cpp index b006b0d5b..ece4182df 100644 --- a/LibCarla/source/carla/client/ActorBlueprint.cpp +++ b/LibCarla/source/carla/client/ActorBlueprint.cpp @@ -6,31 +6,46 @@ #include "carla/client/ActorBlueprint.h" -#include +#include "carla/StringUtil.h" -#ifdef _WIN32 -# include -#else -# include -#endif // _WIN32 +#include namespace carla { namespace client { - static bool MatchWildcards(const std::string &str, const std::string &test) { -#ifdef _WIN32 - return PathMatchSpecA(str.c_str(), test.c_str()); -#else - return 0 == fnmatch(test.c_str(), str.c_str(), 0); -#endif // _WIN32 + template + static void FillMap(Map &destination, Container &source) { + destination.reserve(source.size()); + for (auto &item : source) { + auto id = item.id; + destination.emplace(id, std::move(item)); + } } - bool ActorBlueprint::StartsWith(const std::string &test) const { - return boost::starts_with(GetTypeId(), test); + ActorBlueprint::ActorBlueprint(rpc::ActorDefinition definition) + : _uid(definition.uid), + _id(std::move(definition.id)) { + StringUtil::Split(_tags, definition.tags, ","); + FillMap(_attributes, definition.attributes); } - bool ActorBlueprint::MatchWildcards(const std::string &test) const { - return ::carla::client::MatchWildcards(GetTypeId(), test); + bool ActorBlueprint::MatchTags(const std::string &wildcard_pattern) const { + return std::any_of(_tags.begin(), _tags.end(), [&](const auto &tag) { + return StringUtil::Match(tag, wildcard_pattern); + }); + } + + rpc::ActorDescription ActorBlueprint::MakeActorDescription() const { + rpc::ActorDescription description; + description.uid = _uid; + description.id = _id; + description.attributes.reserve(_attributes.size()); + for (const auto &attribute : *this) { + if (attribute.IsModifiable()) { + description.attributes.push_back(attribute); + } + } + return description; } } // namespace client diff --git a/LibCarla/source/carla/client/ActorBlueprint.h b/LibCarla/source/carla/client/ActorBlueprint.h index 7ec49828d..563b0558c 100644 --- a/LibCarla/source/carla/client/ActorBlueprint.h +++ b/LibCarla/source/carla/client/ActorBlueprint.h @@ -7,37 +7,117 @@ #pragma once #include "carla/Debug.h" -#include "carla/rpc/ActorBlueprint.h" +#include "carla/Iterator.h" +#include "carla/client/ActorAttribute.h" +#include "carla/rpc/ActorDefinition.h" +#include "carla/rpc/ActorDescription.h" + +#include +#include +#include namespace carla { namespace client { + /// Contains all the necessary information for spawning an Actor. class ActorBlueprint { public: - ActorBlueprint(carla::rpc::ActorBlueprint blueprint) - : _blueprint(std::move(blueprint)) {} + // ========================================================================= + /// @name Constructor + // ========================================================================= + /// @{ - ActorBlueprint(const ActorBlueprint &) = default; - ActorBlueprint(ActorBlueprint &&) = default; - ActorBlueprint &operator=(const ActorBlueprint &) = default; - ActorBlueprint &operator=(ActorBlueprint &&) = default; + explicit ActorBlueprint(rpc::ActorDefinition actor_definition); - const std::string &GetTypeId() const { - return _blueprint.type_id; + /// @} + // ========================================================================= + /// @name Id + // ========================================================================= + /// @{ + + public: + + const std::string &GetId() const { + return _id; } - bool StartsWith(const std::string &test) const; + /// @} + // ========================================================================= + /// @name Tags + // ========================================================================= + /// @{ - bool MatchWildcards(const std::string &test) const; + public: - const auto &Serialize() const { - return _blueprint; + bool ContainsTag(const std::string &tag) const { + return _tags.find(tag) != _tags.end(); } + /// Test if any of the flags matches @a wildcard_pattern. + /// + /// @a wildcard_pattern follows Unix shell-style wildcards. + bool MatchTags(const std::string &wildcard_pattern) const; + + std::vector GetTags() const { + return {_tags.begin(), _tags.end()}; + } + + /// @} + // ========================================================================= + /// @name Attributes + // ========================================================================= + /// @{ + + public: + + bool ContainsAttribute(const std::string &id) const { + return _attributes.find(id) != _attributes.end(); + } + + /// @throw std::out_of_range if no such element exists. + const ActorAttribute &GetAttribute(const std::string &id) const { + return _attributes.at(id); + } + + /// Set the value of the attribute given by @a id. + /// + /// @throw std::out_of_range if no such element exists. + /// @throw InvalidAttributeValue if attribute is not modifiable. + /// @throw InvalidAttributeValue if format does not match the attribute type. + void SetAttribute(const std::string &id, std::string value) { + _attributes.at(id).Set(std::move(value)); + } + + auto begin() const { + return iterator::make_map_values_iterator(_attributes.begin()); + } + + auto end() const { + return iterator::make_map_values_iterator(_attributes.end()); + } + + /// @} + // ========================================================================= + /// @name ActorDescription + // ========================================================================= + /// @{ + + public: + + rpc::ActorDescription MakeActorDescription() const; + + /// @} + private: - carla::rpc::ActorBlueprint _blueprint; + uint32_t _uid = 0u; + + std::string _id; + + std::unordered_set _tags; + + std::unordered_map _attributes; }; } // namespace client diff --git a/LibCarla/source/carla/client/BlueprintLibrary.h b/LibCarla/source/carla/client/BlueprintLibrary.h index 3b97acf78..11b1abce7 100644 --- a/LibCarla/source/carla/client/BlueprintLibrary.h +++ b/LibCarla/source/carla/client/BlueprintLibrary.h @@ -9,6 +9,7 @@ #include "carla/Debug.h" #include "carla/NonCopyable.h" #include "carla/client/ActorBlueprint.h" +#include "carla/client/Memory.h" #include #include @@ -16,28 +17,30 @@ namespace carla { namespace client { - class Client; - - class BlueprintLibrary /*: private NonCopyable*/ { + class BlueprintLibrary + : public EnableSharedFromThis, + private NonCopyable { using list_type = std::vector; public: - // BlueprintLibrary() = default; - - // BlueprintLibrary(BlueprintLibrary &&) = default; - // BlueprintLibrary &operator=(BlueprintLibrary &&) = default; - using value_type = list_type::value_type; using size_type = list_type::size_type; using const_iterator = list_type::const_iterator; using const_reference = list_type::const_reference; - BlueprintLibrary Filter(const std::string &wildcard_pattern) const { + explicit BlueprintLibrary(const std::vector &blueprints) + : _blueprints(blueprints.begin(), blueprints.end()) {} + + BlueprintLibrary(BlueprintLibrary &&) = default; + BlueprintLibrary &operator=(BlueprintLibrary &&) = default; + + /// Filters a list of ActorBlueprint with tags matching @a wildcard_pattern. + SharedPtr Filter(const std::string &wildcard_pattern) const { list_type result; std::copy_if(begin(), end(), std::back_inserter(result), [&](const auto &x) { - return x.MatchWildcards(wildcard_pattern); + return x.MatchTags(wildcard_pattern); }); - return result; + return SharedPtr{new BlueprintLibrary(result)}; } const_reference operator[](size_type pos) const { @@ -62,14 +65,9 @@ namespace client { private: - friend class Client; - BlueprintLibrary(list_type blueprints) : _blueprints(std::move(blueprints)) {} - BlueprintLibrary(const std::vector &blueprints) - : _blueprints(blueprints.begin(), blueprints.end()) {} - list_type _blueprints; }; diff --git a/LibCarla/source/carla/client/Client.cpp b/LibCarla/source/carla/client/Client.cpp index f8dfb30da..39fd5855e 100644 --- a/LibCarla/source/carla/client/Client.cpp +++ b/LibCarla/source/carla/client/Client.cpp @@ -23,7 +23,7 @@ namespace client { SharedPtr Client::SpawnActor( const ActorBlueprint &blueprint, const Transform &transform) { - auto actor = Call("spawn_actor", blueprint.Serialize(), transform); + auto actor = Call("spawn_actor", blueprint.MakeActorDescription(), transform); return SharedPtr(new Actor{actor, GetWorld()}); } diff --git a/LibCarla/source/carla/client/Client.h b/LibCarla/source/carla/client/Client.h index 12bcae4fd..68604e39b 100644 --- a/LibCarla/source/carla/client/Client.h +++ b/LibCarla/source/carla/client/Client.h @@ -57,8 +57,8 @@ namespace client { SharedPtr GetWorld(); - BlueprintLibrary GetBlueprintLibrary() { - return Call>("get_blueprints"); + SharedPtr GetBlueprintLibrary() { + return MakeShared(Call>("get_blueprints")); } SharedPtr SpawnActor(const ActorBlueprint &blueprint, const Transform &transform); diff --git a/LibCarla/source/carla/client/Color.h b/LibCarla/source/carla/client/Color.h new file mode 100644 index 000000000..a33268763 --- /dev/null +++ b/LibCarla/source/carla/client/Color.h @@ -0,0 +1,32 @@ +// 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 . + +#pragma once + +#include + +namespace carla { +namespace client { + + struct Color { + Color() = default; + Color(uint8_t r, uint8_t g, uint8_t b) : r(r), g(g), b(b) {} + + bool operator==(const Color &rhs) const { + return (r == rhs.r) && (g == rhs.g) && (b == rhs.b); + } + + bool operator!=(const Color &rhs) const { + return !(*this == rhs); + } + + uint8_t r = 0u; + uint8_t g = 0u; + uint8_t b = 0u; + }; + +} // namespace client +} // namespace carla diff --git a/LibCarla/source/carla/client/Memory.h b/LibCarla/source/carla/client/Memory.h index 1546d26bb..1bc0c39e7 100644 --- a/LibCarla/source/carla/client/Memory.h +++ b/LibCarla/source/carla/client/Memory.h @@ -23,7 +23,7 @@ namespace client { using SharedPtr = boost::shared_ptr; template - auto MakeShared(Args && ... args) { + static inline auto MakeShared(Args && ... args) { return boost::make_shared(std::forward(args) ...); } diff --git a/LibCarla/source/carla/client/World.h b/LibCarla/source/carla/client/World.h index 4a1bc75cf..7597dfe97 100644 --- a/LibCarla/source/carla/client/World.h +++ b/LibCarla/source/carla/client/World.h @@ -24,7 +24,7 @@ namespace client { World(World &&) = default; World &operator=(World &&) = default; - BlueprintLibrary GetBlueprintLibrary() const { + SharedPtr GetBlueprintLibrary() const { return _parent->GetBlueprintLibrary(); } diff --git a/LibCarla/source/carla/rpc/Actor.h b/LibCarla/source/carla/rpc/Actor.h index de0366308..79f3dea53 100644 --- a/LibCarla/source/carla/rpc/Actor.h +++ b/LibCarla/source/carla/rpc/Actor.h @@ -6,7 +6,7 @@ #pragma once -#include "carla/rpc/ActorBlueprint.h" +#include "carla/rpc/ActorDefinition.h" namespace carla { namespace rpc { @@ -18,9 +18,9 @@ namespace rpc { id_type id; - ActorBlueprint blueprint; + ActorDefinition definition; - MSGPACK_DEFINE_ARRAY(id, blueprint); + MSGPACK_DEFINE_ARRAY(id, definition); }; } // namespace rpc diff --git a/LibCarla/source/carla/rpc/ActorAttribute.h b/LibCarla/source/carla/rpc/ActorAttribute.h new file mode 100644 index 000000000..5c6f33adb --- /dev/null +++ b/LibCarla/source/carla/rpc/ActorAttribute.h @@ -0,0 +1,96 @@ +// 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 . + +#pragma once + +#include "carla/rpc/ActorAttributeType.h" +#include "carla/rpc/MsgPack.h" +#include "carla/rpc/String.h" + +#include + +MSGPACK_ADD_ENUM(carla::rpc::ActorAttributeType); + +namespace carla { +namespace rpc { + + class ActorAttribute { + public: + + ActorAttribute() = default; + + std::string id; + + ActorAttributeType type = ActorAttributeType::Int; + + std::string value; + + std::vector recommended_values; + + bool is_modifiable = true; + + bool restrict_to_recommended = false; + +#ifdef LIBCARLA_INCLUDED_FROM_UE4 + + ActorAttribute(const FActorAttribute &Attribute) + : id(FromFString(Attribute.Id)), + type(static_cast(Attribute.Type)), + value(FromFString(Attribute.Value)), + is_modifiable(false) {} + + ActorAttribute(const FActorVariation &Variation) + : id(FromFString(Variation.Id)), + type(static_cast(Variation.Type)), + is_modifiable(true), + restrict_to_recommended(Variation.bRestrictToRecommended) { + recommended_values.reserve(Variation.RecommendedValues.Num()); + for (const auto &Item : Variation.RecommendedValues) { + recommended_values.push_back(FromFString(Item)); + } + if (!recommended_values.empty()) { + value = recommended_values[0u]; + } + } + +#endif // LIBCARLA_INCLUDED_FROM_UE4 + + MSGPACK_DEFINE_ARRAY(id, type, value, recommended_values, is_modifiable, restrict_to_recommended); + }; + + class ActorAttributeValue { + public: + + ActorAttributeValue() = default; + + ActorAttributeValue(const ActorAttribute &attribute) + : id(attribute.id), + type(attribute.type), + value(attribute.value) {} + + std::string id; + + ActorAttributeType type = ActorAttributeType::Int; + + std::string value; + +#ifdef LIBCARLA_INCLUDED_FROM_UE4 + + operator FActorAttribute() const { + FActorAttribute Attribute; + Attribute.Id = ToFString(id); + Attribute.Type = static_cast(type); + Attribute.Value = ToFString(value); + return Attribute; + } + +#endif // LIBCARLA_INCLUDED_FROM_UE4 + + MSGPACK_DEFINE_ARRAY(id, type, value); + }; + +} // namespace rpc +} // namespace carla diff --git a/LibCarla/source/carla/rpc/ActorAttributeType.h b/LibCarla/source/carla/rpc/ActorAttributeType.h new file mode 100644 index 000000000..dda52939f --- /dev/null +++ b/LibCarla/source/carla/rpc/ActorAttributeType.h @@ -0,0 +1,29 @@ +// 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 . + +#pragma once + +#include + +namespace carla { +namespace rpc { + + enum class ActorAttributeType : uint8_t { + Bool, + Int, + Float, + String, + RGBColor, + + SIZE, + INVALID + }; + + // Serialization of this class is in ActorAttribute.h, to reduce dependencies + // since this file is directly included in UE4 code. + +} // namespace rpc +} // namespace carla diff --git a/LibCarla/source/carla/rpc/ActorBlueprint.h b/LibCarla/source/carla/rpc/ActorBlueprint.h deleted file mode 100644 index aab429ee7..000000000 --- a/LibCarla/source/carla/rpc/ActorBlueprint.h +++ /dev/null @@ -1,49 +0,0 @@ -// 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 . - -#pragma once - -#include "carla/rpc/MsgPack.h" - -#ifdef LIBCARLA_INCLUDED_FROM_UE4 -# include "UnrealString.h" -#endif // LIBCARLA_INCLUDED_FROM_UE4 - -#include - -namespace carla { -namespace rpc { - - class ActorBlueprint { - public: - - ActorBlueprint(std::string type_id) - : type_id(std::move(type_id)) {} - - ActorBlueprint() = default; - ActorBlueprint(const ActorBlueprint &) = default; - ActorBlueprint(ActorBlueprint &&) = default; - ActorBlueprint &operator=(const ActorBlueprint &) = default; - ActorBlueprint &operator=(ActorBlueprint &&) = default; - -#ifdef LIBCARLA_INCLUDED_FROM_UE4 - - // ActorBlueprint(const FString &Type) - // : type_id(TCHAR_TO_UTF8(*Type)) {} - - FString GetTypeIdAsFString() const { - return FString(type_id.size(), UTF8_TO_TCHAR(type_id.c_str())); - } - -#endif // LIBCARLA_INCLUDED_FROM_UE4 - - std::string type_id; - - MSGPACK_DEFINE_ARRAY(type_id); - }; - -} // namespace rpc -} // namespace carla diff --git a/LibCarla/source/carla/rpc/ActorDefinition.h b/LibCarla/source/carla/rpc/ActorDefinition.h new file mode 100644 index 000000000..9dd86c365 --- /dev/null +++ b/LibCarla/source/carla/rpc/ActorDefinition.h @@ -0,0 +1,52 @@ +// 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 . + +#pragma once + +#include "carla/rpc/ActorAttribute.h" +#include "carla/rpc/MsgPack.h" +#include "carla/rpc/String.h" + +#include + +namespace carla { +namespace rpc { + + class ActorDefinition { + public: + + ActorDefinition() = default; + + uint32_t uid = 0u; + + std::string id; + + std::string tags; + + std::vector attributes; + +#ifdef LIBCARLA_INCLUDED_FROM_UE4 + + ActorDefinition(const FActorDefinition &Definition) + : uid(Definition.UId), + id(FromFString(Definition.Id)), + tags(FromFString(Definition.Tags)) { + attributes.reserve(Definition.Variations.Num() + Definition.Attributes.Num()); + for (const auto &Item : Definition.Variations) { + attributes.push_back(Item); + } + for (const auto &Item : Definition.Attributes) { + attributes.push_back(Item); + } + } + +#endif // LIBCARLA_INCLUDED_FROM_UE4 + + MSGPACK_DEFINE_ARRAY(uid, id, tags, attributes); + }; + +} // namespace rpc +} // namespace carla diff --git a/LibCarla/source/carla/rpc/ActorDescription.h b/LibCarla/source/carla/rpc/ActorDescription.h new file mode 100644 index 000000000..e8a6471ec --- /dev/null +++ b/LibCarla/source/carla/rpc/ActorDescription.h @@ -0,0 +1,48 @@ +// 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 . + +#pragma once + +#include "carla/rpc/ActorAttribute.h" +#include "carla/rpc/MsgPack.h" +#include "carla/rpc/String.h" + +#include + +namespace carla { +namespace rpc { + + class ActorDescription { + public: + + ActorDescription() = default; + + uint32_t uid = 0u; + + std::string id; + + std::vector attributes; + +#ifdef LIBCARLA_INCLUDED_FROM_UE4 + + operator FActorDescription() const { + FActorVariation Description; + Description.UId = uid; + Description.Id = ToFString(id); + Description.Variations.Reserve(attributes.size()); + for (const auto &item : attributes) { + Description.Variations.Add(item); + } + return Description; + } + +#endif // LIBCARLA_INCLUDED_FROM_UE4 + + MSGPACK_DEFINE_ARRAY(uid, id, attributes); + }; + +} // namespace rpc +} // namespace carla diff --git a/LibCarla/source/carla/rpc/String.h b/LibCarla/source/carla/rpc/String.h new file mode 100644 index 000000000..bf2a365f2 --- /dev/null +++ b/LibCarla/source/carla/rpc/String.h @@ -0,0 +1,31 @@ +// 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 . + +#pragma once + +#include + +#ifdef LIBCARLA_INCLUDED_FROM_UE4 +# include "UnrealString.h" +#endif // LIBCARLA_INCLUDED_FROM_UE4 + +namespace carla { +namespace rpc { + +#ifdef LIBCARLA_INCLUDED_FROM_UE4 + + static inline std::string FromFString(const FString &Str) { + return TCHAR_TO_UTF8(*Str); + } + + static inline FString ToFString(const std::string &str) { + return FString(str.size(), UTF8_TO_TCHAR(str.c_str())); + } + +#endif // LIBCARLA_INCLUDED_FROM_UE4 + +} // namespace rpc +} // namespace carla diff --git a/PythonAPI/source/libcarla/Actor.cpp b/PythonAPI/source/libcarla/Actor.cpp index 09e323c8d..29576da89 100644 --- a/PythonAPI/source/libcarla/Actor.cpp +++ b/PythonAPI/source/libcarla/Actor.cpp @@ -14,7 +14,7 @@ namespace carla { namespace client { std::ostream &operator<<(std::ostream &out, const Actor &actor) { - out << "Actor(id=" << actor.GetId() << ", type_id=" << actor.GetTypeId() << ')'; + out << "Actor(id=" << actor.GetId() /*<< ", type_id=" << actor.GetTypeId()*/ << ')'; return out; } @@ -27,11 +27,11 @@ void export_actor() { class_>("Actor", no_init) .add_property("id", &cc::Actor::GetId) - .add_property("type_id", +[](const cc::Actor &self) -> std::string { - // Needs to copy the string by value. - return self.GetTypeId(); - }) - .add_property("blueprint", &cc::Actor::GetBlueprint) + // .add_property("type_id", +[](const cc::Actor &self) -> std::string { + // // Needs to copy the string by value. + // return self.GetTypeId(); + // }) + // .add_property("blueprint", &cc::Actor::GetBlueprint) .def("get_world", &cc::Actor::GetWorld) .def("apply_control", &cc::Actor::ApplyControl) .def(self_ns::str(self_ns::self)) diff --git a/PythonAPI/source/libcarla/Blueprint.cpp b/PythonAPI/source/libcarla/Blueprint.cpp index 1baf51b8d..b33fa8483 100644 --- a/PythonAPI/source/libcarla/Blueprint.cpp +++ b/PythonAPI/source/libcarla/Blueprint.cpp @@ -14,8 +14,15 @@ namespace carla { namespace client { + std::ostream &operator<<(std::ostream &out, const Color &color) { + out << "Color(r=" << color.r + << ", g=" << color.g + << ", b=" << color.b << ')'; + return out; + } + std::ostream &operator<<(std::ostream &out, const ActorBlueprint &bp) { - out << bp.GetTypeId(); + out << "ActorBlueprint(id=" << bp.GetId() << ')'; return out; } @@ -35,17 +42,68 @@ namespace client { void export_blueprint() { using namespace boost::python; namespace cc = carla::client; + namespace crpc = carla::rpc; - class_("ActorBlueprint", no_init) - .add_property("type_id", +[](const cc::ActorBlueprint &self) -> std::string { - return self.GetTypeId(); - }) - .def("startswith", &cc::ActorBlueprint::StartsWith) - .def("match", &cc::ActorBlueprint::MatchWildcards) + enum_("ActorAttributeType") + .value("Bool", crpc::ActorAttributeType::Bool) + .value("Int", crpc::ActorAttributeType::Int) + .value("Float", crpc::ActorAttributeType::Float) + .value("String", crpc::ActorAttributeType::String) + .value("RGBColor", crpc::ActorAttributeType::RGBColor) + ; + + class_("Color") + .def(init((arg("r")=0, arg("g")=0, arg("b")=0))) + .def_readwrite("r", &cc::Color::r) + .def_readwrite("g", &cc::Color::g) + .def_readwrite("b", &cc::Color::b) .def(self_ns::str(self_ns::self)) ; - class_("BlueprintLibrary", no_init) + class_("ActorAttribute", no_init) + .add_property("is_modifiable", &cc::ActorAttribute::IsModifiable) + .add_property("type", &cc::ActorAttribute::GetType) + .def("as_bool", &cc::ActorAttribute::As) + .def("as_int", &cc::ActorAttribute::As) + .def("as_float", &cc::ActorAttribute::As) + .def("as_str", &cc::ActorAttribute::As) + .def("as_color", &cc::ActorAttribute::As) + .def("__eq__", &cc::ActorAttribute::operator==) + .def("__eq__", &cc::ActorAttribute::operator==) + .def("__eq__", &cc::ActorAttribute::operator==) + .def("__eq__", &cc::ActorAttribute::operator==) + .def("__eq__", &cc::ActorAttribute::operator==) + .def("__eq__", &cc::ActorAttribute::operator==) + .def("__ne__", &cc::ActorAttribute::operator!=) + .def("__ne__", &cc::ActorAttribute::operator!=) + .def("__ne__", &cc::ActorAttribute::operator!=) + .def("__ne__", &cc::ActorAttribute::operator!=) + .def("__ne__", &cc::ActorAttribute::operator!=) + .def("__ne__", &cc::ActorAttribute::operator!=) + .def("__nonzero__", &cc::ActorAttribute::As) + .def("__bool__", &cc::ActorAttribute::As) + .def("__int__", &cc::ActorAttribute::As) + .def("__float__", &cc::ActorAttribute::As) + .def("__str__", &cc::ActorAttribute::As) + ; + + class_("ActorBlueprint", no_init) + .add_property("id", +[](const cc::ActorBlueprint &self) -> std::string { + return self.GetId(); + }) + .def("contains_tag", &cc::ActorBlueprint::ContainsTag) + .def("match_tags", &cc::ActorBlueprint::MatchTags) + .def("get_tags", &cc::ActorBlueprint::GetTags) + .def("contains_attribute", &cc::ActorBlueprint::ContainsAttribute) + .def("get_attribute", +[](const cc::ActorBlueprint &self, const std::string &id) -> cc::ActorAttribute { + return self.GetAttribute(id); + }) + .def("set_attribute", &cc::ActorBlueprint::SetAttribute) + .def("match_tags", &cc::ActorBlueprint::MatchTags) + .def(self_ns::str(self_ns::self)) + ; + + class_>("BlueprintLibrary", no_init) .def("filter", &cc::BlueprintLibrary::Filter) .def("__getitem__", +[](const cc::BlueprintLibrary &self, size_t pos) -> cc::ActorBlueprint { return self[pos]; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorAttribute.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorAttribute.h index 29fd477a7..0ee30a383 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorAttribute.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorAttribute.h @@ -6,22 +6,28 @@ #pragma once +#include + #include "ActorAttribute.generated.h" +#define CARLA_ENUM_FROM_RPC(e) static_cast(carla::rpc::ActorAttributeType:: e) + /// List of valid types for actor attributes. UENUM(BlueprintType) enum class EActorAttributeType : uint8 { - Bool UMETA(DisplayName = "Bool"), - Int UMETA(DisplayName = "Integer"), - Float UMETA(DisplayName = "Float"), - String UMETA(DisplayName = "String"), - RGBColor UMETA(DisplayName = "RGB Color (comma separated)"), + Bool = CARLA_ENUM_FROM_RPC(Bool) UMETA(DisplayName = "Bool"), + Int = CARLA_ENUM_FROM_RPC(Int) UMETA(DisplayName = "Integer"), + Float = CARLA_ENUM_FROM_RPC(Float) UMETA(DisplayName = "Float"), + String = CARLA_ENUM_FROM_RPC(String) UMETA(DisplayName = "String"), + RGBColor = CARLA_ENUM_FROM_RPC(RGBColor) UMETA(DisplayName = "RGB Color (comma separated)"), - SIZE UMETA(Hidden), - INVALID UMETA(Hidden) + SIZE UMETA(Hidden), + INVALID UMETA(Hidden) }; +#undef CARLA_ENUM_FROM_RPC + /// Definition of an actor variation. Variations represent attributes of the /// actor that the user can modify in order to generate variations of the same /// actor. diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDefinition.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDefinition.h index e71a65902..a91389808 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDefinition.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDefinition.h @@ -25,10 +25,6 @@ struct FActorDefinition UPROPERTY(EditAnywhere, BlueprintReadWrite) FString Id; - /// AActor class of the actor to be spawned. - UPROPERTY(EditAnywhere, BlueprintReadWrite) - TSubclassOf Class; - /// A list of comma-separated tags. UPROPERTY(EditAnywhere, BlueprintReadWrite) FString Tags; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDescription.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDescription.h index c37af65c7..bf95b040b 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDescription.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDescription.h @@ -16,17 +16,13 @@ struct FActorDescription { GENERATED_BODY() - /// Uniquely identifies the definition. + /// UId of the definition in which this description was based. uint32 UId = 0u; /// Display ID that identifies the actor. UPROPERTY(EditAnywhere, BlueprintReadWrite) FString Id; - /// AActor class of the actor to be spawned. - UPROPERTY(EditAnywhere, BlueprintReadWrite) - TSubclassOf Class; - /// User selected variations of the actor. Note that at this point are /// represented by non-modifiable attributes. UPROPERTY(EditAnywhere, BlueprintReadWrite) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/RPCServer.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/RPCServer.cpp index 5871ec9aa..ee3a52ff2 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/RPCServer.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/RPCServer.cpp @@ -10,7 +10,6 @@ #include #include #include -#include #include #include #include @@ -52,20 +51,20 @@ void FRPCServer::Initialize(AServer &Server, uint16_t Port) srv.BindAsync("version", []() { return std::string(carla::version()); }); - srv.BindAsync("get_blueprints", []() { - return std::vector{ - cr::ActorBlueprint{"vehicle.mustang.red"}, - cr::ActorBlueprint{"vehicle.mustang.also_red"}, - cr::ActorBlueprint{"vehicle.mustang.still_red"} - }; - }); + // srv.BindAsync("get_blueprints", []() { + // return std::vector{ + // cr::ActorBlueprint{"vehicle.mustang.red"}, + // cr::ActorBlueprint{"vehicle.mustang.also_red"}, + // cr::ActorBlueprint{"vehicle.mustang.still_red"} + // }; + // }); - srv.BindSync("spawn_actor", [&]( - const cr::ActorBlueprint &blueprint, - const cr::Transform &transform) { - auto id = Server.SpawnAgent(transform); - return cr::Actor{static_cast(id), blueprint}; - }); + // srv.BindSync("spawn_actor", [&]( + // const cr::ActorBlueprint &blueprint, + // const cr::Transform &transform) { + // auto id = Server.SpawnAgent(transform); + // return cr::Actor{static_cast(id), blueprint}; + // }); srv.BindSync("apply_control_to_actor", [&]( const cr::Actor &actor, From a905170a9840455d14ef93529d9074ace938bd5f Mon Sep 17 00:00:00 2001 From: nsubiron Date: Thu, 19 Jul 2018 12:42:18 +0200 Subject: [PATCH 18/71] Unity build PythonAPI to increase compilation time --- PythonAPI/setup.py | 3 ++- PythonAPI/source/libcarla/libcarla.cpp | 12 ++++++------ 2 files changed, 8 insertions(+), 7 deletions(-) diff --git a/PythonAPI/setup.py b/PythonAPI/setup.py index 5251b6bb2..f80ec5d8d 100644 --- a/PythonAPI/setup.py +++ b/PythonAPI/setup.py @@ -31,6 +31,7 @@ def get_libcarla_extensions(): yield os.path.join(root, filename) depends = [x for x in walk('dependencies')] + depends += [x for x in walk('source/libcarla')] def make_extension(name, sources): return Extension( @@ -48,7 +49,7 @@ def get_libcarla_extensions(): language='c++14', depends=depends) - return [make_extension('carla.libcarla', glob.glob('source/libcarla/*.cpp'))] + return [make_extension('carla.libcarla', ['source/libcarla/libcarla.cpp'])] setup( diff --git a/PythonAPI/source/libcarla/libcarla.cpp b/PythonAPI/source/libcarla/libcarla.cpp index fbb85e189..3eb158f07 100644 --- a/PythonAPI/source/libcarla/libcarla.cpp +++ b/PythonAPI/source/libcarla/libcarla.cpp @@ -6,12 +6,12 @@ #include -void export_actor(); -void export_blueprint(); -void export_client(); -void export_control(); -void export_transform(); -void export_world(); +#include "Actor.cpp" +#include "Blueprint.cpp" +#include "Client.cpp" +#include "Control.cpp" +#include "Transform.cpp" +#include "World.cpp" BOOST_PYTHON_MODULE(libcarla) { using namespace boost::python; From 5a8bb66c5d114a101754d187c94c3ad2b70fc0bd Mon Sep 17 00:00:00 2001 From: nsubiron Date: Thu, 19 Jul 2018 12:43:21 +0200 Subject: [PATCH 19/71] CMake generate compile commands for compatibility with external tools --- Util/BuildTools/BuildLibCarla.sh | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Util/BuildTools/BuildLibCarla.sh b/Util/BuildTools/BuildLibCarla.sh index 49b73fcb3..b29d8ecc5 100755 --- a/Util/BuildTools/BuildLibCarla.sh +++ b/Util/BuildTools/BuildLibCarla.sh @@ -82,6 +82,7 @@ if ${BUILD_SERVER} ; then -DCMAKE_BUILD_TYPE=Server \ -DCMAKE_TOOLCHAIN_FILE=${LIBCPP_TOOLCHAIN_FILE} \ -DCMAKE_INSTALL_PREFIX=${LIBCARLA_INSTALL_SERVER_FOLDER} \ + -DCMAKE_EXPORT_COMPILE_COMMANDS=1 \ ${CARLA_ROOT_FOLDER} fi @@ -112,6 +113,7 @@ if ${BUILD_CLIENT} ; then -DCMAKE_BUILD_TYPE=Client \ -DCMAKE_TOOLCHAIN_FILE=${LIBSTDCPP_TOOLCHAIN_FILE} \ -DCMAKE_INSTALL_PREFIX=${LIBCARLA_INSTALL_CLIENT_FOLDER} \ + -DCMAKE_EXPORT_COMPILE_COMMANDS=1 \ ${CARLA_ROOT_FOLDER} fi From 03c5ccc9d2b4d2e8b706fd9c6fd467f8e9e9a39d Mon Sep 17 00:00:00 2001 From: nsubiron Date: Mon, 23 Jul 2018 16:42:26 +0200 Subject: [PATCH 20/71] Add game mode for new RPC server --- LibCarla/source/carla/rpc/Server.h | 9 +- Unreal/CarlaUE4/Config/DefaultEngine.ini | 2 +- .../Source/Carla/Actor/ActorDispatcher.cpp | 8 +- .../Source/Carla/Actor/ActorDispatcher.h | 11 +-- .../Source/Carla/Agent/AgentComponent.cpp | 28 ++++-- .../Carla/Source/Carla/Game/CarlaEpisode.h | 77 ++++++++++++++++ .../Source/Carla/Game/CarlaGameInstance.cpp | 23 +++++ .../Source/Carla/Game/CarlaGameInstance.h | 21 ++++- .../Carla/Game/TheNewCarlaGameModeBase.cpp | 81 +++++++++++++++++ .../Carla/Game/TheNewCarlaGameModeBase.h | 52 +++++++++++ .../Carla/Source/Carla/Server/RPCServer.cpp | 90 ------------------- .../Carla/Source/Carla/Server/RPCServer.h | 35 -------- .../Carla/Source/Carla/Server/Server.cpp | 72 --------------- .../Carla/Source/Carla/Server/Server.h | 52 ----------- .../Source/Carla/Server/TheNewCarlaServer.cpp | 69 ++++++++++++++ .../Source/Carla/Server/TheNewCarlaServer.h | 37 ++++++++ 16 files changed, 388 insertions(+), 279 deletions(-) create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.h create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/TheNewCarlaGameModeBase.cpp create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/TheNewCarlaGameModeBase.h delete mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/RPCServer.cpp delete mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/RPCServer.h delete mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/Server.cpp delete mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/Server.h create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.h diff --git a/LibCarla/source/carla/rpc/Server.h b/LibCarla/source/carla/rpc/Server.h index 2a84ed2e4..9beeb5d26 100644 --- a/LibCarla/source/carla/rpc/Server.h +++ b/LibCarla/source/carla/rpc/Server.h @@ -6,10 +6,14 @@ #pragma once +#include "carla/Time.h" + #include #include +#include + namespace carla { namespace rpc { @@ -94,10 +98,9 @@ namespace detail { _server.async_run(worker_threads); } - template - void SyncRunFor(Duration duration) { + void SyncRunFor(time_duration duration) { _sync_io_service.reset(); - _sync_io_service.run_for(duration); + _sync_io_service.run_for(duration.to_chrono()); } /// @warning does not stop the game thread. diff --git a/Unreal/CarlaUE4/Config/DefaultEngine.ini b/Unreal/CarlaUE4/Config/DefaultEngine.ini index 923d374ca..91014e4a8 100644 --- a/Unreal/CarlaUE4/Config/DefaultEngine.ini +++ b/Unreal/CarlaUE4/Config/DefaultEngine.ini @@ -13,7 +13,7 @@ AppliedDefaultGraphicsPerformance=Maximum EditorStartupMap=/Game/Maps/Town01.Town01 GameDefaultMap=/Game/Maps/Town01.Town01 ServerDefaultMap=/Game/Maps/Town01.Town01 -GlobalDefaultGameMode=/Game/Blueprints/Game/CarlaGameMode.CarlaGameMode_C +GlobalDefaultGameMode=/Script/Carla.TheNewCarlaGameModeBase GameInstanceClass=/Script/Carla.CarlaGameInstance TransitionMap=/Game/Maps/Town01.Town01 diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp index f237ddc7a..c5b760f54 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp @@ -10,7 +10,7 @@ #include "Carla/Actor/ActorBlueprintFunctionLibrary.h" #include "Carla/Actor/ActorSpawner.h" -void AActorDispatcher::Bind(FActorDefinition Definition, SpawnFunctionType Functor) +void FActorDispatcher::Bind(FActorDefinition Definition, SpawnFunctionType Functor) { if (UActorBlueprintFunctionLibrary::CheckActorDefinition(Definition)) { @@ -24,7 +24,7 @@ void AActorDispatcher::Bind(FActorDefinition Definition, SpawnFunctionType Funct } } -void AActorDispatcher::Bind(IActorSpawner &ActorSpawner) +void FActorDispatcher::Bind(IActorSpawner &ActorSpawner) { for (const auto &Definition : ActorSpawner.MakeDefinitions()) { @@ -34,7 +34,7 @@ void AActorDispatcher::Bind(IActorSpawner &ActorSpawner) } } -AActor *AActorDispatcher::SpawnActor( +AActor *FActorDispatcher::SpawnActor( const FTransform &Transform, const FActorDescription &Description) { @@ -51,7 +51,7 @@ AActor *AActorDispatcher::SpawnActor( return Actor; } -void AActorDispatcher::DestroyActor(AActor *Actor) +void FActorDispatcher::DestroyActor(AActor *Actor) { if (Actor != nullptr) { diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.h index a45926113..26ece1022 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.h @@ -11,20 +11,14 @@ #include "Carla/Actor/ActorRegistry.h" #include "Containers/Array.h" -#include "GameFramework/Actor.h" #include "Templates/Function.h" -#include "ActorDispatcher.generated.h" - class IActorSpawner; /// Actor in charge of binding ActorDefinitions to spawn functions, as well as /// keeping the registry of all the actors spawned. -UCLASS() -class CARLA_API AActorDispatcher : public AActor +class FActorDispatcher { - GENERATED_BODY() - public: using SpawnFunctionType = TFunction; @@ -44,16 +38,13 @@ public: /// despawn an actor created with this function call DestroyActor. /// /// Return nullptr on failure. - UFUNCTION(BlueprintCallable) AActor *SpawnActor( const FTransform &Transform, const FActorDescription &ActorDescription); /// Destroys an actor, properly removing it from the registry. - UFUNCTION(BlueprintCallable) void DestroyActor(AActor *Actor); - UFUNCTION(BlueprintCallable) const TArray &GetActorDefinitions() const { return Definitions; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Agent/AgentComponent.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Agent/AgentComponent.cpp index de9bdcff5..9c29dffb8 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Agent/AgentComponent.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Agent/AgentComponent.cpp @@ -14,12 +14,11 @@ #include "Engine/Engine.h" #include "Kismet/GameplayStatics.h" -static FDataRouter &GetDataRouter(UWorld *World) +static FDataRouter *GetDataRouter(UWorld *World) { check(World != nullptr); ACarlaGameModeBase *GameMode = Cast(World->GetAuthGameMode()); - check(GameMode != nullptr); - return GameMode->GetDataRouter(); + return GameMode != nullptr ? &GameMode->GetDataRouter() : nullptr; } UAgentComponent::UAgentComponent(const FObjectInitializer& ObjectInitializer) @@ -43,14 +42,18 @@ void UAgentComponent::BeginPlay() if (bRegisterAgentComponent) { /** - * This only returns true if the current game mode is not null + * This only returns true if the current game mode is not null * because you can only access a game mode if you are the host * @param oftheworld UWorld is needed to access the game mode * @return true if there is a game mode and it is not null */ if(UGameplayStatics::GetGameMode(GetWorld())!=nullptr) { - GetDataRouter(GetWorld()).RegisterAgent(this); + auto *DataRouter = GetDataRouter(GetWorld()); + if (DataRouter != nullptr) + { + DataRouter->RegisterAgent(this); + } } else { UCarlaGameInstance* GameInstance = Cast(UGameplayStatics::GetGameInstance(GetWorld())); @@ -64,15 +67,22 @@ void UAgentComponent::EndPlay(const EEndPlayReason::Type EndPlayReason) { if (bAgentComponentIsRegistered) { + FDataRouter *DataRouter = nullptr; if(UGameplayStatics::GetGameMode(GetWorld())!=nullptr) { - GetDataRouter(GetWorld()).DeregisterAgent(this); + DataRouter = GetDataRouter(GetWorld()); } else { - UCarlaGameInstance* GameInstance = Cast(UGameplayStatics::GetGameInstance(GetWorld())); - if(GameInstance) - GameInstance->GetDataRouter().DeregisterAgent(this); + UCarlaGameInstance *GameInstance = Cast(UGameplayStatics::GetGameInstance(GetWorld())); + if(GameInstance) + { + DataRouter = &GameInstance->GetDataRouter(); + } + } + if (DataRouter != nullptr) + { + DataRouter->DeregisterAgent(this); } bAgentComponentIsRegistered = false; } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.h new file mode 100644 index 000000000..9815db121 --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.h @@ -0,0 +1,77 @@ +// 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 . + +#pragma once + +#include "Carla/Actor/ActorDispatcher.h" + +#include "CarlaEpisode.generated.h" + +/// A simulation episode. +/// +/// Each time the level is restarted a new episode is created. +UCLASS(BlueprintType, Blueprintable) +class CARLA_API UCarlaEpisode : public UObject +{ + GENERATED_BODY() + +public: + + void Initialize(const FString &InMapName) + { + MapName = InMapName; + } + + UFUNCTION(BlueprintCallable) + const FString &GetMapName() const + { + return MapName; + } + + void RegisterActorSpawner(IActorSpawner &ActorSpawner) + { + ActorDispatcher.Bind(ActorSpawner); + } + + /// Return the list of actor definitions that are available to be spawned this + /// episode. + UFUNCTION(BlueprintCallable) + const TArray &GetActorDefinitions() const + { + return ActorDispatcher.GetActorDefinitions(); + } + + /// Spawns an actor based on @a ActorDescription at @a Transform. To properly + /// despawn an actor created with this function call DestroyActor. + /// + /// Return nullptr on failure. + UFUNCTION(BlueprintCallable) + AActor *SpawnActor( + const FTransform &Transform, + const FActorDescription &ActorDescription) + { + return ActorDispatcher.SpawnActor(Transform, ActorDescription); + } + + /// Destroys an actor, properly removing it from the registry. + UFUNCTION(BlueprintCallable) + void DestroyActor(AActor *Actor) + { + ActorDispatcher.DestroyActor(Actor); + } + + const FActorRegistry &GetActorRegistry() const + { + return ActorDispatcher.GetActorRegistry(); + } + +private: + + UPROPERTY(VisibleAnywhere) + FString MapName; + + FActorDispatcher ActorDispatcher; +}; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaGameInstance.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaGameInstance.cpp index 467c11e84..6f4e801b8 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaGameInstance.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaGameInstance.cpp @@ -11,6 +11,13 @@ #include "Server/ServerGameController.h" #include "Settings/CarlaSettings.h" +#include + +static uint32 GetNumberOfThreadsForRPCServer() +{ + return std::max(std::thread::hardware_concurrency(), 4u) - 2u; +} + UCarlaGameInstance::UCarlaGameInstance() { CarlaSettings = CreateDefaultSubobject(TEXT("CarlaSettings")); check(CarlaSettings != nullptr); @@ -32,3 +39,19 @@ void UCarlaGameInstance::InitializeGameControllerIfNotPresent( } } } + +void UCarlaGameInstance::NotifyBeginEpisode(UCarlaEpisode &Episode) +{ + if (!bServerIsRunning) + { + Server.Start(CarlaSettings->WorldPort); + Server.AsyncRun(GetNumberOfThreadsForRPCServer()); + bServerIsRunning = true; + } + Server.NotifyBeginEpisode(Episode); +} + +void UCarlaGameInstance::NotifyEndEpisode() +{ + Server.NotifyEndEpisode(); +} diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaGameInstance.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaGameInstance.h index e138c395d..671b01ba8 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaGameInstance.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaGameInstance.h @@ -8,8 +8,9 @@ #include "Engine/GameInstance.h" -#include "Game/CarlaGameControllerBase.h" -#include "Game/DataRouter.h" +#include "Carla/Game/CarlaGameControllerBase.h" +#include "Carla/Game/DataRouter.h" +#include "Carla/Server/TheNewCarlaServer.h" #include "CarlaGameInstance.generated.h" @@ -62,12 +63,26 @@ public: return DataRouter; } + void NotifyBeginEpisode(UCarlaEpisode &Episode); + + void Tick(float /*DeltaSeconds*/) + { + Server.RunSome(10u); /// @todo + } + + void NotifyEndEpisode(); + private: + UPROPERTY(VisibleAnywhere) + bool bServerIsRunning = false; + UPROPERTY(Category = "CARLA Settings", EditAnywhere) - UCarlaSettings *CarlaSettings; + UCarlaSettings *CarlaSettings = nullptr; FDataRouter DataRouter; TUniquePtr GameController; + + FTheNewCarlaServer Server; }; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/TheNewCarlaGameModeBase.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/TheNewCarlaGameModeBase.cpp new file mode 100644 index 000000000..cdbf2d8ac --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/TheNewCarlaGameModeBase.cpp @@ -0,0 +1,81 @@ +// 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 . + +#include "Carla.h" +#include "Carla/Game/TheNewCarlaGameModeBase.h" + +ATheNewCarlaGameModeBase::ATheNewCarlaGameModeBase(const FObjectInitializer& ObjectInitializer) + : Super(ObjectInitializer) +{ + PrimaryActorTick.bCanEverTick = true; + PrimaryActorTick.TickGroup = TG_PrePhysics; + bAllowTickBeforeBeginPlay = false; + + Episode = CreateDefaultSubobject(TEXT("Episode")); +} + +void ATheNewCarlaGameModeBase::InitGame( + const FString &MapName, + const FString &Options, + FString &ErrorMessage) +{ + Super::InitGame(MapName, Options, ErrorMessage); + + check(Episode != nullptr); + Episode->Initialize(MapName); + + GameInstance = Cast(GetGameInstance()); + checkf( + GameInstance != nullptr, + TEXT("GameInstance is not a UCarlaGameInstance, did you forget to set it in the project settings?")); + + SpawnActorSpawners(); +} + +void ATheNewCarlaGameModeBase::BeginPlay() +{ + Super::BeginPlay(); + + GameInstance->NotifyBeginEpisode(*Episode); +} + +void ATheNewCarlaGameModeBase::Tick(float DeltaSeconds) +{ + Super::Tick(DeltaSeconds); + + GameInstance->Tick(DeltaSeconds); +} + +void ATheNewCarlaGameModeBase::EndPlay(const EEndPlayReason::Type EndPlayReason) +{ + GameInstance->NotifyEndEpisode(); + + Super::EndPlay(EndPlayReason); +} + +void ATheNewCarlaGameModeBase::SpawnActorSpawners() +{ + auto *World = GetWorld(); + check(World != nullptr); + + for (auto &SpawnerClass : BlueprintSpawners) + { + if (SpawnerClass != nullptr) + { + auto *Spawner = World->SpawnActor(SpawnerClass); + if (Spawner != nullptr) + { + Episode->RegisterActorSpawner(*Spawner); + BlueprintSpawnerInstances.Add(Spawner); + } + else + { + UE_LOG(LogCarla, Error, TEXT("Failed to spawn actor spawner")); + } + } + } + +} diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/TheNewCarlaGameModeBase.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/TheNewCarlaGameModeBase.h new file mode 100644 index 000000000..23a5931d2 --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/TheNewCarlaGameModeBase.h @@ -0,0 +1,52 @@ +// 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 . + +#pragma once + +#include "Carla/Actor/ActorSpawnerBlueprintBase.h" +#include "Carla/Game/CarlaEpisode.h" + +#include "CoreMinimal.h" +#include "GameFramework/GameModeBase.h" + +#include "TheNewCarlaGameModeBase.generated.h" + +/// Base class for the CARLA Game Mode. +UCLASS(HideCategories=(ActorTick)) +class CARLA_API ATheNewCarlaGameModeBase : public AGameModeBase +{ + GENERATED_BODY() + +public: + + ATheNewCarlaGameModeBase(const FObjectInitializer& ObjectInitializer); + +protected: + + void InitGame(const FString &MapName, const FString &Options, FString &ErrorMessage) override; + + void BeginPlay() override; + + void EndPlay(const EEndPlayReason::Type EndPlayReason) override; + + void Tick(float DeltaSeconds) override; + +private: + + void SpawnActorSpawners(); + + UPROPERTY() + UCarlaGameInstance *GameInstance = nullptr; + + UPROPERTY() + UCarlaEpisode *Episode = nullptr; + + UPROPERTY(EditAnywhere) + TArray> BlueprintSpawners; + + UPROPERTY() + TArray BlueprintSpawnerInstances; +}; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/RPCServer.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/RPCServer.cpp deleted file mode 100644 index ee3a52ff2..000000000 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/RPCServer.cpp +++ /dev/null @@ -1,90 +0,0 @@ -// 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 . - -#include "Carla.h" -#include "Server.h" - -#include -#include -#include -#include -#include -#include -#include - -static FVehicleControl MakeControl(const carla::rpc::VehicleControl &cControl) -{ - FVehicleControl Control; - Control.Throttle = cControl.throttle; - Control.Steer = cControl.steer; - Control.Brake = cControl.brake; - Control.bHandBrake = cControl.hand_brake; - Control.bReverse = cControl.reverse; - return Control; -} - -class FRPCServer::Pimpl -{ -public: - Pimpl(uint16_t port) : Server(port) {} - carla::rpc::Server Server; -}; - -FRPCServer::FRPCServer() : _Pimpl(nullptr) {} - -FRPCServer::~FRPCServer() {} - -void FRPCServer::Initialize(AServer &Server, uint16_t Port) -{ - UE_LOG(LogTemp, Error, TEXT("Initializing rpc-server at port %d"), Port); - - _Pimpl = std::make_unique(Port); - - namespace cr = carla::rpc; - - auto &srv = _Pimpl->Server; - - srv.BindAsync("ping", []() { return true; }); - - srv.BindAsync("version", []() { return std::string(carla::version()); }); - - // srv.BindAsync("get_blueprints", []() { - // return std::vector{ - // cr::ActorBlueprint{"vehicle.mustang.red"}, - // cr::ActorBlueprint{"vehicle.mustang.also_red"}, - // cr::ActorBlueprint{"vehicle.mustang.still_red"} - // }; - // }); - - // srv.BindSync("spawn_actor", [&]( - // const cr::ActorBlueprint &blueprint, - // const cr::Transform &transform) { - // auto id = Server.SpawnAgent(transform); - // return cr::Actor{static_cast(id), blueprint}; - // }); - - srv.BindSync("apply_control_to_actor", [&]( - const cr::Actor &actor, - const cr::VehicleControl &control) { - Server.ApplyControl(actor.id, MakeControl(control)); - }); -} - -void FRPCServer::Run() -{ - _Pimpl->Server.AsyncRun(4); -} - -void FRPCServer::RunSome() -{ - using namespace std::chrono_literals; - _Pimpl->Server.SyncRunFor(20ms); -} - -void FRPCServer::Stop() -{ - _Pimpl->Server.Stop(); -} diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/RPCServer.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/RPCServer.h deleted file mode 100644 index 2ec8c71b6..000000000 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/RPCServer.h +++ /dev/null @@ -1,35 +0,0 @@ -// 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 . - -#pragma once - -#include "CoreMinimal.h" - -#include - -class AServer; - -class FRPCServer -{ -public: - - FRPCServer(); - - ~FRPCServer(); - - void Initialize(AServer &Server, uint16_t Port = 8080u); - - void Run(); - - void RunSome(); - - void Stop(); - -private: - - class Pimpl; - std::unique_ptr _Pimpl; -}; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/Server.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/Server.cpp deleted file mode 100644 index 2a1ab6d95..000000000 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/Server.cpp +++ /dev/null @@ -1,72 +0,0 @@ -// 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 . - -#include "Carla.h" -#include "Server.h" - - -// Sets default values -AServer::AServer() -{ - // Set this actor to call Tick() every frame. You can turn this off to improve performance if you don't need it. - PrimaryActorTick.bCanEverTick = true; - -} - -// Called when the game starts or when spawned -void AServer::BeginPlay() -{ - Super::BeginPlay(); - - _Server.Initialize(*this); - _Server.Run(); -} - -void AServer::EndPlay(EEndPlayReason::Type EndPlayReason) -{ - _Server.Stop(); -} - -// Called every frame -void AServer::Tick(float DeltaTime) -{ - Super::Tick(DeltaTime); - - _Server.RunSome(); -} - -int32 AServer::SpawnAgent(const FTransform &Transform) -{ - check(IsInGameThread()); - UE_LOG(LogTemp, Warning, TEXT("Spawning vehicle at %s"), *Transform.ToString()); - - static int32 COUNT = 0u; - ++COUNT; - - ACarlaWheeledVehicle *Vehicle; - SpawnVehicle(Transform, Vehicle); - if ((Vehicle != nullptr) && !Vehicle->IsPendingKill()) - { - // Vehicle->AIControllerClass = AWheeledVehicleAIController::StaticClass(); - Vehicle->SpawnDefaultController(); - _Agents.Add(COUNT, Vehicle); - return COUNT; - } - return -1; -} - -bool AServer::ApplyControl(int32 AgentId, const FVehicleControl &Control) -{ - UE_LOG(LogTemp, Log, TEXT("Applying control to vehicle %d: throttle = %f, steer = %f"), AgentId, Control.Throttle, Control.Steer); - if (!_Agents.Contains(AgentId)) - { - UE_LOG(LogTemp, Error, TEXT("Vehicle %d does not exist!"), AgentId); - return false; - } - auto *Vehicle = _Agents[AgentId]; - Vehicle->ApplyVehicleControl(Control); - return true; -} diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/Server.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/Server.h deleted file mode 100644 index e8cd23755..000000000 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/Server.h +++ /dev/null @@ -1,52 +0,0 @@ -// 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 . - -#pragma once - -#include "Vehicle/CarlaWheeledVehicle.h" -#include "CoreMinimal.h" -#include "GameFramework/Actor.h" -#include "RPCServer.h" -#include "Vehicle/VehicleControl.h" -#include -#include -#include -#include "Server.generated.h" - -UCLASS() -class CARLA_API AServer : public AActor -{ - GENERATED_BODY() - -public: - // Sets default values for this actor's properties - AServer(); - -protected: - // Called when the game starts or when spawned - virtual void BeginPlay() override; - virtual void EndPlay(EEndPlayReason::Type EndPlayReason) override; - -public: - // Called every frame - virtual void Tick(float DeltaTime) override; - - UFUNCTION(BlueprintCallable) - int32 SpawnAgent(const FTransform &Transform); - - UFUNCTION(BlueprintCallable) - bool ApplyControl(int32 AgentId, const FVehicleControl &Control); - - UFUNCTION(BlueprintImplementableEvent) - void SpawnVehicle(const FTransform &SpawnTransform, ACarlaWheeledVehicle *&SpawnedCharacter); - -private: - - FRPCServer _Server; - - UPROPERTY(VisibleAnywhere) - TMap _Agents; -}; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp new file mode 100644 index 000000000..c41998c2b --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp @@ -0,0 +1,69 @@ +// 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 . + +#include "Carla.h" +#include "TheNewCarlaServer.h" + +#include +#include +#include +#include + +class FTheNewCarlaServer::FPimpl +{ +public: + + FPimpl(uint16_t port) : Server(port) {} + + carla::rpc::Server Server; + + UCarlaEpisode *CurrentEpisode = nullptr; +}; + +FTheNewCarlaServer::FTheNewCarlaServer() : Pimpl(nullptr) {} + +FTheNewCarlaServer::~FTheNewCarlaServer() {} + +void FTheNewCarlaServer::Start(uint16_t Port) +{ + UE_LOG(LogCarlaServer, Log, TEXT("Initializing rpc-server at port %d"), Port); + + Pimpl = MakeUnique(Port); + + namespace cr = carla::rpc; + + auto &srv = Pimpl->Server; + + srv.BindAsync("ping", []() { return true; }); + + srv.BindAsync("version", []() { return std::string(carla::version()); }); +} + +void FTheNewCarlaServer::NotifyBeginEpisode(UCarlaEpisode &Episode) +{ + UE_LOG(LogCarlaServer, Log, TEXT("New episode '%s' started"), *Episode.GetMapName()); + Pimpl->CurrentEpisode = &Episode; +} + +void FTheNewCarlaServer::NotifyEndEpisode() +{ + Pimpl->CurrentEpisode = nullptr; +} + +void FTheNewCarlaServer::AsyncRun(uint32 NumberOfWorkerThreads) +{ + Pimpl->Server.AsyncRun(NumberOfWorkerThreads); +} + +void FTheNewCarlaServer::RunSome(uint32 Milliseconds) +{ + Pimpl->Server.SyncRunFor(carla::time_duration::milliseconds(Milliseconds)); +} + +void FTheNewCarlaServer::Stop() +{ + Pimpl->Server.Stop(); +} diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.h new file mode 100644 index 000000000..cb61ad1c4 --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.h @@ -0,0 +1,37 @@ +// 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 . + +#pragma once + +#include "CoreMinimal.h" + +class UCarlaEpisode; + +class FTheNewCarlaServer +{ +public: + + FTheNewCarlaServer(); + + ~FTheNewCarlaServer(); + + void Start(uint16_t Port); + + void NotifyBeginEpisode(UCarlaEpisode &Episode); + + void NotifyEndEpisode(); + + void AsyncRun(uint32 NumberOfWorkerThreads); + + void RunSome(uint32 Milliseconds); + + void Stop(); + +private: + + class FPimpl; + TUniquePtr Pimpl; +}; From 0f636e84fd51437165a21c91d6016f2777650e55 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Mon, 23 Jul 2018 20:40:59 +0200 Subject: [PATCH 21/71] Full pipeline for spawning actors from Python --- .../source/carla/client/ActorAttribute.cpp | 10 +- LibCarla/source/carla/client/Client.h | 7 +- LibCarla/source/carla/rpc/ActorDescription.h | 2 +- LibCarla/source/carla/rpc/Server.h | 6 ++ PythonAPI/source/libcarla/Exception.cpp | 26 +++++ PythonAPI/source/libcarla/libcarla.cpp | 2 + .../Source/Carla/Actor/ActorDispatcher.cpp | 13 +-- .../Source/Carla/Actor/ActorDispatcher.h | 9 +- .../Source/Carla/Actor/ActorSpawnResult.cpp | 30 ++++++ .../Source/Carla/Actor/ActorSpawnResult.h | 41 ++++++++ .../Carla/Source/Carla/Actor/ActorSpawner.h | 3 +- .../Carla/Actor/ActorSpawnerBlueprintBase.h | 11 ++- .../Carla/Source/Carla/Actor/ActorView.h | 2 +- .../Carla/Source/Carla/Game/CarlaEpisode.h | 19 +++- .../Source/Carla/Server/TheNewCarlaServer.cpp | 96 ++++++++++++++++--- 15 files changed, 236 insertions(+), 41 deletions(-) create mode 100644 PythonAPI/source/libcarla/Exception.cpp create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnResult.cpp create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnResult.h diff --git a/LibCarla/source/carla/client/ActorAttribute.cpp b/LibCarla/source/carla/client/ActorAttribute.cpp index 4b40f9cf7..7db6fb2db 100644 --- a/LibCarla/source/carla/client/ActorAttribute.cpp +++ b/LibCarla/source/carla/client/ActorAttribute.cpp @@ -86,11 +86,11 @@ namespace client { void ActorAttribute::Validate() const { switch (_attribute.type) { - case rpc::ActorAttributeType::Bool: As(); - case rpc::ActorAttributeType::Int: As(); - case rpc::ActorAttributeType::Float: As(); - case rpc::ActorAttributeType::String: As(); - case rpc::ActorAttributeType::RGBColor: As(); + case rpc::ActorAttributeType::Bool: As(); break; + case rpc::ActorAttributeType::Int: As(); break; + case rpc::ActorAttributeType::Float: As(); break; + case rpc::ActorAttributeType::String: As(); break; + case rpc::ActorAttributeType::RGBColor: As(); break; default: LIBCARLA_THROW_INVALID_VALUE("invalid value type"); } diff --git a/LibCarla/source/carla/client/Client.h b/LibCarla/source/carla/client/Client.h index 68604e39b..34d992650 100644 --- a/LibCarla/source/carla/client/Client.h +++ b/LibCarla/source/carla/client/Client.h @@ -58,10 +58,13 @@ namespace client { SharedPtr GetWorld(); SharedPtr GetBlueprintLibrary() { - return MakeShared(Call>("get_blueprints")); + return MakeShared( + Call>("get_actor_definitions")); } - SharedPtr SpawnActor(const ActorBlueprint &blueprint, const Transform &transform); + SharedPtr SpawnActor( + const ActorBlueprint &blueprint, + const Transform &transform); void ApplyControlToActor( const Actor &actor, diff --git a/LibCarla/source/carla/rpc/ActorDescription.h b/LibCarla/source/carla/rpc/ActorDescription.h index e8a6471ec..e54ee0870 100644 --- a/LibCarla/source/carla/rpc/ActorDescription.h +++ b/LibCarla/source/carla/rpc/ActorDescription.h @@ -29,7 +29,7 @@ namespace rpc { #ifdef LIBCARLA_INCLUDED_FROM_UE4 operator FActorDescription() const { - FActorVariation Description; + FActorDescription Description; Description.UId = uid; Description.Id = ToFString(id); Description.Variations.Reserve(attributes.size()); diff --git a/LibCarla/source/carla/rpc/Server.h b/LibCarla/source/carla/rpc/Server.h index 9beeb5d26..84a1c26e9 100644 --- a/LibCarla/source/carla/rpc/Server.h +++ b/LibCarla/source/carla/rpc/Server.h @@ -11,6 +11,7 @@ #include #include +#include #include @@ -108,6 +109,11 @@ namespace detail { _server.stop(); } + template + static void RespondError(T &&error_object) { + ::rpc::this_handler().respond_error(std::forward(error_object)); + } + private: boost::asio::io_service _sync_io_service; diff --git a/PythonAPI/source/libcarla/Exception.cpp b/PythonAPI/source/libcarla/Exception.cpp new file mode 100644 index 000000000..be6438081 --- /dev/null +++ b/PythonAPI/source/libcarla/Exception.cpp @@ -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 . + +#include + +#include + +#include + +void translator(rpc::rpc_error e) { + std::stringstream ss; + ss << e.what() + << " in function " << e.get_function_name() + << ": " << e.get_error().as(); + PyErr_SetString(PyExc_RuntimeError, ss.str().c_str()); +} + +void export_exception() { + using namespace boost::python; + namespace cc = carla::client; + + register_exception_translator(translator); +} diff --git a/PythonAPI/source/libcarla/libcarla.cpp b/PythonAPI/source/libcarla/libcarla.cpp index 3eb158f07..34c38c751 100644 --- a/PythonAPI/source/libcarla/libcarla.cpp +++ b/PythonAPI/source/libcarla/libcarla.cpp @@ -10,6 +10,7 @@ #include "Blueprint.cpp" #include "Client.cpp" #include "Control.cpp" +#include "Exception.cpp" #include "Transform.cpp" #include "World.cpp" @@ -22,4 +23,5 @@ BOOST_PYTHON_MODULE(libcarla) { export_actor(); export_world(); export_client(); + export_exception(); } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp index c5b760f54..6f59ce90b 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp @@ -34,21 +34,18 @@ void FActorDispatcher::Bind(IActorSpawner &ActorSpawner) } } -AActor *FActorDispatcher::SpawnActor( +TPair FActorDispatcher::SpawnActor( const FTransform &Transform, const FActorDescription &Description) { if ((Description.UId == 0) || (Description.UId > SpawnFunctions.Num())) { UE_LOG(LogCarla, Error, TEXT("Invalid ActorDescription \"%s\" (UId=%d)"), *Description.Id, Description.UId); - return nullptr; + return MakeTuple(EActorSpawnResultStatus::InvalidDescription, FActorView()); } - auto *Actor = SpawnFunctions[Description.UId](Transform, Description); - if (Actor != nullptr) - { - Registry.Register(*Actor); - } - return Actor; + auto Result = SpawnFunctions[Description.UId - 1](Transform, Description); + auto View = Result.IsValid() ? Registry.Register(*Result.Actor) : FActorView(); + return MakeTuple(Result.Status, View); } void FActorDispatcher::DestroyActor(AActor *Actor) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.h index 26ece1022..5776766c0 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.h @@ -9,6 +9,7 @@ #include "Carla/Actor/ActorDefinition.h" #include "Carla/Actor/ActorDescription.h" #include "Carla/Actor/ActorRegistry.h" +#include "Carla/Actor/ActorSpawnResult.h" #include "Containers/Array.h" #include "Templates/Function.h" @@ -21,7 +22,7 @@ class FActorDispatcher { public: - using SpawnFunctionType = TFunction; + using SpawnFunctionType = TFunction; /// Bind a definition to a spawn function. When SpawnActor is called with a /// matching description @a Functor is called. @@ -37,8 +38,10 @@ public: /// Spawns an actor based on @a ActorDescription at @a Transform. To properly /// despawn an actor created with this function call DestroyActor. /// - /// Return nullptr on failure. - AActor *SpawnActor( + /// @return A pair containing the result of the spawn function and a view over + /// the actor and its properties. If the status is different of Success the + /// view is invalid. + TPair SpawnActor( const FTransform &Transform, const FActorDescription &ActorDescription); diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnResult.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnResult.cpp new file mode 100644 index 000000000..a517cb1b9 --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnResult.cpp @@ -0,0 +1,30 @@ +// 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 . + +#pragma once + +#include "Carla.h" +#include "Carla/Actor/ActorSpawnResult.h" + +FString FActorSpawnResult::StatusToString(EActorSpawnResultStatus InStatus) +{ + static_assert( + static_cast(EActorSpawnResultStatus::SIZE) == 4u, + "If you add a new status, please update this function."); + + switch (InStatus) + { + case EActorSpawnResultStatus::Success: + return TEXT("Success"); + case EActorSpawnResultStatus::InvalidDescription: + return TEXT("Spawn failed because of invalid actor description"); + case EActorSpawnResultStatus::Collision: + return TEXT("Spawn failed because due to a collision at spawn position"); + case EActorSpawnResultStatus::UnknownError: + default: + return TEXT("Unknown error while trying to spawn actor"); + } +} diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnResult.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnResult.h new file mode 100644 index 000000000..a8fb4da20 --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnResult.h @@ -0,0 +1,41 @@ +// 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 . + +#pragma once + +#include "ActorSpawnResult.generated.h" + +/// List of valid types for actor attributes. +UENUM(BlueprintType) +enum class EActorSpawnResultStatus : uint8 +{ + Success UMETA(DisplayName = "Success"), + InvalidDescription UMETA(DisplayName = "Invalid actor description"), + Collision UMETA(DisplayName = "Failed because collision at spawn position"), + UnknownError UMETA(DisplayName = "Unknown Error"), + + SIZE UMETA(Hidden) +}; + +/// Result of an actor spawn function. +USTRUCT(BlueprintType) +struct FActorSpawnResult +{ + GENERATED_BODY() + + static FString StatusToString(EActorSpawnResultStatus Status); + + bool IsValid() const + { + return (Actor != nullptr) && (Status == EActorSpawnResultStatus::Success); + } + + UPROPERTY(EditAnywhere, BlueprintReadWrite) + AActor *Actor = nullptr; + + UPROPERTY(EditAnywhere, BlueprintReadWrite) + EActorSpawnResultStatus Status = EActorSpawnResultStatus::UnknownError; +}; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawner.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawner.h index b7ac4c0e6..fc6475408 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawner.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawner.h @@ -8,6 +8,7 @@ #include "Carla/Actor/ActorDefinition.h" #include "Carla/Actor/ActorDescription.h" +#include "Carla/Actor/ActorSpawnResult.h" #include "Containers/Array.h" #include "GameFramework/Actor.h" @@ -26,7 +27,7 @@ public: /// /// @pre ActorDescription is expected to be derived from one of the /// definitions retrieved with MakeDefinitions. - virtual AActor *SpawnActor( + virtual FActorSpawnResult SpawnActor( const FTransform &SpawnAtTransform, const FActorDescription &ActorDescription) = 0; }; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnerBlueprintBase.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnerBlueprintBase.h index 89af52382..af7769aa3 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnerBlueprintBase.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnerBlueprintBase.h @@ -7,6 +7,7 @@ #pragma once #include "Carla/Actor/ActorSpawner.h" +#include "Carla/Actor/ActorSpawnResult.h" #include "ActorSpawnerBlueprintBase.generated.h" @@ -28,13 +29,13 @@ public: return GenerateDefinitions(); } - virtual AActor *SpawnActor( + virtual FActorSpawnResult SpawnActor( const FTransform &SpawnAtTransform, const FActorDescription &ActorDescription) final { - AActor *Actor = nullptr; - SpawnActor(SpawnAtTransform, ActorDescription, Actor); - return Actor; + FActorSpawnResult Result; + SpawnActor(SpawnAtTransform, ActorDescription, Result); + return Result; } protected: @@ -46,5 +47,5 @@ protected: void SpawnActor( const FTransform &SpawnAtTransform, const FActorDescription &ActorDescription, - AActor *&Actor); + FActorSpawnResult &SpawnResult); }; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorView.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorView.h index 9eefd1deb..3aad4f04a 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorView.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorView.h @@ -8,7 +8,7 @@ class AActor; -/// An view over an actor and its properties. +/// A view over an actor and its properties. class FActorView { public: diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.h index 9815db121..4b50a0c9d 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.h @@ -47,13 +47,28 @@ public: /// Spawns an actor based on @a ActorDescription at @a Transform. To properly /// despawn an actor created with this function call DestroyActor. /// - /// Return nullptr on failure. + /// @return A pair containing the result of the spawn function and a view over + /// the actor and its properties. If the status is different of Success the + /// view is invalid. + TPair SpawnActorWithInfo( + const FTransform &Transform, + const FActorDescription &ActorDescription) + { + return ActorDispatcher.SpawnActor(Transform, ActorDescription); + } + + /// Spawns an actor based on @a ActorDescription at @a Transform. To properly + /// despawn an actor created with this function call DestroyActor. + /// + /// @return nullptr on failure. + /// + /// @note Special overload for blueprints. UFUNCTION(BlueprintCallable) AActor *SpawnActor( const FTransform &Transform, const FActorDescription &ActorDescription) { - return ActorDispatcher.SpawnActor(Transform, ActorDescription); + return SpawnActorWithInfo(Transform, ActorDescription).Value.GetActor(); } /// Destroys an actor, properly removing it from the registry. diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp index c41998c2b..431889bea 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp @@ -9,20 +9,99 @@ #include #include +#include +#include +#include #include +#include #include +#include + +// ============================================================================= +// -- Static local functions --------------------------------------------------- +// ============================================================================= + +template +static std::vector MakeVectorFromTArray(const TArray &Array) +{ + return {Array.GetData(), Array.GetData() + Array.Num()}; +} + +// ============================================================================= +// -- FTheNewCarlaServer::FPimpl ----------------------------------------------- +// ============================================================================= + class FTheNewCarlaServer::FPimpl { public: - FPimpl(uint16_t port) : Server(port) {} + FPimpl(uint16_t port) : Server(port) { + BindActions(); + } carla::rpc::Server Server; - UCarlaEpisode *CurrentEpisode = nullptr; + UCarlaEpisode *Episode = nullptr; + +private: + + void BindActions(); + + void RespondErrorStr(const std::string &ErrorMessage) { + UE_LOG(LogCarlaServer, Log, TEXT("Responding error, %s"), *carla::rpc::ToFString(ErrorMessage)); + carla::rpc::Server::RespondError(ErrorMessage); + } + + void RespondError(const FString &ErrorMessage) { + RespondErrorStr(carla::rpc::FromFString(ErrorMessage)); + } + + void RequireEpisode() + { + if (Episode == nullptr) + { + RespondErrorStr("episode not ready"); + } + } }; +// ============================================================================= +// -- FTheNewCarlaServer::FPimpl Bind Actions ---------------------------------- +// ============================================================================= + +void FTheNewCarlaServer::FPimpl::BindActions() +{ + namespace cr = carla::rpc; + + Server.BindAsync("ping", []() { return true; }); + + Server.BindAsync("version", []() { return std::string(carla::version()); }); + + Server.BindSync("get_actor_definitions", [this]() { + RequireEpisode(); + return MakeVectorFromTArray(Episode->GetActorDefinitions()); + }); + + Server.BindSync("spawn_actor", [this]( + const cr::Transform &Transform, + const cr::ActorDescription &Definition) { + RequireEpisode(); + auto Result = Episode->SpawnActorWithInfo(Transform, Definition); + if (Result.Key != EActorSpawnResultStatus::Success) + { + RespondError(FActorSpawnResult::StatusToString(Result.Key)); + } + cr::Actor actor; + actor.id = Result.Value.GetActorId(); + return actor; + }); +} + +// ============================================================================= +// -- FTheNewCarlaServer ------------------------------------------------------- +// ============================================================================= + FTheNewCarlaServer::FTheNewCarlaServer() : Pimpl(nullptr) {} FTheNewCarlaServer::~FTheNewCarlaServer() {} @@ -30,27 +109,18 @@ FTheNewCarlaServer::~FTheNewCarlaServer() {} void FTheNewCarlaServer::Start(uint16_t Port) { UE_LOG(LogCarlaServer, Log, TEXT("Initializing rpc-server at port %d"), Port); - Pimpl = MakeUnique(Port); - - namespace cr = carla::rpc; - - auto &srv = Pimpl->Server; - - srv.BindAsync("ping", []() { return true; }); - - srv.BindAsync("version", []() { return std::string(carla::version()); }); } void FTheNewCarlaServer::NotifyBeginEpisode(UCarlaEpisode &Episode) { UE_LOG(LogCarlaServer, Log, TEXT("New episode '%s' started"), *Episode.GetMapName()); - Pimpl->CurrentEpisode = &Episode; + Pimpl->Episode = &Episode; } void FTheNewCarlaServer::NotifyEndEpisode() { - Pimpl->CurrentEpisode = nullptr; + Pimpl->Episode = nullptr; } void FTheNewCarlaServer::AsyncRun(uint32 NumberOfWorkerThreads) From a1663c6e03911cc99939850d0968bd736e5e23ae Mon Sep 17 00:00:00 2001 From: nsubiron Date: Tue, 24 Jul 2018 12:19:45 +0200 Subject: [PATCH 22/71] Attach description to actor instance --- LibCarla/source/carla/client/Actor.h | 10 +++------- LibCarla/source/carla/rpc/Actor.h | 19 ++++++++++++++++--- LibCarla/source/carla/rpc/ActorAttribute.h | 3 +++ LibCarla/source/carla/rpc/ActorDescription.h | 9 +++++++++ LibCarla/source/carla/rpc/Server.cpp | 19 +++++++++++++++++++ LibCarla/source/carla/rpc/Server.h | 6 +----- PythonAPI/source/libcarla/Actor.cpp | 9 ++++----- .../Source/Carla/Actor/ActorDispatcher.cpp | 4 ++-- .../Source/Carla/Actor/ActorDispatcher.h | 2 +- .../Source/Carla/Actor/ActorRegistry.cpp | 4 ++-- .../Carla/Source/Carla/Actor/ActorRegistry.h | 2 +- .../Carla/Source/Carla/Actor/ActorView.h | 18 +++++++++++++++--- .../Carla/Source/Carla/Game/CarlaEpisode.h | 8 ++++---- .../Source/Carla/Server/TheNewCarlaServer.cpp | 8 +++----- 14 files changed, 83 insertions(+), 38 deletions(-) create mode 100644 LibCarla/source/carla/rpc/Server.cpp diff --git a/LibCarla/source/carla/client/Actor.h b/LibCarla/source/carla/client/Actor.h index 9ac4b6cd8..59a55d5bb 100644 --- a/LibCarla/source/carla/client/Actor.h +++ b/LibCarla/source/carla/client/Actor.h @@ -30,13 +30,9 @@ namespace client { return _actor.id; } - // const std::string &GetTypeId() const { - // return _actor.blueprint.type_id; - // } - - // ActorBlueprint GetBlueprint() const { - // return _actor.blueprint; - // } + const std::string &GetTypeId() const { + return _actor.description.id; + } SharedPtr GetWorld() const { return _world; diff --git a/LibCarla/source/carla/rpc/Actor.h b/LibCarla/source/carla/rpc/Actor.h index 79f3dea53..157c4bc87 100644 --- a/LibCarla/source/carla/rpc/Actor.h +++ b/LibCarla/source/carla/rpc/Actor.h @@ -6,7 +6,8 @@ #pragma once -#include "carla/rpc/ActorDefinition.h" +#include "carla/Debug.h" +#include "carla/rpc/ActorDescription.h" namespace carla { namespace rpc { @@ -16,11 +17,23 @@ namespace rpc { using id_type = uint32_t; + Actor() = default; + id_type id; - ActorDefinition definition; + ActorDescription description; - MSGPACK_DEFINE_ARRAY(id, definition); +#ifdef LIBCARLA_INCLUDED_FROM_UE4 + + Actor(FActorView View) + : id(View.GetActorId()), + description(*View.GetActorDescription()) { + DEBUG_ASSERT(View.IsValid()); + } + +#endif // LIBCARLA_INCLUDED_FROM_UE4 + + MSGPACK_DEFINE_ARRAY(id, description); }; } // namespace rpc diff --git a/LibCarla/source/carla/rpc/ActorAttribute.h b/LibCarla/source/carla/rpc/ActorAttribute.h index 5c6f33adb..f20515658 100644 --- a/LibCarla/source/carla/rpc/ActorAttribute.h +++ b/LibCarla/source/carla/rpc/ActorAttribute.h @@ -79,6 +79,9 @@ namespace rpc { #ifdef LIBCARLA_INCLUDED_FROM_UE4 + ActorAttributeValue(const FActorAttribute &Attribute) + : ActorAttributeValue(ActorAttribute(Attribute)) {} + operator FActorAttribute() const { FActorAttribute Attribute; Attribute.Id = ToFString(id); diff --git a/LibCarla/source/carla/rpc/ActorDescription.h b/LibCarla/source/carla/rpc/ActorDescription.h index e54ee0870..67dda35fc 100644 --- a/LibCarla/source/carla/rpc/ActorDescription.h +++ b/LibCarla/source/carla/rpc/ActorDescription.h @@ -28,6 +28,15 @@ namespace rpc { #ifdef LIBCARLA_INCLUDED_FROM_UE4 + ActorDescription(const FActorDescription &Description) + : uid(Description.UId), + id(FromFString(Description.Id)) { + attributes.reserve(Description.Variations.Num()); + for (const auto &Item : Description.Variations) { + attributes.push_back(Item); + } + } + operator FActorDescription() const { FActorDescription Description; Description.UId = uid; diff --git a/LibCarla/source/carla/rpc/Server.cpp b/LibCarla/source/carla/rpc/Server.cpp new file mode 100644 index 000000000..d2bb74810 --- /dev/null +++ b/LibCarla/source/carla/rpc/Server.cpp @@ -0,0 +1,19 @@ +// 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 . + +#include "carla/rpc/Server.h" + +#include + +namespace carla { +namespace rpc { + + void Server::RespondError(std::string error_message) { + ::rpc::this_handler().respond_error(std::move(error_message)); + } + +} // namespace carla +} // namespace rpc diff --git a/LibCarla/source/carla/rpc/Server.h b/LibCarla/source/carla/rpc/Server.h index 84a1c26e9..3b2cf65b9 100644 --- a/LibCarla/source/carla/rpc/Server.h +++ b/LibCarla/source/carla/rpc/Server.h @@ -11,7 +11,6 @@ #include #include -#include #include @@ -109,10 +108,7 @@ namespace detail { _server.stop(); } - template - static void RespondError(T &&error_object) { - ::rpc::this_handler().respond_error(std::forward(error_object)); - } + static void RespondError(std::string error_message); private: diff --git a/PythonAPI/source/libcarla/Actor.cpp b/PythonAPI/source/libcarla/Actor.cpp index 29576da89..342f9a9f7 100644 --- a/PythonAPI/source/libcarla/Actor.cpp +++ b/PythonAPI/source/libcarla/Actor.cpp @@ -27,11 +27,10 @@ void export_actor() { class_>("Actor", no_init) .add_property("id", &cc::Actor::GetId) - // .add_property("type_id", +[](const cc::Actor &self) -> std::string { - // // Needs to copy the string by value. - // return self.GetTypeId(); - // }) - // .add_property("blueprint", &cc::Actor::GetBlueprint) + .add_property("type_id", +[](const cc::Actor &self) -> std::string { + // Needs to copy the string by value. + return self.GetTypeId(); + }) .def("get_world", &cc::Actor::GetWorld) .def("apply_control", &cc::Actor::ApplyControl) .def(self_ns::str(self_ns::self)) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp index 6f59ce90b..68880b594 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp @@ -36,7 +36,7 @@ void FActorDispatcher::Bind(IActorSpawner &ActorSpawner) TPair FActorDispatcher::SpawnActor( const FTransform &Transform, - const FActorDescription &Description) + FActorDescription Description) { if ((Description.UId == 0) || (Description.UId > SpawnFunctions.Num())) { @@ -44,7 +44,7 @@ TPair FActorDispatcher::SpawnActor( return MakeTuple(EActorSpawnResultStatus::InvalidDescription, FActorView()); } auto Result = SpawnFunctions[Description.UId - 1](Transform, Description); - auto View = Result.IsValid() ? Registry.Register(*Result.Actor) : FActorView(); + auto View = Result.IsValid() ? Registry.Register(*Result.Actor, std::move(Description)) : FActorView(); return MakeTuple(Result.Status, View); } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.h index 5776766c0..3db97b815 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.h @@ -43,7 +43,7 @@ public: /// view is invalid. TPair SpawnActor( const FTransform &Transform, - const FActorDescription &ActorDescription); + FActorDescription ActorDescription); /// Destroys an actor, properly removing it from the registry. void DestroyActor(AActor *Actor); diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorRegistry.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorRegistry.cpp index 75499dec9..7d4d70ac0 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorRegistry.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorRegistry.cpp @@ -9,13 +9,13 @@ #include "Carla.h" #include "Carla/Actor/ActorRegistry.h" -FActorView FActorRegistry::Register(AActor &Actor) +FActorView FActorRegistry::Register(AActor &Actor, FActorDescription Description) { static IdType ID_COUNTER = 0u; const auto Id = ++ID_COUNTER; Actors.Emplace(Id, &Actor); Ids.Emplace(&Actor, Id); - auto Result = ActorDatabase.emplace(Id, FActorView(Id, Actor)); + auto Result = ActorDatabase.emplace(Id, FActorView(Id, Actor, std::move(Description))); check(Result.second); check(static_cast(Actors.Num()) == ActorDatabase.size()); check(static_cast(Ids.Num()) == ActorDatabase.size()); diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorRegistry.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorRegistry.h index 8f6342723..563079c75 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorRegistry.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorRegistry.h @@ -33,7 +33,7 @@ public: /// actor. /// /// @warning Undefined if an actor is registered more than once. - FActorView Register(AActor &Actor); + FActorView Register(AActor &Actor, FActorDescription Description); void Deregister(IdType Id); diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorView.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorView.h index 3aad4f04a..1802f1193 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorView.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorView.h @@ -6,6 +6,8 @@ #pragma once +#include "Carla/Actor/ActorDescription.h" + class AActor; /// A view over an actor and its properties. @@ -20,7 +22,7 @@ public: bool IsValid() const { - return TheActor != nullptr; + return (TheActor != nullptr) && Description.IsValid(); } IdType GetActorId() const @@ -38,15 +40,25 @@ public: return TheActor; } + const FActorDescription *GetActorDescription() const + { + return Description.Get(); + } + private: friend class FActorRegistry; - FActorView(IdType ActorId, AActor &Actor) + FActorView(IdType ActorId, AActor &Actor, FActorDescription Description) : Id(ActorId), - TheActor(&Actor) {} + TheActor(&Actor), + Description(MakeShared(std::move(Description))) { + check(Id != 0u); + } IdType Id = 0u; AActor *TheActor = nullptr; + + TSharedPtr Description = nullptr; }; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.h index 4b50a0c9d..7c55fea96 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.h @@ -52,9 +52,9 @@ public: /// view is invalid. TPair SpawnActorWithInfo( const FTransform &Transform, - const FActorDescription &ActorDescription) + FActorDescription ActorDescription) { - return ActorDispatcher.SpawnActor(Transform, ActorDescription); + return ActorDispatcher.SpawnActor(Transform, std::move(ActorDescription)); } /// Spawns an actor based on @a ActorDescription at @a Transform. To properly @@ -66,9 +66,9 @@ public: UFUNCTION(BlueprintCallable) AActor *SpawnActor( const FTransform &Transform, - const FActorDescription &ActorDescription) + FActorDescription ActorDescription) { - return SpawnActorWithInfo(Transform, ActorDescription).Value.GetActor(); + return SpawnActorWithInfo(Transform, std::move(ActorDescription)).Value.GetActor(); } /// Destroys an actor, properly removing it from the registry. diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp index 431889bea..55ec5ac24 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp @@ -85,16 +85,14 @@ void FTheNewCarlaServer::FPimpl::BindActions() Server.BindSync("spawn_actor", [this]( const cr::Transform &Transform, - const cr::ActorDescription &Definition) { + cr::ActorDescription Description) -> cr::Actor { RequireEpisode(); - auto Result = Episode->SpawnActorWithInfo(Transform, Definition); + auto Result = Episode->SpawnActorWithInfo(Transform, std::move(Description)); if (Result.Key != EActorSpawnResultStatus::Success) { RespondError(FActorSpawnResult::StatusToString(Result.Key)); } - cr::Actor actor; - actor.id = Result.Value.GetActorId(); - return actor; + return Result.Value; }); } From 1d9610404d35cc2a4efe8ee6707cb310597da396 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Thu, 19 Jul 2018 16:15:34 +0200 Subject: [PATCH 23/71] #573 Changes for using new repository --- Unreal/CarlaUE4/Config/DefaultEngine.ini | 11 +++++----- Unreal/CarlaUE4/Config/DefaultGame.ini | 22 +++++++++---------- .../Carla/Source/Carla/Game/Tagger.cpp | 2 +- .../Source/CarlaUE4/CarlaMapGenerator.cpp | 2 +- Update.sh | 4 ++-- Util/ContentVersions.txt | 1 + 6 files changed, 22 insertions(+), 20 deletions(-) diff --git a/Unreal/CarlaUE4/Config/DefaultEngine.ini b/Unreal/CarlaUE4/Config/DefaultEngine.ini index 91014e4a8..b043d24c9 100644 --- a/Unreal/CarlaUE4/Config/DefaultEngine.ini +++ b/Unreal/CarlaUE4/Config/DefaultEngine.ini @@ -10,12 +10,13 @@ DefaultGraphicsPerformance=Maximum AppliedDefaultGraphicsPerformance=Maximum [/Script/EngineSettings.GameMapsSettings] -EditorStartupMap=/Game/Maps/Town01.Town01 -GameDefaultMap=/Game/Maps/Town01.Town01 -ServerDefaultMap=/Game/Maps/Town01.Town01 -GlobalDefaultGameMode=/Script/Carla.TheNewCarlaGameModeBase +EditorStartupMap=/Game/Carla/Maps/Town01.Town01 +GameDefaultMap=/Game/Carla/Maps/Town01.Town01 +ServerDefaultMap=/Game/Carla/Maps/Town01.Town01 +GlobalDefaultGameMode=/Game/Carla/Blueprints/Game/CarlaGameMode.CarlaGameMode_C GameInstanceClass=/Script/Carla.CarlaGameInstance -TransitionMap=/Game/Maps/Town01.Town01 +TransitionMap=/Game/Carla/Maps/Town01.Town01 +GlobalDefaultServerGameMode=/Game/Carla/Blueprints/Game/CarlaGameMode.CarlaGameMode_C [/Script/Engine.RendererSettings] r.DefaultFeature.MotionBlur=False diff --git a/Unreal/CarlaUE4/Config/DefaultGame.ini b/Unreal/CarlaUE4/Config/DefaultGame.ini index 72d4d8855..ddf898bad 100644 --- a/Unreal/CarlaUE4/Config/DefaultGame.ini +++ b/Unreal/CarlaUE4/Config/DefaultGame.ini @@ -31,21 +31,21 @@ bCookMapsOnly=False bCompressed=False bEncryptIniFiles=False bSkipEditorContent=False -+MapsToCook=(FilePath="/Game/Maps/Town01") -+MapsToCook=(FilePath="/Game/Maps/Town02") -+DirectoriesToAlwaysCook=(Path="Static/GenericMaterials/Licenseplates/Textures") ++MapsToCook=(FilePath="/Game/Carla/Maps/Town01") ++MapsToCook=(FilePath="/Game/Carla/Maps/Town02") ++DirectoriesToAlwaysCook=(Path="Carla/Static/GenericMaterials/Licenseplates/Textures") bNativizeBlueprintAssets=False bNativizeOnlySelectedBlueprints=False [/Script/Carla.CarlaSettings] -+LowRoadMaterials=(MaterialInterface=MaterialInstanceConstant'"/Game/Static/GenericMaterials/Ground/SimpleRoad/CheapRoad.CheapRoad"',MaterialSlotName="Tileroad_Road",ImportedMaterialSlotName="",UVChannelData=(bInitialized=False,bOverrideDensities=False,LocalUVDensities[0]=0.000000,LocalUVDensities[1]=0.000000,LocalUVDensities[2]=0.000000,LocalUVDensities[3]=0.000000)) -+LowRoadMaterials=(MaterialInterface=MaterialInstanceConstant'"/Game/Static/GenericMaterials/Ground/SimpleRoad/CheapSideWalkCurb.CheapSideWalkCurb"',MaterialSlotName="TileRoad_Curb",ImportedMaterialSlotName="",UVChannelData=(bInitialized=False,bOverrideDensities=False,LocalUVDensities[0]=0.000000,LocalUVDensities[1]=0.000000,LocalUVDensities[2]=0.000000,LocalUVDensities[3]=0.000000)) -+LowRoadMaterials=(MaterialInterface=MaterialInstanceConstant'"/Game/Static/GenericMaterials/Ground/SimpleRoad/CheapSideWalk_00.CheapSideWalk_00"',MaterialSlotName="Tileroad_Sidewalk",ImportedMaterialSlotName="",UVChannelData=(bInitialized=False,bOverrideDensities=False,LocalUVDensities[0]=0.000000,LocalUVDensities[1]=0.000000,LocalUVDensities[2]=0.000000,LocalUVDensities[3]=0.000000)) -+LowRoadMaterials=(MaterialInterface=MaterialInstanceConstant'"/Game/Static/GenericMaterials/Ground/SimpleRoad/CheapLaneMarking.CheapLaneMarking"',MaterialSlotName="TileRoad_LaneMarkingSolid",ImportedMaterialSlotName="",UVChannelData=(bInitialized=False,bOverrideDensities=False,LocalUVDensities[0]=0.000000,LocalUVDensities[1]=0.000000,LocalUVDensities[2]=0.000000,LocalUVDensities[3]=0.000000)) ++LowRoadMaterials=(MaterialInterface=MaterialInstanceConstant'"/Game/Carla/Static/GenericMaterials/Ground/SimpleRoad/CheapRoad.CheapRoad"',MaterialSlotName="Tileroad_Road",ImportedMaterialSlotName="",UVChannelData=(bInitialized=False,bOverrideDensities=False,LocalUVDensities[0]=0.000000,LocalUVDensities[1]=0.000000,LocalUVDensities[2]=0.000000,LocalUVDensities[3]=0.000000)) ++LowRoadMaterials=(MaterialInterface=MaterialInstanceConstant'"/Game/Carla/Static/GenericMaterials/Ground/SimpleRoad/CheapSideWalkCurb.CheapSideWalkCurb"',MaterialSlotName="TileRoad_Curb",ImportedMaterialSlotName="",UVChannelData=(bInitialized=False,bOverrideDensities=False,LocalUVDensities[0]=0.000000,LocalUVDensities[1]=0.000000,LocalUVDensities[2]=0.000000,LocalUVDensities[3]=0.000000)) ++LowRoadMaterials=(MaterialInterface=MaterialInstanceConstant'"/Game/Carla/Static/GenericMaterials/Ground/SimpleRoad/CheapSideWalk_00.CheapSideWalk_00"',MaterialSlotName="Tileroad_Sidewalk",ImportedMaterialSlotName="",UVChannelData=(bInitialized=False,bOverrideDensities=False,LocalUVDensities[0]=0.000000,LocalUVDensities[1]=0.000000,LocalUVDensities[2]=0.000000,LocalUVDensities[3]=0.000000)) ++LowRoadMaterials=(MaterialInterface=MaterialInstanceConstant'"/Game/Carla/Static/GenericMaterials/Ground/SimpleRoad/CheapLaneMarking.CheapLaneMarking"',MaterialSlotName="TileRoad_LaneMarkingSolid",ImportedMaterialSlotName="",UVChannelData=(bInitialized=False,bOverrideDensities=False,LocalUVDensities[0]=0.000000,LocalUVDensities[1]=0.000000,LocalUVDensities[2]=0.000000,LocalUVDensities[3]=0.000000)) LowLightFadeDistance=1000.000000 LowStaticMeshMaxDrawDistance=10000.000000 LowRoadPieceMeshMaxDrawDistance=15000.000000 -+EpicRoadMaterials=(MaterialInterface=MaterialInstanceConstant'"/Game/Static/GenericMaterials/WetPavement/WetPavement_Complex_Road_N2.WetPavement_Complex_Road_N2"',MaterialSlotName="Tileroad_Road",ImportedMaterialSlotName="",UVChannelData=(bInitialized=False,bOverrideDensities=False,LocalUVDensities[0]=0.000000,LocalUVDensities[1]=0.000000,LocalUVDensities[2]=0.000000,LocalUVDensities[3]=0.000000)) -+EpicRoadMaterials=(MaterialInterface=MaterialInstanceConstant'"/Game/Static/GenericMaterials/WetPavement/WetPavement_Complex_Concrete.WetPavement_Complex_Concrete"',MaterialSlotName="TileRoad_Curb",ImportedMaterialSlotName="",UVChannelData=(bInitialized=False,bOverrideDensities=False,LocalUVDensities[0]=0.000000,LocalUVDensities[1]=0.000000,LocalUVDensities[2]=0.000000,LocalUVDensities[3]=0.000000)) -+EpicRoadMaterials=(MaterialInterface=MaterialInstanceConstant'"/Game/Static/GenericMaterials/Ground/SideWalks/SidewalkN4/WetPavement_SidewalkN4.WetPavement_SidewalkN4"',MaterialSlotName="Tileroad_Sidewalk",ImportedMaterialSlotName="",UVChannelData=(bInitialized=False,bOverrideDensities=False,LocalUVDensities[0]=0.000000,LocalUVDensities[1]=0.000000,LocalUVDensities[2]=0.000000,LocalUVDensities[3]=0.000000)) -+EpicRoadMaterials=(MaterialInterface=MaterialInstanceConstant'"/Game/Static/GenericMaterials/LaneMarking/Lanemarking.Lanemarking"',MaterialSlotName="TileRoad_LaneMarkingSolid",ImportedMaterialSlotName="",UVChannelData=(bInitialized=False,bOverrideDensities=False,LocalUVDensities[0]=0.000000,LocalUVDensities[1]=0.000000,LocalUVDensities[2]=0.000000,LocalUVDensities[3]=0.000000)) ++EpicRoadMaterials=(MaterialInterface=MaterialInstanceConstant'"/Game/Carla/Static/GenericMaterials/WetPavement/WetPavement_Complex_Road_N2.WetPavement_Complex_Road_N2"',MaterialSlotName="Tileroad_Road",ImportedMaterialSlotName="",UVChannelData=(bInitialized=False,bOverrideDensities=False,LocalUVDensities[0]=0.000000,LocalUVDensities[1]=0.000000,LocalUVDensities[2]=0.000000,LocalUVDensities[3]=0.000000)) ++EpicRoadMaterials=(MaterialInterface=MaterialInstanceConstant'"/Game/Carla/Static/GenericMaterials/WetPavement/WetPavement_Complex_Concrete.WetPavement_Complex_Concrete"',MaterialSlotName="TileRoad_Curb",ImportedMaterialSlotName="",UVChannelData=(bInitialized=False,bOverrideDensities=False,LocalUVDensities[0]=0.000000,LocalUVDensities[1]=0.000000,LocalUVDensities[2]=0.000000,LocalUVDensities[3]=0.000000)) ++EpicRoadMaterials=(MaterialInterface=MaterialInstanceConstant'"/Game/Carla/Static/GenericMaterials/Ground/SideWalks/SidewalkN4/WetPavement_SidewalkN4.WetPavement_SidewalkN4"',MaterialSlotName="Tileroad_Sidewalk",ImportedMaterialSlotName="",UVChannelData=(bInitialized=False,bOverrideDensities=False,LocalUVDensities[0]=0.000000,LocalUVDensities[1]=0.000000,LocalUVDensities[2]=0.000000,LocalUVDensities[3]=0.000000)) ++EpicRoadMaterials=(MaterialInterface=MaterialInstanceConstant'"/Game/Carla/Static/GenericMaterials/LaneMarking/Lanemarking.Lanemarking"',MaterialSlotName="TileRoad_LaneMarkingSolid",ImportedMaterialSlotName="",UVChannelData=(bInitialized=False,bOverrideDensities=False,LocalUVDensities[0]=0.000000,LocalUVDensities[1]=0.000000,LocalUVDensities[2]=0.000000,LocalUVDensities[3]=0.000000)) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/Tagger.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/Tagger.cpp index f2b1eef91..be582090e 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/Tagger.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/Tagger.cpp @@ -66,7 +66,7 @@ static ECityObjectLabel GetLabelByPath(const T *Object) const FString Path = Object->GetPathName(); TArray StringArray; Path.ParseIntoArray(StringArray, TEXT("/"), false); - return (StringArray.Num() > 3 ? GetLabelByFolderName(StringArray[3]) : ECityObjectLabel::None); + return (StringArray.Num() > 4 ? GetLabelByFolderName(StringArray[4]) : ECityObjectLabel::None); } static void SetStencilValue( diff --git a/Unreal/CarlaUE4/Source/CarlaUE4/CarlaMapGenerator.cpp b/Unreal/CarlaUE4/Source/CarlaUE4/CarlaMapGenerator.cpp index d593e9629..a322704ee 100644 --- a/Unreal/CarlaUE4/Source/CarlaUE4/CarlaMapGenerator.cpp +++ b/Unreal/CarlaUE4/Source/CarlaUE4/CarlaMapGenerator.cpp @@ -17,7 +17,7 @@ ACarlaMapGenerator::ACarlaMapGenerator(const FObjectInitializer& ObjectInitializ SetStaticMesh(ECityMapMeshTag:: Tag, MeshObj.Object); \ } -#define PREFIX_FOLDER "/Game/Static/" +#define PREFIX_FOLDER "/Game/Carla/Static/" SET_STATIC_MESH(RoadTwoLanes_LaneLeft, PREFIX_FOLDER "Road", "St_Road_TileRoad_RoadL"); SET_STATIC_MESH(RoadTwoLanes_LaneRight, PREFIX_FOLDER "Road", "St_Road_TileRoad_RoadR"); diff --git a/Update.sh b/Update.sh index 35043f193..1c8ef4424 100755 --- a/Update.sh +++ b/Update.sh @@ -44,7 +44,7 @@ done SCRIPT_DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )" pushd "$SCRIPT_DIR" >/dev/null -CONTENT_FOLDER=$SCRIPT_DIR/Unreal/CarlaUE4/Content +CONTENT_FOLDER=$SCRIPT_DIR/Unreal/CarlaUE4/Content/Carla CONTENT_GDRIVE_ID=$(tac $SCRIPT_DIR/Util/ContentVersions.txt | egrep -m 1 . | rev | cut -d' ' -f1 | rev) @@ -74,7 +74,7 @@ if $SKIP_DOWNLOAD ; then echo echo " https://drive.google.com/open?id=$CONTENT_GDRIVE_ID" echo - echo "and extract it under Unreal/CarlaUE4/Content." + echo "and extract it under Unreal/CarlaUE4/Content/Carla." exit 0 fi diff --git a/Util/ContentVersions.txt b/Util/ContentVersions.txt index 05354d32d..04cf1f6fa 100644 --- a/Util/ContentVersions.txt +++ b/Util/ContentVersions.txt @@ -13,3 +13,4 @@ 0.8.2: 1llrBkZDvJmxXYh4r3jz0wuwz8Q8jRQeZ 0.8.3: 1z2XKOk9LoKI-EhxcrpI31W5TeYo2-jjn 0.8.4: 1mFNS-w5atQ45yegiTepRIeKBYVm8N8He +Latest: 1UZodZd3uxr5h9SoJt7mI5k8T4j4VM-YP From a1158c6ca81437bd15e6825f1afc23cabd72748f Mon Sep 17 00:00:00 2001 From: nsubiron Date: Tue, 24 Jul 2018 17:38:46 +0200 Subject: [PATCH 24/71] Fix some compilation errors on Windows --- Docs/how_to_build_on_windows.md | 8 +++++++- LibCarla/source/test/util/Message.cpp | 4 +++- .../Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp | 2 +- .../Plugins/Carla/Source/Carla/Util/ScopedStack.h | 1 + 4 files changed, 12 insertions(+), 3 deletions(-) diff --git a/Docs/how_to_build_on_windows.md b/Docs/how_to_build_on_windows.md index 40e2bd73a..4de3aba3a 100644 --- a/Docs/how_to_build_on_windows.md +++ b/Docs/how_to_build_on_windows.md @@ -1,5 +1,11 @@

How to build CARLA on Windows

+!!! important + Since version 0.9.0 the build system changed, the instructions in this + document are no longer valid. While we work on fixing this, we recommend + either compile Carla on Linux or switch to the `stable` branch. Sorry for + the inconvenience. +

Necessary software

- [Git](https://git-scm.com/downloads) - [Make](http://gnuwin32.sourceforge.net/downlinks/make-bin-zip.php) @@ -22,7 +28,7 @@ You have different options: - [Enable a 64-Bit Visual C++ Toolset on the Command Line](https://msdn.microsoft.com/en-us/library/x4d2c09s.aspx) (the instructions will depend on the version of VS that you have). !!! note - Take care if you have **Cygwin** installed. This could cause the errors like + Take care if you have **Cygwin** installed. This could cause the errors like `/usr/bin/sh: rd: command not found` While executing `Reuild.bat`.

Clone the repository

diff --git a/LibCarla/source/test/util/Message.cpp b/LibCarla/source/test/util/Message.cpp index fb34fd9a4..073c75ddb 100644 --- a/LibCarla/source/test/util/Message.cpp +++ b/LibCarla/source/test/util/Message.cpp @@ -6,6 +6,8 @@ #include "Message.h" +#include + #include #include @@ -21,7 +23,7 @@ namespace message { shared_message make_random(size_t size) { if (size == 0u) return make_empty(); - using random_bytes_engine = std::independent_bits_engine< + using random_bytes_engine = boost::random::independent_bits_engine< std::random_device, CHAR_BIT, unsigned char>; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp index 68880b594..b09246f6a 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp @@ -38,7 +38,7 @@ TPair FActorDispatcher::SpawnActor( const FTransform &Transform, FActorDescription Description) { - if ((Description.UId == 0) || (Description.UId > SpawnFunctions.Num())) + if ((Description.UId == 0u) || (Description.UId > static_cast(SpawnFunctions.Num()))) { UE_LOG(LogCarla, Error, TEXT("Invalid ActorDescription \"%s\" (UId=%d)"), *Description.Id, Description.UId); return MakeTuple(EActorSpawnResultStatus::InvalidDescription, FActorView()); diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/ScopedStack.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/ScopedStack.h index dab2c1d1d..099520889 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/ScopedStack.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/ScopedStack.h @@ -7,6 +7,7 @@ #pragma once #include +#include /// A stack to keep track of nested scopes. template From 60d866d5b674ae1bd6643cada67aef0a6e6141cb Mon Sep 17 00:00:00 2001 From: nsubiron Date: Wed, 25 Jul 2018 11:45:16 +0200 Subject: [PATCH 25/71] Access Python blueprints with bounds checking --- LibCarla/source/carla/client/BlueprintLibrary.h | 4 ++++ PythonAPI/source/libcarla/Blueprint.cpp | 2 +- 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/LibCarla/source/carla/client/BlueprintLibrary.h b/LibCarla/source/carla/client/BlueprintLibrary.h index 11b1abce7..634019cae 100644 --- a/LibCarla/source/carla/client/BlueprintLibrary.h +++ b/LibCarla/source/carla/client/BlueprintLibrary.h @@ -47,6 +47,10 @@ namespace client { return _blueprints[pos]; } + const_reference at(size_type pos) const { + return _blueprints.at(pos); + } + const_iterator begin() const /*noexcept*/ { return _blueprints.begin(); } diff --git a/PythonAPI/source/libcarla/Blueprint.cpp b/PythonAPI/source/libcarla/Blueprint.cpp index b33fa8483..bf2d1ca7a 100644 --- a/PythonAPI/source/libcarla/Blueprint.cpp +++ b/PythonAPI/source/libcarla/Blueprint.cpp @@ -106,7 +106,7 @@ void export_blueprint() { class_>("BlueprintLibrary", no_init) .def("filter", &cc::BlueprintLibrary::Filter) .def("__getitem__", +[](const cc::BlueprintLibrary &self, size_t pos) -> cc::ActorBlueprint { - return self[pos]; + return self.at(pos); }) .def("__len__", &cc::BlueprintLibrary::size) .def("__iter__", range(&cc::BlueprintLibrary::begin, &cc::BlueprintLibrary::end)) From 8ae2770e1a1afaa2d8f65ecd059965487c3aa1b5 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Wed, 25 Jul 2018 11:47:57 +0200 Subject: [PATCH 26/71] Improvements to actor spawners --- LibCarla/source/carla/client/Client.cpp | 2 +- PythonAPI/source/libcarla/Exception.cpp | 9 ++-- .../Carla/Source/Carla/Actor/ActorAttribute.h | 4 +- .../Source/Carla/Actor/ActorDefinition.h | 7 +++ .../Source/Carla/Actor/ActorDescription.h | 4 ++ .../Source/Carla/Actor/ActorDispatcher.cpp | 24 ++++++++- .../Source/Carla/Actor/ActorDispatcher.h | 6 ++- .../Source/Carla/Actor/ActorSpawnResult.cpp | 2 +- .../Source/Carla/Actor/ActorSpawnResult.h | 8 +++ .../Carla/Source/Carla/Actor/ActorSpawner.h | 25 +++++++-- ...lueprintBase.h => ActorSpawnerBlueprint.h} | 16 +++--- .../Carla/Source/Carla/Game/CarlaEpisode.h | 2 +- .../Carla/Game/TheNewCarlaGameModeBase.cpp | 6 +-- .../Carla/Game/TheNewCarlaGameModeBase.h | 8 +-- .../Source/Carla/Server/TheNewCarlaServer.cpp | 54 ++++++++++++++++--- 15 files changed, 139 insertions(+), 38 deletions(-) rename Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/{ActorSpawnerBlueprintBase.h => ActorSpawnerBlueprint.h} (75%) diff --git a/LibCarla/source/carla/client/Client.cpp b/LibCarla/source/carla/client/Client.cpp index 39fd5855e..81b3d5b30 100644 --- a/LibCarla/source/carla/client/Client.cpp +++ b/LibCarla/source/carla/client/Client.cpp @@ -23,7 +23,7 @@ namespace client { SharedPtr Client::SpawnActor( const ActorBlueprint &blueprint, const Transform &transform) { - auto actor = Call("spawn_actor", blueprint.MakeActorDescription(), transform); + auto actor = Call("spawn_actor", transform, blueprint.MakeActorDescription()); return SharedPtr(new Actor{actor, GetWorld()}); } diff --git a/PythonAPI/source/libcarla/Exception.cpp b/PythonAPI/source/libcarla/Exception.cpp index be6438081..e9ceffeee 100644 --- a/PythonAPI/source/libcarla/Exception.cpp +++ b/PythonAPI/source/libcarla/Exception.cpp @@ -10,11 +10,12 @@ #include -void translator(rpc::rpc_error e) { +void translator(const rpc::rpc_error &e) { std::stringstream ss; - ss << e.what() - << " in function " << e.get_function_name() - << ": " << e.get_error().as(); + ss << e.what() << " in function " << e.get_function_name(); + /// @todo Supposedly we can extract the error string here as provided by the + /// server with e.get_error().as(), but it gives the wrong + /// string. PyErr_SetString(PyExc_RuntimeError, ss.str().c_str()); } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorAttribute.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorAttribute.h index 0ee30a383..985ea1460 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorAttribute.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorAttribute.h @@ -43,7 +43,7 @@ struct CARLA_API FActorVariation FString Id; UPROPERTY(EditAnywhere, BlueprintReadWrite) - EActorAttributeType Type = EActorAttributeType::Int; + EActorAttributeType Type = EActorAttributeType::String; UPROPERTY(EditAnywhere, BlueprintReadWrite) TArray RecommendedValues; @@ -63,7 +63,7 @@ struct CARLA_API FActorAttribute FString Id; UPROPERTY(EditAnywhere, BlueprintReadWrite) - EActorAttributeType Type = EActorAttributeType::Int; + EActorAttributeType Type = EActorAttributeType::String; UPROPERTY(EditAnywhere, BlueprintReadWrite) FString Value; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDefinition.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDefinition.h index a91389808..4e2c5bd45 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDefinition.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDefinition.h @@ -25,6 +25,13 @@ struct FActorDefinition UPROPERTY(EditAnywhere, BlueprintReadWrite) FString Id; + /// Class of the actor to be spawned (Optional). + /// + /// Note that this parameter is not exposed on the client-side, only used by + /// the spawner itself. + UPROPERTY(EditAnywhere, BlueprintReadWrite) + TSubclassOf Class; + /// A list of comma-separated tags. UPROPERTY(EditAnywhere, BlueprintReadWrite) FString Tags; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDescription.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDescription.h index bf95b040b..927af8a17 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDescription.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDescription.h @@ -23,6 +23,10 @@ struct FActorDescription UPROPERTY(EditAnywhere, BlueprintReadWrite) FString Id; + /// Class of the actor to be spawned. + UPROPERTY(EditAnywhere, BlueprintReadWrite) + TSubclassOf Class; + /// User selected variations of the actor. Note that at this point are /// represented by non-modifiable attributes. UPROPERTY(EditAnywhere, BlueprintReadWrite) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp index b09246f6a..db6d1b7f9 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp @@ -17,6 +17,7 @@ void FActorDispatcher::Bind(FActorDefinition Definition, SpawnFunctionType Funct Definition.UId = static_cast(SpawnFunctions.Num()) + 1u; Definitions.Emplace(Definition); SpawnFunctions.Emplace(Functor); + Classes.Emplace(Definition.Class); } else { @@ -24,7 +25,7 @@ void FActorDispatcher::Bind(FActorDefinition Definition, SpawnFunctionType Funct } } -void FActorDispatcher::Bind(IActorSpawner &ActorSpawner) +void FActorDispatcher::Bind(AActorSpawner &ActorSpawner) { for (const auto &Definition : ActorSpawner.MakeDefinitions()) { @@ -40,11 +41,30 @@ TPair FActorDispatcher::SpawnActor( { if ((Description.UId == 0u) || (Description.UId > static_cast(SpawnFunctions.Num()))) { - UE_LOG(LogCarla, Error, TEXT("Invalid ActorDescription \"%s\" (UId=%d)"), *Description.Id, Description.UId); + UE_LOG(LogCarla, Error, TEXT("Invalid ActorDescription '%s' (UId=%d)"), *Description.Id, Description.UId); return MakeTuple(EActorSpawnResultStatus::InvalidDescription, FActorView()); } + + UE_LOG(LogCarla, Log, TEXT("Spawning actor '%s'"), *Description.Id); + + Description.Class = Classes[Description.UId - 1]; auto Result = SpawnFunctions[Description.UId - 1](Transform, Description); + + if ((Result.Status == EActorSpawnResultStatus::Success) && (Result.Actor == nullptr)) + { + UE_LOG(LogCarla, Warning, TEXT("ActorSpawnResult: Trying to spawn '%s'"), *Description.Id); + UE_LOG(LogCarla, Warning, TEXT("ActorSpawnResult: Reported success but did not return an actor")); + Result.Status = EActorSpawnResultStatus::UnknownError; + } + auto View = Result.IsValid() ? Registry.Register(*Result.Actor, std::move(Description)) : FActorView(); + + if (!View.IsValid()) + { + UE_LOG(LogCarla, Warning, TEXT("Failed to spawn actor '%s'"), *Description.Id); + check(Result.Status != EActorSpawnResultStatus::Success); + } + return MakeTuple(Result.Status, View); } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.h index 3db97b815..f679fecc2 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.h @@ -14,7 +14,7 @@ #include "Containers/Array.h" #include "Templates/Function.h" -class IActorSpawner; +class AActorSpawner; /// Actor in charge of binding ActorDefinitions to spawn functions, as well as /// keeping the registry of all the actors spawned. @@ -33,7 +33,7 @@ public: /// Bind all the definitions of @a ActorSpawner to its spawn function. /// /// @warning Invalid definitions are ignored. - void Bind(IActorSpawner &ActorSpawner); + void Bind(AActorSpawner &ActorSpawner); /// Spawns an actor based on @a ActorDescription at @a Transform. To properly /// despawn an actor created with this function call DestroyActor. @@ -64,5 +64,7 @@ private: TArray SpawnFunctions; + TArray> Classes; + FActorRegistry Registry; }; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnResult.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnResult.cpp index a517cb1b9..13f844989 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnResult.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnResult.cpp @@ -22,7 +22,7 @@ FString FActorSpawnResult::StatusToString(EActorSpawnResultStatus InStatus) case EActorSpawnResultStatus::InvalidDescription: return TEXT("Spawn failed because of invalid actor description"); case EActorSpawnResultStatus::Collision: - return TEXT("Spawn failed because due to a collision at spawn position"); + return TEXT("Spawn failed because of collision at spawn position"); case EActorSpawnResultStatus::UnknownError: default: return TEXT("Unknown error while trying to spawn actor"); diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnResult.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnResult.h index a8fb4da20..a7c3e93c8 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnResult.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnResult.h @@ -26,6 +26,14 @@ struct FActorSpawnResult { GENERATED_BODY() + FActorSpawnResult() = default; + + explicit FActorSpawnResult(AActor *InActor) + : Actor(InActor), + Status(Actor != nullptr ? + EActorSpawnResultStatus::Success : + EActorSpawnResultStatus::UnknownError) {} + static FString StatusToString(EActorSpawnResultStatus Status); bool IsValid() const diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawner.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawner.h index fc6475408..ec3e61082 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawner.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawner.h @@ -13,15 +13,27 @@ #include "Containers/Array.h" #include "GameFramework/Actor.h" -/// Interface for Carla actor spawners. -class IActorSpawner +#include "ActorSpawner.generated.h" + +/// Base class for Carla actor spawners. +UCLASS(Abstract) +class CARLA_API AActorSpawner : public AActor { + GENERATED_BODY() + public: - virtual ~IActorSpawner() {} + AActorSpawner(const FObjectInitializer& ObjectInitializer) + : Super(ObjectInitializer) + { + PrimaryActorTick.bCanEverTick = false; + } /// Retrieve the list of actor definitions that this class is able to spawn. - virtual TArray MakeDefinitions() = 0; + virtual TArray MakeDefinitions() { + unimplemented(); + return {}; + } /// Spawn an actor based on @a ActorDescription and @a Transform. /// @@ -29,5 +41,8 @@ public: /// definitions retrieved with MakeDefinitions. virtual FActorSpawnResult SpawnActor( const FTransform &SpawnAtTransform, - const FActorDescription &ActorDescription) = 0; + const FActorDescription &ActorDescription) { + unimplemented(); + return {}; + } }; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnerBlueprintBase.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnerBlueprint.h similarity index 75% rename from Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnerBlueprintBase.h rename to Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnerBlueprint.h index af7769aa3..a75db3eaa 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnerBlueprintBase.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnerBlueprint.h @@ -9,27 +9,27 @@ #include "Carla/Actor/ActorSpawner.h" #include "Carla/Actor/ActorSpawnResult.h" -#include "ActorSpawnerBlueprintBase.generated.h" +#include "GameFramework/Actor.h" -/// Base class for Blueprints implementing IActorSpawner interface. +#include "ActorSpawnerBlueprint.generated.h" + +/// Base class for Blueprints implementing AActorSpawner interface. /// /// Blueprints deriving from this class are expected to override /// GenerateDefinitions and SpawnActor functions. -UCLASS(BlueprintType, Blueprintable) -class CARLA_API AActorSpawnerBlueprintBase - : public AActor, - public IActorSpawner +UCLASS(Abstract, BlueprintType, Blueprintable) +class CARLA_API AActorSpawnerBlueprint : public AActorSpawner { GENERATED_BODY() public: - virtual TArray MakeDefinitions() final + TArray MakeDefinitions() final { return GenerateDefinitions(); } - virtual FActorSpawnResult SpawnActor( + FActorSpawnResult SpawnActor( const FTransform &SpawnAtTransform, const FActorDescription &ActorDescription) final { diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.h index 7c55fea96..8a24220ef 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.h @@ -31,7 +31,7 @@ public: return MapName; } - void RegisterActorSpawner(IActorSpawner &ActorSpawner) + void RegisterActorSpawner(AActorSpawner &ActorSpawner) { ActorDispatcher.Bind(ActorSpawner); } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/TheNewCarlaGameModeBase.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/TheNewCarlaGameModeBase.cpp index cdbf2d8ac..b762837b8 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/TheNewCarlaGameModeBase.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/TheNewCarlaGameModeBase.cpp @@ -61,15 +61,15 @@ void ATheNewCarlaGameModeBase::SpawnActorSpawners() auto *World = GetWorld(); check(World != nullptr); - for (auto &SpawnerClass : BlueprintSpawners) + for (auto &SpawnerClass : ActorSpawners) { if (SpawnerClass != nullptr) { - auto *Spawner = World->SpawnActor(SpawnerClass); + auto *Spawner = World->SpawnActor(SpawnerClass); if (Spawner != nullptr) { Episode->RegisterActorSpawner(*Spawner); - BlueprintSpawnerInstances.Add(Spawner); + ActorSpawnerInstances.Add(Spawner); } else { diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/TheNewCarlaGameModeBase.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/TheNewCarlaGameModeBase.h index 23a5931d2..1412dcfa2 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/TheNewCarlaGameModeBase.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/TheNewCarlaGameModeBase.h @@ -6,7 +6,7 @@ #pragma once -#include "Carla/Actor/ActorSpawnerBlueprintBase.h" +#include "Carla/Actor/ActorSpawner.h" #include "Carla/Game/CarlaEpisode.h" #include "CoreMinimal.h" @@ -44,9 +44,11 @@ private: UPROPERTY() UCarlaEpisode *Episode = nullptr; + /// List of actor spawners that will be used to define and spawn the actors + /// available in game. UPROPERTY(EditAnywhere) - TArray> BlueprintSpawners; + TSet> ActorSpawners; UPROPERTY() - TArray BlueprintSpawnerInstances; + TArray ActorSpawnerInstances; }; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp index 55ec5ac24..eceb31ffd 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp @@ -28,6 +28,12 @@ static std::vector MakeVectorFromTArray(const TArray &Array) return {Array.GetData(), Array.GetData() + Array.Num()}; } +static void AttachActors(AActor *Child, AActor *Parent) +{ + Child->AttachToActor(Parent, FAttachmentTransformRules::KeepRelativeTransform); + Child->SetOwner(Parent); +} + // ============================================================================= // -- FTheNewCarlaServer::FPimpl ----------------------------------------------- // ============================================================================= @@ -64,6 +70,30 @@ private: RespondErrorStr("episode not ready"); } } + + auto SpawnActor(const FTransform &Transform, FActorDescription Description) + { + auto Result = Episode->SpawnActorWithInfo(Transform, std::move(Description)); + if (Result.Key != EActorSpawnResultStatus::Success) + { + RespondError(FActorSpawnResult::StatusToString(Result.Key)); + } + check(Result.Value.IsValid()); + return Result.Value; + } + + void AttachActors(FActorView Child, FActorView Parent) + { + if (!Child.IsValid()) + { + RespondError("unable to attach actor: child actor not found"); + } + if (!Parent.IsValid()) + { + RespondError("unable to attach actor: parent actor not found"); + } + ::AttachActors(Child.GetActor(), Parent.GetActor()); + } }; // ============================================================================= @@ -87,12 +117,24 @@ void FTheNewCarlaServer::FPimpl::BindActions() const cr::Transform &Transform, cr::ActorDescription Description) -> cr::Actor { RequireEpisode(); - auto Result = Episode->SpawnActorWithInfo(Transform, std::move(Description)); - if (Result.Key != EActorSpawnResultStatus::Success) - { - RespondError(FActorSpawnResult::StatusToString(Result.Key)); - } - return Result.Value; + return SpawnActor(Transform, Description); + }); + + Server.BindSync("spawn_actor_with_parent", [this]( + const cr::Transform &Transform, + cr::ActorDescription Description, + cr::Actor Parent) -> cr::Actor { + RequireEpisode(); + auto ActorView = SpawnActor(Transform, Description); + auto ParentActorView = Episode->GetActorRegistry().Find(Parent.id); + AttachActors(ActorView, ParentActorView); + return ActorView; + }); + + Server.BindSync("attach_actors", [this](cr::Actor Child, cr::Actor Parent) { + RequireEpisode(); + auto &Registry = Episode->GetActorRegistry(); + AttachActors(Registry.Find(Child.id), Registry.Find(Parent.id)); }); } From ab431e3847dfad1663cbfffa0aa05c89c84868ce Mon Sep 17 00:00:00 2001 From: nsubiron Date: Thu, 26 Jul 2018 17:49:57 +0200 Subject: [PATCH 27/71] Exposing cameras in Python API --- LibCarla/source/carla/Time.h | 2 +- LibCarla/source/carla/client/Actor.h | 12 ++- LibCarla/source/carla/client/Client.cpp | 4 + LibCarla/source/carla/client/Client.h | 11 +++ LibCarla/source/carla/client/Image.cpp | 85 +++++++++++++++++++ LibCarla/source/carla/client/Image.h | 83 ++++++++++++++++++ LibCarla/source/carla/client/Sensor.h | 37 ++++++++ LibCarla/source/carla/client/World.h | 14 ++- LibCarla/source/carla/rpc/Actor.h | 31 ++++++- LibCarla/source/carla/streaming/Client.h | 10 ++- LibCarla/source/carla/streaming/Message.h | 3 + LibCarla/source/carla/streaming/Stream.h | 6 +- LibCarla/source/carla/streaming/Token.h | 25 ++++++ .../source/carla/streaming/detail/Token.cpp | 11 +++ .../source/carla/streaming/detail/Token.h | 11 +-- LibCarla/source/compiler/disable-ue4-macros.h | 3 + LibCarla/source/compiler/enable-ue4-macros.h | 2 + PythonAPI/source/libcarla/Actor.cpp | 73 +++++++++++++++- PythonAPI/source/libcarla/libcarla.cpp | 1 + .../Source/Carla/Actor/ActorRegistry.cpp | 11 ++- .../Source/Carla/Sensor/SensorSpawner.cpp | 72 ++++++++++++++++ .../Carla/Source/Carla/Sensor/SensorSpawner.h | 27 ++++++ .../Source/Carla/Server/TheNewCarlaServer.cpp | 65 +++++++++++++- 23 files changed, 566 insertions(+), 33 deletions(-) create mode 100644 LibCarla/source/carla/client/Image.cpp create mode 100644 LibCarla/source/carla/client/Image.h create mode 100644 LibCarla/source/carla/client/Sensor.h create mode 100644 LibCarla/source/carla/streaming/Token.h create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SensorSpawner.cpp create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SensorSpawner.h diff --git a/LibCarla/source/carla/Time.h b/LibCarla/source/carla/Time.h index 74efb7423..612ab1d92 100644 --- a/LibCarla/source/carla/Time.h +++ b/LibCarla/source/carla/Time.h @@ -25,7 +25,7 @@ namespace carla { return std::chrono::milliseconds(timeout); } - constexpr time_duration() : _milliseconds(0u) {} + constexpr time_duration() noexcept : _milliseconds(0u) {} template time_duration(std::chrono::duration duration) diff --git a/LibCarla/source/carla/client/Actor.h b/LibCarla/source/carla/client/Actor.h index 59a55d5bb..879151ed7 100644 --- a/LibCarla/source/carla/client/Actor.h +++ b/LibCarla/source/carla/client/Actor.h @@ -23,6 +23,8 @@ namespace client { private NonCopyable { public: + virtual ~Actor() = default; + Actor(Actor &&) = default; Actor &operator=(Actor &&) = default; @@ -39,16 +41,14 @@ namespace client { } void ApplyControl(const VehicleControl &control) { - _world->ApplyControlToActor(*this, control); + _world->GetClient().ApplyControlToActor(*this, control); } const auto &Serialize() const { return _actor; } - private: - - friend class Client; + protected: Actor(carla::rpc::Actor actor, SharedPtr world) : _actor(actor), @@ -56,6 +56,10 @@ namespace client { DEBUG_ASSERT(_world != nullptr); } + private: + + friend class Client; + carla::rpc::Actor _actor; SharedPtr _world; diff --git a/LibCarla/source/carla/client/Client.cpp b/LibCarla/source/carla/client/Client.cpp index 81b3d5b30..f2f0c0545 100644 --- a/LibCarla/source/carla/client/Client.cpp +++ b/LibCarla/source/carla/client/Client.cpp @@ -8,6 +8,7 @@ #include "carla/client/Actor.h" #include "carla/client/Control.h" +#include "carla/client/Sensor.h" #include "carla/client/World.h" namespace carla { @@ -24,6 +25,9 @@ namespace client { const ActorBlueprint &blueprint, const Transform &transform) { auto actor = Call("spawn_actor", transform, blueprint.MakeActorDescription()); + if (actor.IsASensor()) { + return SharedPtr(new Sensor{actor, GetWorld()}); + } return SharedPtr(new Actor{actor, GetWorld()}); } diff --git a/LibCarla/source/carla/client/Client.h b/LibCarla/source/carla/client/Client.h index 34d992650..153194e40 100644 --- a/LibCarla/source/carla/client/Client.h +++ b/LibCarla/source/carla/client/Client.h @@ -13,8 +13,10 @@ #include "carla/client/Memory.h" #include "carla/client/Transform.h" #include "carla/rpc/Client.h" +#include "carla/streaming/Client.h" #include +#include namespace carla { namespace client { @@ -31,7 +33,9 @@ namespace client { template explicit Client(Args && ... args) : _client(std::forward(args) ...) { + /// @todo Make these arguments. SetTimeout(10'000); + _streaming_client.AsyncRun(std::thread::hardware_concurrency()); } void SetTimeout(int64_t milliseconds) { @@ -43,6 +47,11 @@ namespace client { return _client.call(function, std::forward(args) ...).template as(); } + template + void SubscribeToStream(const streaming::Token &token, Functor &&callback) { + _streaming_client.Subscribe(token, std::forward(callback)); + } + std::string GetClientVersion() const { return ::carla::version(); } @@ -74,6 +83,8 @@ namespace client { carla::rpc::Client _client; + carla::streaming::Client _streaming_client; + SharedPtr _active_world; }; diff --git a/LibCarla/source/carla/client/Image.cpp b/LibCarla/source/carla/client/Image.cpp new file mode 100644 index 000000000..086e5c13b --- /dev/null +++ b/LibCarla/source/carla/client/Image.cpp @@ -0,0 +1,85 @@ +// 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 . + +#include "carla/Debug.h" +#include "carla/client/Image.h" + +#include +#include + +namespace carla { +namespace client { + + /// @todo This object should be shared and packed. + struct FImageHeaderData + { + uint64_t FrameNumber; + uint32_t Width; + uint32_t Height; + uint32_t Type; + float FOV; + }; + + static std::string GetTypeString(uint32_t type) { + switch (type) { + case 0u: return "None"; + case 1u: return "SceneFinal"; + case 2u: return "Depth"; + case 3u: return "SemanticSegmentation"; + default: return "Invalid"; + } + } + + SharedPtr Image::FromBuffer(boost::asio::const_buffer buffer) { + if (buffer.size() < sizeof(FImageHeaderData)) { + throw std::invalid_argument("buffer too small to be an image"); + } + auto begin = reinterpret_cast(buffer.data()); + auto image = MakeShared(); + FImageHeaderData data; + std::memcpy(&data, begin, sizeof(data)); + image->_frame_number = data.FrameNumber; + image->_width = data.Width; + image->_height = data.Height; + image->_type = GetTypeString(data.Type); + image->_fov = data.FOV; + const auto size = image->GetSize(); + DEBUG_ASSERT((size + sizeof(FImageHeaderData)) == buffer.size()); + auto raw_data = std::make_unique(size); + std::memcpy(raw_data.get(), begin + sizeof(FImageHeaderData), size); + image->_raw_data = std::move(raw_data); + return image; + } + + Image::Image() { + Clear(); + } + + Image::Image(Image &&rhs) { + (*this) = std::move(rhs); + } + + Image &Image::operator=(Image &&rhs) { + _width = rhs._width; + _height = rhs._height; + _type = rhs._type; + _fov = rhs._fov; + _raw_data = std::move(rhs._raw_data); + rhs.Clear(); + return *this; + } + + void Image::Clear() { + _frame_number = 0u; + _width = 0u; + _height = 0u; + _type = "Invalid"; + _fov = 0.0f; + _raw_data = nullptr; + } + +} // namespace client +} // namespace carla diff --git a/LibCarla/source/carla/client/Image.h b/LibCarla/source/carla/client/Image.h new file mode 100644 index 000000000..48b9c3035 --- /dev/null +++ b/LibCarla/source/carla/client/Image.h @@ -0,0 +1,83 @@ +// 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 . + +#pragma once + +#include "carla/NonCopyable.h" +#include "carla/client/Memory.h" + +#include + +#include + +namespace carla { +namespace client { + + class Image + : public EnableSharedFromThis, + private NonCopyable { + public: + + using byte_type = unsigned char; + + static SharedPtr FromBuffer(boost::asio::const_buffer buffer); + + Image(); + + Image(Image &&rhs); + Image &operator=(Image &&rhs); + + void Clear(); + + size_t GetFrameNumber() const { + return _frame_number; + } + + size_t GetWidth() const { + return _width; + } + + size_t GetHeight() const { + return _height; + } + + const std::string &GetType() const { + return _type; + } + + float GetFOV() const { + return _fov; + } + + byte_type *GetData() { + return _raw_data.get(); + } + + const byte_type *GetData() const { + return _raw_data.get(); + } + + size_t GetSize() const { + return 4u * _width * _height; + } + + private: + + size_t _frame_number; + + size_t _width; + + size_t _height; + + std::string _type; + + float _fov; + + std::unique_ptr _raw_data; + }; + +} // namespace client +} // namespace carla diff --git a/LibCarla/source/carla/client/Sensor.h b/LibCarla/source/carla/client/Sensor.h new file mode 100644 index 000000000..7ed90a3b4 --- /dev/null +++ b/LibCarla/source/carla/client/Sensor.h @@ -0,0 +1,37 @@ +// 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 . + +#pragma once + +#include "carla/Logging.h" +#include "carla/client/Actor.h" + +namespace carla { +namespace client { + + class Sensor : public Actor { + public: + + template + void Listen(Functor callback) { + /// @todo should we check if we are already listening? + log_debug("sensor", GetId(), "type", GetTypeId(), ": subscribing to stream"); + GetWorld()->GetClient().SubscribeToStream(_stream_token, std::forward(callback)); + } + + private: + + friend class Client; + + Sensor(carla::rpc::Actor actor, SharedPtr world) + : Actor(actor, std::move(world)), + _stream_token(actor.GetStreamToken()) {} + + streaming::Token _stream_token; + }; + +} // namespace client +} // namespace carla diff --git a/LibCarla/source/carla/client/World.h b/LibCarla/source/carla/client/World.h index 7597dfe97..4710474d4 100644 --- a/LibCarla/source/carla/client/World.h +++ b/LibCarla/source/carla/client/World.h @@ -21,9 +21,6 @@ namespace client { private NonCopyable { public: - World(World &&) = default; - World &operator=(World &&) = default; - SharedPtr GetBlueprintLibrary() const { return _parent->GetBlueprintLibrary(); } @@ -38,17 +35,18 @@ namespace client { return _parent->SpawnActor(blueprint, transform); } - template - void ApplyControlToActor(const Actor &actor, const ControlType &control) { - _parent->ApplyControlToActor(actor, control); + Client &GetClient() const { + DEBUG_ASSERT(_parent != nullptr); + return *_parent; } private: friend class Client; - explicit World(SharedPtr parent) : _parent(std::move(parent)) { - DEBUG_ASSERT(parent != nullptr); + explicit World(SharedPtr parent) + : _parent(std::move(parent)) { + DEBUG_ASSERT(_parent != nullptr); } SharedPtr _parent; diff --git a/LibCarla/source/carla/rpc/Actor.h b/LibCarla/source/carla/rpc/Actor.h index 157c4bc87..aa271bcba 100644 --- a/LibCarla/source/carla/rpc/Actor.h +++ b/LibCarla/source/carla/rpc/Actor.h @@ -8,6 +8,9 @@ #include "carla/Debug.h" #include "carla/rpc/ActorDescription.h" +#include "carla/streaming/Token.h" + +#include namespace carla { namespace rpc { @@ -23,6 +26,25 @@ namespace rpc { ActorDescription description; + /// @todo This is only used by sensors actually. + /// @name Sensor functionality + /// @{ + + std::vector stream_token; + + bool IsASensor() const { + return stream_token.size() == sizeof(streaming::Token::data); + } + + streaming::Token GetStreamToken() const { + DEBUG_ASSERT(IsASensor()); + streaming::Token token; + std::memcpy(&token.data[0u], stream_token.data(), stream_token.size()); + return token; + } + + /// @} + #ifdef LIBCARLA_INCLUDED_FROM_UE4 Actor(FActorView View) @@ -31,9 +53,16 @@ namespace rpc { DEBUG_ASSERT(View.IsValid()); } + Actor(FActorView View, const streaming::Token &StreamToken) + : id(View.GetActorId()), + description(*View.GetActorDescription()), + stream_token(StreamToken.data.begin(), StreamToken.data.end()) { + DEBUG_ASSERT(View.IsValid()); + } + #endif // LIBCARLA_INCLUDED_FROM_UE4 - MSGPACK_DEFINE_ARRAY(id, description); + MSGPACK_DEFINE_ARRAY(id, description, stream_token); }; } // namespace rpc diff --git a/LibCarla/source/carla/streaming/Client.h b/LibCarla/source/carla/streaming/Client.h index d6c9c1834..16c5cb4f8 100644 --- a/LibCarla/source/carla/streaming/Client.h +++ b/LibCarla/source/carla/streaming/Client.h @@ -6,9 +6,11 @@ #pragma once +#include "carla/Logging.h" #include "carla/ThreadGroup.h" -#include "carla/streaming/low_level/Client.h" +#include "carla/streaming/Token.h" #include "carla/streaming/detail/tcp/Client.h" +#include "carla/streaming/low_level/Client.h" #include @@ -21,12 +23,14 @@ namespace streaming { class Client { public: + Client() : _io_service(), _work_to_do(_io_service) {} + ~Client() { Stop(); } template - void Subscribe(const stream_token &token, Functor &&callback) { + void Subscribe(const Token &token, Functor &&callback) { _client.Subscribe(_io_service, token, std::forward(callback)); } @@ -49,6 +53,8 @@ namespace streaming { boost::asio::io_service _io_service; + boost::asio::io_service::work _work_to_do; + ThreadGroup _workers; underlying_client _client; diff --git a/LibCarla/source/carla/streaming/Message.h b/LibCarla/source/carla/streaming/Message.h index 559d540bc..e4ae5713d 100644 --- a/LibCarla/source/carla/streaming/Message.h +++ b/LibCarla/source/carla/streaming/Message.h @@ -47,9 +47,12 @@ namespace streaming { explicit Message(uint64_t size) : Message([size]() { +#ifndef LIBCARLA_INCLUDED_FROM_UE4 + /// @todo What to do with exceptions? if (size > std::numeric_limits::max()) { throw std::invalid_argument("message size too big"); } +#endif // LIBCARLA_INCLUDED_FROM_UE4 return static_cast(size); } ()) {} diff --git a/LibCarla/source/carla/streaming/Stream.h b/LibCarla/source/carla/streaming/Stream.h index d33940135..fd8183eb1 100644 --- a/LibCarla/source/carla/streaming/Stream.h +++ b/LibCarla/source/carla/streaming/Stream.h @@ -8,8 +8,8 @@ #include "carla/Debug.h" #include "carla/streaming/Message.h" +#include "carla/streaming/Token.h" #include "carla/streaming/detail/StreamState.h" -#include "carla/streaming/detail/Token.h" #include @@ -24,8 +24,6 @@ namespace detail { } // namespace detail - using stream_token = detail::token_type; - class Stream { public: @@ -37,7 +35,7 @@ namespace detail { Stream &operator=(const Stream &) = default; Stream &operator=(Stream &&) = default; - stream_token token() const { + Token token() const { return _shared_state->token(); } diff --git a/LibCarla/source/carla/streaming/Token.h b/LibCarla/source/carla/streaming/Token.h new file mode 100644 index 000000000..906045621 --- /dev/null +++ b/LibCarla/source/carla/streaming/Token.h @@ -0,0 +1,25 @@ +// 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 . + +#pragma once + +#include "carla/rpc/MsgPack.h" + +#include + +namespace carla { +namespace streaming { + + class Token { + public: + + std::array data; + + MSGPACK_DEFINE_ARRAY(data); + }; + +} // namespace streaming +} // namespace carla diff --git a/LibCarla/source/carla/streaming/detail/Token.cpp b/LibCarla/source/carla/streaming/detail/Token.cpp index 2ac50c6e5..e5b6ec0da 100644 --- a/LibCarla/source/carla/streaming/detail/Token.cpp +++ b/LibCarla/source/carla/streaming/detail/Token.cpp @@ -6,6 +6,7 @@ #include "carla/streaming/detail/Token.h" +#include #include namespace carla { @@ -31,6 +32,16 @@ namespace detail { return boost::asio::ip::address_v6(_token.address.v6); } + token_type::token_type(const Token &rhs) { + std::memcpy(&_token, &rhs.data[0u], sizeof(_token)); + } + + token_type::operator Token() const { + Token token; + std::memcpy(&token.data[0u], &_token, token.data.size()); + return token; + } + } // namespace detail } // namespace streaming } // namespace carla diff --git a/LibCarla/source/carla/streaming/detail/Token.h b/LibCarla/source/carla/streaming/detail/Token.h index 5dc70464e..fe74918d8 100644 --- a/LibCarla/source/carla/streaming/detail/Token.h +++ b/LibCarla/source/carla/streaming/detail/Token.h @@ -7,6 +7,7 @@ #pragma once #include "carla/Debug.h" +#include "carla/streaming/Token.h" #include "carla/streaming/detail/Types.h" #include @@ -45,7 +46,7 @@ namespace detail { #pragma pack(pop) static_assert( - sizeof(token_data) == 24u, + sizeof(token_data) == sizeof(Token::data), "Size shouldn't be more than" " v6 address : 128" " + state : 16" @@ -92,6 +93,10 @@ namespace detail { token_type() = default; token_type(const token_type &) = default; + token_type(const Token &rhs); + + operator Token() const; + auto get_stream_id() const { return _token.stream_id; } @@ -129,10 +134,6 @@ namespace detail { return get_endpoint(); } - boost::asio::const_buffer as_buffer() const { - return boost::asio::buffer(&_token, sizeof(_token)); - } - private: friend class Dispatcher; diff --git a/LibCarla/source/compiler/disable-ue4-macros.h b/LibCarla/source/compiler/disable-ue4-macros.h index 8051a982b..f53c60ef7 100644 --- a/LibCarla/source/compiler/disable-ue4-macros.h +++ b/LibCarla/source/compiler/disable-ue4-macros.h @@ -13,6 +13,9 @@ #pragma push_macro("check") #undef check +#pragma clang diagnostic push +#pragma clang diagnostic ignored "-Wmissing-braces" + #define LIBCARLA_INCLUDED_FROM_UE4 #ifndef BOOST_ERROR_CODE_HEADER_ONLY diff --git a/LibCarla/source/compiler/enable-ue4-macros.h b/LibCarla/source/compiler/enable-ue4-macros.h index b084365f8..5d2e09698 100644 --- a/LibCarla/source/compiler/enable-ue4-macros.h +++ b/LibCarla/source/compiler/enable-ue4-macros.h @@ -6,4 +6,6 @@ #pragma pop_macro("check") +#pragma clang diagnostic pop + #undef LIBCARLA_INCLUDED_FROM_UE4 diff --git a/PythonAPI/source/libcarla/Actor.cpp b/PythonAPI/source/libcarla/Actor.cpp index 342f9a9f7..3040727a8 100644 --- a/PythonAPI/source/libcarla/Actor.cpp +++ b/PythonAPI/source/libcarla/Actor.cpp @@ -5,16 +5,43 @@ // For a copy, see . #include +#include +#include #include #include +#include + +/// Aquires a lock on the Python's Global Interpreter Lock, necessary for +/// calling Python code from a different thread. +/// +/// https://wiki.python.org/moin/GlobalInterpreterLock +class GILLockGuard { +public: + + GILLockGuard() + : _state(PyGILState_Ensure()) {} + + ~GILLockGuard() { + PyGILState_Release(_state); + } + +private: + + PyGILState_STATE _state; +}; namespace carla { namespace client { std::ostream &operator<<(std::ostream &out, const Actor &actor) { - out << "Actor(id=" << actor.GetId() /*<< ", type_id=" << actor.GetTypeId()*/ << ')'; + out << "Actor(id=" << actor.GetId() << ", type=" << actor.GetTypeId() << ')'; + return out; + } + + std::ostream &operator<<(std::ostream &out, const Sensor &sensor) { + out << "Sensor(id=" << sensor.GetId() << ", type=" << sensor.GetTypeId() << ')'; return out; } @@ -25,14 +52,56 @@ void export_actor() { using namespace boost::python; namespace cc = carla::client; + class_>("Image", no_init) + .add_property("frame_number", &cc::Image::GetFrameNumber) + .add_property("width", &cc::Image::GetWidth) + .add_property("height", &cc::Image::GetHeight) + .add_property("type", +[](const cc::Image &self) -> std::string { + return self.GetType(); + }) + .add_property("fov", &cc::Image::GetFOV) + .add_property("raw_data", +[](cc::Image &self) { + auto *ptr = PyBuffer_FromMemory(self.GetData(), self.GetSize()); + return object(handle<>(ptr)); + }) + ; + class_>("Actor", no_init) .add_property("id", &cc::Actor::GetId) .add_property("type_id", +[](const cc::Actor &self) -> std::string { - // Needs to copy the string by value. return self.GetTypeId(); }) .def("get_world", &cc::Actor::GetWorld) .def("apply_control", &cc::Actor::ApplyControl) .def(self_ns::str(self_ns::self)) ; + + class_, boost::noncopyable, boost::shared_ptr>("Sensor", no_init) + .def("listen", +[](cc::Sensor &self, boost::python::object callback) { + // Make sure the callback is actually callable. + if (!PyCallable_Check(callback.ptr())) { + PyErr_SetString(PyExc_TypeError, "callback argument must be callable!"); + throw_error_already_set(); + return; + } + + // Subscribe to the sensor. + self.Listen([callback](auto message) { + cc::SharedPtr image; + try { + image = cc::Image::FromBuffer(message->buffer()); + } catch (const std::exception &e) { + std::cerr << "exception while parsing the image: " << e.what() << std::endl; + return; + } + + GILLockGuard gil_lock; + try { + call(callback.ptr(), object(image)); + } catch (const error_already_set &e) { + PyErr_Print(); + } + }); + }) + ; } diff --git a/PythonAPI/source/libcarla/libcarla.cpp b/PythonAPI/source/libcarla/libcarla.cpp index 34c38c751..8f53449d0 100644 --- a/PythonAPI/source/libcarla/libcarla.cpp +++ b/PythonAPI/source/libcarla/libcarla.cpp @@ -16,6 +16,7 @@ BOOST_PYTHON_MODULE(libcarla) { using namespace boost::python; + PyEval_InitThreads(); scope().attr("__path__") = "libcarla"; export_transform(); export_control(); diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorRegistry.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorRegistry.cpp index 7d4d70ac0..c318dbc09 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorRegistry.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorRegistry.cpp @@ -14,11 +14,19 @@ FActorView FActorRegistry::Register(AActor &Actor, FActorDescription Description static IdType ID_COUNTER = 0u; const auto Id = ++ID_COUNTER; Actors.Emplace(Id, &Actor); + if (Ids.Contains(&Actor)) + { + UE_LOG( + LogCarla, + Warning, + TEXT("This actor's memory address is already registered, " + "either you forgot to deregister the actor " + "or the actor was garbage collected.")); + } Ids.Emplace(&Actor, Id); auto Result = ActorDatabase.emplace(Id, FActorView(Id, Actor, std::move(Description))); check(Result.second); check(static_cast(Actors.Num()) == ActorDatabase.size()); - check(static_cast(Ids.Num()) == ActorDatabase.size()); return Result.first->second; } @@ -31,7 +39,6 @@ void FActorRegistry::Deregister(IdType Id) Actors.Remove(Id); Ids.Remove(Actor); check(static_cast(Actors.Num()) == ActorDatabase.size()); - check(static_cast(Ids.Num()) == ActorDatabase.size()); } void FActorRegistry::Deregister(AActor *Actor) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SensorSpawner.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SensorSpawner.cpp new file mode 100644 index 000000000..8e68d80d9 --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SensorSpawner.cpp @@ -0,0 +1,72 @@ +// 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 . + +#include "Carla.h" +#include "Carla/Sensor/SensorSpawner.h" + +#include "Carla/Sensor/SceneCaptureCamera.h" + +template +static FActorDefinition MakeSensorDefinition(const FString &Id) +{ + FActorDefinition Definition; + Definition.Id = Id; + Definition.Class = T::StaticClass(); + Definition.Tags = TEXT("sensor,") + Id; + return Definition; +} + +TArray ASensorSpawner::MakeDefinitions() +{ + // Cameras. + auto Cameras = MakeSensorDefinition("camera"); + { + FActorVariation PostProcessing; + PostProcessing.Id = TEXT("PostProcessing"); + PostProcessing.Type = EActorAttributeType::String; + PostProcessing.RecommendedValues = { + TEXT("None"), + TEXT("SceneFinal"), + TEXT("Depth"), + TEXT("SemanticSegmentation") + }; + PostProcessing.bRestrictToRecommended = true; + FActorVariation FOV; + FOV.Id = TEXT("FOV"); + FOV.Type = EActorAttributeType::Float; + FOV.RecommendedValues = { TEXT("90.0") }; + FOV.bRestrictToRecommended = false; + FActorVariation ResX; + ResX.Id = TEXT("ImageSizeX"); + ResX.Type = EActorAttributeType::Int; + ResX.RecommendedValues = { TEXT("800") }; + ResX.bRestrictToRecommended = false; + FActorVariation ResY; + ResY.Id = TEXT("ImageSizeY"); + ResY.Type = EActorAttributeType::Int; + ResY.RecommendedValues = { TEXT("600") }; + ResY.bRestrictToRecommended = false; + Cameras.Variations = {PostProcessing, ResX, ResY, FOV}; + } + return {Cameras}; +} + +FActorSpawnResult ASensorSpawner::SpawnActor( + const FTransform &Transform, + const FActorDescription &Description) +{ + FActorSpawnParameters Params; + static int32 COUNTER = 0u; + Params.Name = FName(*(Description.Id + FString::FromInt(++COUNTER))); + auto *World = GetWorld(); + if (World == nullptr) + { + return {}; + } + auto *Sensor = World->SpawnActor(Description.Class, Transform, Params); + /// @todo Set description: Actor->Set(Description); + return FActorSpawnResult{Sensor}; +} diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SensorSpawner.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SensorSpawner.h new file mode 100644 index 000000000..f1237b5c2 --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SensorSpawner.h @@ -0,0 +1,27 @@ +// 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 . + +#pragma once + +#include "Carla/Actor/ActorSpawner.h" +#include "Carla/Actor/ActorSpawnResult.h" + +#include "GameFramework/Actor.h" + +#include "SensorSpawner.generated.h" + +/// Object in charge of spawning sensors. +UCLASS() +class CARLA_API ASensorSpawner : public AActorSpawner +{ + GENERATED_BODY() + + TArray MakeDefinitions() final; + + FActorSpawnResult SpawnActor( + const FTransform &SpawnAtTransform, + const FActorDescription &ActorDescription) final; +}; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp index eceb31ffd..46a2b522d 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp @@ -7,6 +7,8 @@ #include "Carla.h" #include "TheNewCarlaServer.h" +#include "Carla/Sensor/Sensor.h" + #include #include #include @@ -14,6 +16,7 @@ #include #include #include +#include #include #include @@ -34,6 +37,36 @@ static void AttachActors(AActor *Child, AActor *Parent) Child->SetOwner(Parent); } +// ============================================================================= +// -- FStreamingSensorDataSink ------------------------------------------------- +// ============================================================================= + +class FStreamingSensorDataSink : public ISensorDataSink { +public: + + FStreamingSensorDataSink(carla::streaming::Stream InStream) + : TheStream(InStream) {} + + ~FStreamingSensorDataSink() + { + UE_LOG(LogCarlaServer, Log, TEXT("Destroying sensor data sink")); + } + + void Write(const FSensorDataView &SensorData) final { + auto MakeBuffer = [](FReadOnlyBufferView View) { + return boost::asio::buffer(View.GetData(), View.GetSize()); + }; + std::array SequencedBuffer; + SequencedBuffer[0u] = MakeBuffer(SensorData.GetHeader()); + SequencedBuffer[1u] = MakeBuffer(SensorData.GetData()); + TheStream.Write(SequencedBuffer); + } + +private: + + carla::streaming::Stream TheStream; +}; + // ============================================================================= // -- FTheNewCarlaServer::FPimpl ----------------------------------------------- // ============================================================================= @@ -42,12 +75,16 @@ class FTheNewCarlaServer::FPimpl { public: - FPimpl(uint16_t port) : Server(port) { + FPimpl(uint16_t port) + : Server(port), + StreamingServer(port + 1u) { BindActions(); } carla::rpc::Server Server; + carla::streaming::Server StreamingServer; + UCarlaEpisode *Episode = nullptr; private: @@ -94,6 +131,22 @@ private: } ::AttachActors(Child.GetActor(), Parent.GetActor()); } + + carla::rpc::Actor SerializeActor(FActorView ActorView) + { + if (ActorView.IsValid()) + { + auto *Sensor = Cast(ActorView.GetActor()); + if (Sensor != nullptr) + { + UE_LOG(LogCarlaServer, Log, TEXT("Making a new sensor stream for actor '%s'"), *ActorView.GetActorDescription()->Id); + auto Stream = StreamingServer.MakeStream(); + Sensor->SetSensorDataSink(MakeShared(Stream)); + return {ActorView, Stream.token()}; + } + } + return ActorView; + } }; // ============================================================================= @@ -117,7 +170,7 @@ void FTheNewCarlaServer::FPimpl::BindActions() const cr::Transform &Transform, cr::ActorDescription Description) -> cr::Actor { RequireEpisode(); - return SpawnActor(Transform, Description); + return SerializeActor(SpawnActor(Transform, Description)); }); Server.BindSync("spawn_actor_with_parent", [this]( @@ -128,7 +181,7 @@ void FTheNewCarlaServer::FPimpl::BindActions() auto ActorView = SpawnActor(Transform, Description); auto ParentActorView = Episode->GetActorRegistry().Find(Parent.id); AttachActors(ActorView, ParentActorView); - return ActorView; + return SerializeActor(ActorView); }); Server.BindSync("attach_actors", [this](cr::Actor Child, cr::Actor Parent) { @@ -165,7 +218,11 @@ void FTheNewCarlaServer::NotifyEndEpisode() void FTheNewCarlaServer::AsyncRun(uint32 NumberOfWorkerThreads) { - Pimpl->Server.AsyncRun(NumberOfWorkerThreads); + /// @todo Define better the number of threads each server gets. + auto RPCThreads = NumberOfWorkerThreads / 2u; + auto StreamingThreads = NumberOfWorkerThreads - RPCThreads; + Pimpl->Server.AsyncRun(std::max(2u, RPCThreads)); + Pimpl->StreamingServer.AsyncRun(std::max(2u, StreamingThreads)); } void FTheNewCarlaServer::RunSome(uint32 Milliseconds) From 4f9299c2b564cf2246d4c5ca60f28ec2995bc890 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Thu, 26 Jul 2018 17:51:33 +0200 Subject: [PATCH 28/71] Compile all client code with setup.py and custom boost version --- LibCarla/cmake/client/CMakeLists.txt | 42 ++++++++++++++++++++++++---- LibCarla/cmake/server/CMakeLists.txt | 9 ++++++ PythonAPI/setup.py | 17 ++++++----- Util/BuildTools/Check.sh | 2 +- Util/BuildTools/Linux.mk | 2 +- Util/BuildTools/Setup.sh | 25 +++++++++++++++-- 6 files changed, 81 insertions(+), 16 deletions(-) diff --git a/LibCarla/cmake/client/CMakeLists.txt b/LibCarla/cmake/client/CMakeLists.txt index 396fb61ce..a88759ec8 100644 --- a/LibCarla/cmake/client/CMakeLists.txt +++ b/LibCarla/cmake/client/CMakeLists.txt @@ -11,7 +11,11 @@ file(GLOB libcarla_sources file(GLOB_RECURSE libcarla_client_sources "${libcarla_source_path}/carla/client/*.h" - "${libcarla_source_path}/carla/client/*.cpp") + "${libcarla_source_path}/carla/client/*.cpp" + "${libcarla_source_path}/carla/rpc/*.h" + "${libcarla_source_path}/carla/rpc/*.cpp" + "${libcarla_source_path}/carla/streaming/*.h" + "${libcarla_source_path}/carla/streaming/*.cpp") # Create targets for debug and release in the same build type. foreach(target carla_client_debug carla_client) @@ -33,14 +37,42 @@ set_target_properties(carla_client PROPERTIES COMPILE_FLAGS ${CMAKE_CXX_FLAGS_RE # Install headers. -file(GLOB libcarla_carla_headers "${libcarla_source_path}/carla/*.h") +install(DIRECTORY "${BOOST_INCLUDE_PATH}/boost" DESTINATION include) + +file(GLOB boost_libraries "${BOOST_LIB_PATH}/*") +install(FILES ${boost_libraries} DESTINATION lib) + +file(GLOB libcarla_carla_headers + "${libcarla_source_path}/carla/*.cpp" + "${libcarla_source_path}/carla/*.h") install(FILES ${libcarla_carla_headers} DESTINATION include/carla) -file(GLOB libcarla_carla_client_headers "${libcarla_source_path}/carla/client/*.h") +file(GLOB libcarla_carla_client_headers + "${libcarla_source_path}/carla/client/*.cpp" + "${libcarla_source_path}/carla/client/*.h") install(FILES ${libcarla_carla_client_headers} DESTINATION include/carla/client) -file(GLOB libcarla_carla_rpc_headers "${libcarla_source_path}/carla/rpc/*.h") +file(GLOB libcarla_carla_rpc_headers + "${libcarla_source_path}/carla/rpc/*.cpp" + "${libcarla_source_path}/carla/rpc/*.h") install(FILES ${libcarla_carla_rpc_headers} DESTINATION include/carla/rpc) -file(GLOB libcarla_carla_streaming_headers "${libcarla_source_path}/carla/streaming/*.h") +file(GLOB libcarla_carla_streaming_headers + "${libcarla_source_path}/carla/streaming/*.cpp" + "${libcarla_source_path}/carla/streaming/*.h") install(FILES ${libcarla_carla_streaming_headers} DESTINATION include/carla/streaming) + +file(GLOB libcarla_carla_streaming_detail_headers + "${libcarla_source_path}/carla/streaming/detail/*.cpp" + "${libcarla_source_path}/carla/streaming/detail/*.h") +install(FILES ${libcarla_carla_streaming_detail_headers} DESTINATION include/carla/streaming/detail) + +file(GLOB libcarla_carla_streaming_detail_tcp_headers + "${libcarla_source_path}/carla/streaming/detail/tcp/*.cpp" + "${libcarla_source_path}/carla/streaming/detail/tcp/*.h") +install(FILES ${libcarla_carla_streaming_detail_tcp_headers} DESTINATION include/carla/streaming/detail/tcp) + +file(GLOB libcarla_carla_streaming_low_level_headers + "${libcarla_source_path}/carla/streaming/low_level/*.cpp" + "${libcarla_source_path}/carla/streaming/low_level/*.h") +install(FILES ${libcarla_carla_streaming_low_level_headers} DESTINATION include/carla/streaming/low_level) diff --git a/LibCarla/cmake/server/CMakeLists.txt b/LibCarla/cmake/server/CMakeLists.txt index 56a1bbac7..fbb5b5650 100644 --- a/LibCarla/cmake/server/CMakeLists.txt +++ b/LibCarla/cmake/server/CMakeLists.txt @@ -22,6 +22,15 @@ install(FILES ${libcarla_carla_rpc_headers} DESTINATION include/carla/rpc) file(GLOB libcarla_carla_streaming_headers "${libcarla_source_path}/carla/streaming/*.h") install(FILES ${libcarla_carla_streaming_headers} DESTINATION include/carla/streaming) +file(GLOB libcarla_carla_streaming_detail_headers "${libcarla_source_path}/carla/streaming/detail/*.h") +install(FILES ${libcarla_carla_streaming_detail_headers} DESTINATION include/carla/streaming/detail) + +file(GLOB libcarla_carla_streaming_detail_tcp_headers "${libcarla_source_path}/carla/streaming/detail/tcp/*.h") +install(FILES ${libcarla_carla_streaming_detail_tcp_headers} DESTINATION include/carla/streaming/detail/tcp) + +file(GLOB libcarla_carla_streaming_low_level_headers "${libcarla_source_path}/carla/streaming/low_level/*.h") +install(FILES ${libcarla_carla_streaming_low_level_headers} DESTINATION include/carla/streaming/low_level) + install(DIRECTORY "${BOOST_INCLUDE_PATH}/boost" DESTINATION include) # carla_server library. diff --git a/PythonAPI/setup.py b/PythonAPI/setup.py index f80ec5d8d..e38c4d9de 100644 --- a/PythonAPI/setup.py +++ b/PythonAPI/setup.py @@ -30,26 +30,29 @@ def get_libcarla_extensions(): for filename in fnmatch.filter(filenames, file_filter): yield os.path.join(root, filename) - depends = [x for x in walk('dependencies')] - depends += [x for x in walk('source/libcarla')] + depends = [x for x in walk('source/libcarla')] + depends += [x for x in walk('dependencies')] def make_extension(name, sources): return Extension( name, sources=sources, include_dirs=[ - '/usr/local/include', 'dependencies/include'], library_dirs=[ - '/usr/local/lib/boost', 'dependencies/lib'], - runtime_library_dirs=['/usr/local/lib/boost'], + runtime_library_dirs=['dependencies/lib'], libraries=libraries, - extra_compile_args=['-fPIC', '-std=c++14'], + extra_compile_args=['-fPIC', '-std=c++14', '-DBOOST_ERROR_CODE_HEADER_ONLY', '-Wno-missing-braces'], language='c++14', depends=depends) - return [make_extension('carla.libcarla', ['source/libcarla/libcarla.cpp'])] + sources = ['source/libcarla/libcarla.cpp'] + sources += [x for x in walk('dependencies/include', '*.cpp')] + + print('compiling:\n - %s' % '\n - '.join(sources)) + + return [make_extension('carla.libcarla', sources)] setup( diff --git a/Util/BuildTools/Check.sh b/Util/BuildTools/Check.sh index c31b8420a..41feed55a 100755 --- a/Util/BuildTools/Check.sh +++ b/Util/BuildTools/Check.sh @@ -52,7 +52,7 @@ while true; do LIBCARLA_RELEASE=true; LIBCARLA_DEBUG=true; PYTHON_API_2=true; - PYTHON_API_3=true; + PYTHON_API_3=false; # @todo Python 3 not supported yet. shift ;; --libcarla-release ) LIBCARLA_RELEASE=true; diff --git a/Util/BuildTools/Linux.mk b/Util/BuildTools/Linux.mk index a1100969e..130727c94 100644 --- a/Util/BuildTools/Linux.mk +++ b/Util/BuildTools/Linux.mk @@ -44,7 +44,7 @@ CarlaUE4Editor: LibCarla .PHONY: PythonAPI PythonAPI: LibCarla - @${CARLA_BUILD_TOOLS_FOLDER}/BuildPythonAPI.sh --py2 --py3 + @${CARLA_BUILD_TOOLS_FOLDER}/BuildPythonAPI.sh --py2 .PHONY: LibCarla LibCarla: setup diff --git a/Util/BuildTools/Setup.sh b/Util/BuildTools/Setup.sh index ea4157385..db0ca3943 100755 --- a/Util/BuildTools/Setup.sh +++ b/Util/BuildTools/Setup.sh @@ -74,19 +74,39 @@ unset LLVM_BASENAME BOOST_BASENAME=boost-1.67.0 BOOST_INCLUDE=${PWD}/${BOOST_BASENAME}-install/include +BOOST_LIBPATH=${PWD}/${BOOST_BASENAME}-install/lib if [[ -d "${BOOST_BASENAME}-install" ]] ; then log "${BOOST_BASENAME} already installed." else + rm -Rf ${BOOST_BASENAME}-source + log "Retrieving boost." wget https://dl.bintray.com/boostorg/release/1.67.0/source/boost_1_67_0.tar.gz log "Extracting boost." tar -xzf boost_1_67_0.tar.gz rm boost_1_67_0.tar.gz mkdir -p ${BOOST_BASENAME}-install/include - mv boost_1_67_0/boost ${BOOST_BASENAME}-install/include/ - rm -Rf boost_1_67_0 + mv boost_1_67_0 ${BOOST_BASENAME}-source + # rm -Rf boost_1_67_0 + + pushd ${BOOST_BASENAME}-source >/dev/null + + BOOST_TOOLSET="clang-5.0" + BOOST_CFLAGS="-fPIC -std=c++14 -DBOOST_ERROR_CODE_HEADER_ONLY" + + ./bootstrap.sh \ + --with-toolset=clang \ + --prefix=../boost-install \ + --with-libraries=python + ./b2 clean + ./b2 toolset="${BOOST_TOOLSET}" cxxflags="${BOOST_CFLAGS}" --prefix="../${BOOST_BASENAME}-install" -j 12 stage release + ./b2 install toolset="${BOOST_TOOLSET}" cxxflags="${BOOST_CFLAGS}" --prefix="../${BOOST_BASENAME}-install" -j 12 + + popd >/dev/null + + rm -Rf ${BOOST_BASENAME}-source fi @@ -250,6 +270,7 @@ elseif (CMAKE_BUILD_TYPE STREQUAL "Client") # Here libraries linking libstdc++. set(RPCLIB_INCLUDE_PATH "${RPCLIB_LIBSTDCXX_INCLUDE}") set(RPCLIB_LIB_PATH "${RPCLIB_LIBSTDCXX_LIBPATH}") + set(BOOST_LIB_PATH "${BOOST_LIBPATH}") endif () EOL From 2d84d242070aed54d87052aef9a73bf8cfa21403 Mon Sep 17 00:00:00 2001 From: danil-tolkachev Date: Thu, 28 Jun 2018 09:57:51 +0300 Subject: [PATCH 29/71] add default values to CarlaMap class and remove copy-pasted ones --- PythonClient/carla/planner/city_track.py | 7 +------ PythonClient/carla/planner/map.py | 2 +- PythonClient/manual_control.py | 2 +- PythonClient/view_start_positions.py | 2 +- 4 files changed, 4 insertions(+), 9 deletions(-) diff --git a/PythonClient/carla/planner/city_track.py b/PythonClient/carla/planner/city_track.py index 3751c0d29..316f8a6f2 100644 --- a/PythonClient/carla/planner/city_track.py +++ b/PythonClient/carla/planner/city_track.py @@ -13,12 +13,7 @@ from carla.planner.map import CarlaMap class CityTrack(object): def __init__(self, city_name): - - # These values are fixed for every city. - self._node_density = 50.0 - self._pixel_density = 0.1643 - - self._map = CarlaMap(city_name, self._pixel_density, self._node_density) + self._map = CarlaMap(city_name) self._astar = AStar() diff --git a/PythonClient/carla/planner/map.py b/PythonClient/carla/planner/map.py index 0351e9e3b..67404e1fb 100644 --- a/PythonClient/carla/planner/map.py +++ b/PythonClient/carla/planner/map.py @@ -31,7 +31,7 @@ def color_to_angle(color): class CarlaMap(object): - def __init__(self, city, pixel_density, node_density): + def __init__(self, city, pixel_density=0.1643, node_density=50): dir_path = os.path.dirname(__file__) city_file = os.path.join(dir_path, city + '.txt') diff --git a/PythonClient/manual_control.py b/PythonClient/manual_control.py index 4f5190a25..a727bbb37 100755 --- a/PythonClient/manual_control.py +++ b/PythonClient/manual_control.py @@ -170,7 +170,7 @@ class CarlaGame(object): self._on_new_episode() if self._city_name is not None: - self._map = CarlaMap(self._city_name, 0.1643, 50.0) + self._map = CarlaMap(self._city_name) self._map_shape = self._map.map_image.shape self._map_view = self._map.get_map(WINDOW_HEIGHT) diff --git a/PythonClient/view_start_positions.py b/PythonClient/view_start_positions.py index 6a12e02af..629a79985 100755 --- a/PythonClient/view_start_positions.py +++ b/PythonClient/view_start_positions.py @@ -39,7 +39,7 @@ def view_start_positions(args): try: image = mpimg.imread('carla/planner/%s.png' % scene.map_name) - carla_map = CarlaMap(scene.map_name, 0.1653, 50) + carla_map = CarlaMap(scene.map_name) except IOError as exception: logging.error(exception) logging.error('Cannot find map "%s"', scene.map_name) From e211ffdd80d0c4bf96d7e9ff6c789324037bc263 Mon Sep 17 00:00:00 2001 From: danil-tolkachev Date: Thu, 28 Jun 2018 10:01:49 +0300 Subject: [PATCH 30/71] remove hard-coded height in pixel_to_world transformaton --- PythonClient/carla/planner/converter.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/PythonClient/carla/planner/converter.py b/PythonClient/carla/planner/converter.py index d33c8bada..95a774b73 100644 --- a/PythonClient/carla/planner/converter.py +++ b/PythonClient/carla/planner/converter.py @@ -124,7 +124,7 @@ class Converter(object): world = [ relative_location[0] + self._mapoffset[0] - self._worldoffset[0], relative_location[1] + self._mapoffset[1] - self._worldoffset[1], - 22 + self._mapoffset[2] - self._worldoffset[2] ] return world From ad8487b4102c5efbaad8c1c337c0e8fe58ba0b23 Mon Sep 17 00:00:00 2001 From: danil-tolkachev Date: Thu, 28 Jun 2018 10:07:28 +0300 Subject: [PATCH 31/71] add get_map_resolution to CarlaMap --- PythonClient/carla/planner/converter.py | 3 +++ PythonClient/carla/planner/map.py | 4 +++- 2 files changed, 6 insertions(+), 1 deletion(-) diff --git a/PythonClient/carla/planner/converter.py b/PythonClient/carla/planner/converter.py index 95a774b73..f9ffff982 100644 --- a/PythonClient/carla/planner/converter.py +++ b/PythonClient/carla/planner/converter.py @@ -90,6 +90,9 @@ class Converter(object): else: raise ValueError('Invalid node to be converted') + def get_map_resolution(self): + return self._pixel_density + def _node_to_pixel(self, node): """ Conversion from node format (graph) to pixel (image) diff --git a/PythonClient/carla/planner/map.py b/PythonClient/carla/planner/map.py index 67404e1fb..59fb06f87 100644 --- a/PythonClient/carla/planner/map.py +++ b/PythonClient/carla/planner/map.py @@ -64,9 +64,11 @@ class CarlaMap(object): self.map_image_center = np.asarray(self.map_image_center, dtype="int32") def get_graph_resolution(self): - return self._graph.get_resolution() + def get_map_resolution(self): + return self._converter.get_map_resolution() + def get_map(self, height=None): if height is not None: img = Image.fromarray(self.map_image.astype(np.uint8)) From 3f81303cbf4cb4595aa5154480eda20e63fe86b4 Mon Sep 17 00:00:00 2001 From: danil-tolkachev Date: Thu, 28 Jun 2018 11:04:42 +0300 Subject: [PATCH 32/71] fix mistakes --- PythonClient/carla/planner/city_track.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/PythonClient/carla/planner/city_track.py b/PythonClient/carla/planner/city_track.py index 316f8a6f2..74f7e3b99 100644 --- a/PythonClient/carla/planner/city_track.py +++ b/PythonClient/carla/planner/city_track.py @@ -48,10 +48,10 @@ class CityTrack(object): return self._map.get_intersection_nodes() def get_pixel_density(self): - return self._pixel_density + return self._map.get_map_resolution() def get_node_density(self): - return self._node_density + return self._map.get_graph_resolution() def is_at_goal(self, source, target): return source == target From f89f7288716343daceca45534f852ac586bc65a3 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Thu, 26 Jul 2018 20:37:15 +0200 Subject: [PATCH 33/71] Add function to spawn actor attached to another actor --- LibCarla/source/carla/client/Client.cpp | 7 +++++-- LibCarla/source/carla/client/Client.h | 3 ++- LibCarla/source/carla/client/World.cpp | 9 +++++---- LibCarla/source/carla/client/World.h | 8 +++++--- PythonAPI/source/libcarla/World.cpp | 6 ++++-- 5 files changed, 21 insertions(+), 12 deletions(-) diff --git a/LibCarla/source/carla/client/Client.cpp b/LibCarla/source/carla/client/Client.cpp index f2f0c0545..70ab33ad0 100644 --- a/LibCarla/source/carla/client/Client.cpp +++ b/LibCarla/source/carla/client/Client.cpp @@ -23,8 +23,11 @@ namespace client { SharedPtr Client::SpawnActor( const ActorBlueprint &blueprint, - const Transform &transform) { - auto actor = Call("spawn_actor", transform, blueprint.MakeActorDescription()); + const Transform &transform, + Actor *parent) { + auto actor = parent != nullptr ? + Call("spawn_actor_with_parent", transform, blueprint.MakeActorDescription(), parent->Serialize()) : + Call("spawn_actor", transform, blueprint.MakeActorDescription()); if (actor.IsASensor()) { return SharedPtr(new Sensor{actor, GetWorld()}); } diff --git a/LibCarla/source/carla/client/Client.h b/LibCarla/source/carla/client/Client.h index 153194e40..faa3accc2 100644 --- a/LibCarla/source/carla/client/Client.h +++ b/LibCarla/source/carla/client/Client.h @@ -73,7 +73,8 @@ namespace client { SharedPtr SpawnActor( const ActorBlueprint &blueprint, - const Transform &transform); + const Transform &transform, + Actor *parent = nullptr); void ApplyControlToActor( const Actor &actor, diff --git a/LibCarla/source/carla/client/World.cpp b/LibCarla/source/carla/client/World.cpp index 0b720149e..bd2b8bc26 100644 --- a/LibCarla/source/carla/client/World.cpp +++ b/LibCarla/source/carla/client/World.cpp @@ -13,11 +13,12 @@ namespace client { SharedPtr World::TrySpawnActor( const ActorBlueprint &blueprint, - const Transform &transform) { + const Transform &transform, + Actor *parent) { try { - return SpawnActor(blueprint, transform); - } catch (const std::exception & DEBUG_ONLY(e)) { - DEBUG_ONLY(log_debug("TrySpawnActor: failed with:", e.what())); + return SpawnActor(blueprint, transform, parent); + } catch (const std::exception &e) { + log_warning("TrySpawnActor: failed with:", e.what()); return nullptr; } } diff --git a/LibCarla/source/carla/client/World.h b/LibCarla/source/carla/client/World.h index 4710474d4..a23cb8412 100644 --- a/LibCarla/source/carla/client/World.h +++ b/LibCarla/source/carla/client/World.h @@ -27,12 +27,14 @@ namespace client { SharedPtr TrySpawnActor( const ActorBlueprint &blueprint, - const Transform &transform); + const Transform &transform, + Actor *parent = nullptr); SharedPtr SpawnActor( const ActorBlueprint &blueprint, - const Transform &transform) { - return _parent->SpawnActor(blueprint, transform); + const Transform &transform, + Actor *parent = nullptr) { + return _parent->SpawnActor(blueprint, transform, parent); } Client &GetClient() const { diff --git a/PythonAPI/source/libcarla/World.cpp b/PythonAPI/source/libcarla/World.cpp index d4140a0e3..3f26e1d23 100644 --- a/PythonAPI/source/libcarla/World.cpp +++ b/PythonAPI/source/libcarla/World.cpp @@ -15,7 +15,9 @@ void export_world() { class_>("World", no_init) .def("get_blueprint_library", &cc::World::GetBlueprintLibrary) - .def("try_spawn_actor", &cc::World::TrySpawnActor) - .def("spawn_actor", &cc::World::SpawnActor) + .def("try_spawn_actor", &cc::World::TrySpawnActor, + (arg("blueprint"), arg("transform"), arg("attach_to")=cc::SharedPtr())) + .def("spawn_actor", &cc::World::SpawnActor, + (arg("blueprint"), arg("transform"), arg("attach_to")=cc::SharedPtr())) ; } From d543c3812ee159ff5c66526391278515e127d0c0 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Thu, 26 Jul 2018 22:04:44 +0200 Subject: [PATCH 34/71] Add function to apply control to vehicles --- LibCarla/source/carla/client/Actor.h | 5 --- LibCarla/source/carla/client/Client.cpp | 3 +- LibCarla/source/carla/client/Vehicle.h | 31 +++++++++++++++++++ LibCarla/source/carla/rpc/VehicleControl.h | 21 +++++++++++++ PythonAPI/source/libcarla/Actor.cpp | 14 ++++++++- .../Source/Carla/Server/TheNewCarlaServer.cpp | 18 +++++++++-- 6 files changed, 83 insertions(+), 9 deletions(-) create mode 100644 LibCarla/source/carla/client/Vehicle.h diff --git a/LibCarla/source/carla/client/Actor.h b/LibCarla/source/carla/client/Actor.h index 879151ed7..c7c641b1e 100644 --- a/LibCarla/source/carla/client/Actor.h +++ b/LibCarla/source/carla/client/Actor.h @@ -8,7 +8,6 @@ #include "carla/Debug.h" #include "carla/NonCopyable.h" -#include "carla/client/Control.h" #include "carla/client/Memory.h" #include "carla/client/World.h" #include "carla/rpc/Actor.h" @@ -40,10 +39,6 @@ namespace client { return _world; } - void ApplyControl(const VehicleControl &control) { - _world->GetClient().ApplyControlToActor(*this, control); - } - const auto &Serialize() const { return _actor; } diff --git a/LibCarla/source/carla/client/Client.cpp b/LibCarla/source/carla/client/Client.cpp index 70ab33ad0..7bc92fe33 100644 --- a/LibCarla/source/carla/client/Client.cpp +++ b/LibCarla/source/carla/client/Client.cpp @@ -9,6 +9,7 @@ #include "carla/client/Actor.h" #include "carla/client/Control.h" #include "carla/client/Sensor.h" +#include "carla/client/Vehicle.h" #include "carla/client/World.h" namespace carla { @@ -31,7 +32,7 @@ namespace client { if (actor.IsASensor()) { return SharedPtr(new Sensor{actor, GetWorld()}); } - return SharedPtr(new Actor{actor, GetWorld()}); + return SharedPtr(new Vehicle{actor, GetWorld()}); } void Client::ApplyControlToActor( diff --git a/LibCarla/source/carla/client/Vehicle.h b/LibCarla/source/carla/client/Vehicle.h new file mode 100644 index 000000000..e0dfb328d --- /dev/null +++ b/LibCarla/source/carla/client/Vehicle.h @@ -0,0 +1,31 @@ +// 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 . + +#pragma once + +#include "carla/client/Actor.h" +#include "carla/client/Control.h" + +namespace carla { +namespace client { + + class Vehicle : public Actor { + public: + + void ApplyControl(const VehicleControl &control) { + GetWorld()->GetClient().ApplyControlToActor(*this, control); + } + + private: + + friend class Client; + + template + Vehicle(Args && ... args) : Actor(std::forward(args)...) {} + }; + +} // namespace client +} // namespace carla diff --git a/LibCarla/source/carla/rpc/VehicleControl.h b/LibCarla/source/carla/rpc/VehicleControl.h index 018977f85..bc7447cf5 100644 --- a/LibCarla/source/carla/rpc/VehicleControl.h +++ b/LibCarla/source/carla/rpc/VehicleControl.h @@ -34,6 +34,27 @@ namespace rpc { bool hand_brake = false; bool reverse = false; +#ifdef LIBCARLA_INCLUDED_FROM_UE4 + + VehicleControl(const FVehicleControl &Control) + : throttle(Control.Throttle), + steer(Control.Steer), + brake(Control.Brake), + hand_brake(Control.bHandBrake), + reverse(Control.bReverse) {} + + operator FVehicleControl() const { + FVehicleControl Control; + Control.Throttle = throttle; + Control.Steer = steer; + Control.Brake = brake; + Control.bHandBrake = hand_brake; + Control.bReverse = reverse; + return Control; + } + +#endif // LIBCARLA_INCLUDED_FROM_UE4 + MSGPACK_DEFINE_ARRAY( throttle, steer, diff --git a/PythonAPI/source/libcarla/Actor.cpp b/PythonAPI/source/libcarla/Actor.cpp index 3040727a8..1a59a889d 100644 --- a/PythonAPI/source/libcarla/Actor.cpp +++ b/PythonAPI/source/libcarla/Actor.cpp @@ -7,6 +7,7 @@ #include #include #include +#include #include @@ -40,6 +41,11 @@ namespace client { return out; } + std::ostream &operator<<(std::ostream &out, const Vehicle &vehicle) { + out << "Vehicle(id=" << vehicle.GetId() << ", type=" << vehicle.GetTypeId() << ')'; + return out; + } + std::ostream &operator<<(std::ostream &out, const Sensor &sensor) { out << "Sensor(id=" << sensor.GetId() << ", type=" << sensor.GetTypeId() << ')'; return out; @@ -51,6 +57,7 @@ namespace client { void export_actor() { using namespace boost::python; namespace cc = carla::client; + namespace cr = carla::rpc; class_>("Image", no_init) .add_property("frame_number", &cc::Image::GetFrameNumber) @@ -72,7 +79,11 @@ void export_actor() { return self.GetTypeId(); }) .def("get_world", &cc::Actor::GetWorld) - .def("apply_control", &cc::Actor::ApplyControl) + .def(self_ns::str(self_ns::self)) + ; + + class_, boost::noncopyable, boost::shared_ptr>("Vehicle", no_init) + .def("apply_control", &cc::Vehicle::ApplyControl) .def(self_ns::str(self_ns::self)) ; @@ -103,5 +114,6 @@ void export_actor() { } }); }) + .def(self_ns::str(self_ns::self)) ; } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp index 46a2b522d..29ea5652a 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp @@ -16,6 +16,7 @@ #include #include #include +#include #include #include @@ -123,11 +124,11 @@ private: { if (!Child.IsValid()) { - RespondError("unable to attach actor: child actor not found"); + RespondErrorStr("unable to attach actor: child actor not found"); } if (!Parent.IsValid()) { - RespondError("unable to attach actor: parent actor not found"); + RespondErrorStr("unable to attach actor: parent actor not found"); } ::AttachActors(Child.GetActor(), Parent.GetActor()); } @@ -189,6 +190,19 @@ void FTheNewCarlaServer::FPimpl::BindActions() auto &Registry = Episode->GetActorRegistry(); AttachActors(Registry.Find(Child.id), Registry.Find(Parent.id)); }); + + Server.BindSync("apply_control_to_actor", [this](cr::Actor Actor, cr::VehicleControl Control) { + RequireEpisode(); + auto ActorView = Episode->GetActorRegistry().Find(Actor.id); + if (!ActorView.IsValid()) { + RespondErrorStr("unable to apply control: actor not found"); + } + auto Vehicle = Cast(ActorView.GetActor()); + if (Vehicle == nullptr) { + RespondErrorStr("unable to apply control: actor is not a vehicle"); + } + Vehicle->ApplyVehicleControl(Control); + }); } // ============================================================================= From 4ee7c80448217a4603d56a42297b8224219cc36e Mon Sep 17 00:00:00 2001 From: nsubiron Date: Thu, 26 Jul 2018 22:31:37 +0200 Subject: [PATCH 35/71] Helpers for building vehicle definitions --- .../Actor/ActorBlueprintFunctionLibrary.cpp | 65 +++++++++++++++++++ .../Actor/ActorBlueprintFunctionLibrary.h | 33 ++++++++++ 2 files changed, 98 insertions(+) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp index 658f1ad0b..221a5f147 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp @@ -149,6 +149,20 @@ private: FScopedStack Stack; }; +template +static FString JoinStrings(const FString &Separator, ARGS && ... Args) { + return FString::Join(TArray{std::forward(Args)...}, *Separator); +} + +static FString ColorToFString(const FColor &Color) +{ + return JoinStrings( + TEXT(","), + FString::FromInt(Color.R), + FString::FromInt(Color.G), + FString::FromInt(Color.B)); +} + bool UActorBlueprintFunctionLibrary::CheckActorDefinition(const FActorDefinition &ActorDefinition) { FActorDefinitionValidator Validator; @@ -160,3 +174,54 @@ bool UActorBlueprintFunctionLibrary::CheckActorDefinitions(const TArray +static void FillActorDefinitionArray( + const TArray &ParameterArray, + TArray &Definitions, + Functor Maker) +{ + for (auto &Item : ParameterArray) + { + FActorDefinition Definition; + bool Success = false; + Maker(Item, Success, Definition); + if (Success) + { + Definitions.Emplace(std::move(Definition)); + } + } +} + +void UActorBlueprintFunctionLibrary::MakeVehicleDefinitions( + const TArray &ParameterArray, + TArray &Definitions) +{ + FillActorDefinitionArray(ParameterArray, Definitions, &MakeVehicleDefinition); +} diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.h index bbdfb3d5b..b0afa1780 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.h @@ -7,11 +7,33 @@ #pragma once #include "Carla/Actor/ActorDefinition.h" +#include "Carla/Vehicle/CarlaWheeledVehicle.h" #include "Kismet/BlueprintFunctionLibrary.h" #include "ActorBlueprintFunctionLibrary.generated.h" +USTRUCT(BlueprintType) +struct CARLA_API FVehicleParameters +{ + GENERATED_BODY() + + UPROPERTY(EditAnywhere, BlueprintReadWrite) + FString Make; + + UPROPERTY(EditAnywhere, BlueprintReadWrite) + FString Model; + + UPROPERTY(EditAnywhere, BlueprintReadWrite) + TSubclassOf Class; + + UPROPERTY(EditAnywhere, BlueprintReadWrite) + int32 NumberOfWheels = 4; + + UPROPERTY(EditAnywhere, BlueprintReadWrite) + TArray RecommendedColors; +}; + UCLASS() class UActorBlueprintFunctionLibrary : public UBlueprintFunctionLibrary { @@ -27,5 +49,16 @@ public: /// errors found. UFUNCTION(Category = "Carla Actor", BlueprintCallable) static bool CheckActorDefinitions(const TArray &ActorDefinitions); + + UFUNCTION(Category = "Carla Actor", BlueprintCallable) + static void MakeVehicleDefinition( + const FVehicleParameters &Parameters, + bool &Success, + FActorDefinition &Definition); + + UFUNCTION(Category = "Carla Actor", BlueprintCallable) + static void MakeVehicleDefinitions( + const TArray &ParameterArray, + TArray &Definitions); }; From 2e71467ff5154d2850233860f76ae09cb69f357e Mon Sep 17 00:00:00 2001 From: nsubiron Date: Fri, 27 Jul 2018 12:59:38 +0200 Subject: [PATCH 36/71] Add find function to blueprint library --- .../source/carla/client/BlueprintLibrary.cpp | 41 ++++++++++++++ .../source/carla/client/BlueprintLibrary.h | 53 +++++++++++-------- PythonAPI/source/libcarla/Blueprint.cpp | 3 ++ 3 files changed, 75 insertions(+), 22 deletions(-) create mode 100644 LibCarla/source/carla/client/BlueprintLibrary.cpp diff --git a/LibCarla/source/carla/client/BlueprintLibrary.cpp b/LibCarla/source/carla/client/BlueprintLibrary.cpp new file mode 100644 index 000000000..eaec8397f --- /dev/null +++ b/LibCarla/source/carla/client/BlueprintLibrary.cpp @@ -0,0 +1,41 @@ +// 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 . + +#include "carla/client/BlueprintLibrary.h" + +#include +#include + +namespace carla { +namespace client { + + BlueprintLibrary::BlueprintLibrary( + const std::vector &blueprints) { + _blueprints.reserve(blueprints.size()); + for (auto &definition : blueprints) { + _blueprints.emplace(definition.id, definition); + } + } + + SharedPtr BlueprintLibrary::Filter( + const std::string &wildcard_pattern) const { + map_type result; + for (auto &pair : _blueprints) { + if (pair.second.MatchTags(wildcard_pattern)) { + result.emplace(pair); + } + } + return SharedPtr{new BlueprintLibrary(result)}; + } + + BlueprintLibrary::const_reference BlueprintLibrary::at(size_type pos) const { + if (pos >= size()) + throw std::out_of_range("index out of range"); + return operator[](pos); + } + +} // namespace client +} // namespace carla diff --git a/LibCarla/source/carla/client/BlueprintLibrary.h b/LibCarla/source/carla/client/BlueprintLibrary.h index 634019cae..a86a696b5 100644 --- a/LibCarla/source/carla/client/BlueprintLibrary.h +++ b/LibCarla/source/carla/client/BlueprintLibrary.h @@ -7,56 +7,65 @@ #pragma once #include "carla/Debug.h" +#include "carla/Iterator.h" #include "carla/NonCopyable.h" #include "carla/client/ActorBlueprint.h" #include "carla/client/Memory.h" -#include +#include +#include #include namespace carla { namespace client { + /// @todo Works as a list but its actually a map. We should assess the use + /// cases and reconsider this implementation. class BlueprintLibrary : public EnableSharedFromThis, private NonCopyable { - using list_type = std::vector; + using map_type = std::unordered_map; public: - using value_type = list_type::value_type; - using size_type = list_type::size_type; - using const_iterator = list_type::const_iterator; - using const_reference = list_type::const_reference; + // Here we force a bit the typedefs to make this class look like a list. + using key_type = map_type::key_type; + using value_type = map_type::mapped_type; + using size_type = map_type::size_type; + using const_iterator = decltype(carla::iterator::make_map_values_iterator(map_type::const_iterator{})); + using const_reference = const value_type &; + using const_pointer = const value_type *; - explicit BlueprintLibrary(const std::vector &blueprints) - : _blueprints(blueprints.begin(), blueprints.end()) {} + explicit BlueprintLibrary(const std::vector &blueprints); BlueprintLibrary(BlueprintLibrary &&) = default; BlueprintLibrary &operator=(BlueprintLibrary &&) = default; /// Filters a list of ActorBlueprint with tags matching @a wildcard_pattern. - SharedPtr Filter(const std::string &wildcard_pattern) const { - list_type result; - std::copy_if(begin(), end(), std::back_inserter(result), [&](const auto &x) { - return x.MatchTags(wildcard_pattern); - }); - return SharedPtr{new BlueprintLibrary(result)}; + SharedPtr Filter(const std::string &wildcard_pattern) const; + + const_pointer Find(const std::string &key) const { + auto it = _blueprints.find(key); + return it != _blueprints.end() ? &it->second : nullptr; } + const_reference at(const std::string &key) const { + return _blueprints.at(key); + } + + /// @warning Linear complexity. const_reference operator[](size_type pos) const { - return _blueprints[pos]; + return std::next(_blueprints.begin(), pos)->second; } - const_reference at(size_type pos) const { - return _blueprints.at(pos); - } + /// @warning Linear complexity. + const_reference at(size_type pos) const; const_iterator begin() const /*noexcept*/ { - return _blueprints.begin(); + return iterator::make_map_values_iterator(_blueprints.begin()); } const_iterator end() const /*noexcept*/ { - return _blueprints.end(); + return iterator::make_map_values_iterator(_blueprints.end()); } bool empty() const /*noexcept*/ { @@ -69,10 +78,10 @@ namespace client { private: - BlueprintLibrary(list_type blueprints) + BlueprintLibrary(map_type blueprints) : _blueprints(std::move(blueprints)) {} - list_type _blueprints; + map_type _blueprints; }; } // namespace client diff --git a/PythonAPI/source/libcarla/Blueprint.cpp b/PythonAPI/source/libcarla/Blueprint.cpp index bf2d1ca7a..490a96d57 100644 --- a/PythonAPI/source/libcarla/Blueprint.cpp +++ b/PythonAPI/source/libcarla/Blueprint.cpp @@ -105,6 +105,9 @@ void export_blueprint() { class_>("BlueprintLibrary", no_init) .def("filter", &cc::BlueprintLibrary::Filter) + .def("find", +[](const cc::BlueprintLibrary &self, const std::string &key) -> cc::ActorBlueprint { + return self.at(key); + }) .def("__getitem__", +[](const cc::BlueprintLibrary &self, size_t pos) -> cc::ActorBlueprint { return self.at(pos); }) From 81ba9782cbcf692033948eff9153c46133b0eb68 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Fri, 27 Jul 2018 14:51:30 +0200 Subject: [PATCH 37/71] Helpers to convert actor attribute values --- LibCarla/source/carla/rpc/ActorDescription.h | 4 +- .../Actor/ActorBlueprintFunctionLibrary.cpp | 133 ++++++++++++++++++ .../Actor/ActorBlueprintFunctionLibrary.h | 64 +++++++++ .../Source/Carla/Actor/ActorDescription.h | 5 +- 4 files changed, 203 insertions(+), 3 deletions(-) diff --git a/LibCarla/source/carla/rpc/ActorDescription.h b/LibCarla/source/carla/rpc/ActorDescription.h index 67dda35fc..21dff5008 100644 --- a/LibCarla/source/carla/rpc/ActorDescription.h +++ b/LibCarla/source/carla/rpc/ActorDescription.h @@ -33,7 +33,7 @@ namespace rpc { id(FromFString(Description.Id)) { attributes.reserve(Description.Variations.Num()); for (const auto &Item : Description.Variations) { - attributes.push_back(Item); + attributes.emplace_back(Item.Value); } } @@ -43,7 +43,7 @@ namespace rpc { Description.Id = ToFString(id); Description.Variations.Reserve(attributes.size()); for (const auto &item : attributes) { - Description.Variations.Add(item); + Description.Variations.Emplace(ToFString(item.id), item); } return Description; } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp index 221a5f147..cdd5644bb 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp @@ -10,6 +10,7 @@ #include "Carla/Util/ScopedStack.h" #include +#include #include /// Checks validity of FActorDefinition. @@ -225,3 +226,135 @@ void UActorBlueprintFunctionLibrary::MakeVehicleDefinitions( { FillActorDefinitionArray(ParameterArray, Definitions, &MakeVehicleDefinition); } + +bool UActorBlueprintFunctionLibrary::ActorAttributeToBool( + const FActorAttribute &ActorAttribute, + bool Default) +{ + if (ActorAttribute.Type != EActorAttributeType::Bool) + { + UE_LOG(LogCarla, Error, TEXT("ActorAttribute '%s' is not a bool"), *ActorAttribute.Id); + return Default; + } + return ActorAttribute.Value.ToBool(); +} + +int32 UActorBlueprintFunctionLibrary::ActorAttributeToInt( + const FActorAttribute &ActorAttribute, + int32 Default) +{ + if (ActorAttribute.Type != EActorAttributeType::Int) + { + UE_LOG(LogCarla, Error, TEXT("ActorAttribute '%s' is not an int"), *ActorAttribute.Id); + return Default; + } + return FCString::Atoi(*ActorAttribute.Value); +} + +float UActorBlueprintFunctionLibrary::ActorAttributeToFloat( + const FActorAttribute &ActorAttribute, + float Default) +{ + if (ActorAttribute.Type != EActorAttributeType::Float) + { + UE_LOG(LogCarla, Error, TEXT("ActorAttribute '%s' is not a float"), *ActorAttribute.Id); + return Default; + } + return FCString::Atof(*ActorAttribute.Value); +} + +FString UActorBlueprintFunctionLibrary::ActorAttributeToString( + const FActorAttribute &ActorAttribute, + const FString &Default) +{ + if (ActorAttribute.Type != EActorAttributeType::String) + { + UE_LOG(LogCarla, Error, TEXT("ActorAttribute '%s' is not a string"), *ActorAttribute.Id); + return Default; + } + return ActorAttribute.Value; +} + +FColor UActorBlueprintFunctionLibrary::ActorAttributeToColor( + const FActorAttribute &ActorAttribute, + const FColor &Default) +{ + if (ActorAttribute.Type != EActorAttributeType::RGBColor) + { + UE_LOG(LogCarla, Error, TEXT("ActorAttribute '%s' is not a color"), *ActorAttribute.Id); + return Default; + } + TArray Channels; + ActorAttribute.Value.ParseIntoArray(Channels, TEXT(","), false); + if (Channels.Num() != 3) + { + UE_LOG(LogCarla, Error, TEXT("ActorAttribute '%s': invalid color '%s'"), *ActorAttribute.Id, *ActorAttribute.Value); + return Default; + } + TArray Colors; + for (auto &Str : Channels) + { + auto Val = FCString::Atoi(*Str); + if ((Val < 0) || (Val > std::numeric_limits::max())) + { + UE_LOG(LogCarla, Error, TEXT("ActorAttribute '%s': invalid color '%s'"), *ActorAttribute.Id, *ActorAttribute.Value); + return Default; + } + Colors.Add(Val); + } + FColor Color; + Color.R = Colors[0u]; + Color.G = Colors[1u]; + Color.B = Colors[2u]; + return Color; +} + +bool UActorBlueprintFunctionLibrary::RetrieveActorAttributeToBool( + const FString &Id, + const TMap &Attributes, + bool Default) +{ + return Attributes.Contains(Id) ? + ActorAttributeToBool(Attributes[Id], Default) : + Default; +} + +int32 UActorBlueprintFunctionLibrary::RetrieveActorAttributeToInt( + const FString &Id, + const TMap &Attributes, + int32 Default) +{ + return Attributes.Contains(Id) ? + ActorAttributeToInt(Attributes[Id], Default) : + Default; +} + +float UActorBlueprintFunctionLibrary::RetrieveActorAttributeToFloat( + const FString &Id, + const TMap &Attributes, + float Default) +{ + return Attributes.Contains(Id) ? + ActorAttributeToFloat(Attributes[Id], Default) : + Default; +} + +FString UActorBlueprintFunctionLibrary::RetrieveActorAttributeToString( + const FString &Id, + const TMap &Attributes, + const FString &Default) +{ + return Attributes.Contains(Id) ? + ActorAttributeToString(Attributes[Id], Default) : + Default; +} + +FColor UActorBlueprintFunctionLibrary::RetrieveActorAttributeToColor( + const FString &Id, + const TMap &Attributes, + const FColor &Default) +{ + return Attributes.Contains(Id) ? + ActorAttributeToColor(Attributes[Id], Default) : + Default; +} diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.h index b0afa1780..8cbd73d22 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.h @@ -41,6 +41,11 @@ class UActorBlueprintFunctionLibrary : public UBlueprintFunctionLibrary public: + /// ========================================================================== + /// @name Actor definition validators + /// ========================================================================== + /// @{ + /// Return whether the actor definition is valid. Prints all the errors found. UFUNCTION(Category = "Carla Actor", BlueprintCallable) static bool CheckActorDefinition(const FActorDefinition &ActorDefinitions); @@ -50,6 +55,12 @@ public: UFUNCTION(Category = "Carla Actor", BlueprintCallable) static bool CheckActorDefinitions(const TArray &ActorDefinitions); + /// @} + /// ========================================================================== + /// @name Helpers to create actor definitions + /// ========================================================================== + /// @{ + UFUNCTION(Category = "Carla Actor", BlueprintCallable) static void MakeVehicleDefinition( const FVehicleParameters &Parameters, @@ -60,5 +71,58 @@ public: static void MakeVehicleDefinitions( const TArray &ParameterArray, TArray &Definitions); + + /// @} + /// ========================================================================== + /// @name Helpers to retrieve attribute values + /// ========================================================================== + /// @{ + + UFUNCTION(Category = "Carla Actor", BlueprintCallable) + static bool ActorAttributeToBool(const FActorAttribute &ActorAttribute, bool Default); + + UFUNCTION(Category = "Carla Actor", BlueprintCallable) + static int32 ActorAttributeToInt(const FActorAttribute &ActorAttribute, int32 Default); + + UFUNCTION(Category = "Carla Actor", BlueprintCallable) + static float ActorAttributeToFloat(const FActorAttribute &ActorAttribute, float Default); + + UFUNCTION(Category = "Carla Actor", BlueprintCallable) + static FString ActorAttributeToString(const FActorAttribute &ActorAttribute, const FString &Default); + + UFUNCTION(Category = "Carla Actor", BlueprintCallable) + static FColor ActorAttributeToColor(const FActorAttribute &ActorAttribute, const FColor &Default); + + UFUNCTION(Category = "Carla Actor", BlueprintCallable) + static bool RetrieveActorAttributeToBool( + const FString &Id, + const TMap &Attributes, + bool Default); + + UFUNCTION(Category = "Carla Actor", BlueprintCallable) + static int32 RetrieveActorAttributeToInt( + const FString &Id, + const TMap &Attributes, + int32 Default); + + UFUNCTION(Category = "Carla Actor", BlueprintCallable) + static float RetrieveActorAttributeToFloat( + const FString &Id, + const TMap &Attributes, + float Default); + + UFUNCTION(Category = "Carla Actor", BlueprintCallable) + static FString RetrieveActorAttributeToString( + const FString &Id, + const TMap &Attributes, + const FString &Default); + + UFUNCTION(Category = "Carla Actor", BlueprintCallable) + static FColor RetrieveActorAttributeToColor( + const FString &Id, + const TMap &Attributes, + const FColor &Default); + + /// @} }; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDescription.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDescription.h index 927af8a17..72e26a37c 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDescription.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDescription.h @@ -29,6 +29,9 @@ struct FActorDescription /// User selected variations of the actor. Note that at this point are /// represented by non-modifiable attributes. + /// + /// Key: Id of the attribute. + /// Value: The attribute. UPROPERTY(EditAnywhere, BlueprintReadWrite) - TArray Variations; + TMap Variations; }; From 0fb1edc6af8881ffd0140aeb3bf02cfebd2c84be Mon Sep 17 00:00:00 2001 From: nsubiron Date: Fri, 27 Jul 2018 15:24:48 +0200 Subject: [PATCH 38/71] Rename spawners to factories --- .../Source/Carla/Actor/ActorDispatcher.cpp | 8 +- .../Source/Carla/Actor/ActorDispatcher.h | 6 +- .../{ActorSpawner.h => CarlaActorFactory.h} | 12 +- ...ueprint.h => CarlaActorFactoryBlueprint.h} | 12 +- .../Carla/Source/Carla/Game/CarlaEpisode.h | 4 +- .../Source/Carla/Game/CarlaGameModeBase.cpp | 2 +- .../Carla/Game/TheNewCarlaGameModeBase.cpp | 16 +-- .../Carla/Game/TheNewCarlaGameModeBase.h | 8 +- .../Source/Carla/Sensor/OldSensorFactory.cpp | 60 ++++++++++ .../Source/Carla/Sensor/OldSensorFactory.h | 33 ++++++ .../Source/Carla/Sensor/SensorFactory.cpp | 108 ++++++++++-------- .../Carla/Source/Carla/Sensor/SensorFactory.h | 30 ++--- .../Source/Carla/Sensor/SensorSpawner.cpp | 72 ------------ .../Carla/Source/Carla/Sensor/SensorSpawner.h | 27 ----- 14 files changed, 198 insertions(+), 200 deletions(-) rename Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/{ActorSpawner.h => CarlaActorFactory.h} (76%) rename Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/{ActorSpawnerBlueprint.h => CarlaActorFactoryBlueprint.h} (75%) create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/OldSensorFactory.cpp create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/OldSensorFactory.h delete mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SensorSpawner.cpp delete mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SensorSpawner.h diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp index db6d1b7f9..39c189717 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp @@ -8,7 +8,7 @@ #include "Carla/Actor/ActorDispatcher.h" #include "Carla/Actor/ActorBlueprintFunctionLibrary.h" -#include "Carla/Actor/ActorSpawner.h" +#include "Carla/Actor/CarlaActorFactory.h" void FActorDispatcher::Bind(FActorDefinition Definition, SpawnFunctionType Functor) { @@ -25,12 +25,12 @@ void FActorDispatcher::Bind(FActorDefinition Definition, SpawnFunctionType Funct } } -void FActorDispatcher::Bind(AActorSpawner &ActorSpawner) +void FActorDispatcher::Bind(ACarlaActorFactory &ActorFactory) { - for (const auto &Definition : ActorSpawner.MakeDefinitions()) + for (const auto &Definition : ActorFactory.GetDefinitions()) { Bind(Definition, [&](const FTransform &Transform, const FActorDescription &Description) { - return ActorSpawner.SpawnActor(Transform, Description); + return ActorFactory.SpawnActor(Transform, Description); }); } } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.h index f679fecc2..e7d1a6bbd 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.h @@ -14,7 +14,7 @@ #include "Containers/Array.h" #include "Templates/Function.h" -class AActorSpawner; +class ACarlaActorFactory; /// Actor in charge of binding ActorDefinitions to spawn functions, as well as /// keeping the registry of all the actors spawned. @@ -30,10 +30,10 @@ public: /// @warning Invalid definitions are ignored. void Bind(FActorDefinition Definition, SpawnFunctionType SpawnFunction); - /// Bind all the definitions of @a ActorSpawner to its spawn function. + /// Bind all the definitions of @a ActorFactory to its spawn function. /// /// @warning Invalid definitions are ignored. - void Bind(AActorSpawner &ActorSpawner); + void Bind(ACarlaActorFactory &ActorFactory); /// Spawns an actor based on @a ActorDescription at @a Transform. To properly /// despawn an actor created with this function call DestroyActor. diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawner.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActorFactory.h similarity index 76% rename from Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawner.h rename to Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActorFactory.h index ec3e61082..96e2e3b54 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawner.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActorFactory.h @@ -13,24 +13,24 @@ #include "Containers/Array.h" #include "GameFramework/Actor.h" -#include "ActorSpawner.generated.h" +#include "CarlaActorFactory.generated.h" -/// Base class for Carla actor spawners. +/// Base class for Carla actor factories. UCLASS(Abstract) -class CARLA_API AActorSpawner : public AActor +class CARLA_API ACarlaActorFactory : public AActor { GENERATED_BODY() public: - AActorSpawner(const FObjectInitializer& ObjectInitializer) + ACarlaActorFactory(const FObjectInitializer& ObjectInitializer) : Super(ObjectInitializer) { PrimaryActorTick.bCanEverTick = false; } /// Retrieve the list of actor definitions that this class is able to spawn. - virtual TArray MakeDefinitions() { + virtual TArray GetDefinitions() { unimplemented(); return {}; } @@ -38,7 +38,7 @@ public: /// Spawn an actor based on @a ActorDescription and @a Transform. /// /// @pre ActorDescription is expected to be derived from one of the - /// definitions retrieved with MakeDefinitions. + /// definitions retrieved with GetDefinitions. virtual FActorSpawnResult SpawnActor( const FTransform &SpawnAtTransform, const FActorDescription &ActorDescription) { diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnerBlueprint.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActorFactoryBlueprint.h similarity index 75% rename from Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnerBlueprint.h rename to Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActorFactoryBlueprint.h index a75db3eaa..edce20ae9 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorSpawnerBlueprint.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActorFactoryBlueprint.h @@ -6,25 +6,25 @@ #pragma once -#include "Carla/Actor/ActorSpawner.h" #include "Carla/Actor/ActorSpawnResult.h" +#include "Carla/Actor/CarlaActorFactory.h" #include "GameFramework/Actor.h" -#include "ActorSpawnerBlueprint.generated.h" +#include "CarlaActorFactoryBlueprint.generated.h" -/// Base class for Blueprints implementing AActorSpawner interface. +/// Base class for Blueprints implementing ACarlaActorFactory interface. /// /// Blueprints deriving from this class are expected to override -/// GenerateDefinitions and SpawnActor functions. +/// GetDefinitions and SpawnActor functions. UCLASS(Abstract, BlueprintType, Blueprintable) -class CARLA_API AActorSpawnerBlueprint : public AActorSpawner +class CARLA_API ACarlaActorFactoryBlueprint : public ACarlaActorFactory { GENERATED_BODY() public: - TArray MakeDefinitions() final + TArray GetDefinitions() final { return GenerateDefinitions(); } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.h index 8a24220ef..94d9ed4c5 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.h @@ -31,9 +31,9 @@ public: return MapName; } - void RegisterActorSpawner(AActorSpawner &ActorSpawner) + void RegisterActorFactory(ACarlaActorFactory &ActorFactory) { - ActorDispatcher.Bind(ActorSpawner); + ActorDispatcher.Bind(ActorFactory); } /// Return the list of actor definitions that are available to be spawned this diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaGameModeBase.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaGameModeBase.cpp index 1e0049d30..fbe152f09 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaGameModeBase.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaGameModeBase.cpp @@ -12,8 +12,8 @@ #include "Game/CarlaPlayerState.h" #include "Game/Tagger.h" #include "Game/TaggerDelegate.h" +#include "Sensor/OldSensorFactory.h" #include "Sensor/Sensor.h" -#include "Sensor/SensorFactory.h" #include "Settings/CarlaSettings.h" #include "Settings/CarlaSettingsDelegate.h" #include "Util/RandomEngine.h" diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/TheNewCarlaGameModeBase.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/TheNewCarlaGameModeBase.cpp index b762837b8..ee4eb9f5b 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/TheNewCarlaGameModeBase.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/TheNewCarlaGameModeBase.cpp @@ -32,7 +32,7 @@ void ATheNewCarlaGameModeBase::InitGame( GameInstance != nullptr, TEXT("GameInstance is not a UCarlaGameInstance, did you forget to set it in the project settings?")); - SpawnActorSpawners(); + SpawnActorFactories(); } void ATheNewCarlaGameModeBase::BeginPlay() @@ -56,20 +56,20 @@ void ATheNewCarlaGameModeBase::EndPlay(const EEndPlayReason::Type EndPlayReason) Super::EndPlay(EndPlayReason); } -void ATheNewCarlaGameModeBase::SpawnActorSpawners() +void ATheNewCarlaGameModeBase::SpawnActorFactories() { auto *World = GetWorld(); check(World != nullptr); - for (auto &SpawnerClass : ActorSpawners) + for (auto &FactoryClass : ActorFactories) { - if (SpawnerClass != nullptr) + if (FactoryClass != nullptr) { - auto *Spawner = World->SpawnActor(SpawnerClass); - if (Spawner != nullptr) + auto *Factory = World->SpawnActor(FactoryClass); + if (Factory != nullptr) { - Episode->RegisterActorSpawner(*Spawner); - ActorSpawnerInstances.Add(Spawner); + Episode->RegisterActorFactory(*Factory); + ActorFactoryInstances.Add(Factory); } else { diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/TheNewCarlaGameModeBase.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/TheNewCarlaGameModeBase.h index 1412dcfa2..553981c81 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/TheNewCarlaGameModeBase.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/TheNewCarlaGameModeBase.h @@ -6,7 +6,7 @@ #pragma once -#include "Carla/Actor/ActorSpawner.h" +#include "Carla/Actor/CarlaActorFactory.h" #include "Carla/Game/CarlaEpisode.h" #include "CoreMinimal.h" @@ -36,7 +36,7 @@ protected: private: - void SpawnActorSpawners(); + void SpawnActorFactories(); UPROPERTY() UCarlaGameInstance *GameInstance = nullptr; @@ -47,8 +47,8 @@ private: /// List of actor spawners that will be used to define and spawn the actors /// available in game. UPROPERTY(EditAnywhere) - TSet> ActorSpawners; + TSet> ActorFactories; UPROPERTY() - TArray ActorSpawnerInstances; + TArray ActorFactoryInstances; }; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/OldSensorFactory.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/OldSensorFactory.cpp new file mode 100644 index 000000000..787948e9a --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/OldSensorFactory.cpp @@ -0,0 +1,60 @@ +// 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 . + +#pragma once + +#include "Carla.h" +#include "OldSensorFactory.h" + +#include "Sensor/Lidar.h" +#include "Sensor/SceneCaptureCamera.h" +#include "Settings/CameraDescription.h" +#include "Settings/LidarDescription.h" + +template +static T *SpawnSensor(const D &Description, UWorld &World) +{ + FActorSpawnParameters Params; + Params.Name = FName(*Description.Name); + return World.SpawnActor(Description.Position, Description.Rotation, Params); +} + +ASensor *FSensorFactory::Make( + const USensorDescription &Description, + UWorld &World) +{ + FSensorFactory Visitor(World); + Description.AcceptVisitor(Visitor); + check(Visitor.Sensor != nullptr); + return Visitor.Sensor; +} + +FSensorFactory::FSensorFactory(UWorld &World) : World(World) {} + +void FSensorFactory::Visit(const UCameraDescription &Description) +{ + auto Camera = SpawnSensor(Description, World); + Camera->Set(Description); + UE_LOG( + LogCarla, + Log, + TEXT("Created Capture Camera %d with postprocess \"%s\""), + Camera->GetId(), + *PostProcessEffect::ToString(Camera->GetPostProcessEffect())); + Sensor = Camera; +} + +void FSensorFactory::Visit(const ULidarDescription &Description) +{ + auto Lidar = SpawnSensor(Description, World); + Lidar->Set(Description); + UE_LOG( + LogCarla, + Log, + TEXT("Created Lidar %d"), + Lidar->GetId()); + Sensor = Lidar; +} diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/OldSensorFactory.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/OldSensorFactory.h new file mode 100644 index 000000000..11b334cbe --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/OldSensorFactory.h @@ -0,0 +1,33 @@ +// 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 . + +#pragma once + +#include "Settings/SensorDescriptionVisitor.h" + +class ASensor; +class UWorld; + +class FSensorFactory : private ISensorDescriptionVisitor +{ +public: + + static ASensor *Make( + const USensorDescription &Description, + UWorld &World); + +private: + + FSensorFactory(UWorld &World); + + virtual void Visit(const UCameraDescription &) final; + + virtual void Visit(const ULidarDescription &) final; + + UWorld &World; + + ASensor *Sensor = nullptr; +}; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SensorFactory.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SensorFactory.cpp index c49f7b79c..230a8f9d3 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SensorFactory.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SensorFactory.cpp @@ -4,57 +4,69 @@ // This work is licensed under the terms of the MIT license. // For a copy, see . -#pragma once - #include "Carla.h" -#include "SensorFactory.h" +#include "Carla/Sensor/SensorFactory.h" -#include "Sensor/Lidar.h" -#include "Sensor/SceneCaptureCamera.h" -#include "Settings/CameraDescription.h" -#include "Settings/LidarDescription.h" +#include "Carla/Sensor/SceneCaptureCamera.h" -template -static T *SpawnSensor(const D &Description, UWorld &World) +template +static FActorDefinition MakeSensorDefinition(const FString &Id) +{ + FActorDefinition Definition; + Definition.Id = Id; + Definition.Class = T::StaticClass(); + Definition.Tags = TEXT("sensor,") + Id; + return Definition; +} + +TArray ASensorFactory::GetDefinitions() +{ + // Cameras. + auto Cameras = MakeSensorDefinition("camera"); + { + FActorVariation PostProcessing; + PostProcessing.Id = TEXT("PostProcessing"); + PostProcessing.Type = EActorAttributeType::String; + PostProcessing.RecommendedValues = { + TEXT("None"), + TEXT("SceneFinal"), + TEXT("Depth"), + TEXT("SemanticSegmentation") + }; + PostProcessing.bRestrictToRecommended = true; + FActorVariation FOV; + FOV.Id = TEXT("FOV"); + FOV.Type = EActorAttributeType::Float; + FOV.RecommendedValues = { TEXT("90.0") }; + FOV.bRestrictToRecommended = false; + FActorVariation ResX; + ResX.Id = TEXT("ImageSizeX"); + ResX.Type = EActorAttributeType::Int; + ResX.RecommendedValues = { TEXT("800") }; + ResX.bRestrictToRecommended = false; + FActorVariation ResY; + ResY.Id = TEXT("ImageSizeY"); + ResY.Type = EActorAttributeType::Int; + ResY.RecommendedValues = { TEXT("600") }; + ResY.bRestrictToRecommended = false; + Cameras.Variations = {PostProcessing, ResX, ResY, FOV}; + } + return {Cameras}; +} + +FActorSpawnResult ASensorFactory::SpawnActor( + const FTransform &Transform, + const FActorDescription &Description) { FActorSpawnParameters Params; - Params.Name = FName(*Description.Name); - return World.SpawnActor(Description.Position, Description.Rotation, Params); -} - -ASensor *FSensorFactory::Make( - const USensorDescription &Description, - UWorld &World) -{ - FSensorFactory Visitor(World); - Description.AcceptVisitor(Visitor); - check(Visitor.Sensor != nullptr); - return Visitor.Sensor; -} - -FSensorFactory::FSensorFactory(UWorld &World) : World(World) {} - -void FSensorFactory::Visit(const UCameraDescription &Description) -{ - auto Camera = SpawnSensor(Description, World); - Camera->Set(Description); - UE_LOG( - LogCarla, - Log, - TEXT("Created Capture Camera %d with postprocess \"%s\""), - Camera->GetId(), - *PostProcessEffect::ToString(Camera->GetPostProcessEffect())); - Sensor = Camera; -} - -void FSensorFactory::Visit(const ULidarDescription &Description) -{ - auto Lidar = SpawnSensor(Description, World); - Lidar->Set(Description); - UE_LOG( - LogCarla, - Log, - TEXT("Created Lidar %d"), - Lidar->GetId()); - Sensor = Lidar; + static int32 COUNTER = 0u; + Params.Name = FName(*(Description.Id + FString::FromInt(++COUNTER))); + auto *World = GetWorld(); + if (World == nullptr) + { + return {}; + } + auto *Sensor = World->SpawnActor(Description.Class, Transform, Params); + /// @todo Set description: Actor->Set(Description); + return FActorSpawnResult{Sensor}; } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SensorFactory.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SensorFactory.h index 11b334cbe..dbebd2864 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SensorFactory.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SensorFactory.h @@ -6,28 +6,20 @@ #pragma once -#include "Settings/SensorDescriptionVisitor.h" +#include "Carla/Actor/ActorSpawnResult.h" +#include "Carla/Actor/CarlaActorFactory.h" -class ASensor; -class UWorld; +#include "SensorFactory.generated.h" -class FSensorFactory : private ISensorDescriptionVisitor +/// Object in charge of spawning sensors. +UCLASS() +class CARLA_API ASensorFactory : public ACarlaActorFactory { -public: + GENERATED_BODY() - static ASensor *Make( - const USensorDescription &Description, - UWorld &World); + TArray GetDefinitions() final; -private: - - FSensorFactory(UWorld &World); - - virtual void Visit(const UCameraDescription &) final; - - virtual void Visit(const ULidarDescription &) final; - - UWorld &World; - - ASensor *Sensor = nullptr; + FActorSpawnResult SpawnActor( + const FTransform &SpawnAtTransform, + const FActorDescription &ActorDescription) final; }; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SensorSpawner.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SensorSpawner.cpp deleted file mode 100644 index 8e68d80d9..000000000 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SensorSpawner.cpp +++ /dev/null @@ -1,72 +0,0 @@ -// 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 . - -#include "Carla.h" -#include "Carla/Sensor/SensorSpawner.h" - -#include "Carla/Sensor/SceneCaptureCamera.h" - -template -static FActorDefinition MakeSensorDefinition(const FString &Id) -{ - FActorDefinition Definition; - Definition.Id = Id; - Definition.Class = T::StaticClass(); - Definition.Tags = TEXT("sensor,") + Id; - return Definition; -} - -TArray ASensorSpawner::MakeDefinitions() -{ - // Cameras. - auto Cameras = MakeSensorDefinition("camera"); - { - FActorVariation PostProcessing; - PostProcessing.Id = TEXT("PostProcessing"); - PostProcessing.Type = EActorAttributeType::String; - PostProcessing.RecommendedValues = { - TEXT("None"), - TEXT("SceneFinal"), - TEXT("Depth"), - TEXT("SemanticSegmentation") - }; - PostProcessing.bRestrictToRecommended = true; - FActorVariation FOV; - FOV.Id = TEXT("FOV"); - FOV.Type = EActorAttributeType::Float; - FOV.RecommendedValues = { TEXT("90.0") }; - FOV.bRestrictToRecommended = false; - FActorVariation ResX; - ResX.Id = TEXT("ImageSizeX"); - ResX.Type = EActorAttributeType::Int; - ResX.RecommendedValues = { TEXT("800") }; - ResX.bRestrictToRecommended = false; - FActorVariation ResY; - ResY.Id = TEXT("ImageSizeY"); - ResY.Type = EActorAttributeType::Int; - ResY.RecommendedValues = { TEXT("600") }; - ResY.bRestrictToRecommended = false; - Cameras.Variations = {PostProcessing, ResX, ResY, FOV}; - } - return {Cameras}; -} - -FActorSpawnResult ASensorSpawner::SpawnActor( - const FTransform &Transform, - const FActorDescription &Description) -{ - FActorSpawnParameters Params; - static int32 COUNTER = 0u; - Params.Name = FName(*(Description.Id + FString::FromInt(++COUNTER))); - auto *World = GetWorld(); - if (World == nullptr) - { - return {}; - } - auto *Sensor = World->SpawnActor(Description.Class, Transform, Params); - /// @todo Set description: Actor->Set(Description); - return FActorSpawnResult{Sensor}; -} diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SensorSpawner.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SensorSpawner.h deleted file mode 100644 index f1237b5c2..000000000 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SensorSpawner.h +++ /dev/null @@ -1,27 +0,0 @@ -// 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 . - -#pragma once - -#include "Carla/Actor/ActorSpawner.h" -#include "Carla/Actor/ActorSpawnResult.h" - -#include "GameFramework/Actor.h" - -#include "SensorSpawner.generated.h" - -/// Object in charge of spawning sensors. -UCLASS() -class CARLA_API ASensorSpawner : public AActorSpawner -{ - GENERATED_BODY() - - TArray MakeDefinitions() final; - - FActorSpawnResult SpawnActor( - const FTransform &SpawnAtTransform, - const FActorDescription &ActorDescription) final; -}; From 5b310cb541eb9a483a7ae3c04f0c5cd460aa50d6 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Fri, 27 Jul 2018 18:41:25 +0200 Subject: [PATCH 39/71] Better definition of cameras --- .../Actor/ActorBlueprintFunctionLibrary.cpp | 52 +++++++++++++++ .../Actor/ActorBlueprintFunctionLibrary.h | 18 ++++++ .../Source/Carla/Sensor/SensorFactory.cpp | 63 +++++++------------ .../Carla/Settings/PostProcessEffect.cpp | 29 ++++++--- .../Source/Carla/Settings/PostProcessEffect.h | 18 ++++-- 5 files changed, 124 insertions(+), 56 deletions(-) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp index cdd5644bb..0f8a9d2cc 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp @@ -7,6 +7,7 @@ #include "Carla.h" #include "Carla/Actor/ActorBlueprintFunctionLibrary.h" +#include "Carla/Settings/PostProcessEffect.h" #include "Carla/Util/ScopedStack.h" #include @@ -164,6 +165,10 @@ static FString ColorToFString(const FColor &Color) FString::FromInt(Color.B)); } +/// ============================================================================ +/// -- Actor definition validators --------------------------------------------- +/// ============================================================================ + bool UActorBlueprintFunctionLibrary::CheckActorDefinition(const FActorDefinition &ActorDefinition) { FActorDefinitionValidator Validator; @@ -176,6 +181,49 @@ bool UActorBlueprintFunctionLibrary::CheckActorDefinitions(const TArray Class; +}; + USTRUCT(BlueprintType) struct CARLA_API FVehicleParameters { @@ -61,6 +73,12 @@ public: /// ========================================================================== /// @{ + UFUNCTION(Category = "Carla Actor", BlueprintCallable) + static void MakeCameraDefinition( + const FCameraParameters &Parameters, + bool &Success, + FActorDefinition &Definition); + UFUNCTION(Category = "Carla Actor", BlueprintCallable) static void MakeVehicleDefinition( const FVehicleParameters &Parameters, diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SensorFactory.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SensorFactory.cpp index 230a8f9d3..7a853d8ea 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SensorFactory.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SensorFactory.cpp @@ -7,50 +7,18 @@ #include "Carla.h" #include "Carla/Sensor/SensorFactory.h" +#include "Carla/Actor/ActorBlueprintFunctionLibrary.h" #include "Carla/Sensor/SceneCaptureCamera.h" -template -static FActorDefinition MakeSensorDefinition(const FString &Id) -{ - FActorDefinition Definition; - Definition.Id = Id; - Definition.Class = T::StaticClass(); - Definition.Tags = TEXT("sensor,") + Id; - return Definition; -} - TArray ASensorFactory::GetDefinitions() { - // Cameras. - auto Cameras = MakeSensorDefinition("camera"); - { - FActorVariation PostProcessing; - PostProcessing.Id = TEXT("PostProcessing"); - PostProcessing.Type = EActorAttributeType::String; - PostProcessing.RecommendedValues = { - TEXT("None"), - TEXT("SceneFinal"), - TEXT("Depth"), - TEXT("SemanticSegmentation") - }; - PostProcessing.bRestrictToRecommended = true; - FActorVariation FOV; - FOV.Id = TEXT("FOV"); - FOV.Type = EActorAttributeType::Float; - FOV.RecommendedValues = { TEXT("90.0") }; - FOV.bRestrictToRecommended = false; - FActorVariation ResX; - ResX.Id = TEXT("ImageSizeX"); - ResX.Type = EActorAttributeType::Int; - ResX.RecommendedValues = { TEXT("800") }; - ResX.bRestrictToRecommended = false; - FActorVariation ResY; - ResY.Id = TEXT("ImageSizeY"); - ResY.Type = EActorAttributeType::Int; - ResY.RecommendedValues = { TEXT("600") }; - ResY.bRestrictToRecommended = false; - Cameras.Variations = {PostProcessing, ResX, ResY, FOV}; - } + FActorDefinition Cameras; + bool Success = false; + UActorBlueprintFunctionLibrary::MakeCameraDefinition( + {TEXT("camera"), ASceneCaptureCamera::StaticClass()}, + Success, + Cameras); + check(Success); return {Cameras}; } @@ -66,7 +34,18 @@ FActorSpawnResult ASensorFactory::SpawnActor( { return {}; } - auto *Sensor = World->SpawnActor(Description.Class, Transform, Params); - /// @todo Set description: Actor->Set(Description); + auto *Sensor = World->SpawnActor(Description.Class, Transform, Params); + if (Sensor != nullptr) + { + using ABFL = UActorBlueprintFunctionLibrary; + Sensor->SetImageSize( + ABFL::RetrieveActorAttributeToInt("image_size_x", Description.Variations, 800), + ABFL::RetrieveActorAttributeToInt("image_size_y", Description.Variations, 600)); + Sensor->SetFOVAngle( + ABFL::RetrieveActorAttributeToFloat("fov", Description.Variations, 90.0f)); + Sensor->SetPostProcessEffect( + PostProcessEffect::FromString( + ABFL::RetrieveActorAttributeToString("post_processing", Description.Variations, "SceneFinal"))); + } return FActorSpawnResult{Sensor}; } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/PostProcessEffect.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/PostProcessEffect.cpp index 12c5c2297..ef80d64fd 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/PostProcessEffect.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/PostProcessEffect.cpp @@ -7,25 +7,34 @@ #include "Carla.h" #include "PostProcessEffect.h" -#include "Package.h" - FString PostProcessEffect::ToString(EPostProcessEffect PostProcessEffect) { - const UEnum* ptr = FindObject(ANY_PACKAGE, TEXT("EPostProcessEffect"), true); - if(!ptr) - return FString("Invalid"); - return ptr->GetNameStringByIndex(static_cast(PostProcessEffect)); + static_assert( + static_cast(EPostProcessEffect::SIZE) == 4u, + "If you add a new post-process effect, please update these functions."); + + switch (PostProcessEffect) + { + case EPostProcessEffect::None: return TEXT("None"); + case EPostProcessEffect::SceneFinal: return TEXT("SceneFinal"); + case EPostProcessEffect::Depth: return TEXT("Depth"); + case EPostProcessEffect::SemanticSegmentation: return TEXT("SemanticSegmentation"); + default: + UE_LOG(LogCarla, Error, TEXT("Invalid post-processing effect \"%d\""), ToUInt(PostProcessEffect)); + return TEXT("INVALID"); + } } EPostProcessEffect PostProcessEffect::FromString(const FString &String) { - if (String == "None") { + auto Str = String.ToLower(); + if (Str == "none") { return EPostProcessEffect::None; - } else if (String == "SceneFinal") { + } else if (Str == "scenefinal") { return EPostProcessEffect::SceneFinal; - } else if (String == "Depth") { + } else if (Str == "depth") { return EPostProcessEffect::Depth; - } else if (String == "SemanticSegmentation") { + } else if (Str == "semanticsegmentation") { return EPostProcessEffect::SemanticSegmentation; } else { UE_LOG(LogCarla, Error, TEXT("Invalid post-processing effect \"%s\""), *String); diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/PostProcessEffect.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/PostProcessEffect.h index c217fefb0..d6b51b0ef 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/PostProcessEffect.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/PostProcessEffect.h @@ -26,12 +26,22 @@ public: using uint_type = typename std::underlying_type::type; - static FString ToString(EPostProcessEffect PostProcessEffect); - - static EPostProcessEffect FromString(const FString &String); - static constexpr uint_type ToUInt(EPostProcessEffect PostProcessEffect) { return static_cast(PostProcessEffect); } + + static constexpr EPostProcessEffect FromUInt(uint_type Index) + { + return static_cast(Index); + } + + static FString ToString(EPostProcessEffect PostProcessEffect); + + static FString ToString(uint_type Index) + { + return ToString(FromUInt(Index)); + } + + static EPostProcessEffect FromString(const FString &String); }; From 167cef21a01eb579fcbcc18ecc916a9b6686edd3 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Fri, 27 Jul 2018 18:42:00 +0200 Subject: [PATCH 40/71] Fix try spawn actor catching too general exception --- LibCarla/source/carla/client/World.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/LibCarla/source/carla/client/World.cpp b/LibCarla/source/carla/client/World.cpp index bd2b8bc26..c8c1fd851 100644 --- a/LibCarla/source/carla/client/World.cpp +++ b/LibCarla/source/carla/client/World.cpp @@ -8,6 +8,8 @@ #include "carla/Logging.h" +#include + namespace carla { namespace client { @@ -17,7 +19,7 @@ namespace client { Actor *parent) { try { return SpawnActor(blueprint, transform, parent); - } catch (const std::exception &e) { + } catch (const ::rpc::rpc_error &e) { log_warning("TrySpawnActor: failed with:", e.what()); return nullptr; } From eb2cbc7839227db06e2ff34cd303d33ebfaf9184 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Fri, 27 Jul 2018 18:42:49 +0200 Subject: [PATCH 41/71] Expose recommended attribute values in Python --- LibCarla/source/carla/client/ActorAttribute.h | 4 +++ PythonAPI/source/libcarla/Blueprint.cpp | 36 +++++++++++++++---- 2 files changed, 33 insertions(+), 7 deletions(-) diff --git a/LibCarla/source/carla/client/ActorAttribute.h b/LibCarla/source/carla/client/ActorAttribute.h index 4be38b897..1f022da21 100644 --- a/LibCarla/source/carla/client/ActorAttribute.h +++ b/LibCarla/source/carla/client/ActorAttribute.h @@ -67,6 +67,10 @@ namespace client { return _attribute.type; } + const std::vector &GetRecommendedValues() const { + return _attribute.recommended_values; + } + /// Cast the value to the given type. /// /// @throw BadAttributeCast if the cast fails. diff --git a/PythonAPI/source/libcarla/Blueprint.cpp b/PythonAPI/source/libcarla/Blueprint.cpp index 490a96d57..d9ff73976 100644 --- a/PythonAPI/source/libcarla/Blueprint.cpp +++ b/PythonAPI/source/libcarla/Blueprint.cpp @@ -8,9 +8,29 @@ #include #include +#include #include +template +static std::ostream &PrintList(std::ostream &out, const Iterable &list) { + auto it = list.begin(); + out << '[' << *it; + for (++it; it != list.end(); ++it) { + out << ", " << *it; + } + out << ']'; + return out; +} + +namespace std { + + std::ostream &operator<<(std::ostream &out, const std::vector &vector_of_strings) { + return PrintList(out, vector_of_strings); + } + +} // namespace std + namespace carla { namespace client { @@ -27,13 +47,7 @@ namespace client { } std::ostream &operator<<(std::ostream &out, const BlueprintLibrary &blueprints) { - auto it = blueprints.begin(); - out << '[' << *it; - for (++it; it != blueprints.end(); ++it) { - out << ", " << *it; - } - out << ']'; - return out; + return PrintList(out, blueprints); } } // namespace client @@ -60,9 +74,17 @@ void export_blueprint() { .def(self_ns::str(self_ns::self)) ; + class_>("vector_of_strings") + .def(vector_indexing_suite>()) + .def(self_ns::str(self_ns::self)) + ; + class_("ActorAttribute", no_init) .add_property("is_modifiable", &cc::ActorAttribute::IsModifiable) .add_property("type", &cc::ActorAttribute::GetType) + .add_property("recommended_values", +[](const cc::ActorAttribute &self) -> std::vector { + return self.GetRecommendedValues(); + }) .def("as_bool", &cc::ActorAttribute::As) .def("as_int", &cc::ActorAttribute::As) .def("as_float", &cc::ActorAttribute::As) From ad876a282fd2aa381ac7db15b94ec2a7d3b32141 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Fri, 27 Jul 2018 18:43:27 +0200 Subject: [PATCH 42/71] Better validation of actor descriptions --- LibCarla/source/carla/client/ActorAttribute.cpp | 2 ++ .../Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp | 5 +++-- .../Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp | 2 +- 3 files changed, 6 insertions(+), 3 deletions(-) diff --git a/LibCarla/source/carla/client/ActorAttribute.cpp b/LibCarla/source/carla/client/ActorAttribute.cpp index 7db6fb2db..7a9b5066d 100644 --- a/LibCarla/source/carla/client/ActorAttribute.cpp +++ b/LibCarla/source/carla/client/ActorAttribute.cpp @@ -6,6 +6,7 @@ #include "carla/client/ActorAttribute.h" +#include "carla/Logging.h" #include "carla/StringUtil.h" namespace carla { @@ -70,6 +71,7 @@ namespace client { std::vector channels; StringUtil::Split(channels, _attribute.value, ","); if (channels.size() != 3u) { + log_error("invalid color", _attribute.value); LIBCARLA_THROW_INVALID_VALUE("colors must have 3 channels (R,G,B)"); } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp index 0f8a9d2cc..2533dfe86 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp @@ -99,7 +99,7 @@ private: bool IsIdValid(const FString &Id) { /// @todo Do more checks. - return OnScreenAssert(!Id.IsEmpty(), TEXT("Id cannot be empty")); + return OnScreenAssert((!Id.IsEmpty() && Id != TEXT(".")), TEXT("Id cannot be empty")); } bool AreTagsValid(const FString &Tags) @@ -111,7 +111,7 @@ private: bool IsValid(const EActorAttributeType Type) { /// @todo Do more checks. - return OnScreenAssert(Type < EActorAttributeType::SIZE, TEXT("Invalid Type")); + return OnScreenAssert(Type < EActorAttributeType::SIZE, TEXT("Invalid type")); } bool ValueIsValid(const EActorAttributeType Type, const FString &Value) @@ -125,6 +125,7 @@ private: return IsIdValid(Variation.Id) && IsValid(Variation.Type) && + OnScreenAssert(Variation.RecommendedValues.Num() > 0, TEXT("Recommended values cannot be empty")) && ForEach(TEXT("Recommended Value"), Variation.RecommendedValues, [&](auto &Value) { return ValueIsValid(Variation.Type, Value); }); diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp index 39c189717..f445c4ec4 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp @@ -21,7 +21,7 @@ void FActorDispatcher::Bind(FActorDefinition Definition, SpawnFunctionType Funct } else { - UE_LOG(LogCarla, Warning, TEXT("Invalid definition ignored")); + UE_LOG(LogCarla, Warning, TEXT("Invalid definition '%s' ignored"), *Definition.Id); } } From c4c15cbb41f224bfe39969fdfc03f7144400d16e Mon Sep 17 00:00:00 2001 From: nsubiron Date: Fri, 27 Jul 2018 19:56:00 +0200 Subject: [PATCH 43/71] Add function to enable autopilot from Python --- LibCarla/source/carla/client/Client.cpp | 6 ++++++ LibCarla/source/carla/client/Client.h | 4 ++++ LibCarla/source/carla/client/Vehicle.h | 4 ++++ PythonAPI/source/libcarla/Actor.cpp | 1 + .../Source/Carla/Server/TheNewCarlaServer.cpp | 19 ++++++++++++++++++- .../Vehicle/WheeledVehicleAIController.cpp | 8 ++++++++ 6 files changed, 41 insertions(+), 1 deletion(-) diff --git a/LibCarla/source/carla/client/Client.cpp b/LibCarla/source/carla/client/Client.cpp index 7bc92fe33..93c11d61b 100644 --- a/LibCarla/source/carla/client/Client.cpp +++ b/LibCarla/source/carla/client/Client.cpp @@ -41,5 +41,11 @@ namespace client { _client.call("apply_control_to_actor", actor.Serialize(), control); } + void Client::SetActorAutopilot( + const Actor &actor, + const bool enabled) { + _client.call("set_actor_autopilot", actor.Serialize(), enabled); + } + } // namespace client } // namespace carla diff --git a/LibCarla/source/carla/client/Client.h b/LibCarla/source/carla/client/Client.h index faa3accc2..9ecca995a 100644 --- a/LibCarla/source/carla/client/Client.h +++ b/LibCarla/source/carla/client/Client.h @@ -80,6 +80,10 @@ namespace client { const Actor &actor, const VehicleControl &control); + void SetActorAutopilot( + const Actor &actor, + bool enabled); + private: carla::rpc::Client _client; diff --git a/LibCarla/source/carla/client/Vehicle.h b/LibCarla/source/carla/client/Vehicle.h index e0dfb328d..79eefd17a 100644 --- a/LibCarla/source/carla/client/Vehicle.h +++ b/LibCarla/source/carla/client/Vehicle.h @@ -19,6 +19,10 @@ namespace client { GetWorld()->GetClient().ApplyControlToActor(*this, control); } + void SetAutopilot(bool enabled = true) { + GetWorld()->GetClient().SetActorAutopilot(*this, enabled); + } + private: friend class Client; diff --git a/PythonAPI/source/libcarla/Actor.cpp b/PythonAPI/source/libcarla/Actor.cpp index 1a59a889d..5821bb2e1 100644 --- a/PythonAPI/source/libcarla/Actor.cpp +++ b/PythonAPI/source/libcarla/Actor.cpp @@ -84,6 +84,7 @@ void export_actor() { class_, boost::noncopyable, boost::shared_ptr>("Vehicle", no_init) .def("apply_control", &cc::Vehicle::ApplyControl) + .def("set_autopilot", &cc::Vehicle::SetAutopilot, (arg("enabled")=true)) .def(self_ns::str(self_ns::self)) ; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp index 29ea5652a..35d7b7bcf 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp @@ -194,7 +194,7 @@ void FTheNewCarlaServer::FPimpl::BindActions() Server.BindSync("apply_control_to_actor", [this](cr::Actor Actor, cr::VehicleControl Control) { RequireEpisode(); auto ActorView = Episode->GetActorRegistry().Find(Actor.id); - if (!ActorView.IsValid()) { + if (!ActorView.IsValid() || ActorView.GetActor()->IsPendingKill()) { RespondErrorStr("unable to apply control: actor not found"); } auto Vehicle = Cast(ActorView.GetActor()); @@ -203,6 +203,23 @@ void FTheNewCarlaServer::FPimpl::BindActions() } Vehicle->ApplyVehicleControl(Control); }); + + Server.BindSync("set_actor_autopilot", [this](cr::Actor Actor, bool bEnabled) { + RequireEpisode(); + auto ActorView = Episode->GetActorRegistry().Find(Actor.id); + if (!ActorView.IsValid() || ActorView.GetActor()->IsPendingKill()) { + RespondErrorStr("unable to set autopilot: actor not found"); + } + auto Vehicle = Cast(ActorView.GetActor()); + if (Vehicle == nullptr) { + RespondErrorStr("unable to set autopilot: actor is not a vehicle"); + } + auto Controller = Cast(Vehicle->GetController()); + if (Controller == nullptr) { + RespondErrorStr("unable to set autopilot: vehicle has an incompatible controller"); + } + Controller->SetAutopilot(bEnabled); + }); } // ============================================================================= diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/WheeledVehicleAIController.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/WheeledVehicleAIController.cpp index c8a2cf8e6..f97a71e6c 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/WheeledVehicleAIController.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/WheeledVehicleAIController.cpp @@ -75,6 +75,8 @@ AWheeledVehicleAIController::AWheeledVehicleAIController(const FObjectInitialize { RandomEngine = CreateDefaultSubobject(TEXT("RandomEngine")); + RandomEngine->Seed(RandomEngine->GenerateRandomSeed()); + PrimaryActorTick.bCanEverTick = true; PrimaryActorTick.TickGroup = TG_PrePhysics; } @@ -98,6 +100,12 @@ void AWheeledVehicleAIController::Possess(APawn *aPawn) MaximumSteerAngle = Vehicle->GetMaximumSteerAngle(); check(MaximumSteerAngle > 0.0f); ConfigureAutopilot(bAutopilotEnabled); + + if (RoadMap == nullptr) + { + TActorIterator It(GetWorld()); + RoadMap = (It ? It->GetRoadMap() : nullptr); + } } void AWheeledVehicleAIController::Tick(const float DeltaTime) From ae900053dce15f94deee559df9c045d3dfccba0b Mon Sep 17 00:00:00 2001 From: nsubiron Date: Fri, 27 Jul 2018 21:10:39 +0200 Subject: [PATCH 44/71] Do not use post-process None as default --- .../Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp index 2533dfe86..5b5cd2b50 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp @@ -198,10 +198,12 @@ void UActorBlueprintFunctionLibrary::MakeCameraDefinition( FActorVariation PostProcessing; PostProcessing.Id = TEXT("post_processing"); PostProcessing.Type = EActorAttributeType::String; - for (uint8 i = 0u; i < PostProcessEffect::ToUInt(EPostProcessEffect::SIZE); ++i) + for (uint8 i = 1u; i < PostProcessEffect::ToUInt(EPostProcessEffect::SIZE); ++i) { PostProcessing.RecommendedValues.Add(PostProcessEffect::ToString(i)); } + // By defaul goes to the first one, we don't want None as default. + PostProcessing.RecommendedValues.Add(PostProcessEffect::ToString(0u)); PostProcessing.bRestrictToRecommended = true; // FOV. FActorVariation FOV; From 3bd383a46deef9abd46584dc4a1e63e2dbd2a830 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Fri, 27 Jul 2018 21:11:16 +0200 Subject: [PATCH 45/71] Fix camera settings ignored --- .../Carla/Source/Carla/Sensor/SensorFactory.cpp | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SensorFactory.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SensorFactory.cpp index 7a853d8ea..1f9f0c5ff 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SensorFactory.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SensorFactory.cpp @@ -27,14 +27,17 @@ FActorSpawnResult ASensorFactory::SpawnActor( const FActorDescription &Description) { FActorSpawnParameters Params; - static int32 COUNTER = 0u; - Params.Name = FName(*(Description.Id + FString::FromInt(++COUNTER))); auto *World = GetWorld(); if (World == nullptr) { return {}; } - auto *Sensor = World->SpawnActor(Description.Class, Transform, Params); + auto *Sensor = World->SpawnActorDeferred( + Description.Class, + Transform, + this, + nullptr, + ESpawnActorCollisionHandlingMethod::AlwaysSpawn); if (Sensor != nullptr) { using ABFL = UActorBlueprintFunctionLibrary; @@ -47,5 +50,6 @@ FActorSpawnResult ASensorFactory::SpawnActor( PostProcessEffect::FromString( ABFL::RetrieveActorAttributeToString("post_processing", Description.Variations, "SceneFinal"))); } + UGameplayStatics::FinishSpawningActor(Sensor, Transform); return FActorSpawnResult{Sensor}; } From 8c656b548647f8a413e27c264193da483404de54 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Fri, 27 Jul 2018 21:12:04 +0200 Subject: [PATCH 46/71] Add the tagger to the new game mode --- .../Carla/Game/TheNewCarlaGameModeBase.cpp | 18 ++++++++++++++++++ .../Carla/Game/TheNewCarlaGameModeBase.h | 5 +++++ 2 files changed, 23 insertions(+) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/TheNewCarlaGameModeBase.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/TheNewCarlaGameModeBase.cpp index ee4eb9f5b..56b2dd44e 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/TheNewCarlaGameModeBase.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/TheNewCarlaGameModeBase.cpp @@ -7,6 +7,9 @@ #include "Carla.h" #include "Carla/Game/TheNewCarlaGameModeBase.h" +#include "Game/Tagger.h" +#include "Game/TaggerDelegate.h" + ATheNewCarlaGameModeBase::ATheNewCarlaGameModeBase(const FObjectInitializer& ObjectInitializer) : Super(ObjectInitializer) { @@ -15,6 +18,8 @@ ATheNewCarlaGameModeBase::ATheNewCarlaGameModeBase(const FObjectInitializer& Obj bAllowTickBeforeBeginPlay = false; Episode = CreateDefaultSubobject(TEXT("Episode")); + + TaggerDelegate = CreateDefaultSubobject(TEXT("TaggerDelegate")); } void ATheNewCarlaGameModeBase::InitGame( @@ -32,6 +37,13 @@ void ATheNewCarlaGameModeBase::InitGame( GameInstance != nullptr, TEXT("GameInstance is not a UCarlaGameInstance, did you forget to set it in the project settings?")); + if (TaggerDelegate != nullptr) { + check(GetWorld() != nullptr); + TaggerDelegate->RegisterSpawnHandler(GetWorld()); + } else { + UE_LOG(LogCarla, Error, TEXT("Missing TaggerDelegate!")); + } + SpawnActorFactories(); } @@ -39,6 +51,12 @@ void ATheNewCarlaGameModeBase::BeginPlay() { Super::BeginPlay(); + if (true) { /// @todo If semantic segmentation enabled. + check(GetWorld() != nullptr); + ATagger::TagActorsInLevel(*GetWorld(), true); + TaggerDelegate->SetSemanticSegmentationEnabled(); + } + GameInstance->NotifyBeginEpisode(*Episode); } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/TheNewCarlaGameModeBase.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/TheNewCarlaGameModeBase.h index 553981c81..237543b7f 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/TheNewCarlaGameModeBase.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/TheNewCarlaGameModeBase.h @@ -14,6 +14,8 @@ #include "TheNewCarlaGameModeBase.generated.h" +class UTaggerDelegate; + /// Base class for the CARLA Game Mode. UCLASS(HideCategories=(ActorTick)) class CARLA_API ATheNewCarlaGameModeBase : public AGameModeBase @@ -41,6 +43,9 @@ private: UPROPERTY() UCarlaGameInstance *GameInstance = nullptr; + UPROPERTY() + UTaggerDelegate *TaggerDelegate = nullptr; + UPROPERTY() UCarlaEpisode *Episode = nullptr; From c785437f081782645b8664d7622ed1647ac8bc8b Mon Sep 17 00:00:00 2001 From: nsubiron Date: Sat, 28 Jul 2018 13:03:16 +0200 Subject: [PATCH 47/71] Fix images overexposed --- .../Source/Carla/Sensor/SceneCaptureCamera.cpp | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureCamera.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureCamera.cpp index 712cc5164..6db2e471a 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureCamera.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureCamera.cpp @@ -52,6 +52,8 @@ struct FImageHeaderData float FOV; }; +static void SetCameraDefaultOverrides(USceneCaptureComponent2D &CaptureComponent2D); + static void RemoveShowFlags(FEngineShowFlags &ShowFlags); // ============================================================================= @@ -97,6 +99,7 @@ ASceneCaptureCamera::ASceneCaptureCamera(const FObjectInitializer &ObjectInitial CaptureComponent2D = CreateDefaultSubobject( TEXT("SceneCaptureComponent2D")); CaptureComponent2D->SetupAttachment(MeshComp); + SetCameraDefaultOverrides(*CaptureComponent2D); // Load post-processing materials. static ConstructorHelpers::FObjectFinder DEPTH( @@ -433,6 +436,19 @@ void ASceneCaptureCamera::UpdateDrawFrustum() // -- Local static functions implementations ----------------------------------- // ============================================================================= +static void SetCameraDefaultOverrides(USceneCaptureComponent2D &CaptureComponent2D) +{ + auto &PostProcessSettings = CaptureComponent2D.PostProcessSettings; + PostProcessSettings.bOverride_AutoExposureMethod = true; + PostProcessSettings.AutoExposureMethod = AEM_Histogram; + PostProcessSettings.bOverride_AutoExposureMinBrightness = true; + PostProcessSettings.AutoExposureMinBrightness = 0.27f; + PostProcessSettings.bOverride_AutoExposureMaxBrightness = true; + PostProcessSettings.AutoExposureMaxBrightness = 5.0f; + PostProcessSettings.bOverride_AutoExposureBias = true; + PostProcessSettings.AutoExposureBias = -3.5f; +} + // Remove the show flags that might interfere with post-processing effects like // depth and semantic segmentation. static void RemoveShowFlags(FEngineShowFlags &ShowFlags) From 67643485ccf2a4906f0ef7e76e842a16cad87254 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Sat, 28 Jul 2018 13:04:14 +0200 Subject: [PATCH 48/71] Fix long-standing crash when a vehicle is destroyed --- .../Vehicle/WheeledVehicleAIController.cpp | 18 ++++++++++++++++-- .../Carla/Vehicle/WheeledVehicleAIController.h | 6 ++++-- 2 files changed, 20 insertions(+), 4 deletions(-) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/WheeledVehicleAIController.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/WheeledVehicleAIController.cpp index f97a71e6c..f94283463 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/WheeledVehicleAIController.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/WheeledVehicleAIController.cpp @@ -91,7 +91,8 @@ void AWheeledVehicleAIController::Possess(APawn *aPawn) { Super::Possess(aPawn); - if (IsPossessingAVehicle()) { + if (IsPossessingAVehicle()) + { UE_LOG(LogCarla, Error, TEXT("Controller already possessing a vehicle!")); return; } @@ -108,13 +109,26 @@ void AWheeledVehicleAIController::Possess(APawn *aPawn) } } +void AWheeledVehicleAIController::UnPossess() +{ + Super::UnPossess(); + + Vehicle = nullptr; +} + void AWheeledVehicleAIController::Tick(const float DeltaTime) { Super::Tick(DeltaTime); + if (!IsPossessingAVehicle()) + { + return; + } + TickAutopilotController(); - if (bAutopilotEnabled) { + if (bAutopilotEnabled) + { Vehicle->ApplyVehicleControl(AutopilotControl); } } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/WheeledVehicleAIController.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/WheeledVehicleAIController.h index 2e7f36bf9..b80be8674 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/WheeledVehicleAIController.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/WheeledVehicleAIController.h @@ -42,9 +42,11 @@ public: /// @{ public: - virtual void Possess(APawn *aPawn) override; + void Possess(APawn *aPawn) override; - virtual void Tick(float DeltaTime) override; + void UnPossess() override; + + void Tick(float DeltaTime) override; /// @} // =========================================================================== From f9b7578d6c84dbc60e54211441f84375d698017c Mon Sep 17 00:00:00 2001 From: nsubiron Date: Sat, 28 Jul 2018 13:04:59 +0200 Subject: [PATCH 49/71] Allow destroying actors from Python --- LibCarla/source/carla/client/Actor.cpp | 18 ++++++++++++++++++ LibCarla/source/carla/client/Actor.h | 2 ++ LibCarla/source/carla/client/Client.cpp | 4 ++++ LibCarla/source/carla/client/Client.h | 2 ++ PythonAPI/source/libcarla/Actor.cpp | 1 + .../Source/Carla/Server/TheNewCarlaServer.cpp | 9 +++++++++ 6 files changed, 36 insertions(+) create mode 100644 LibCarla/source/carla/client/Actor.cpp diff --git a/LibCarla/source/carla/client/Actor.cpp b/LibCarla/source/carla/client/Actor.cpp new file mode 100644 index 000000000..7ad70ccca --- /dev/null +++ b/LibCarla/source/carla/client/Actor.cpp @@ -0,0 +1,18 @@ +// 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 . + +#include "carla/client/Actor.h" +#include "carla/client/Client.h" + +namespace carla { +namespace client { + + void Actor::Destroy() { + GetWorld()->GetClient().DestroyActor(*this); + } + +} // namespace client +} // namespace carla diff --git a/LibCarla/source/carla/client/Actor.h b/LibCarla/source/carla/client/Actor.h index c7c641b1e..6216eae92 100644 --- a/LibCarla/source/carla/client/Actor.h +++ b/LibCarla/source/carla/client/Actor.h @@ -43,6 +43,8 @@ namespace client { return _actor; } + void Destroy(); + protected: Actor(carla::rpc::Actor actor, SharedPtr world) diff --git a/LibCarla/source/carla/client/Client.cpp b/LibCarla/source/carla/client/Client.cpp index 93c11d61b..43eb5c1c5 100644 --- a/LibCarla/source/carla/client/Client.cpp +++ b/LibCarla/source/carla/client/Client.cpp @@ -35,6 +35,10 @@ namespace client { return SharedPtr(new Vehicle{actor, GetWorld()}); } + void Client::DestroyActor(Actor &actor) { + _client.call("destroy_actor", actor.Serialize()); + } + void Client::ApplyControlToActor( const Actor &actor, const VehicleControl &control) { diff --git a/LibCarla/source/carla/client/Client.h b/LibCarla/source/carla/client/Client.h index 9ecca995a..c1446ddc7 100644 --- a/LibCarla/source/carla/client/Client.h +++ b/LibCarla/source/carla/client/Client.h @@ -76,6 +76,8 @@ namespace client { const Transform &transform, Actor *parent = nullptr); + void DestroyActor(Actor &actor); + void ApplyControlToActor( const Actor &actor, const VehicleControl &control); diff --git a/PythonAPI/source/libcarla/Actor.cpp b/PythonAPI/source/libcarla/Actor.cpp index 5821bb2e1..a3f75c776 100644 --- a/PythonAPI/source/libcarla/Actor.cpp +++ b/PythonAPI/source/libcarla/Actor.cpp @@ -79,6 +79,7 @@ void export_actor() { return self.GetTypeId(); }) .def("get_world", &cc::Actor::GetWorld) + .def("destroy", &cc::Actor::Destroy) .def(self_ns::str(self_ns::self)) ; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp index 35d7b7bcf..d3c94f1e2 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp @@ -185,6 +185,15 @@ void FTheNewCarlaServer::FPimpl::BindActions() return SerializeActor(ActorView); }); + Server.BindSync("destroy_actor", [this](cr::Actor Actor) { + RequireEpisode(); + auto ActorView = Episode->GetActorRegistry().Find(Actor.id); + if (!ActorView.IsValid() || ActorView.GetActor()->IsPendingKill()) { + RespondErrorStr("unable to destroy actor: actor not found"); + } + Episode->DestroyActor(ActorView.GetActor()); + }); + Server.BindSync("attach_actors", [this](cr::Actor Child, cr::Actor Parent) { RequireEpisode(); auto &Registry = Episode->GetActorRegistry(); From 225387740589e308d1052b4599c3abc8bf20b8bd Mon Sep 17 00:00:00 2001 From: nsubiron Date: Sat, 28 Jul 2018 13:59:31 +0200 Subject: [PATCH 50/71] Name some arguments for Python --- LibCarla/source/carla/client/Client.cpp | 8 ++++++++ LibCarla/source/carla/client/Client.h | 18 ++++++++++-------- PythonAPI/source/libcarla/Actor.cpp | 4 ++-- PythonAPI/source/libcarla/Client.cpp | 5 +++-- 4 files changed, 23 insertions(+), 12 deletions(-) diff --git a/LibCarla/source/carla/client/Client.cpp b/LibCarla/source/carla/client/Client.cpp index 43eb5c1c5..f13e39223 100644 --- a/LibCarla/source/carla/client/Client.cpp +++ b/LibCarla/source/carla/client/Client.cpp @@ -12,9 +12,17 @@ #include "carla/client/Vehicle.h" #include "carla/client/World.h" +#include + namespace carla { namespace client { + Client::Client(const std::string &host, uint16_t port, size_t worker_threads) + : _client(host, port) { + _streaming_client.AsyncRun( + worker_threads > 0u ? worker_threads : std::thread::hardware_concurrency()); + } + SharedPtr Client::GetWorld() { if (_active_world == nullptr) { _active_world.reset(new World(shared_from_this())); diff --git a/LibCarla/source/carla/client/Client.h b/LibCarla/source/carla/client/Client.h index c1446ddc7..bdc8f0644 100644 --- a/LibCarla/source/carla/client/Client.h +++ b/LibCarla/source/carla/client/Client.h @@ -16,7 +16,6 @@ #include "carla/streaming/Client.h" #include -#include namespace carla { namespace client { @@ -30,13 +29,16 @@ namespace client { private NonCopyable { public: - template - explicit Client(Args && ... args) - : _client(std::forward(args) ...) { - /// @todo Make these arguments. - SetTimeout(10'000); - _streaming_client.AsyncRun(std::thread::hardware_concurrency()); - } + /// Construct a carla client. + /// + /// @param host IP address of the host machine running the simulator. + /// @param port TCP port to connect with the simulator. + /// @param worker_threads number of asynchronous threads to use, or 0 to use + /// all available hardware concurrency. + explicit Client( + const std::string &host, + uint16_t port, + size_t worker_threads = 0u); void SetTimeout(int64_t milliseconds) { _client.set_timeout(milliseconds); diff --git a/PythonAPI/source/libcarla/Actor.cpp b/PythonAPI/source/libcarla/Actor.cpp index a3f75c776..0bcdbb285 100644 --- a/PythonAPI/source/libcarla/Actor.cpp +++ b/PythonAPI/source/libcarla/Actor.cpp @@ -84,7 +84,7 @@ void export_actor() { ; class_, boost::noncopyable, boost::shared_ptr>("Vehicle", no_init) - .def("apply_control", &cc::Vehicle::ApplyControl) + .def("apply_control", &cc::Vehicle::ApplyControl, (arg("control"))) .def("set_autopilot", &cc::Vehicle::SetAutopilot, (arg("enabled")=true)) .def(self_ns::str(self_ns::self)) ; @@ -115,7 +115,7 @@ void export_actor() { PyErr_Print(); } }); - }) + }, (arg("callback"))) .def(self_ns::str(self_ns::self)) ; } diff --git a/PythonAPI/source/libcarla/Client.cpp b/PythonAPI/source/libcarla/Client.cpp index bd8735ed7..9fdf25324 100644 --- a/PythonAPI/source/libcarla/Client.cpp +++ b/PythonAPI/source/libcarla/Client.cpp @@ -13,8 +13,9 @@ void export_client() { using namespace boost::python; namespace cc = carla::client; - class_>("Client", init()) - .def("set_timeout", &cc::Client::SetTimeout) + class_>("Client", + init((arg("host"), arg("port"), arg("worker_threads")=0u))) + .def("set_timeout", &cc::Client::SetTimeout, (arg("milliseconds"))) .def("get_client_version", &cc::Client::GetClientVersion) .def("get_server_version", &cc::Client::GetServerVersion) .def("ping", &cc::Client::Ping) From 7d1f51e9cc22f29b3fd286cfd2053498030c5fc1 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Sat, 28 Jul 2018 15:23:57 +0200 Subject: [PATCH 51/71] Add functions to set actor location and transform --- LibCarla/source/carla/client/Actor.cpp | 8 +++++ LibCarla/source/carla/client/Actor.h | 4 +++ LibCarla/source/carla/client/Client.cpp | 12 +++++-- LibCarla/source/carla/client/Client.h | 10 ++++-- PythonAPI/source/libcarla/Actor.cpp | 2 ++ .../Source/Carla/Server/TheNewCarlaServer.cpp | 34 +++++++++++++++++++ 6 files changed, 65 insertions(+), 5 deletions(-) diff --git a/LibCarla/source/carla/client/Actor.cpp b/LibCarla/source/carla/client/Actor.cpp index 7ad70ccca..640b15ca6 100644 --- a/LibCarla/source/carla/client/Actor.cpp +++ b/LibCarla/source/carla/client/Actor.cpp @@ -10,6 +10,14 @@ namespace carla { namespace client { + bool Actor::SetLocation(const Location &location) { + return GetWorld()->GetClient().SetActorLocation(*this, location); + } + + bool Actor::SetTransform(const Transform &transform) { + return GetWorld()->GetClient().SetActorTransform(*this, transform); + } + void Actor::Destroy() { GetWorld()->GetClient().DestroyActor(*this); } diff --git a/LibCarla/source/carla/client/Actor.h b/LibCarla/source/carla/client/Actor.h index 6216eae92..8e8d22c48 100644 --- a/LibCarla/source/carla/client/Actor.h +++ b/LibCarla/source/carla/client/Actor.h @@ -39,6 +39,10 @@ namespace client { return _world; } + bool SetLocation(const Location &location); + + bool SetTransform(const Transform &transform); + const auto &Serialize() const { return _actor; } diff --git a/LibCarla/source/carla/client/Client.cpp b/LibCarla/source/carla/client/Client.cpp index f13e39223..a6fd8d453 100644 --- a/LibCarla/source/carla/client/Client.cpp +++ b/LibCarla/source/carla/client/Client.cpp @@ -47,14 +47,22 @@ namespace client { _client.call("destroy_actor", actor.Serialize()); } + bool Client::SetActorLocation(Actor &actor, const Location &location) { + return Call("set_actor_location", actor.Serialize(), location); + } + + bool Client::SetActorTransform(Actor &actor, const Transform &transform) { + return Call("set_actor_transform", actor.Serialize(), transform); + } + void Client::ApplyControlToActor( - const Actor &actor, + Actor &actor, const VehicleControl &control) { _client.call("apply_control_to_actor", actor.Serialize(), control); } void Client::SetActorAutopilot( - const Actor &actor, + Actor &actor, const bool enabled) { _client.call("set_actor_autopilot", actor.Serialize(), enabled); } diff --git a/LibCarla/source/carla/client/Client.h b/LibCarla/source/carla/client/Client.h index bdc8f0644..0fcdac79d 100644 --- a/LibCarla/source/carla/client/Client.h +++ b/LibCarla/source/carla/client/Client.h @@ -80,13 +80,17 @@ namespace client { void DestroyActor(Actor &actor); + bool SetActorLocation(Actor &actor, const Location &location); + + bool SetActorTransform(Actor &actor, const Transform &transform); + void ApplyControlToActor( - const Actor &actor, + Actor &actor, const VehicleControl &control); void SetActorAutopilot( - const Actor &actor, - bool enabled); + Actor &actor, + bool enabled = true); private: diff --git a/PythonAPI/source/libcarla/Actor.cpp b/PythonAPI/source/libcarla/Actor.cpp index 0bcdbb285..a1e17af0c 100644 --- a/PythonAPI/source/libcarla/Actor.cpp +++ b/PythonAPI/source/libcarla/Actor.cpp @@ -79,6 +79,8 @@ void export_actor() { return self.GetTypeId(); }) .def("get_world", &cc::Actor::GetWorld) + .def("set_location", &cc::Actor::SetLocation, (arg("location"))) + .def("set_transform", &cc::Actor::SetTransform, (arg("transform"))) .def("destroy", &cc::Actor::Destroy) .def(self_ns::str(self_ns::self)) ; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp index d3c94f1e2..740fe3a6d 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp @@ -200,6 +200,40 @@ void FTheNewCarlaServer::FPimpl::BindActions() AttachActors(Registry.Find(Child.id), Registry.Find(Parent.id)); }); + Server.BindSync("set_actor_location", [this]( + cr::Actor Actor, + cr::Location Location) -> bool { + RequireEpisode(); + auto ActorView = Episode->GetActorRegistry().Find(Actor.id); + if (!ActorView.IsValid() || ActorView.GetActor()->IsPendingKill()) { + RespondErrorStr("unable to set actor location: actor not found"); + } + // This function only works with teleport physics, to reset speeds we need + // another method. + return ActorView.GetActor()->SetActorLocation( + Location, + false, + nullptr, + ETeleportType::TeleportPhysics); + }); + + Server.BindSync("set_actor_transform", [this]( + cr::Actor Actor, + cr::Transform Transform) -> bool { + RequireEpisode(); + auto ActorView = Episode->GetActorRegistry().Find(Actor.id); + if (!ActorView.IsValid() || ActorView.GetActor()->IsPendingKill()) { + RespondErrorStr("unable to set actor transform: actor not found"); + } + // This function only works with teleport physics, to reset speeds we need + // another method. + return ActorView.GetActor()->SetActorTransform( + Transform, + false, + nullptr, + ETeleportType::TeleportPhysics); + }); + Server.BindSync("apply_control_to_actor", [this](cr::Actor Actor, cr::VehicleControl Control) { RequireEpisode(); auto ActorView = Episode->GetActorRegistry().Find(Actor.id); From 1b69494772a5f28218e6b88dc4a2778549903de5 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Sat, 28 Jul 2018 16:10:59 +0200 Subject: [PATCH 52/71] Print blueprint tags too --- PythonAPI/source/libcarla/Blueprint.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/PythonAPI/source/libcarla/Blueprint.cpp b/PythonAPI/source/libcarla/Blueprint.cpp index d9ff73976..9502921eb 100644 --- a/PythonAPI/source/libcarla/Blueprint.cpp +++ b/PythonAPI/source/libcarla/Blueprint.cpp @@ -42,7 +42,7 @@ namespace client { } std::ostream &operator<<(std::ostream &out, const ActorBlueprint &bp) { - out << "ActorBlueprint(id=" << bp.GetId() << ')'; + out << "ActorBlueprint(id=" << bp.GetId() << "tags=" << bp.GetTags() << ')'; return out; } From 12243aa84e4a475c6b969519100c46d5220e6b7b Mon Sep 17 00:00:00 2001 From: nsubiron Date: Sat, 28 Jul 2018 17:46:26 +0200 Subject: [PATCH 53/71] Add functions to get actor location and transform --- LibCarla/source/carla/client/Actor.cpp | 8 +++++++ LibCarla/source/carla/client/Actor.h | 4 ++++ LibCarla/source/carla/client/Client.cpp | 8 +++++++ LibCarla/source/carla/client/Client.h | 4 ++++ LibCarla/source/carla/rpc/Transform.h | 22 ++++++++++++++++++- PythonAPI/source/libcarla/Actor.cpp | 2 ++ .../Source/Carla/Server/TheNewCarlaServer.cpp | 18 +++++++++++++++ 7 files changed, 65 insertions(+), 1 deletion(-) diff --git a/LibCarla/source/carla/client/Actor.cpp b/LibCarla/source/carla/client/Actor.cpp index 640b15ca6..6f5489a99 100644 --- a/LibCarla/source/carla/client/Actor.cpp +++ b/LibCarla/source/carla/client/Actor.cpp @@ -10,6 +10,14 @@ namespace carla { namespace client { + Location Actor::GetLocation() { + return GetWorld()->GetClient().GetActorLocation(*this); + } + + Transform Actor::GetTransform() { + return GetWorld()->GetClient().GetActorTransform(*this); + } + bool Actor::SetLocation(const Location &location) { return GetWorld()->GetClient().SetActorLocation(*this, location); } diff --git a/LibCarla/source/carla/client/Actor.h b/LibCarla/source/carla/client/Actor.h index 8e8d22c48..0a9be0977 100644 --- a/LibCarla/source/carla/client/Actor.h +++ b/LibCarla/source/carla/client/Actor.h @@ -39,6 +39,10 @@ namespace client { return _world; } + Location GetLocation(); + + Transform GetTransform(); + bool SetLocation(const Location &location); bool SetTransform(const Transform &transform); diff --git a/LibCarla/source/carla/client/Client.cpp b/LibCarla/source/carla/client/Client.cpp index a6fd8d453..5f1504c1d 100644 --- a/LibCarla/source/carla/client/Client.cpp +++ b/LibCarla/source/carla/client/Client.cpp @@ -47,6 +47,14 @@ namespace client { _client.call("destroy_actor", actor.Serialize()); } + Location Client::GetActorLocation(Actor &actor) { + return Call("get_actor_location", actor.Serialize()); + } + + Transform Client::GetActorTransform(Actor &actor) { + return Call("get_actor_transform", actor.Serialize()); + } + bool Client::SetActorLocation(Actor &actor, const Location &location) { return Call("set_actor_location", actor.Serialize(), location); } diff --git a/LibCarla/source/carla/client/Client.h b/LibCarla/source/carla/client/Client.h index 0fcdac79d..67bffb89b 100644 --- a/LibCarla/source/carla/client/Client.h +++ b/LibCarla/source/carla/client/Client.h @@ -80,6 +80,10 @@ namespace client { void DestroyActor(Actor &actor); + Location GetActorLocation(Actor &actor); + + Transform GetActorTransform(Actor &actor); + bool SetActorLocation(Actor &actor, const Location &location); bool SetActorTransform(Actor &actor, const Transform &transform); diff --git a/LibCarla/source/carla/rpc/Transform.h b/LibCarla/source/carla/rpc/Transform.h index 2d97e2bf4..6133a6ee6 100644 --- a/LibCarla/source/carla/rpc/Transform.h +++ b/LibCarla/source/carla/rpc/Transform.h @@ -40,7 +40,27 @@ namespace rpc { #endif // LIBCARLA_INCLUDED_FROM_UE4 - MSGPACK_DEFINE_ARRAY(x, y, z); + // ========================================================================= + /// @todo The following is copy-pasted from MSGPACK_DEFINE_ARRAY. + /// This is a workaround for an issue in msgpack library. The + /// MSGPACK_DEFINE_ARRAY macro is shadowing our `z` variable. + /// https://github.com/msgpack/msgpack-c/issues/709 + // ========================================================================= + template + void msgpack_pack(Packer& pk) const + { + clmdep_msgpack::type::make_define_array(x, y, z).msgpack_pack(pk); + } + void msgpack_unpack(clmdep_msgpack::object const& o) + { + clmdep_msgpack::type::make_define_array(x, y, z).msgpack_unpack(o); + } + template + void msgpack_object(MSGPACK_OBJECT* o, clmdep_msgpack::zone& sneaky_variable_that_shadows_z) const + { + clmdep_msgpack::type::make_define_array(x, y, z).msgpack_object(o, sneaky_variable_that_shadows_z); + } + // ========================================================================= }; class Rotation { diff --git a/PythonAPI/source/libcarla/Actor.cpp b/PythonAPI/source/libcarla/Actor.cpp index a1e17af0c..c0225fd44 100644 --- a/PythonAPI/source/libcarla/Actor.cpp +++ b/PythonAPI/source/libcarla/Actor.cpp @@ -79,6 +79,8 @@ void export_actor() { return self.GetTypeId(); }) .def("get_world", &cc::Actor::GetWorld) + .def("get_location", &cc::Actor::GetLocation) + .def("get_transform", &cc::Actor::GetTransform) .def("set_location", &cc::Actor::SetLocation, (arg("location"))) .def("set_transform", &cc::Actor::SetTransform, (arg("transform"))) .def("destroy", &cc::Actor::Destroy) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp index 740fe3a6d..b560127ff 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp @@ -200,6 +200,24 @@ void FTheNewCarlaServer::FPimpl::BindActions() AttachActors(Registry.Find(Child.id), Registry.Find(Parent.id)); }); + Server.BindSync("get_actor_location", [this](cr::Actor Actor) -> cr::Location { + RequireEpisode(); + auto ActorView = Episode->GetActorRegistry().Find(Actor.id); + if (!ActorView.IsValid() || ActorView.GetActor()->IsPendingKill()) { + RespondErrorStr("unable to get actor location: actor not found"); + } + return {ActorView.GetActor()->GetActorLocation()}; + }); + + Server.BindSync("get_actor_transform", [this](cr::Actor Actor) -> cr::Transform { + RequireEpisode(); + auto ActorView = Episode->GetActorRegistry().Find(Actor.id); + if (!ActorView.IsValid() || ActorView.GetActor()->IsPendingKill()) { + RespondErrorStr("unable to get actor transform: actor not found"); + } + return {ActorView.GetActor()->GetActorTransform()}; + }); + Server.BindSync("set_actor_location", [this]( cr::Actor Actor, cr::Location Location) -> bool { From b870a35fbf149e336e360a395ba411d51a40e5f3 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Sat, 28 Jul 2018 19:32:05 +0200 Subject: [PATCH 54/71] Update content link --- Unreal/CarlaUE4/Config/DefaultEngine.ini | 2 +- Util/ContentVersions.txt | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Unreal/CarlaUE4/Config/DefaultEngine.ini b/Unreal/CarlaUE4/Config/DefaultEngine.ini index b043d24c9..afbe07120 100644 --- a/Unreal/CarlaUE4/Config/DefaultEngine.ini +++ b/Unreal/CarlaUE4/Config/DefaultEngine.ini @@ -13,7 +13,7 @@ AppliedDefaultGraphicsPerformance=Maximum EditorStartupMap=/Game/Carla/Maps/Town01.Town01 GameDefaultMap=/Game/Carla/Maps/Town01.Town01 ServerDefaultMap=/Game/Carla/Maps/Town01.Town01 -GlobalDefaultGameMode=/Game/Carla/Blueprints/Game/CarlaGameMode.CarlaGameMode_C +GlobalDefaultGameMode=/Game/Carla/Blueprints/Game/TheNewGameMode.TheNewGameMode_C GameInstanceClass=/Script/Carla.CarlaGameInstance TransitionMap=/Game/Carla/Maps/Town01.Town01 GlobalDefaultServerGameMode=/Game/Carla/Blueprints/Game/CarlaGameMode.CarlaGameMode_C diff --git a/Util/ContentVersions.txt b/Util/ContentVersions.txt index 04cf1f6fa..668f68dbe 100644 --- a/Util/ContentVersions.txt +++ b/Util/ContentVersions.txt @@ -13,4 +13,4 @@ 0.8.2: 1llrBkZDvJmxXYh4r3jz0wuwz8Q8jRQeZ 0.8.3: 1z2XKOk9LoKI-EhxcrpI31W5TeYo2-jjn 0.8.4: 1mFNS-w5atQ45yegiTepRIeKBYVm8N8He -Latest: 1UZodZd3uxr5h9SoJt7mI5k8T4j4VM-YP +0.9.0: 10QmgEZxMj3ZYfWeMOf0omRjj4M_eiuC8 From bf05c1220ad4f7b7edaa3894c93194512cea25dd Mon Sep 17 00:00:00 2001 From: nsubiron Date: Sat, 28 Jul 2018 19:47:18 +0200 Subject: [PATCH 55/71] Add example.py --- PythonAPI/example.py | 114 +++++++++++++++++++++++++++++++++++++ Util/BuildTools/Package.sh | 5 +- 2 files changed, 117 insertions(+), 2 deletions(-) create mode 100644 PythonAPI/example.py diff --git a/PythonAPI/example.py b/PythonAPI/example.py new file mode 100644 index 000000000..27821ea5f --- /dev/null +++ b/PythonAPI/example.py @@ -0,0 +1,114 @@ +#!/usr/bin/env python + +import sys + +sys.path.append( + 'PythonAPI/carla-0.9.0-py%d.%d-linux-x86_64.egg' % (sys.version_info.major, + sys.version_info.minor)) + +import carla + +import os +import random +import time + +# This function is here because this functionality haven't been ported to the +# new API yet. +def save_to_disk(image): + """Save this image to disk (requires PIL installed).""" + + filename = '_images/{:0>6d}_{:s}.png'.format(image.frame_number, image.type) + + try: + from PIL import Image as PImage + except ImportError: + raise RuntimeError( + 'cannot import PIL, make sure pillow package is installed') + + image = PImage.frombytes( + mode='RGBA', + size=(image.width, image.height), + data=image.raw_data, + decoder_name='raw') + color = image.split() + image = PImage.merge("RGB", color[2::-1]) + + folder = os.path.dirname(filename) + if not os.path.isdir(folder): + os.makedirs(folder) + image.save(filename) + + +def main(add_a_camera, enable_autopilot): + client = carla.Client('localhost', 2020) + client.set_timeout(2000) + + print('client version: %s' % client.get_client_version()) + print('server version: %s' % client.get_server_version()) + + world = client.get_world() + + blueprint_library = world.get_blueprint_library(); + + vehicle_blueprints = blueprint_library.filter('vehicle'); + + + actor_list = [] + + try: + + while True: + + bp = random.choice(vehicle_blueprints) + + if bp.contains_attribute('number_of_wheels'): + n = bp.get_attribute('number_of_wheels') + print('spawning vehicle %r with %d wheels' % (bp.id, n)) + + color = random.choice(bp.get_attribute('color').recommended_values) + bp.set_attribute('color', color) + + transform = carla.Transform( + carla.Location(x=180.0, y=199.0, z=40.0), + carla.Rotation(yaw=0.0)) + + vehicle = world.try_spawn_actor(bp, transform) + + if vehicle is None: + continue + + actor_list.append(vehicle) + + print(vehicle) + + if add_a_camera: + add_a_camera = False + + camera_bp = blueprint_library.find('camera') + # camera_bp.set_attribute('post_processing', 'Depth') + camera_transform = carla.Transform(carla.Location(x=0.4, y=0.0, z=1.4)) + camera = world.spawn_actor(camera_bp, camera_transform, attach_to=vehicle) + camera.listen(save_to_disk) + + if enable_autopilot: + vehicle.set_autopilot() + else: + vehicle.apply_control(carla.VehicleControl(throttle=1.0, steer=-1.0)) + + time.sleep(3) + + print('vehicle at %s' % vehicle.get_location()) + vehicle.set_location(carla.Location(x=220, y=199, z=38)) + print('is now at %s' % vehicle.get_location()) + + time.sleep(2) + + finally: + + for actor in actor_list: + actor.destroy() + + +if __name__ == '__main__': + + main(add_a_camera=False, enable_autopilot=True) diff --git a/Util/BuildTools/Package.sh b/Util/BuildTools/Package.sh index 92155640d..697e877cd 100755 --- a/Util/BuildTools/Package.sh +++ b/Util/BuildTools/Package.sh @@ -96,9 +96,10 @@ if $DO_COPY_FILES ; then copy_if_changed "./LICENSE" "${DESTINATION}/LICENSE" copy_if_changed "./CHANGELOG.md" "${DESTINATION}/CHANGELOG" copy_if_changed "./Docs/release_readme.md" "${DESTINATION}/README" - copy_if_changed "./Docs/Example.CarlaSettings.ini" "${DESTINATION}/Example.CarlaSettings.ini" + # copy_if_changed "./Docs/Example.CarlaSettings.ini" "${DESTINATION}/Example.CarlaSettings.ini" copy_if_changed "./Util/Docker/Release.Dockerfile" "${DESTINATION}/Dockerfile" - copy_if_changed "./PythonAPI/dist/*.egg" "${DESTINATION}/PythonAPI" + copy_if_changed "./PythonAPI/dist/*.egg" "${DESTINATION}/PythonAPI/" + copy_if_changed "./PythonAPI/example.py" "${DESTINATION}/example.py" popd >/dev/null From 78571e299f9078933ea127132bc410ffa7afa342 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Sat, 28 Jul 2018 19:29:31 +0200 Subject: [PATCH 56/71] Minimal documentation of the new API --- Docs/CONTRIBUTING.md | 10 +- Docs/benchmark_creating.md | 44 +++---- Docs/cameras_and_sensors.md | 6 + Docs/carla_settings.md | 12 +- Docs/coding_standard.md | 4 +- Docs/configuring_the_simulation.md | 3 + Docs/getting_started.md | 60 +++++++-- Docs/index.md | 18 ++- Docs/python_api.md | 117 ++++++++++++++++++ PythonAPI/source/libcarla/Blueprint.cpp | 5 +- .../Source/Carla/Settings/CarlaSettings.cpp | 1 + mkdocs.yml | 13 +- 12 files changed, 234 insertions(+), 59 deletions(-) create mode 100644 Docs/python_api.md diff --git a/Docs/CONTRIBUTING.md b/Docs/CONTRIBUTING.md index cd966e32f..a77d3b8be 100644 --- a/Docs/CONTRIBUTING.md +++ b/Docs/CONTRIBUTING.md @@ -76,11 +76,11 @@ usually offers that make it very affordable. #### What should I know before I get started? -Check out the ["CARLA Design"](carla_design.md) document to get an idea on the -different modules that compose CARLA, and chose the most appropriate one to hold -the new feature. We are aware the developers documentation is still scarce, -please ask us in case of doubt, and of course don't hesitate to improve the -current documentation if you feel confident enough. +Check out the ["CARLA Design"](index.md) document to get an idea +on the different modules that compose CARLA, and chose the most appropriate one +to hold the new feature. We are aware the developers documentation is still +scarce, please ask us in case of doubt, and of course don't hesitate to improve +the current documentation if you feel confident enough. #### Are there any examples in CARLA to see how Unreal programming works? diff --git a/Docs/benchmark_creating.md b/Docs/benchmark_creating.md index 61b846f69..e49981181 100644 --- a/Docs/benchmark_creating.md +++ b/Docs/benchmark_creating.md @@ -13,7 +13,7 @@ In this tutorial we show: ![Benchmark_structure](img/benchmark_diagram_small.png) The driving benchmark is associated with other two modules. -The *agent* module, that is a controller which performs in +The *agent* module, that is a controller which performs in another module: the *experiment suite*. Both modules are abstract classes that must be redefined by the user. @@ -54,11 +54,11 @@ Let's start by deriving a simple forward agent: from carla.agent.agent import Agent from carla.client import VehicleControl - + class ForwardAgent(Agent): -To have its performance evaluated, the ForwardAgent derived class _must_ +To have its performance evaluated, the ForwardAgent derived class _must_ redefine the *run_step* function as it is done in the following excerpt: def run_step(self, measurements, sensor_data, directions, target): @@ -71,18 +71,18 @@ redefine the *run_step* function as it is done in the following excerpt: This function receives the following parameters: - - * [Measurements](measurements.md): the entire state of the world received + + * [Measurements](index.md): the entire state of the world received by the client from the CARLA Simulator. These measurements contains agent position, orientation, dynamic objects information, etc. - * [Sensor Data](cameras_and_sensors.md): The measured data from defined sensors, + * [Sensor Data](cameras_and_sensors.md): The measured data from defined sensors, such as Lidars or RGB cameras. * Directions: Information from the high level planner. Currently the planner sends a high level command from the follwoing set: STRAIGHT, RIGHT, LEFT, NOTHING. * Target Position: The position and orientation of the target. - - With all this information, the *run_step* function is expected - to return a [vehicle control message](measurements.md), containing: + + With all this information, the *run_step* function is expected + to return a [vehicle control message](index.md), containing: steering value, throttle value, brake value, etc. @@ -108,12 +108,12 @@ as in the following code excerpt: from carla.agent_benchmark.experiment import Experiment from carla.sensor import Camera from carla.settings import CarlaSettings - + from .experiment_suite import ExperimentSuite - - + + class BasicExperimentSuite(ExperimentSuite): - + ##### Define test and train weather conditions The user must select the weathers to be used. One should select the set @@ -126,7 +126,7 @@ class property as in the following example: @property def test_weathers(self): return [1] - + ##### Building Experiments @@ -134,15 +134,15 @@ The [experiments are composed by a *task* that is defined by a set of *poses*](b Let's start by selecting poses for one of the cities, let's take Town01, for instance. First of all, we need to see all the possible positions, for that, with a CARLA simulator running in a terminal, run: - + python view_start_positions.py - + ![town01_positions](img/town01_positions.png) - - + + Now let's choose, for instance, 140 as start position and 134 as the end position. This two positions can be visualized by running: - + python view_start_positions.py --pos 140,134 --no-labels ![town01_positions](img/town01_140_134.png) @@ -165,7 +165,7 @@ the number of dynamic objects for each of these tasks and repeat the arbitrary position task to have it also defined with dynamic objects. In the following code excerpt we show the final defined positions and the number of dynamic objects for each task: - + # Define the start/end position below as tasks poses_task0 = [[7, 3]] poses_task1 = [[138, 17]] @@ -212,7 +212,7 @@ vector as we show in the following code excerpt: - + The full code could be found at [basic_experiment_suite.py](https://github.com/carla-simulator/carla/blob/master/PythonClient/carla/driving_benchmark/experiment_suites/basic_experiment_suite.py) @@ -228,7 +228,7 @@ For that you should run the CARLA simulator as: The example presented in this tutorial can be executed for Town01 as: ./driving_benchmark_example.py -c Town01 - + You should expect these results: [town01_basic_forward_results](benchmark_basic_results_town01) For Town02: diff --git a/Docs/cameras_and_sensors.md b/Docs/cameras_and_sensors.md index c2afd113f..d3e0d029e 100644 --- a/Docs/cameras_and_sensors.md +++ b/Docs/cameras_and_sensors.md @@ -1,5 +1,11 @@

Cameras and sensors

+!!! important + This document still refers to the 0.8.X API (stable version). The + proceedings stated here may not apply to latest versions, 0.9.0 or later. + Latest versions introduced significant changes in the API, we are still + working on documenting everything, sorry for the inconvenience. + !!! important Since version 0.8.0 the positions of the sensors are specified in meters instead of centimeters. Always relative to the vehicle. diff --git a/Docs/carla_settings.md b/Docs/carla_settings.md index 25c270f5c..091260510 100644 --- a/Docs/carla_settings.md +++ b/Docs/carla_settings.md @@ -2,6 +2,12 @@ > _This document is a work in progress and might be incomplete._ +!!! important + This document still refers to the 0.8.X API (stable version). The + proceedings stated here may not apply to latest versions, 0.9.0 or later. + Latest versions introduced significant changes in the API, we are still + working on documenting everything, sorry for the inconvenience. + CarlaSettings.ini ----------------- @@ -14,7 +20,7 @@ hierarchy overriding earlier values. 1. `{CarlaFolder}/Unreal/CarlaUE4/Config/CarlaSettings.ini`. 2. File provided by command-line argument `-carla-settings="Path/To/CarlaSettings.ini"`. - 3. Other command-line arguments as `-carla-server` or `-world-port`. + 3. Other command-line arguments like `-carla-port`. 4. Settings file sent by the client on every new episode. Take a look at the [CARLA Settings example][settingslink]. @@ -54,8 +60,6 @@ WeatherId=6 Simulator command-line options ------------------------------ - * `-carla-server` Launches CARLA as server, the execution hangs until a client connects. * `-carla-settings="Path/To/CarlaSettings.ini"` Load settings from the given INI file. See Example.CarlaSettings.ini. - * `-carla-world-port=N` Listen for client connections at port N, agent ports are set to N+1 and N+2 respectively. Activates server. + * `-carla-port=N` Listen for client connections at port N, streaming port is set to N+1. * `-carla-no-hud` Do not display the HUD by default. - * `-carla-no-networking` Disable networking. Overrides `-carla-server` if present. diff --git a/Docs/coding_standard.md b/Docs/coding_standard.md index 157b81570..27ff6f98e 100644 --- a/Docs/coding_standard.md +++ b/Docs/coding_standard.md @@ -26,11 +26,11 @@ C++ --- * Compilation should not give any error or warning - (`clang++ -Wall -Wextra -std=C++14`). + (`clang++ -Wall -Wextra -std=C++14 -Wno-missing-braces`). * Unreal C++ code (CarlaUE4 and Carla plugin) follow the [Unreal Engine's Coding Standard][ue4link] with the exception of using spaces instead of tabs. - * CarlaServer uses [Google's style guide][googlelink]. + * LibCarla uses a variation of [Google's style guide][googlelink]. [ue4link]: https://docs.unrealengine.com/latest/INT/Programming/Development/CodingStandard/ [googlelink]: https://google.github.io/styleguide/cppguide.html diff --git a/Docs/configuring_the_simulation.md b/Docs/configuring_the_simulation.md index d7d6ec5d4..52c8cedfc 100644 --- a/Docs/configuring_the_simulation.md +++ b/Docs/configuring_the_simulation.md @@ -40,6 +40,8 @@ run the simulation at a fixed time-step of 0.2 seconds we execute It is important to note that this mode can only be enabled when launching the simulator since this is actually a feature of Unreal Engine. + diff --git a/Docs/getting_started.md b/Docs/getting_started.md index d090ade58..a772a13b6 100644 --- a/Docs/getting_started.md +++ b/Docs/getting_started.md @@ -2,6 +2,11 @@ ![Welcome to CARLA](img/welcome.png) +!!! important + This tutorial refers to the latest development versions of CARLA, 0.9.0 or + later. For the documentation of the stable version please switch to the + [stable branch](https://carla.readthedocs.io/en/stable/getting_started/). + Welcome to CARLA! This tutorial provides the basic steps for getting started using CARLA. @@ -14,17 +19,50 @@ the package in a folder of your choice. The release package contains the following * The CARLA simulator. - * The "carla" Python module. - * Some Python client examples. + * The "carla" Python API module. + * An "example.py" script. -For now we will focus on the simulator only. The simulator can be run in two -different modes +The simulator can be started by running `CarlaUE4.sh` on Linux, or +`CarlaUE4.exe` on Windows. Unlike previous versions, now the simulator +automatically starts in "server mode". That is, you can already start connecting +your Python scripts to control the actors in the simulation. - * **Server mode:** The simulator is controlled by a client application that - collects data and sends driving instructions. In this mode the simulator - hangs until a client starts a connection. - * **Standalone mode:** The simulator starts in sort of _video-game mode_ in - which you can control the vehicle with the keyboard. +CARLA requires two available TCP ports on your computer, by default 2000 and +2001. Make sure you don't have a firewall or another application blocking those +ports. Alternatively, you can manually change the port CARLA uses by launching +the simulator with the command-line argument `-carla-port=N`, the second port +will be automatically set to `N+1`. -In the next item in this tutorial we will run the **standalone mode** to take a -first look into CARLA. +!!! tip + You can launch the simulator in windowed mode by using the argument + `-windowed`, and control the window size with `-ResX=N` and `-ResY=N`. + +#### Running the example script + +Run the example script with + +```sh +python example.py +``` + +If everything went well you should start seeing cars appearing in the scene. + +_We strongly recommend taking a look at the example code to understand how it +works, and modify it at will. We'll have soon tutorials for writing your own +scripts, but for now the examples is all we have._ + +#### Changing the map + +By default, the simulator starts up in our _"Town01"_ map. The second map can be +started by passing the path to the map as first argument when launching the +simulator + +```sh +# On Linux +$ ./CarlaUE4.sh /Game/Carla/Maps/Town02 +``` + +```cmd +rem On Windows +> CarlaUE4.exe /Game/Carla/Maps/Town02 +``` diff --git a/Docs/index.md b/Docs/index.md index a7e682caf..d11e779fe 100644 --- a/Docs/index.md +++ b/Docs/index.md @@ -1,12 +1,17 @@

CARLA Documentation

+!!! important + This documentation refers to the latest development versions of CARLA, 0.9.0 + or later. For the documentation of the stable version please switch to the + [stable branch](https://carla.readthedocs.io/en/stable/). +

Quick start

* [Getting started](getting_started.md) - * [Running the simulator](running_simulator_standalone.md) - * [Connecting a Python client](connecting_the_client.md) + + * [Configuring the simulation](configuring_the_simulation.md) - * [Measurements](measurements.md) + * [Cameras and sensors](cameras_and_sensors.md) * [F.A.Q.](faq.md) @@ -25,7 +30,8 @@

Advanced topics

* [CARLA settings](carla_settings.md) - * [Simulator keyboard input](simulator_keyboard_input.md) + * [Python API](python_api.md) + * [Running without display and selecting GPUs](carla_headless.md) * [How to link Epic's Automotive Materials](epic_automotive_materials.md) @@ -39,6 +45,6 @@ * [Map customization](map_customization.md) * [How to add assets](how_to_add_assets.md) - * [CARLA design](carla_design.md) - * [CarlaServer documentation](carla_server.md) + + * [Build system](build_system.md) diff --git a/Docs/python_api.md b/Docs/python_api.md new file mode 100644 index 000000000..0c7504c08 --- /dev/null +++ b/Docs/python_api.md @@ -0,0 +1,117 @@ +

Python API

+ +!!! important + Versions prior to 0.9.0 have a very different API. For the documentation of + the stable version please switch to the + [stable branch](https://carla.readthedocs.io/en/stable/). + +## `carla.Client` + +- `Client(host, port, worker_threads=0)` +- `set_timeout(milliseconds)` +- `get_client_version()` +- `get_server_version()` +- `ping()` +- `get_world()` + +## `carla.World` + +- `get_blueprint_library()` +- `spawn_actor(blueprint, transform, attach_to=None)` +- `try_spawn_actor(blueprint, transform, attach_to=None)` + +## `carla.BlueprintLibrary` + +- `find(id)` +- `filter(wildcard_pattern)` +- `__getitem__(pos)` +- `__len__()` +- `__iter__()` + +## `carla.ActorBlueprint` + +- `id` +- `tags` +- `contains_tag(tag)` +- `match_tags(wildcard_pattern)` +- `contains_attribute(key)` +- `get_attribute(key)` +- `set_attribute(key, value)` + +## `carla.ActorAttribute` + +- `is_modifiable` +- `type` +- `recommended_values` +- `as_bool()` +- `as_int()` +- `as_float()` +- `as_str()` +- `as_color()` +- `__eq__()` +- `__ne__()` +- `__nonzero__()` +- `__bool__()` +- `__int__()` +- `__float__()` +- `__str__()` + +## `carla.Actor` + +- `id` +- `type_id` +- `get_world()` +- `get_location()` +- `get_transform()` +- `set_location(location)` +- `set_transform(transform)` +- `destroy()` + +## `carla.Vehicle(carla.Actor)` + +- `apply_control(vehicle_control)` +- `set_autopilot(enabled=True)` + +## `carla.Sensor(carla.Actor)` + +- `listen(callback_function)` + +## `carla.Image` + +- `frame_number` +- `width` +- `height` +- `type` +- `fov` +- `raw_data` + +## `carla.VehicleControl` + +- `throttle` +- `steer` +- `brake` +- `hand_brake` +- `reverse` + +## `carla.Location` + +- `x` +- `y` +- `z` + +## `carla.Rotation` + +- `pitch` +- `yaw` +- `roll` + +## `carla.Transform` + +- `location` +- `rotation` + +## `carla.Color` + +- `r` +- `g` +- `b` diff --git a/PythonAPI/source/libcarla/Blueprint.cpp b/PythonAPI/source/libcarla/Blueprint.cpp index 9502921eb..897f55794 100644 --- a/PythonAPI/source/libcarla/Blueprint.cpp +++ b/PythonAPI/source/libcarla/Blueprint.cpp @@ -113,23 +113,22 @@ void export_blueprint() { .add_property("id", +[](const cc::ActorBlueprint &self) -> std::string { return self.GetId(); }) + .add_property("tags", &cc::ActorBlueprint::GetTags) .def("contains_tag", &cc::ActorBlueprint::ContainsTag) .def("match_tags", &cc::ActorBlueprint::MatchTags) - .def("get_tags", &cc::ActorBlueprint::GetTags) .def("contains_attribute", &cc::ActorBlueprint::ContainsAttribute) .def("get_attribute", +[](const cc::ActorBlueprint &self, const std::string &id) -> cc::ActorAttribute { return self.GetAttribute(id); }) .def("set_attribute", &cc::ActorBlueprint::SetAttribute) - .def("match_tags", &cc::ActorBlueprint::MatchTags) .def(self_ns::str(self_ns::self)) ; class_>("BlueprintLibrary", no_init) - .def("filter", &cc::BlueprintLibrary::Filter) .def("find", +[](const cc::BlueprintLibrary &self, const std::string &key) -> cc::ActorBlueprint { return self.at(key); }) + .def("filter", &cc::BlueprintLibrary::Filter) .def("__getitem__", +[](const cc::BlueprintLibrary &self, size_t pos) -> cc::ActorBlueprint { return self.at(pos); }) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/CarlaSettings.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/CarlaSettings.cpp index 805ef1254..87b049be3 100755 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/CarlaSettings.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/CarlaSettings.cpp @@ -198,6 +198,7 @@ void UCarlaSettings::LoadSettings() } uint32 Value; if (FParse::Value(FCommandLine::Get(), TEXT("-world-port="), Value) || + FParse::Value(FCommandLine::Get(), TEXT("-carla-port="), Value) || FParse::Value(FCommandLine::Get(), TEXT("-carla-world-port="), Value)) { WorldPort = Value; bUseNetworking = true; diff --git a/mkdocs.yml b/mkdocs.yml index 3a366e59b..f6bfa3e71 100644 --- a/mkdocs.yml +++ b/mkdocs.yml @@ -7,10 +7,10 @@ pages: - Home: 'index.md' - Quick start: - 'Getting started': 'getting_started.md' - - 'Running the simulator': 'running_simulator_standalone.md' - - 'Connecting a Python client': 'connecting_the_client.md' + # - 'Running the simulator': 'running_simulator_standalone.md' + # - 'Connecting a Python client': 'connecting_the_client.md' - 'Configuring the simulation': 'configuring_the_simulation.md' - - 'Measurements': 'measurements.md' + # - 'Measurements': 'measurements.md' - 'Cameras and sensors': 'cameras_and_sensors.md' - 'F.A.Q.': 'faq.md' - Driving Benchmark: @@ -23,7 +23,8 @@ pages: - 'How to build on Windows': 'how_to_build_on_windows.md' - Advanced topics: - 'CARLA Settings': 'carla_settings.md' - - 'Simulator keyboard input': 'simulator_keyboard_input.md' + - 'Python API': 'python_api.md' + # - 'Simulator keyboard input': 'simulator_keyboard_input.md' - 'Running without display and selecting GPUs': 'carla_headless.md' - "How to link Epic's Automotive Materials": 'epic_automotive_materials.md' - Contributing: @@ -33,8 +34,8 @@ pages: - Development: - 'Map customization': 'map_customization.md' - 'How to add assets': 'how_to_add_assets.md' - - 'CARLA design': 'carla_design.md' - - 'CarlaServer documentation': 'carla_server.md' + # - 'CARLA design': 'carla_design.md' + # - 'CarlaServer documentation': 'carla_server.md' - 'Build system': 'build_system.md' - Appendix: - 'Driving Benchmark Sample Results Town01': 'benchmark_basic_results_town01.md' From 63d6f11d416227dea6757be410c393bef4436169 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Sat, 28 Jul 2018 20:33:35 +0200 Subject: [PATCH 57/71] Make example.py executable --- PythonAPI/example.py | 0 1 file changed, 0 insertions(+), 0 deletions(-) mode change 100644 => 100755 PythonAPI/example.py diff --git a/PythonAPI/example.py b/PythonAPI/example.py old mode 100644 new mode 100755 From 4f5044a495a85991f44ff8517e03952c1b4fc1f1 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Sun, 29 Jul 2018 11:28:16 +0200 Subject: [PATCH 58/71] Expose spectator pawn --- Docs/python_api.md | 1 + LibCarla/source/carla/client/Client.cpp | 11 +++++ LibCarla/source/carla/client/Client.h | 9 ++-- LibCarla/source/carla/client/World.h | 4 ++ PythonAPI/source/libcarla/World.cpp | 1 + Unreal/CarlaUE4/Config/DefaultEngine.ini | 2 +- Unreal/CarlaUE4/Config/DefaultInput.ini | 47 ++----------------- .../Source/Carla/Actor/ActorDispatcher.h | 5 ++ .../Carla/Source/Carla/Game/CarlaEpisode.cpp | 35 ++++++++++++++ .../Carla/Source/Carla/Game/CarlaEpisode.h | 13 ++++- .../Carla/Game/TheNewCarlaGameModeBase.cpp | 7 ++- .../Source/Carla/Server/TheNewCarlaServer.cpp | 11 +++++ Util/ContentVersions.txt | 2 +- 13 files changed, 95 insertions(+), 53 deletions(-) create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.cpp diff --git a/Docs/python_api.md b/Docs/python_api.md index 0c7504c08..29f0fa9b7 100644 --- a/Docs/python_api.md +++ b/Docs/python_api.md @@ -17,6 +17,7 @@ ## `carla.World` - `get_blueprint_library()` +- `get_spectator()` - `spawn_actor(blueprint, transform, attach_to=None)` - `try_spawn_actor(blueprint, transform, attach_to=None)` diff --git a/LibCarla/source/carla/client/Client.cpp b/LibCarla/source/carla/client/Client.cpp index 5f1504c1d..cb7612572 100644 --- a/LibCarla/source/carla/client/Client.cpp +++ b/LibCarla/source/carla/client/Client.cpp @@ -7,6 +7,7 @@ #include "carla/client/Client.h" #include "carla/client/Actor.h" +#include "carla/client/BlueprintLibrary.h" #include "carla/client/Control.h" #include "carla/client/Sensor.h" #include "carla/client/Vehicle.h" @@ -30,6 +31,16 @@ namespace client { return _active_world; } + SharedPtr Client::GetBlueprintLibrary() { + return MakeShared( + Call>("get_actor_definitions")); + } + + SharedPtr Client::GetSpectator() { + auto spectator = Call("get_spectator"); + return SharedPtr(new Actor{spectator, GetWorld()}); + } + SharedPtr Client::SpawnActor( const ActorBlueprint &blueprint, const Transform &transform, diff --git a/LibCarla/source/carla/client/Client.h b/LibCarla/source/carla/client/Client.h index 67bffb89b..c14fc7b8f 100644 --- a/LibCarla/source/carla/client/Client.h +++ b/LibCarla/source/carla/client/Client.h @@ -8,7 +8,6 @@ #include "carla/NonCopyable.h" #include "carla/Version.h" -#include "carla/client/BlueprintLibrary.h" #include "carla/client/Control.h" #include "carla/client/Memory.h" #include "carla/client/Transform.h" @@ -22,6 +21,7 @@ namespace client { class Actor; class ActorBlueprint; + class BlueprintLibrary; class World; class Client @@ -68,10 +68,9 @@ namespace client { SharedPtr GetWorld(); - SharedPtr GetBlueprintLibrary() { - return MakeShared( - Call>("get_actor_definitions")); - } + SharedPtr GetBlueprintLibrary(); + + SharedPtr GetSpectator(); SharedPtr SpawnActor( const ActorBlueprint &blueprint, diff --git a/LibCarla/source/carla/client/World.h b/LibCarla/source/carla/client/World.h index a23cb8412..e460b8f69 100644 --- a/LibCarla/source/carla/client/World.h +++ b/LibCarla/source/carla/client/World.h @@ -25,6 +25,10 @@ namespace client { return _parent->GetBlueprintLibrary(); } + SharedPtr GetSpectator() const { + return _parent->GetSpectator(); + } + SharedPtr TrySpawnActor( const ActorBlueprint &blueprint, const Transform &transform, diff --git a/PythonAPI/source/libcarla/World.cpp b/PythonAPI/source/libcarla/World.cpp index 3f26e1d23..d1c3f95c8 100644 --- a/PythonAPI/source/libcarla/World.cpp +++ b/PythonAPI/source/libcarla/World.cpp @@ -15,6 +15,7 @@ void export_world() { class_>("World", no_init) .def("get_blueprint_library", &cc::World::GetBlueprintLibrary) + .def("get_spectator", &cc::World::GetSpectator) .def("try_spawn_actor", &cc::World::TrySpawnActor, (arg("blueprint"), arg("transform"), arg("attach_to")=cc::SharedPtr())) .def("spawn_actor", &cc::World::SpawnActor, diff --git a/Unreal/CarlaUE4/Config/DefaultEngine.ini b/Unreal/CarlaUE4/Config/DefaultEngine.ini index afbe07120..84609565a 100644 --- a/Unreal/CarlaUE4/Config/DefaultEngine.ini +++ b/Unreal/CarlaUE4/Config/DefaultEngine.ini @@ -13,7 +13,7 @@ AppliedDefaultGraphicsPerformance=Maximum EditorStartupMap=/Game/Carla/Maps/Town01.Town01 GameDefaultMap=/Game/Carla/Maps/Town01.Town01 ServerDefaultMap=/Game/Carla/Maps/Town01.Town01 -GlobalDefaultGameMode=/Game/Carla/Blueprints/Game/TheNewGameMode.TheNewGameMode_C +GlobalDefaultGameMode=/Game/Carla/Blueprints/Game/TheNewCarlaGameMode.TheNewCarlaGameMode_C GameInstanceClass=/Script/Carla.CarlaGameInstance TransitionMap=/Game/Carla/Maps/Town01.Town01 GlobalDefaultServerGameMode=/Game/Carla/Blueprints/Game/CarlaGameMode.CarlaGameMode_C diff --git a/Unreal/CarlaUE4/Config/DefaultInput.ini b/Unreal/CarlaUE4/Config/DefaultInput.ini index 1989a8d7d..4eedea317 100644 --- a/Unreal/CarlaUE4/Config/DefaultInput.ini +++ b/Unreal/CarlaUE4/Config/DefaultInput.ini @@ -6,27 +6,6 @@ -AxisConfig=(AxisKeyName="Gamepad_RightY",AxisProperties=(DeadZone=0.25,Exponent=1.f,Sensitivity=1.f)) -AxisConfig=(AxisKeyName="MouseX",AxisProperties=(DeadZone=0.f,Exponent=1.f,Sensitivity=0.07f)) -AxisConfig=(AxisKeyName="MouseY",AxisProperties=(DeadZone=0.f,Exponent=1.f,Sensitivity=0.07f)) --AxisConfig=(AxisKeyName="Gamepad_LeftX",AxisProperties=(DeadZone=0.250000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) --AxisConfig=(AxisKeyName="Gamepad_LeftY",AxisProperties=(DeadZone=0.250000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) --AxisConfig=(AxisKeyName="Gamepad_RightX",AxisProperties=(DeadZone=0.250000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) --AxisConfig=(AxisKeyName="Gamepad_RightY",AxisProperties=(DeadZone=0.250000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) --AxisConfig=(AxisKeyName="MouseX",AxisProperties=(DeadZone=0.000000,Sensitivity=0.070000,Exponent=1.000000,bInvert=False)) --AxisConfig=(AxisKeyName="MouseY",AxisProperties=(DeadZone=0.000000,Sensitivity=0.070000,Exponent=1.000000,bInvert=False)) --AxisConfig=(AxisKeyName="MouseWheelAxis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) --AxisConfig=(AxisKeyName="Gamepad_LeftTriggerAxis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) --AxisConfig=(AxisKeyName="Gamepad_RightTriggerAxis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) --AxisConfig=(AxisKeyName="MotionController_Left_Thumbstick_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) --AxisConfig=(AxisKeyName="MotionController_Left_Thumbstick_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) --AxisConfig=(AxisKeyName="MotionController_Left_TriggerAxis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) --AxisConfig=(AxisKeyName="MotionController_Left_Grip1Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) --AxisConfig=(AxisKeyName="MotionController_Left_Grip2Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) --AxisConfig=(AxisKeyName="MotionController_Right_Thumbstick_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) --AxisConfig=(AxisKeyName="MotionController_Right_Thumbstick_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) --AxisConfig=(AxisKeyName="MotionController_Right_TriggerAxis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) --AxisConfig=(AxisKeyName="MotionController_Right_Grip1Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) --AxisConfig=(AxisKeyName="MotionController_Right_Grip2Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) --AxisConfig=(AxisKeyName="Gamepad_Special_Left_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) --AxisConfig=(AxisKeyName="Gamepad_Special_Left_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) +AxisConfig=(AxisKeyName="Gamepad_LeftX",AxisProperties=(DeadZone=0.250000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) +AxisConfig=(AxisKeyName="Gamepad_LeftY",AxisProperties=(DeadZone=0.250000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) +AxisConfig=(AxisKeyName="Gamepad_RightX",AxisProperties=(DeadZone=0.250000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) @@ -59,16 +38,6 @@ bCaptureMouseOnLaunch=True DefaultViewportMouseCaptureMode=CapturePermanently_IncludingInitialMouseDown bDefaultViewportMouseLock=False DefaultViewportMouseLockMode=LockOnCapture --ActionMappings=(ActionName="RestartLevel",Key=R,bShift=False,bCtrl=False,bAlt=False,bCmd=False) --ActionMappings=(ActionName="Handbrake",Key=SpaceBar,bShift=False,bCtrl=False,bAlt=False,bCmd=False) --ActionMappings=(ActionName="ToggleManualMode",Key=M,bShift=False,bCtrl=False,bAlt=False,bCmd=False) --ActionMappings=(ActionName="ToggleHUD",Key=G,bShift=False,bCtrl=False,bAlt=False,bCmd=False) --ActionMappings=(ActionName="Jump",Key=Enter,bShift=False,bCtrl=False,bAlt=False,bCmd=False) --ActionMappings=(ActionName="ToggleReverse",Key=Q,bShift=False,bCtrl=False,bAlt=False,bCmd=False) --ActionMappings=(ActionName="UseTheForce",Key=F,bShift=False,bCtrl=False,bAlt=False,bCmd=False) --ActionMappings=(ActionName="ToggleCamera",Key=Tab,bShift=False,bCtrl=False,bAlt=False,bCmd=False) --ActionMappings=(ActionName="ChangeWeather",Key=C,bShift=False,bCtrl=False,bAlt=False,bCmd=False) --ActionMappings=(ActionName="ToggleAutopilot",Key=None,bShift=False,bCtrl=False,bAlt=False,bCmd=False) +ActionMappings=(ActionName="RestartLevel",Key=R,bShift=False,bCtrl=False,bAlt=False,bCmd=False) +ActionMappings=(ActionName="Handbrake",Key=SpaceBar,bShift=False,bCtrl=False,bAlt=False,bCmd=False) +ActionMappings=(ActionName="ToggleManualMode",Key=M,bShift=False,bCtrl=False,bAlt=False,bCmd=False) @@ -79,17 +48,6 @@ DefaultViewportMouseLockMode=LockOnCapture +ActionMappings=(ActionName="ToggleCamera",Key=Tab,bShift=False,bCtrl=False,bAlt=False,bCmd=False) +ActionMappings=(ActionName="ChangeWeather",Key=C,bShift=False,bCtrl=False,bAlt=False,bCmd=False) +ActionMappings=(ActionName="ToggleAutopilot",Key=P,bShift=False,bCtrl=False,bAlt=False,bCmd=False) --AxisMappings=(AxisName="CameraZoom",Key=MouseWheelAxis,Scale=-20.000000) --AxisMappings=(AxisName="CameraZoom",Key=PageUp,Scale=-10.000000) --AxisMappings=(AxisName="CameraZoom",Key=PageDown,Scale=10.000000) --AxisMappings=(AxisName="CameraUp",Key=Up,Scale=1.000000) --AxisMappings=(AxisName="CameraUp",Key=Down,Scale=-1.000000) --AxisMappings=(AxisName="CameraRight",Key=Right,Scale=1.000000) --AxisMappings=(AxisName="CameraRight",Key=Left,Scale=-1.000000) --AxisMappings=(AxisName="MoveForward",Key=W,Scale=1.000000) --AxisMappings=(AxisName="MoveRight",Key=D,Scale=1.000000) --AxisMappings=(AxisName="MoveRight",Key=A,Scale=-1.000000) --AxisMappings=(AxisName="Brake",Key=S,Scale=1.000000) +AxisMappings=(AxisName="CameraZoom",Key=MouseWheelAxis,Scale=-20.000000) +AxisMappings=(AxisName="CameraZoom",Key=PageUp,Scale=-10.000000) +AxisMappings=(AxisName="CameraZoom",Key=PageDown,Scale=10.000000) @@ -100,7 +58,10 @@ DefaultViewportMouseLockMode=LockOnCapture +AxisMappings=(AxisName="MoveForward",Key=W,Scale=1.000000) +AxisMappings=(AxisName="MoveRight",Key=D,Scale=1.000000) +AxisMappings=(AxisName="MoveRight",Key=A,Scale=-1.000000) -+AxisMappings=(AxisName="Brake",Key=S,Scale=1.000000) ++AxisMappings=(AxisName="Brake",Key=B,Scale=1.000000) ++AxisMappings=(AxisName="MoveForward",Key=S,Scale=-1.000000) ++AxisMappings=(AxisName="MoveUp",Key=E,Scale=1.000000) ++AxisMappings=(AxisName="MoveUp",Key=Q,Scale=-1.000000) bAlwaysShowTouchInterface=False bShowConsoleOnFourFingerTap=True DefaultTouchInterface=/Engine/MobileResources/HUD/DefaultVirtualJoysticks.DefaultVirtualJoysticks diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.h index e7d1a6bbd..cbfcc6de3 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.h @@ -53,6 +53,11 @@ public: return Definitions; } + FActorRegistry &GetActorRegistry() + { + return Registry; + } + const FActorRegistry &GetActorRegistry() const { return Registry; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.cpp new file mode 100644 index 000000000..93677e573 --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.cpp @@ -0,0 +1,35 @@ +// 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 . + +#include "Carla.h" +#include "Carla/Game/CarlaEpisode.h" + +#include "EngineUtils.h" +#include "GameFramework/SpectatorPawn.h" + +void UCarlaEpisode::InitializeAtBeginPlay() +{ + auto World = GetWorld(); + check(World != nullptr); + auto PlayerController = UGameplayStatics::GetPlayerController(GetWorld(), 0); + if (PlayerController == nullptr) + { + UE_LOG(LogCarla, Error, TEXT("Can't find player controller!")); + return; + } + Spectator = PlayerController->GetPawn(); + if (Spectator != nullptr) + { + FActorDescription Description; + Description.Id = TEXT("spectator"); + Description.Class = Spectator->GetClass(); + ActorDispatcher.GetActorRegistry().Register(*Spectator, Description); + } + else + { + UE_LOG(LogCarla, Error, TEXT("Can't find spectator!")); + } +} diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.h index 94d9ed4c5..295885a88 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.h @@ -20,17 +20,25 @@ class CARLA_API UCarlaEpisode : public UObject public: - void Initialize(const FString &InMapName) + void SetMapName(const FString &InMapName) { MapName = InMapName; } + void InitializeAtBeginPlay(); + UFUNCTION(BlueprintCallable) const FString &GetMapName() const { return MapName; } + UFUNCTION(BlueprintCallable) + APawn *GetSpectatorPawn() const + { + return Spectator; + } + void RegisterActorFactory(ACarlaActorFactory &ActorFactory) { ActorDispatcher.Bind(ActorFactory); @@ -89,4 +97,7 @@ private: FString MapName; FActorDispatcher ActorDispatcher; + + UPROPERTY(VisibleAnywhere) + APawn *Spectator = nullptr; }; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/TheNewCarlaGameModeBase.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/TheNewCarlaGameModeBase.cpp index 56b2dd44e..b30071732 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/TheNewCarlaGameModeBase.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/TheNewCarlaGameModeBase.cpp @@ -29,8 +29,10 @@ void ATheNewCarlaGameModeBase::InitGame( { Super::InitGame(MapName, Options, ErrorMessage); - check(Episode != nullptr); - Episode->Initialize(MapName); + checkf( + Episode != nullptr, + TEXT("Missing episode, can't continue without an episode!")); + Episode->SetMapName(MapName); GameInstance = Cast(GetGameInstance()); checkf( @@ -57,6 +59,7 @@ void ATheNewCarlaGameModeBase::BeginPlay() TaggerDelegate->SetSemanticSegmentationEnabled(); } + Episode->InitializeAtBeginPlay(); GameInstance->NotifyBeginEpisode(*Episode); } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp index b560127ff..987d61c64 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/TheNewCarlaServer.cpp @@ -9,6 +9,8 @@ #include "Carla/Sensor/Sensor.h" +#include "GameFramework/SpectatorPawn.h" + #include #include #include @@ -167,6 +169,15 @@ void FTheNewCarlaServer::FPimpl::BindActions() return MakeVectorFromTArray(Episode->GetActorDefinitions()); }); + Server.BindSync("get_spectator", [this]() -> cr::Actor { + RequireEpisode(); + auto ActorView = Episode->GetActorRegistry().Find(Episode->GetSpectatorPawn()); + if (!ActorView.IsValid() || ActorView.GetActor()->IsPendingKill()) { + RespondErrorStr("unable to find spectator"); + } + return ActorView; + }); + Server.BindSync("spawn_actor", [this]( const cr::Transform &Transform, cr::ActorDescription Description) -> cr::Actor { diff --git a/Util/ContentVersions.txt b/Util/ContentVersions.txt index 668f68dbe..ff6e4bef0 100644 --- a/Util/ContentVersions.txt +++ b/Util/ContentVersions.txt @@ -13,4 +13,4 @@ 0.8.2: 1llrBkZDvJmxXYh4r3jz0wuwz8Q8jRQeZ 0.8.3: 1z2XKOk9LoKI-EhxcrpI31W5TeYo2-jjn 0.8.4: 1mFNS-w5atQ45yegiTepRIeKBYVm8N8He -0.9.0: 10QmgEZxMj3ZYfWeMOf0omRjj4M_eiuC8 +0.9.0: 1FtC00CrDb7Kz5StBAwb6vqOGbzZtpROx From e34a5891b185934c4a64973aa21739dd7e85d579 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Sun, 29 Jul 2018 18:04:57 +0200 Subject: [PATCH 59/71] Add addition and subtraction operators to locations --- LibCarla/source/carla/rpc/Location.h | 91 +++++++++++++++++++++++++ LibCarla/source/carla/rpc/Transform.h | 49 +------------ PythonAPI/source/libcarla/Transform.cpp | 4 ++ 3 files changed, 96 insertions(+), 48 deletions(-) create mode 100644 LibCarla/source/carla/rpc/Location.h diff --git a/LibCarla/source/carla/rpc/Location.h b/LibCarla/source/carla/rpc/Location.h new file mode 100644 index 000000000..90e82a981 --- /dev/null +++ b/LibCarla/source/carla/rpc/Location.h @@ -0,0 +1,91 @@ +// 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 . + +#pragma once + +#include "carla/rpc/MsgPack.h" + +#ifdef LIBCARLA_INCLUDED_FROM_UE4 +# include "Math/Vector.h" +#endif // LIBCARLA_INCLUDED_FROM_UE4 + +namespace carla { +namespace rpc { + + class Location { + public: + + float x = 0.0f; + float y = 0.0f; + float z = 0.0f; + + Location() = default; + + Location(float ix, float iy, float iz) + : x(ix), + y(iy), + z(iz) {} + + Location &operator+=(const Location &rhs) { + x += rhs.x; + y += rhs.y; + z += rhs.z; + return *this; + } + + friend Location operator+(Location lhs, const Location &rhs) { + lhs += rhs; + return lhs; + } + + Location &operator-=(const Location &rhs) { + x -= rhs.x; + y -= rhs.y; + z -= rhs.z; + return *this; + } + + friend Location operator-(Location lhs, const Location &rhs) { + lhs -= rhs; + return lhs; + } + +#ifdef LIBCARLA_INCLUDED_FROM_UE4 + + Location(const FVector &vector) // from centimeters to meters. + : Location(1e-2f * vector.X, 1e-2f * vector.Y, 1e-2f * vector.Z) {} + + operator FVector() const { + return FVector{1e2f * x, 1e2f * y, 1e2f * z}; // from meters to centimeters. + } + +#endif // LIBCARLA_INCLUDED_FROM_UE4 + + // ========================================================================= + /// @todo The following is copy-pasted from MSGPACK_DEFINE_ARRAY. + /// This is a workaround for an issue in msgpack library. The + /// MSGPACK_DEFINE_ARRAY macro is shadowing our `z` variable. + /// https://github.com/msgpack/msgpack-c/issues/709 + // ========================================================================= + template + void msgpack_pack(Packer& pk) const + { + clmdep_msgpack::type::make_define_array(x, y, z).msgpack_pack(pk); + } + void msgpack_unpack(clmdep_msgpack::object const& o) + { + clmdep_msgpack::type::make_define_array(x, y, z).msgpack_unpack(o); + } + template + void msgpack_object(MSGPACK_OBJECT* o, clmdep_msgpack::zone& sneaky_variable_that_shadows_z) const + { + clmdep_msgpack::type::make_define_array(x, y, z).msgpack_object(o, sneaky_variable_that_shadows_z); + } + // ========================================================================= + }; + +} // namespace rpc +} // namespace carla diff --git a/LibCarla/source/carla/rpc/Transform.h b/LibCarla/source/carla/rpc/Transform.h index 6133a6ee6..8fe8b1cc7 100644 --- a/LibCarla/source/carla/rpc/Transform.h +++ b/LibCarla/source/carla/rpc/Transform.h @@ -6,6 +6,7 @@ #pragma once +#include "carla/rpc/Location.h" #include "carla/rpc/MsgPack.h" #ifdef LIBCARLA_INCLUDED_FROM_UE4 @@ -15,54 +16,6 @@ namespace carla { namespace rpc { - class Location { - public: - - Location() = default; - - Location(float ix, float iy, float iz) - : x(ix), - y(iy), - z(iz) {} - - float x = 0.0f; - float y = 0.0f; - float z = 0.0f; - -#ifdef LIBCARLA_INCLUDED_FROM_UE4 - - Location(const FVector &vector) // from centimeters to meters. - : Location(1e-2f * vector.X, 1e-2f * vector.Y, 1e-2f * vector.Z) {} - - operator FVector() const { - return FVector{1e2f * x, 1e2f * y, 1e2f * z}; // from meters to centimeters. - } - -#endif // LIBCARLA_INCLUDED_FROM_UE4 - - // ========================================================================= - /// @todo The following is copy-pasted from MSGPACK_DEFINE_ARRAY. - /// This is a workaround for an issue in msgpack library. The - /// MSGPACK_DEFINE_ARRAY macro is shadowing our `z` variable. - /// https://github.com/msgpack/msgpack-c/issues/709 - // ========================================================================= - template - void msgpack_pack(Packer& pk) const - { - clmdep_msgpack::type::make_define_array(x, y, z).msgpack_pack(pk); - } - void msgpack_unpack(clmdep_msgpack::object const& o) - { - clmdep_msgpack::type::make_define_array(x, y, z).msgpack_unpack(o); - } - template - void msgpack_object(MSGPACK_OBJECT* o, clmdep_msgpack::zone& sneaky_variable_that_shadows_z) const - { - clmdep_msgpack::type::make_define_array(x, y, z).msgpack_object(o, sneaky_variable_that_shadows_z); - } - // ========================================================================= - }; - class Rotation { public: diff --git a/PythonAPI/source/libcarla/Transform.cpp b/PythonAPI/source/libcarla/Transform.cpp index beb1a0e40..fda1aa341 100644 --- a/PythonAPI/source/libcarla/Transform.cpp +++ b/PythonAPI/source/libcarla/Transform.cpp @@ -44,6 +44,10 @@ void export_transform() { .def_readwrite("x", &cc::Location::x) .def_readwrite("y", &cc::Location::y) .def_readwrite("z", &cc::Location::z) + .def(self += self) + .def(self + self) + .def(self -= self) + .def(self - self) .def(self_ns::str(self_ns::self)) ; From 4c3b6127b17c4b91f02a6c20198fa08ff007559d Mon Sep 17 00:00:00 2001 From: nsubiron Date: Sun, 29 Jul 2018 18:05:19 +0200 Subject: [PATCH 60/71] Minor fixes --- PythonAPI/example.py | 2 +- Unreal/CarlaUE4/.gitignore | 4 +++- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/PythonAPI/example.py b/PythonAPI/example.py index 27821ea5f..9c6857993 100755 --- a/PythonAPI/example.py +++ b/PythonAPI/example.py @@ -40,7 +40,7 @@ def save_to_disk(image): def main(add_a_camera, enable_autopilot): - client = carla.Client('localhost', 2020) + client = carla.Client('localhost', 2000) client.set_timeout(2000) print('client version: %s' % client.get_client_version()) diff --git a/Unreal/CarlaUE4/.gitignore b/Unreal/CarlaUE4/.gitignore index a8b3ead2a..882d66865 100644 --- a/Unreal/CarlaUE4/.gitignore +++ b/Unreal/CarlaUE4/.gitignore @@ -17,6 +17,8 @@ Content* Config/CarlaSettings.ini Config/DefaultEditor.ini +*.code-workspace +.idea +.vscode CMakeLists.txt Makefile -.vscode From 4dac1b532f6e1f7f1029f16d47953bac2b16c045 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Sun, 29 Jul 2018 22:43:09 +0200 Subject: [PATCH 61/71] Rename camera id --- PythonAPI/example.py | 2 +- .../Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/PythonAPI/example.py b/PythonAPI/example.py index 9c6857993..5b50c6afa 100755 --- a/PythonAPI/example.py +++ b/PythonAPI/example.py @@ -84,7 +84,7 @@ def main(add_a_camera, enable_autopilot): if add_a_camera: add_a_camera = False - camera_bp = blueprint_library.find('camera') + camera_bp = blueprint_library.find('sensor.camera') # camera_bp.set_attribute('post_processing', 'Depth') camera_transform = carla.Transform(carla.Location(x=0.4, y=0.0, z=1.4)) camera = world.spawn_actor(camera_bp, camera_transform, attach_to=vehicle) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp index 5b5cd2b50..d7fa2510a 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp @@ -191,7 +191,7 @@ void UActorBlueprintFunctionLibrary::MakeCameraDefinition( bool &Success, FActorDefinition &Definition) { - Definition.Id = Parameters.Id.ToLower(); + Definition.Id = JoinStrings(TEXT("."), TEXT("sensor"), Parameters.Id).ToLower(); Definition.Class = Parameters.Class; Definition.Tags = JoinStrings(TEXT(","), TEXT("sensor"), Parameters.Id).ToLower(); // Post-processing. From f40c90942f7a00c37e53c43f710f1bf9354eee5a Mon Sep 17 00:00:00 2001 From: nsubiron Date: Sun, 29 Jul 2018 23:52:13 +0200 Subject: [PATCH 62/71] Add more examples --- PythonAPI/manual_control.py | 203 +++++++++++++++++++++++++++++++++++ PythonAPI/vehicle_gallery.py | 48 +++++++++ Util/BuildTools/Package.sh | 2 + 3 files changed, 253 insertions(+) create mode 100755 PythonAPI/manual_control.py create mode 100755 PythonAPI/vehicle_gallery.py diff --git a/PythonAPI/manual_control.py b/PythonAPI/manual_control.py new file mode 100755 index 000000000..bf0904c31 --- /dev/null +++ b/PythonAPI/manual_control.py @@ -0,0 +1,203 @@ +#!/usr/bin/env python + +# 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 . + +# Keyboard controlling for CARLA. Please refer to client_example.py for a simpler +# and more documented example. + +""" +Welcome to CARLA manual control. + +Use ARROWS or WASD keys for control. + + W : throttle + S : brake + AD : steer + Q : toggle reverse + Space : hand-brake + P : toggle autopilot + +STARTING in a moment... +""" + +from __future__ import print_function + +import sys + +sys.path.append( + 'PythonAPI/carla-0.9.0-py%d.%d-linux-x86_64.egg' % (sys.version_info.major, + sys.version_info.minor)) + +import carla + +import argparse +import logging +import random +import time + +try: + import pygame + from pygame.locals import K_DOWN + from pygame.locals import K_LEFT + from pygame.locals import K_RIGHT + from pygame.locals import K_SPACE + from pygame.locals import K_UP + from pygame.locals import K_a + from pygame.locals import K_d + 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') + + +WINDOW_WIDTH = 800 +WINDOW_HEIGHT = 600 +START_POSITION = carla.Transform(carla.Location(x=180.0, y=199.0, z=40.0)) +CAMERA_POSITION = carla.Transform(carla.Location(x=0.5, z=1.40)) + + +class CarlaGame(object): + def __init__(self, args): + self._client = carla.Client(args.host, args.port) + self._display = None + self._surface = None + self._camera = None + self._vehicle = None + self._autopilot_enabled = args.autopilot + self._is_on_reverse = False + + def execute(self): + pygame.init() + try: + self._display = pygame.display.set_mode( + (WINDOW_WIDTH, WINDOW_HEIGHT), + pygame.HWSURFACE | pygame.DOUBLEBUF) + logging.debug('pygame started') + + world = self._client.get_world() + blueprint = random.choice(world.get_blueprint_library().filter('vehicle')) + self._vehicle = world.spawn_actor(blueprint, START_POSITION) + self._vehicle.set_autopilot(self._autopilot_enabled) + cam_blueprint = world.get_blueprint_library().find('sensor.camera') + self._camera = world.spawn_actor(cam_blueprint, CAMERA_POSITION, attach_to=self._vehicle) + + self._camera.listen(lambda image: self._parse_image(image)) + + while True: + for event in pygame.event.get(): + if event.type == pygame.QUIT: + return + self._on_loop() + self._on_render() + finally: + pygame.quit() + if self._camera is not None: + self._camera.destroy() + self._camera = None + if self._vehicle is not None: + self._vehicle.destroy() + self._vehicle = None + + def _parse_image(self, image): + 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)) + + def _on_loop(self): + autopilot = self._autopilot_enabled + control = self._get_keyboard_control(pygame.key.get_pressed()) + if autopilot != self._autopilot_enabled: + self._vehicle.set_autopilot(autopilot) + self._autopilot_enabled = autopilot + if not self._autopilot_enabled: + self._vehicle.apply_control(control) + + def _get_keyboard_control(self, keys): + control = carla.VehicleControl() + if keys[K_LEFT] or keys[K_a]: + control.steer = -1.0 + if keys[K_RIGHT] or keys[K_d]: + control.steer = 1.0 + if keys[K_UP] or keys[K_w]: + control.throttle = 1.0 + if keys[K_DOWN] or keys[K_s]: + control.brake = 1.0 + if keys[K_SPACE]: + control.hand_brake = True + if keys[K_q]: + self._is_on_reverse = not self._is_on_reverse + if keys[K_p]: + self._autopilot_enabled = not self._autopilot_enabled + control.reverse = self._is_on_reverse + return control + + def _on_render(self): + if self._surface is not None: + self._display.blit(self._surface, (0, 0)) + pygame.display.flip() + + +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='localhost', + help='IP of the host server (default: localhost)') + 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') + args = argparser.parse_args() + + 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__) + + while True: + try: + + game = CarlaGame(args) + game.execute() + break + + except Exception as error: + logging.error(error) + time.sleep(1) + + +if __name__ == '__main__': + + try: + main() + except KeyboardInterrupt: + print('\nCancelled by user. Bye!') diff --git a/PythonAPI/vehicle_gallery.py b/PythonAPI/vehicle_gallery.py new file mode 100755 index 000000000..48319ab17 --- /dev/null +++ b/PythonAPI/vehicle_gallery.py @@ -0,0 +1,48 @@ +#!/usr/bin/env python + +import sys + +sys.path.append( + 'PythonAPI/carla-0.9.0-py%d.%d-linux-x86_64.egg' % (sys.version_info.major, + sys.version_info.minor)) + +import carla + +import math +import time + +# Nice spot on Town01. +LOCATION = carla.Location(x=155.5, y=55.8, z=39) + + +def get_transform(angle, d=6.5): + a = math.radians(angle) + location = carla.Location(d * math.cos(a), d * math.sin(a), 2.0) + LOCATION + return carla.Transform(location, carla.Rotation(yaw=180 + angle, pitch=-15)) + + +def main(): + client = carla.Client('localhost', 2000) + world = client.get_world() + spectator = world.get_spectator() + vehicle_blueprints = world.get_blueprint_library().filter('vehicle'); + + for blueprint in vehicle_blueprints: + transform = carla.Transform(LOCATION, carla.Rotation(yaw=-45.0)) + vehicle = world.spawn_actor(blueprint, transform) + + try: + + print(vehicle.type_id) + for x in range(2, 360, 2): + spectator.set_transform(get_transform(x - 90)) + time.sleep(0.02) + + finally: + + vehicle.destroy() + + +if __name__ == '__main__': + + main() diff --git a/Util/BuildTools/Package.sh b/Util/BuildTools/Package.sh index 697e877cd..d0f5a68f2 100755 --- a/Util/BuildTools/Package.sh +++ b/Util/BuildTools/Package.sh @@ -100,6 +100,8 @@ if $DO_COPY_FILES ; then copy_if_changed "./Util/Docker/Release.Dockerfile" "${DESTINATION}/Dockerfile" copy_if_changed "./PythonAPI/dist/*.egg" "${DESTINATION}/PythonAPI/" copy_if_changed "./PythonAPI/example.py" "${DESTINATION}/example.py" + copy_if_changed "./PythonAPI/manual_control.py" "${DESTINATION}/manual_control.py" + copy_if_changed "./PythonAPI/vehicle_gallery.py" "${DESTINATION}/vehicle_gallery.py" popd >/dev/null From 3b3bb1868a268e1106d8a522ec634a1a5384bfd6 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Mon, 30 Jul 2018 12:11:31 +0200 Subject: [PATCH 63/71] Fix the build --- Docs/how_to_build_on_linux.md | 6 ++-- LibCarla/cmake/client/CMakeLists.txt | 3 +- PythonAPI/setup.py | 32 ++++++++++++------- .../Plugins/Carla/Source/Carla/Carla.Build.cs | 3 ++ 4 files changed, 28 insertions(+), 16 deletions(-) diff --git a/Docs/how_to_build_on_linux.md b/Docs/how_to_build_on_linux.md index 360bbfcd6..5939d8ef0 100644 --- a/Docs/how_to_build_on_linux.md +++ b/Docs/how_to_build_on_linux.md @@ -7,9 +7,9 @@ Install the build tools and dependencies ``` sudo add-apt-repository ppa:ubuntu-toolchain-r/test -sudo apt-get install build-essential clang-5.0 lld-5.0 g++-7 ninja-build python python-pip python3 python3-pip libboost-python-dev python-dev tzdata sed curl wget unzip autoconf libtool -pip2 install --user setuptools nose2 -pip3 install --user setuptools nose2 +sudo apt-get update +sudo apt-get install build-essential clang-5.0 lld-5.0 g++-7 ninja-build python python-pip python-dev tzdata sed curl wget unzip autoconf libtool +pip install --user setuptools nose2 ``` To avoid compatibility issues between Unreal Engine and the CARLA dependencies, diff --git a/LibCarla/cmake/client/CMakeLists.txt b/LibCarla/cmake/client/CMakeLists.txt index a88759ec8..2ce528bb9 100644 --- a/LibCarla/cmake/client/CMakeLists.txt +++ b/LibCarla/cmake/client/CMakeLists.txt @@ -25,7 +25,8 @@ foreach(target carla_client_debug carla_client) "${BOOST_INCLUDE_PATH}" "${RPCLIB_INCLUDE_PATH}") - install(TARGETS ${target} DESTINATION lib) + # @todo This was disabled because now everything is built in the setup.py. + # install(TARGETS ${target} DESTINATION lib) endforeach(target) # Specific options for debug. diff --git a/PythonAPI/setup.py b/PythonAPI/setup.py index e38c4d9de..59c75d16c 100644 --- a/PythonAPI/setup.py +++ b/PythonAPI/setup.py @@ -7,21 +7,31 @@ from setuptools import setup, Extension import fnmatch -import glob import os import platform import sys def get_libcarla_extensions(): - libraries = ['carla_client', 'rpc'] + include_dirs = ['dependencies/include'] + library_dirs = ['dependencies/lib'] + libraries = [] if os.name == "posix": if platform.dist()[0] == "Ubuntu": - libraries += ["boost_python-py%d%d" % (sys.version_info.major, - sys.version_info.minor)] - else: - libraries += ["boost_python"] + pwd = os.path.dirname(os.path.realpath(__file__)) + pylib = "libboost_python%d%d.a" % (sys.version_info.major, + sys.version_info.minor) + extra_link_args = [ + os.path.join(pwd, 'dependencies/lib/librpc.a'), + os.path.join(pwd, 'dependencies/lib', pylib)] + extra_compile_args = [ + '-fPIC', '-std=c++14', '-DBOOST_ERROR_CODE_HEADER_ONLY', '-Wno-missing-braces' + ] + # @todo Why would we need this? + include_dirs += ['/usr/lib/gcc/x86_64-linux-gnu/7/include'] + library_dirs += ['/usr/lib/gcc/x86_64-linux-gnu/7'] + extra_link_args += ['/usr/lib/gcc/x86_64-linux-gnu/7/libstdc++.a'] else: raise NotImplementedError @@ -37,13 +47,11 @@ def get_libcarla_extensions(): return Extension( name, sources=sources, - include_dirs=[ - 'dependencies/include'], - library_dirs=[ - 'dependencies/lib'], - runtime_library_dirs=['dependencies/lib'], + include_dirs=include_dirs, + library_dirs=library_dirs, libraries=libraries, - extra_compile_args=['-fPIC', '-std=c++14', '-DBOOST_ERROR_CODE_HEADER_ONLY', '-Wno-missing-braces'], + extra_compile_args=extra_compile_args, + extra_link_args=extra_link_args, language='c++14', depends=depends) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Carla.Build.cs b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Carla.Build.cs index acb900025..2b6e84bd3 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Carla.Build.cs +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Carla.Build.cs @@ -115,5 +115,8 @@ public class Carla : ModuleRules string LibCarlaIncludePath = Path.Combine(LibCarlaInstallPath, "include"); PublicIncludePaths.Add(LibCarlaIncludePath); PrivateIncludePaths.Add(LibCarlaIncludePath); + + /// @todo This is necessary because rpclib uses exceptions to notify errors. + bEnableExceptions = true; } } From cec246c0282ac4c25891df1661d28255a3f0ba57 Mon Sep 17 00:00:00 2001 From: Marc Garcia Puig Date: Fri, 27 Jul 2018 14:19:47 +0200 Subject: [PATCH 64/71] Create releases_info.md --- Docs/releases_info.md | 19 +++++++++++++++++++ 1 file changed, 19 insertions(+) create mode 100644 Docs/releases_info.md diff --git a/Docs/releases_info.md b/Docs/releases_info.md new file mode 100644 index 000000000..449201932 --- /dev/null +++ b/Docs/releases_info.md @@ -0,0 +1,19 @@ +# Download + +### Stable + +> The most tested and robust release out there! + +- [CARLA 0.8.2](https://github.com/carla-simulator/carla/releases/tag/0.8.2) - + [[Blog post](http://carla.org/2018/04/23/release-0.8.2/)] - _Driving Benchmark_ + +### Development +> These are the version of CARLA, more frequently updated and with the latest features. +Keep in mind that everything in this channel can (and probably will) change. + +- [CARLA 0.8.4](https://github.com/carla-simulator/carla/releases/tag/0.8.4) - + [[Blog post](http://carla.org/2018/06/18/release-0.8.4/)] - _Fixes And More!_ +- [CARLA 0.8.3](https://github.com/carla-simulator/carla/releases/tag/0.8.3) - + [[Blog post](http://carla.org/2018/06/08/release-0.8.3/)] - _Now with bikes!_ +- [CARLA 0.8.1](https://github.com/carla-simulator/carla/releases/tag/0.8.1) - + [[Blog post](http://carla.org/2018/04/05/release-0.8.1/)] - _Start positions_ From 62bc70887eab5199c12b1c45225e61958ba40105 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Mon, 30 Jul 2018 14:10:23 +0200 Subject: [PATCH 65/71] Rename download page and update README --- Docs/{releases_info.md => download.md} | 0 README.md | 4 +--- 2 files changed, 1 insertion(+), 3 deletions(-) rename Docs/{releases_info.md => download.md} (100%) diff --git a/Docs/releases_info.md b/Docs/download.md similarity index 100% rename from Docs/releases_info.md rename to Docs/download.md diff --git a/README.md b/README.md index d324ab098..1592221ef 100644 --- a/README.md +++ b/README.md @@ -5,10 +5,8 @@ CARLA Simulator [![Documentation](https://readthedocs.org/projects/carla/badge/?version=latest)](http://carla.readthedocs.io) [![Waffle.io](https://badge.waffle.io/carla-simulator/carla.svg?columns=Next,In%20Progress,Review)](https://waffle.io/carla-simulator/carla) -### Carla is hiring! [Software Engineer](http://www.cvc.uab.es/?p=3853) - [![carla.org](Docs/img/btn/web.png)](http://carla.org) -[![download](Docs/img/btn/download.png)](https://github.com/carla-simulator/carla/releases/latest) +[![download](Docs/img/btn/download.png)](https://github.com/carla-simulator/carla/blob/master/Docs/download.md) [![documentation](Docs/img/btn/docs.png)](http://carla.readthedocs.io) [![discord](Docs/img/btn/chat.png)](https://discord.gg/8kqACuC) From 20fc5a38f831935e5c74c52ec292032e1dff819a Mon Sep 17 00:00:00 2001 From: nsubiron Date: Mon, 30 Jul 2018 14:28:51 +0200 Subject: [PATCH 66/71] Upgrade version --- CHANGELOG.md | 21 +++++++++++++++++++++ Docs/download.md | 4 +++- Docs/getting_started.md | 4 ++-- Docs/python_api.md | 2 +- 4 files changed, 27 insertions(+), 4 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 15c10aff1..937cf5da0 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,3 +1,24 @@ +## CARLA 0.9.0 + + * Upgraded to Unreal Engine 4.19 + * Redesign of the networking architecture + - Allows any number of clients to connect simultaneously + - Now is possible to add and remove at any time any vehicle or camera + - Now is possible to control any vehicle or camera + - Now is possible to place cameras anywhere + - Reduced to two ports instead of three + - First port uses an RPC protocol based on [rpclib](http://rpclib.net/) + - Second port is for the streaming of the sensor data + * Redesign of the Python API + - Actors and sensors are now exposed in the API and can be independently controlled + - The Python module is built in C++, with significant performance gain in some operations + - Many functionality haven't been ported yet, so expect a lot of things missing + * Redesign of the build system to accommodate the changes in dependencies + - Everything can be done now with the Makefile + - For the moment only Linux is supported, sorry + * Massive clean up of all unused assets + * Some aesthetic fixes to the vehicles + ## CARLA 0.8.4 * Community contribution: ROS bridge by @laurent-george diff --git a/Docs/download.md b/Docs/download.md index 449201932..da865783b 100644 --- a/Docs/download.md +++ b/Docs/download.md @@ -8,9 +8,11 @@ [[Blog post](http://carla.org/2018/04/23/release-0.8.2/)] - _Driving Benchmark_ ### Development -> These are the version of CARLA, more frequently updated and with the latest features. +> These are the version of CARLA, more frequently updated and with the latest features. Keep in mind that everything in this channel can (and probably will) change. +- [CARLA 0.9.0](https://github.com/carla-simulator/carla/releases/tag/0.9.0) - + [[Blog post](http://carla.org/2018/07/30/release-0.9.0/)] - _New API, multi-client multi-agent support_ - [CARLA 0.8.4](https://github.com/carla-simulator/carla/releases/tag/0.8.4) - [[Blog post](http://carla.org/2018/06/18/release-0.8.4/)] - _Fixes And More!_ - [CARLA 0.8.3](https://github.com/carla-simulator/carla/releases/tag/0.8.3) - diff --git a/Docs/getting_started.md b/Docs/getting_started.md index a772a13b6..a12067d04 100644 --- a/Docs/getting_started.md +++ b/Docs/getting_started.md @@ -11,7 +11,7 @@ Welcome to CARLA! This tutorial provides the basic steps for getting started using CARLA. -

Get the latest release

+

Get the latest release

Download the latest release from our GitHub page and extract all the contents of the package in a folder of your choice. @@ -20,7 +20,7 @@ The release package contains the following * The CARLA simulator. * The "carla" Python API module. - * An "example.py" script. + * A few Python scripts with usage examples. The simulator can be started by running `CarlaUE4.sh` on Linux, or `CarlaUE4.exe` on Windows. Unlike previous versions, now the simulator diff --git a/Docs/python_api.md b/Docs/python_api.md index 29f0fa9b7..9e97342b8 100644 --- a/Docs/python_api.md +++ b/Docs/python_api.md @@ -1,4 +1,4 @@ -

Python API

+

Python API Reference

!!! important Versions prior to 0.9.0 have a very different API. For the documentation of From a05854e16ae6a6eef8a10f6e2bcfd3dff42227fc Mon Sep 17 00:00:00 2001 From: nsubiron Date: Mon, 30 Jul 2018 15:57:14 +0200 Subject: [PATCH 67/71] Remove 0.8.1 from download page --- Docs/download.md | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/Docs/download.md b/Docs/download.md index da865783b..fd4e8cdbf 100644 --- a/Docs/download.md +++ b/Docs/download.md @@ -8,6 +8,7 @@ [[Blog post](http://carla.org/2018/04/23/release-0.8.2/)] - _Driving Benchmark_ ### Development + > These are the version of CARLA, more frequently updated and with the latest features. Keep in mind that everything in this channel can (and probably will) change. @@ -17,5 +18,3 @@ Keep in mind that everything in this channel can (and probably will) change. [[Blog post](http://carla.org/2018/06/18/release-0.8.4/)] - _Fixes And More!_ - [CARLA 0.8.3](https://github.com/carla-simulator/carla/releases/tag/0.8.3) - [[Blog post](http://carla.org/2018/06/08/release-0.8.3/)] - _Now with bikes!_ -- [CARLA 0.8.1](https://github.com/carla-simulator/carla/releases/tag/0.8.1) - - [[Blog post](http://carla.org/2018/04/05/release-0.8.1/)] - _Start positions_ From 4a3dfe1f3b43d9dee55cea7b8d2d3b3050ea99e5 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Mon, 30 Jul 2018 17:06:59 +0200 Subject: [PATCH 68/71] Config for probot-stale --- .github/stale.yml | 18 ++++++++++++++++++ 1 file changed, 18 insertions(+) create mode 100644 .github/stale.yml diff --git a/.github/stale.yml b/.github/stale.yml new file mode 100644 index 000000000..687e7eb9f --- /dev/null +++ b/.github/stale.yml @@ -0,0 +1,18 @@ +# Number of days of inactivity before an issue becomes stale +daysUntilStale: 60 +# Number of days of inactivity before a stale issue is closed +daysUntilClose: 7 +# Issues with these labels will never be considered stale +exemptLabels: + - backlog + - next + - in progress +# Label to use when marking an issue as stale +staleLabel: stale +# Comment to post when marking an issue as stale. Set to `false` to disable +markComment: > + This issue has been automatically marked as stale because it has not had + recent activity. It will be closed if no further activity occurs. Thank you + for your contributions. +# Comment to post when closing a stale issue. Set to `false` to disable +closeComment: false From e0c84c2c7e620e8b0d68f304851784712987c74b Mon Sep 17 00:00:00 2001 From: TheNihilisticRobot <33029416+TheNihilisticRobot@users.noreply.github.com> Date: Mon, 9 Jul 2018 17:31:31 +0200 Subject: [PATCH 69/71] Update how_to_add_assets.md Added guidelines for 2wheeled vehicles and cleared some points in 4 wheeled vehicles section. --- Docs/how_to_add_assets.md | 58 +++++++++++++++++++++++++++++++++++---- 1 file changed, 52 insertions(+), 6 deletions(-) diff --git a/Docs/how_to_add_assets.md b/Docs/how_to_add_assets.md index f60962373..f12d49250 100644 --- a/Docs/how_to_add_assets.md +++ b/Docs/how_to_add_assets.md @@ -11,23 +11,69 @@ for creating the Skeletal Mesh and Physics Asset. And [Vehicles User Guide](https://docs.unrealengine.com/latest/INT/Engine/Physics/Vehicles/VehicleUserGuide/) for the rest. +!!! important + If you want a simpler way you might copy our "General4wheeledSkeleton" from our project, either by + exporting it and copying it into your model or by creating your skelleton using the same bone names and orientation. + Bind it to your vehicle model and choose it when importing your vehicle into the editor. + This way you won't need to configure the animation, you might just use "General4wheeledAnimation" (step 3) + You also won't need to configure the bone names for your wheels (Step 7. Be carefull, you'll still need to asign the wheel blueprints). + + * Import fbx as Skelletal Mesh to its own folder inside `Content/Static/Vehicles`. A Physics asset and a Skeleton should be automatically created and linked the three together. * Tune the Physics asset. Delete the automatically created ones and add boxes to the `Vehicle_Base` bone matching the shape, make sure generate hit events is enabled. Add a sphere for each wheel and set their "Physics Type" to "Kinematic". * Inside that folder create an "Animation Blueprint", while creating select "VehicleAnimInstance" as parent class and the skeleton of this car model as the target skeleton. Add the animation graph as shown in the links given above (or look for it in other cars' animation, like Mustang). * Create folder `Content/Blueprints/Vehicles/` * Inside that folder create two blueprint classes derived from "VehicleWheel" class. Call them `_FrontWheel` and `_RearWheel`. Set their "Shape Radius" to exactly match the mesh wheel radius (careful, radius not diameter). Set their "Tire Config" to "CommonTireConfig". On the front wheel uncheck "Affected by Handbrake" and on the rear wheel set "Steer Angle" to zero. - * Inside the same folder create a blueprint class derived from `BaseVehiclePawn` call it ``. Open it for edit and select component "Mesh", setup the "Skeletal Mesh" and the "Anim Class" to the corresponding ones. Then select component "VehicleMovement", under "Vehicle Setup" expand "Wheel Setups", setup each wheel + * Inside the same folder create a blueprint class derived from `BaseVehiclePawn` call it ``. Open it for edit and select component "Mesh", setup the "Skeletal Mesh" and the "Anim Class" to the corresponding ones. Then select the VehicleBounds component and set the size to cover vehicle's volume as close as possible. + * Select component "VehicleMovement", under "Vehicle Setup" expand "Wheel Setups", setup each wheel - 0 : Wheel Class=`_FrontWheel`, Bone Name=`Wheel_Front_Left` - 1 : Wheel Class=`_FrontWheel`, Bone Name=`Wheel_Front_Right` - 2 : Wheel Class=`_RearWheel`, Bone Name=`Wheel_Rear_Left` - 3 : Wheel Class=`_RearWheel`, Bone Name=`Wheel_Rear_Right` - * Add a box component to it called "Box" (see Mustang blueprint) and set the size to cover vehicle's area as seen from above. Make sure the following is set - - Hidden in game - - Simulate physics is disable - - Generate overlap events is disable - - Collision presets is set to "NoCollision" * Test it, go to CarlaGameMode blueprint and change "Default Pawn Class" to the newly created car blueprint +Adding a 2 wheeled vehicle +-------------------------- + +Adding 2 wheeled vehicles is similar to adding a 4 wheeled one but due to the complexity of the animation you'll need to set up aditional bones to guide the driver's animation: + +As with the 4 wheeled vehicles, orient the model towards positive "x" and every bone axis towards positive x and with the z axis facing upwards. + +```yaml +Bone Setup: + - Bike_Rig: # The origin point of the mesh. Place it in the point 0 of the scenecomment + - BikeBody: # The model's body centre. + - Pedals: # If the vehicle is a bike bind the pedalier to this bone, will rotate with the bike acceleration. + - RightPedal: # Sets the driver's feet position and rotates with the pedalier if the vehicle is a bike. + - LeftPedal: # ^ + - RearWheel: # Rear Wheel of the vehicle + - Handler: # Rotates with the frontal wheel of the vehicle bind the vehicle handler to it. + - HandlerMidBone: # Positioned over the front wheel bone to orient the handler with the wheel + - HandlerRight: # Sets the position of the driver's hand, no need to bind it to anything. + - HandlerLeft: # ^ + - Frontwheel: # Frontal wheel of the vehicle. + - RightHelperRotator: # This four additional bones are here for an obsolete system of making the bike stable by using aditional invisible wheels + - RightHelprWheel: # ^ + - LeftHelperRotator: # ^ + - LeftHelperWheel: # ^ + - Seat: # Sets the position of the drivers hip bone. No need to bind it to anything but place it carefully. +``` + + * Import fbx as Skelletal Mesh to its own folder inside `Content/Static/Vehicles/2Wheeled`.When importing select "General2WheeledVehicleSkeleton" as skelleton A Physics asset should be automatically created and linked. + * Tune the Physics asset. Delete the automatically created ones and add boxes to the `BikeBody` bone trying to match the shape as possible, make sure generate hit events is enabled. Add a sphere for each wheel and set their "Physics Type" to "Kinematic". + * Create folder `Content/Blueprints/Vehicles/` + * Inside that folder create two blueprint classes derived from "VehicleWheel" class. Call them `_FrontWheel` and `_RearWheel`. Set their "Shape Radius" to exactly match the mesh wheel radius (careful, radius not diameter). Set their "Tire Config" to "CommonTireConfig". On the front wheel uncheck "Affected by Handbrake" and on the rear wheel set "Steer Angle" to zero. + * Inside the same folder create a blueprint class derived from `Base2WheeledVehicle` call it ``. Open it for edit and select component "Mesh", setup the "Skeletal Mesh" and the "Anim Class" to the corresponding ones. Then select the VehicleBounds component and set the size to cover vehicle's area as seen from above. + * Select component "VehicleMovement", under "Vehicle Setup" expand "Wheel Setups", setup each wheel + - 0 : Wheel Class=`_FrontWheel`, Bone Name=`FrontWheel` + - 1 : Wheel Class=`_FrontWheel`, Bone Name=`FrontWheel` + - 2 : Wheel Class=`_RearWheel`, Bone Name=`RearWheel` + - 3 : Wheel Class=`_RearWheel`, Bone Name=`RearWheel` + (You'll notice that we are basically placing two wheels in each bone. The vehicle class unreal provides does not support vehicles with wheel numbers different from 4 so we had to make it believe the vehicle has 4 wheels) + * Select the variable "is bike" and tick it if your model is a bike. This will activate the pedalier rotation. Leave unmarked if you are setting up a motorbike. + * Find the variable back Rotation and set it as it fit better select the component SkeletalMesh (The driver) and move it along x axis until its in the seat position. + * Test it, go to CarlaGameMode blueprint and change "Default Pawn Class" to the newly created bike blueprint. + Map generation -------------- From d04e0eca8d9ff58a790cdb95122031bc9b404a17 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Mon, 30 Jul 2018 18:26:37 +0200 Subject: [PATCH 70/71] Fix file paths --- Docs/how_to_add_assets.md | 140 +++++++++++++++++++------------------- 1 file changed, 70 insertions(+), 70 deletions(-) diff --git a/Docs/how_to_add_assets.md b/Docs/how_to_add_assets.md index f12d49250..2c390385f 100644 --- a/Docs/how_to_add_assets.md +++ b/Docs/how_to_add_assets.md @@ -12,19 +12,19 @@ for creating the Skeletal Mesh and Physics Asset. And for the rest. !!! important - If you want a simpler way you might copy our "General4wheeledSkeleton" from our project, either by - exporting it and copying it into your model or by creating your skelleton using the same bone names and orientation. + If you want a simpler way you might copy our "General4wheeledSkeleton" from our project, either by + exporting it and copying it into your model or by creating your skelleton using the same bone names and orientation. Bind it to your vehicle model and choose it when importing your vehicle into the editor. - This way you won't need to configure the animation, you might just use "General4wheeledAnimation" (step 3) + This way you won't need to configure the animation, you might just use "General4wheeledAnimation" (step 3) You also won't need to configure the bone names for your wheels (Step 7. Be carefull, you'll still need to asign the wheel blueprints). - * Import fbx as Skelletal Mesh to its own folder inside `Content/Static/Vehicles`. A Physics asset and a Skeleton should be automatically created and linked the three together. + * Import fbx as Skelletal Mesh to its own folder inside `Content/Carla/Static/Vehicles`. A Physics asset and a Skeleton should be automatically created and linked the three together. * Tune the Physics asset. Delete the automatically created ones and add boxes to the `Vehicle_Base` bone matching the shape, make sure generate hit events is enabled. Add a sphere for each wheel and set their "Physics Type" to "Kinematic". * Inside that folder create an "Animation Blueprint", while creating select "VehicleAnimInstance" as parent class and the skeleton of this car model as the target skeleton. Add the animation graph as shown in the links given above (or look for it in other cars' animation, like Mustang). * Create folder `Content/Blueprints/Vehicles/` * Inside that folder create two blueprint classes derived from "VehicleWheel" class. Call them `_FrontWheel` and `_RearWheel`. Set their "Shape Radius" to exactly match the mesh wheel radius (careful, radius not diameter). Set their "Tire Config" to "CommonTireConfig". On the front wheel uncheck "Affected by Handbrake" and on the rear wheel set "Steer Angle" to zero. - * Inside the same folder create a blueprint class derived from `BaseVehiclePawn` call it ``. Open it for edit and select component "Mesh", setup the "Skeletal Mesh" and the "Anim Class" to the corresponding ones. Then select the VehicleBounds component and set the size to cover vehicle's volume as close as possible. + * Inside the same folder create a blueprint class derived from `BaseVehiclePawn` call it ``. Open it for edit and select component "Mesh", setup the "Skeletal Mesh" and the "Anim Class" to the corresponding ones. Then select the VehicleBounds component and set the size to cover vehicle's volume as close as possible. * Select component "VehicleMovement", under "Vehicle Setup" expand "Wheel Setups", setup each wheel - 0 : Wheel Class=`_FrontWheel`, Bone Name=`Wheel_Front_Left` - 1 : Wheel Class=`_FrontWheel`, Bone Name=`Wheel_Front_Right` @@ -42,28 +42,28 @@ As with the 4 wheeled vehicles, orient the model towards positive "x" and every ```yaml Bone Setup: - Bike_Rig: # The origin point of the mesh. Place it in the point 0 of the scenecomment - - BikeBody: # The model's body centre. - - Pedals: # If the vehicle is a bike bind the pedalier to this bone, will rotate with the bike acceleration. - - RightPedal: # Sets the driver's feet position and rotates with the pedalier if the vehicle is a bike. - - LeftPedal: # ^ - - RearWheel: # Rear Wheel of the vehicle - - Handler: # Rotates with the frontal wheel of the vehicle bind the vehicle handler to it. - - HandlerMidBone: # Positioned over the front wheel bone to orient the handler with the wheel - - HandlerRight: # Sets the position of the driver's hand, no need to bind it to anything. - - HandlerLeft: # ^ - - Frontwheel: # Frontal wheel of the vehicle. - - RightHelperRotator: # This four additional bones are here for an obsolete system of making the bike stable by using aditional invisible wheels - - RightHelprWheel: # ^ - - LeftHelperRotator: # ^ - - LeftHelperWheel: # ^ - - Seat: # Sets the position of the drivers hip bone. No need to bind it to anything but place it carefully. + - BikeBody: # The model's body centre. + - Pedals: # If the vehicle is a bike bind the pedalier to this bone, will rotate with the bike acceleration. + - RightPedal: # Sets the driver's feet position and rotates with the pedalier if the vehicle is a bike. + - LeftPedal: # ^ + - RearWheel: # Rear Wheel of the vehicle + - Handler: # Rotates with the frontal wheel of the vehicle bind the vehicle handler to it. + - HandlerMidBone: # Positioned over the front wheel bone to orient the handler with the wheel + - HandlerRight: # Sets the position of the driver's hand, no need to bind it to anything. + - HandlerLeft: # ^ + - Frontwheel: # Frontal wheel of the vehicle. + - RightHelperRotator: # This four additional bones are here for an obsolete system of making the bike stable by using aditional invisible wheels + - RightHelprWheel: # ^ + - LeftHelperRotator: # ^ + - LeftHelperWheel: # ^ + - Seat: # Sets the position of the drivers hip bone. No need to bind it to anything but place it carefully. ``` - * Import fbx as Skelletal Mesh to its own folder inside `Content/Static/Vehicles/2Wheeled`.When importing select "General2WheeledVehicleSkeleton" as skelleton A Physics asset should be automatically created and linked. + * Import fbx as Skelletal Mesh to its own folder inside `Content/Carla/Static/Vehicles/2Wheeled`. When importing select "General2WheeledVehicleSkeleton" as skelleton A Physics asset should be automatically created and linked. * Tune the Physics asset. Delete the automatically created ones and add boxes to the `BikeBody` bone trying to match the shape as possible, make sure generate hit events is enabled. Add a sphere for each wheel and set their "Physics Type" to "Kinematic". * Create folder `Content/Blueprints/Vehicles/` * Inside that folder create two blueprint classes derived from "VehicleWheel" class. Call them `_FrontWheel` and `_RearWheel`. Set their "Shape Radius" to exactly match the mesh wheel radius (careful, radius not diameter). Set their "Tire Config" to "CommonTireConfig". On the front wheel uncheck "Affected by Handbrake" and on the rear wheel set "Steer Angle" to zero. - * Inside the same folder create a blueprint class derived from `Base2WheeledVehicle` call it ``. Open it for edit and select component "Mesh", setup the "Skeletal Mesh" and the "Anim Class" to the corresponding ones. Then select the VehicleBounds component and set the size to cover vehicle's area as seen from above. + * Inside the same folder create a blueprint class derived from `Base2WheeledVehicle` call it ``. Open it for edit and select component "Mesh", setup the "Skeletal Mesh" and the "Anim Class" to the corresponding ones. Then select the VehicleBounds component and set the size to cover vehicle's area as seen from above. * Select component "VehicleMovement", under "Vehicle Setup" expand "Wheel Setups", setup each wheel - 0 : Wheel Class=`_FrontWheel`, Bone Name=`FrontWheel` - 1 : Wheel Class=`_FrontWheel`, Bone Name=`FrontWheel` @@ -81,55 +81,55 @@ For the road generation, the following meshes are expected to be found ``` # Enum Filepath -RoadTwoLanes_LaneLeft at "Content/Static/Road/St_Road_TileRoad_RoadL.uasset" -RoadTwoLanes_LaneRight at "Content/Static/Road/St_Road_TileRoad_RoadR.uasset" -RoadTwoLanes_SidewalkLeft at "Content/Static/SideWalk/St_Road_TileRoad_SidewalkL.uasset" -RoadTwoLanes_SidewalkRight at "Content/Static/SideWalk/St_Road_TileRoad_SidewalkR.uasset" -RoadTwoLanes_LaneMarkingSolid at "Content/Static/RoadLines/St_Road_TileRoad_LaneMarkingSolid.uasset" -RoadTwoLanes_LaneMarkingBroken at "Content/Static/RoadLines/St_Road_TileRoad_LaneMarkingBroken.uasset" +RoadTwoLanes_LaneLeft at "Content/Carla/Static/Road/St_Road_TileRoad_RoadL.uasset" +RoadTwoLanes_LaneRight at "Content/Carla/Static/Road/St_Road_TileRoad_RoadR.uasset" +RoadTwoLanes_SidewalkLeft at "Content/Carla/Static/SideWalk/St_Road_TileRoad_SidewalkL.uasset" +RoadTwoLanes_SidewalkRight at "Content/Carla/Static/SideWalk/St_Road_TileRoad_SidewalkR.uasset" +RoadTwoLanes_LaneMarkingSolid at "Content/Carla/Static/RoadLines/St_Road_TileRoad_LaneMarkingSolid.uasset" +RoadTwoLanes_LaneMarkingBroken at "Content/Carla/Static/RoadLines/St_Road_TileRoad_LaneMarkingBroken.uasset" -Road90DegTurn_Lane0 at "Content/Static/Road/St_Road_Curve_Road1.uasset" -Road90DegTurn_Lane1 at "Content/Static/Road/St_Road_Curve_Road2.uasset" -Road90DegTurn_Lane2 at "Content/Static/Road/St_Road_Curve_Road3.uasset" -Road90DegTurn_Lane3 at "Content/Static/Road/St_Road_Curve_Road4.uasset" -Road90DegTurn_Lane3 at "Content/Static/Road/St_Road_Curve_Road5.uasset" -Road90DegTurn_Lane3 at "Content/Static/Road/St_Road_Curve_Road6.uasset" -Road90DegTurn_Lane3 at "Content/Static/Road/St_Road_Curve_Road7.uasset" -Road90DegTurn_Lane3 at "Content/Static/Road/St_Road_Curve_Road8.uasset" -Road90DegTurn_Lane3 at "Content/Static/Road/St_Road_Curve_Road9.uasset" -Road90DegTurn_Sidewalk0 at "Content/Static/SideWalk/St_Road_Curve_Sidewalk1.uasset" -Road90DegTurn_Sidewalk1 at "Content/Static/SideWalk/St_Road_Curve_Sidewalk2.uasset" -Road90DegTurn_Sidewalk2 at "Content/Static/SideWalk/St_Road_Curve_Sidewalk3.uasset" -Road90DegTurn_Sidewalk3 at "Content/Static/SideWalk/St_Road_Curve_Sidewalk4.uasset" -Road90DegTurn_LaneMarking at "Content/Static/Road/St_Road_Curve_LaneMarking.uasset" +Road90DegTurn_Lane0 at "Content/Carla/Static/Road/St_Road_Curve_Road1.uasset" +Road90DegTurn_Lane1 at "Content/Carla/Static/Road/St_Road_Curve_Road2.uasset" +Road90DegTurn_Lane2 at "Content/Carla/Static/Road/St_Road_Curve_Road3.uasset" +Road90DegTurn_Lane3 at "Content/Carla/Static/Road/St_Road_Curve_Road4.uasset" +Road90DegTurn_Lane3 at "Content/Carla/Static/Road/St_Road_Curve_Road5.uasset" +Road90DegTurn_Lane3 at "Content/Carla/Static/Road/St_Road_Curve_Road6.uasset" +Road90DegTurn_Lane3 at "Content/Carla/Static/Road/St_Road_Curve_Road7.uasset" +Road90DegTurn_Lane3 at "Content/Carla/Static/Road/St_Road_Curve_Road8.uasset" +Road90DegTurn_Lane3 at "Content/Carla/Static/Road/St_Road_Curve_Road9.uasset" +Road90DegTurn_Sidewalk0 at "Content/Carla/Static/SideWalk/St_Road_Curve_Sidewalk1.uasset" +Road90DegTurn_Sidewalk1 at "Content/Carla/Static/SideWalk/St_Road_Curve_Sidewalk2.uasset" +Road90DegTurn_Sidewalk2 at "Content/Carla/Static/SideWalk/St_Road_Curve_Sidewalk3.uasset" +Road90DegTurn_Sidewalk3 at "Content/Carla/Static/SideWalk/St_Road_Curve_Sidewalk4.uasset" +Road90DegTurn_LaneMarking at "Content/Carla/Static/Road/St_Road_Curve_LaneMarking.uasset" -RoadTIntersection_Lane0 at "Content/Static/Road/St_Road_TCross_Road1.uasset" -RoadTIntersection_Lane1 at "Content/Static/Road/St_Road_TCross_Road2.uasset" -RoadTIntersection_Lane2 at "Content/Static/Road/St_Road_TCross_Road3.uasset" -RoadTIntersection_Lane3 at "Content/Static/Road/St_Road_TCross_Road4.uasset" -RoadTIntersection_Lane3 at "Content/Static/Road/St_Road_TCross_Road5.uasset" -RoadTIntersection_Lane3 at "Content/Static/Road/St_Road_TCross_Road6.uasset" -RoadTIntersection_Lane3 at "Content/Static/Road/St_Road_TCross_Road7.uasset" -RoadTIntersection_Lane3 at "Content/Static/Road/St_Road_TCross_Road8.uasset" -RoadTIntersection_Lane3 at "Content/Static/Road/St_Road_TCross_Road9.uasset" -RoadTIntersection_Sidewalk0 at "Content/Static/SideWalk/St_Road_TCross_Sidewalk1.uasset" -RoadTIntersection_Sidewalk1 at "Content/Static/SideWalk/St_Road_TCross_Sidewalk2.uasset" -RoadTIntersection_Sidewalk2 at "Content/Static/SideWalk/St_Road_TCross_Sidewalk3.uasset" -RoadTIntersection_Sidewalk3 at "Content/Static/SideWalk/St_Road_TCross_Sidewalk4.uasset" -RoadTIntersection_LaneMarking at "Content/Static/RoadLines/St_Road_TCross_LaneMarking.uasset" +RoadTIntersection_Lane0 at "Content/Carla/Static/Road/St_Road_TCross_Road1.uasset" +RoadTIntersection_Lane1 at "Content/Carla/Static/Road/St_Road_TCross_Road2.uasset" +RoadTIntersection_Lane2 at "Content/Carla/Static/Road/St_Road_TCross_Road3.uasset" +RoadTIntersection_Lane3 at "Content/Carla/Static/Road/St_Road_TCross_Road4.uasset" +RoadTIntersection_Lane3 at "Content/Carla/Static/Road/St_Road_TCross_Road5.uasset" +RoadTIntersection_Lane3 at "Content/Carla/Static/Road/St_Road_TCross_Road6.uasset" +RoadTIntersection_Lane3 at "Content/Carla/Static/Road/St_Road_TCross_Road7.uasset" +RoadTIntersection_Lane3 at "Content/Carla/Static/Road/St_Road_TCross_Road8.uasset" +RoadTIntersection_Lane3 at "Content/Carla/Static/Road/St_Road_TCross_Road9.uasset" +RoadTIntersection_Sidewalk0 at "Content/Carla/Static/SideWalk/St_Road_TCross_Sidewalk1.uasset" +RoadTIntersection_Sidewalk1 at "Content/Carla/Static/SideWalk/St_Road_TCross_Sidewalk2.uasset" +RoadTIntersection_Sidewalk2 at "Content/Carla/Static/SideWalk/St_Road_TCross_Sidewalk3.uasset" +RoadTIntersection_Sidewalk3 at "Content/Carla/Static/SideWalk/St_Road_TCross_Sidewalk4.uasset" +RoadTIntersection_LaneMarking at "Content/Carla/Static/RoadLines/St_Road_TCross_LaneMarking.uasset" -RoadXIntersection_Lane0 at "Content/Static/Road/St_Road_XCross_Road1.uasset" -RoadXIntersection_Lane1 at "Content/Static/Road/St_Road_XCross_Road2.uasset" -RoadXIntersection_Lane2 at "Content/Static/Road/St_Road_XCross_Road3.uasset" -RoadXIntersection_Lane3 at "Content/Static/Road/St_Road_XCross_Road4.uasset" -RoadXIntersection_Lane3 at "Content/Static/Road/St_Road_XCross_Road5.uasset" -RoadXIntersection_Lane3 at "Content/Static/Road/St_Road_XCross_Road6.uasset" -RoadXIntersection_Lane3 at "Content/Static/Road/St_Road_XCross_Road7.uasset" -RoadXIntersection_Lane3 at "Content/Static/Road/St_Road_XCross_Road8.uasset" -RoadXIntersection_Lane3 at "Content/Static/Road/St_Road_XCross_Road9.uasset" -RoadXIntersection_Sidewalk0 at "Content/Static/SideWalk/St_Road_XCross_Sidewalk1.uasset" -RoadXIntersection_Sidewalk1 at "Content/Static/SideWalk/St_Road_XCross_Sidewalk2.uasset" -RoadXIntersection_Sidewalk2 at "Content/Static/SideWalk/St_Road_XCross_Sidewalk3.uasset" -RoadXIntersection_Sidewalk3 at "Content/Static/SideWalk/St_Road_XCross_Sidewalk4.uasset" -RoadXIntersection_LaneMarking at "Content/Static/RoadLines/St_Road_XCross_LaneMarking.uasset" +RoadXIntersection_Lane0 at "Content/Carla/Static/Road/St_Road_XCross_Road1.uasset" +RoadXIntersection_Lane1 at "Content/Carla/Static/Road/St_Road_XCross_Road2.uasset" +RoadXIntersection_Lane2 at "Content/Carla/Static/Road/St_Road_XCross_Road3.uasset" +RoadXIntersection_Lane3 at "Content/Carla/Static/Road/St_Road_XCross_Road4.uasset" +RoadXIntersection_Lane3 at "Content/Carla/Static/Road/St_Road_XCross_Road5.uasset" +RoadXIntersection_Lane3 at "Content/Carla/Static/Road/St_Road_XCross_Road6.uasset" +RoadXIntersection_Lane3 at "Content/Carla/Static/Road/St_Road_XCross_Road7.uasset" +RoadXIntersection_Lane3 at "Content/Carla/Static/Road/St_Road_XCross_Road8.uasset" +RoadXIntersection_Lane3 at "Content/Carla/Static/Road/St_Road_XCross_Road9.uasset" +RoadXIntersection_Sidewalk0 at "Content/Carla/Static/SideWalk/St_Road_XCross_Sidewalk1.uasset" +RoadXIntersection_Sidewalk1 at "Content/Carla/Static/SideWalk/St_Road_XCross_Sidewalk2.uasset" +RoadXIntersection_Sidewalk2 at "Content/Carla/Static/SideWalk/St_Road_XCross_Sidewalk3.uasset" +RoadXIntersection_Sidewalk3 at "Content/Carla/Static/SideWalk/St_Road_XCross_Sidewalk4.uasset" +RoadXIntersection_LaneMarking at "Content/Carla/Static/RoadLines/St_Road_XCross_LaneMarking.uasset" ``` From be31711d5146cbd8785b55096d56a550a35879e6 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Mon, 30 Jul 2018 19:11:23 +0200 Subject: [PATCH 71/71] Mark as stale everything but backlog --- .github/stale.yml | 2 -- 1 file changed, 2 deletions(-) diff --git a/.github/stale.yml b/.github/stale.yml index 687e7eb9f..80ef6cce0 100644 --- a/.github/stale.yml +++ b/.github/stale.yml @@ -5,8 +5,6 @@ daysUntilClose: 7 # Issues with these labels will never be considered stale exemptLabels: - backlog - - next - - in progress # Label to use when marking an issue as stale staleLabel: stale # Comment to post when marking an issue as stale. Set to `false` to disable