More progress, fix deprecations and modify CMakeLists.txt
This commit is contained in:
parent
440a349425
commit
e4130f627a
|
@ -48,3 +48,6 @@ _out*
|
|||
_site
|
||||
core
|
||||
profiler.csv
|
||||
|
||||
.clangd
|
||||
.cache/
|
193
CMakeLists.txt
193
CMakeLists.txt
|
@ -1,6 +1,191 @@
|
|||
cmake_minimum_required(VERSION 3.5.1)
|
||||
project(CARLA)
|
||||
cmake_minimum_required (VERSION 3.12.0)
|
||||
|
||||
include("Build/CMakeLists.txt.in")
|
||||
project (CARLA)
|
||||
|
||||
add_subdirectory("LibCarla/cmake")
|
||||
set (CARLA_VERSION)
|
||||
|
||||
set (CMAKE_CXX_STANDARD 20)
|
||||
set (CMAKE_CXX_STANDARD_REQUIRED ON)
|
||||
set (CMAKE_EXPORT_COMPILE_COMMANDS ON)
|
||||
|
||||
option (LIBCARLA_CLIENT "Whether to build the LibCarla client." ON)
|
||||
option (LIBCARLA_SERVER "Whether to build the LibCarla server." ON)
|
||||
option (LIBCARLA_PYTORCH_ENABLE "Whether to enable pytorch." OFF)
|
||||
option (PYTHON_API "Whether to build the CARLA Python API." ON)
|
||||
option (LIBCARLA_CLIENT_RSS "Whether to enable RSS components (ad-rss-lib)" OFF)
|
||||
option (LIBCARLA_INSTALL "Whether to install LibCarla and all of its dependencies." ON)
|
||||
option (OSM_ENABLE "" OFF)
|
||||
|
||||
set (LIBCARLA_SOURCE_PATH ${CMAKE_CURRENT_SOURCE_DIR}/LibCarla/source)
|
||||
set (LIBCARLA_THIRD_PARTY_SOURCE_PATH ${LIBCARLA_SOURCE_PATH}/third-party)
|
||||
set (PYTHONAPI_SOURCE_PATH ${CMAKE_CURRENT_SOURCE_DIR}/PythonAPI)
|
||||
|
||||
set (BOOST_INCLUDE_PATH ${CMAKE_CURRENT_BINARY_DIR}/boost-install/include)
|
||||
set (BOOST_LIBRARY_PATH ${CMAKE_CURRENT_BINARY_DIR}/boost-install/lib)
|
||||
set (CHRONO_INCLUDE_PATH ${CMAKE_CURRENT_BINARY_DIR}/chrono-install/include)
|
||||
set (CHRONO_LIBRARY_PATH ${CMAKE_CURRENT_BINARY_DIR}/chrono-install/lib)
|
||||
set (EIGEN_INCLUDE_PATH ${CMAKE_CURRENT_BINARY_DIR}/eigen-install/include)
|
||||
set (EIGEN_LIBRARY_PATH ${CMAKE_CURRENT_BINARY_DIR}/eigen-install/lib)
|
||||
set (GOOGLETEST_INCLUDE_PATH ${CMAKE_CURRENT_BINARY_DIR}/gtest-install/include)
|
||||
set (GOOGLETEST_LIBRARY_PATH ${CMAKE_CURRENT_BINARY_DIR}/gtest-install/lib)
|
||||
set (LIBPNG_INCLUDE_PATH ${CMAKE_CURRENT_BINARY_DIR}/libpng-install/include)
|
||||
set (LIBPNG_LIBRARY_PATH ${CMAKE_CURRENT_BINARY_DIR}/libpng-install/lib)
|
||||
set (PROJ_INCLUDE_PATH ${CMAKE_CURRENT_BINARY_DIR}/proj-install/include)
|
||||
set (PROJ_LIBRARY_PATH ${CMAKE_CURRENT_BINARY_DIR}/proj-install/lib)
|
||||
set (RECAST_INCLUDE_PATH ${CMAKE_CURRENT_BINARY_DIR}/recast-install/include)
|
||||
set (RECAST_LIBRARY_PATH ${CMAKE_CURRENT_BINARY_DIR}/recast-install/lib)
|
||||
set (RPCLIB_INCLUDE_PATH ${CMAKE_CURRENT_BINARY_DIR}/rpclib-install/include)
|
||||
set (RPCLIB_LIBRARY_PATH ${CMAKE_CURRENT_BINARY_DIR}/rpclib-install/lib)
|
||||
set (SQLITE_INCLUDE_PATH ${CMAKE_CURRENT_BINARY_DIR}/sqlite-install/include)
|
||||
set (SQLITE_LIBRARY_PATH ${CMAKE_CURRENT_BINARY_DIR}/sqlite-install/lib)
|
||||
set (XERCESC_INCLUDE_PATH ${CMAKE_CURRENT_BINARY_DIR}/xercesc-install/include)
|
||||
set (XERCESC_LIBRARY_PATH ${CMAKE_CURRENT_BINARY_DIR}/xercesc-install/lib)
|
||||
set (ZLIB_INCLUDE_PATH ${CMAKE_CURRENT_BINARY_DIR}/zlib-install/include)
|
||||
set (ZLIB_LIBRARY_PATH ${CMAKE_CURRENT_BINARY_DIR}/zlib-install/lib)
|
||||
set (ZLIB_INCLUDE_PATH ${CMAKE_CURRENT_BINARY_DIR}/zlib-source)
|
||||
set (ZLIB_LIBRARY_PATH ${CMAKE_CURRENT_BINARY_DIR}/zlib-build)
|
||||
|
||||
add_compile_definitions (BOOST_ERROR_CODE_HEADER_ONLY)
|
||||
add_compile_definitions (LIBCARLA_IMAGE_WITH_PNG_SUPPORT)
|
||||
|
||||
if (WIN32)
|
||||
# https://learn.microsoft.com/en-us/cpp/porting/modifying-winver-and-win32-winnt?view=msvc-170
|
||||
add_compile_definitions (_WIN32_WINNT=0x0A00) # Windows 10
|
||||
add_compile_definitions (_CRT_SECURE_NO_WARNINGS)
|
||||
endif ()
|
||||
|
||||
if (LIBCARLA_SERVER)
|
||||
set (LIBCARLA_SERVER_INCLUDE_PATHS
|
||||
${LIBCARLA_SOURCE_PATH}
|
||||
${BOOST_INCLUDE_PATH}
|
||||
${RPCLIB_INCLUDE_PATH})
|
||||
add_compile_definitions (BOOST_TYPE_INDEX_FORCE_NO_RTTI_COMPATIBILITY)
|
||||
add_compile_options (/EHsc)
|
||||
add_compile_definitions (ASIO_NO_EXCEPTIONS)
|
||||
add_compile_definitions (BOOST_NO_EXCEPTIONS)
|
||||
add_compile_definitions (LIBCARLA_NO_EXCEPTIONS)
|
||||
add_compile_definitions (PUGIXML_NO_EXCEPTIONS)
|
||||
file(GLOB LIBCARLA_SERVER_SOURCES
|
||||
${LIBCARLA_SOURCE_PATH}/carla/*.h
|
||||
${LIBCARLA_SOURCE_PATH}/carla/Buffer.cpp
|
||||
${LIBCARLA_SOURCE_PATH}/carla/Exception.cpp
|
||||
${LIBCARLA_SOURCE_PATH}/carla/geom/*.cpp
|
||||
${LIBCARLA_SOURCE_PATH}/carla/geom/*.h
|
||||
${LIBCARLA_SOURCE_PATH}/carla/opendrive/*.cpp
|
||||
${LIBCARLA_SOURCE_PATH}/carla/opendrive/*.h
|
||||
${LIBCARLA_SOURCE_PATH}/carla/opendrive/parser/*.cpp
|
||||
${LIBCARLA_SOURCE_PATH}/carla/opendrive/parser/*.h
|
||||
${LIBCARLA_SOURCE_PATH}/carla/road/*.cpp
|
||||
${LIBCARLA_SOURCE_PATH}/carla/road/*.h
|
||||
${LIBCARLA_SOURCE_PATH}/carla/road/element/*.cpp
|
||||
${LIBCARLA_SOURCE_PATH}/carla/road/element/*.h
|
||||
${LIBCARLA_SOURCE_PATH}/carla/road/general/*.cpp
|
||||
${LIBCARLA_SOURCE_PATH}/carla/road/general/*.h
|
||||
${LIBCARLA_SOURCE_PATH}/carla/road/object/*.cpp
|
||||
${LIBCARLA_SOURCE_PATH}/carla/road/object/*.h
|
||||
${LIBCARLA_SOURCE_PATH}/carla/road/signal/*.cpp
|
||||
${LIBCARLA_SOURCE_PATH}/carla/road/signal/*.h
|
||||
${LIBCARLA_SOURCE_PATH}/carla/rpc/*.cpp
|
||||
${LIBCARLA_SOURCE_PATH}/carla/rpc/*.h
|
||||
${LIBCARLA_SOURCE_PATH}/carla/sensor/*.h
|
||||
${LIBCARLA_SOURCE_PATH}/carla/sensor/s11n/*.h
|
||||
${LIBCARLA_SOURCE_PATH}/carla/sensor/s11n/SensorHeaderSerializer.cpp
|
||||
${LIBCARLA_SOURCE_PATH}/carla/streaming/*.h
|
||||
${LIBCARLA_SOURCE_PATH}/carla/streaming/detail/*.cpp
|
||||
${LIBCARLA_SOURCE_PATH}/carla/streaming/detail/*.h
|
||||
${LIBCARLA_SOURCE_PATH}/carla/streaming/detail/tcp/*.cpp
|
||||
${LIBCARLA_SOURCE_PATH}/carla/streaming/low_level/*.h
|
||||
${LIBCARLA_SOURCE_PATH}/carla/multigpu/*.h
|
||||
${LIBCARLA_SOURCE_PATH}/carla/multigpu/*.cpp
|
||||
${LIBCARLA_THIRD_PARTY_SOURCE_PATH}/odrSpiral/*.cpp
|
||||
${LIBCARLA_THIRD_PARTY_SOURCE_PATH}/odrSpiral/*.h
|
||||
${LIBCARLA_THIRD_PARTY_SOURCE_PATH}/moodycamel/*.cpp
|
||||
${LIBCARLA_THIRD_PARTY_SOURCE_PATH}/moodycamel/*.h
|
||||
${LIBCARLA_THIRD_PARTY_SOURCE_PATH}/pugixml/*.cpp
|
||||
${LIBCARLA_THIRD_PARTY_SOURCE_PATH}/pugixml/*.hpp
|
||||
)
|
||||
add_library (LibCarla-Server STATIC ${LIBCARLA_SERVER_SOURCES})
|
||||
target_include_directories (LibCarla-Server PRIVATE ${LIBCARLA_SERVER_INCLUDE_PATHS})
|
||||
endif ()
|
||||
|
||||
if (LIBCARLA_CLIENT)
|
||||
project (LibCarla-Client)
|
||||
set (LIBCARLA_CLIENT_INCLUDE_PATHS
|
||||
${LIBCARLA_SOURCE_PATH}
|
||||
${BOOST_INCLUDE_PATH}
|
||||
${RPCLIB_INCLUDE_PATH}
|
||||
${RECAST_INCLUDE_PATH}
|
||||
${LIBPNG_INCLUDE_PATH})
|
||||
file (GLOB LIBCARLA_CLIENT_SOURCES
|
||||
${LIBCARLA_SOURCE_PATH}/carla/*.h
|
||||
${LIBCARLA_SOURCE_PATH}/carla/*.cpp
|
||||
${LIBCARLA_SOURCE_PATH}/carla/client/*.h
|
||||
${LIBCARLA_SOURCE_PATH}/carla/client/*.cpp
|
||||
${LIBCARLA_SOURCE_PATH}carla/client/detail/*.cpp
|
||||
${LIBCARLA_SOURCE_PATH}carla/client/detail/*.h
|
||||
${LIBCARLA_SOURCE_PATH}carla/geom/*.cpp
|
||||
${LIBCARLA_SOURCE_PATH}carla/geom/*.h
|
||||
${LIBCARLA_SOURCE_PATH}carla/image/*.cpp
|
||||
${LIBCARLA_SOURCE_PATH}carla/image/*.h
|
||||
${LIBCARLA_SOURCE_PATH}carla/nav/*.cpp
|
||||
${LIBCARLA_SOURCE_PATH}carla/nav/*.h
|
||||
${LIBCARLA_SOURCE_PATH}carla/opendrive/*.cpp
|
||||
${LIBCARLA_SOURCE_PATH}carla/opendrive/*.h
|
||||
${LIBCARLA_SOURCE_PATH}carla/opendrive/parser/*.cpp
|
||||
${LIBCARLA_SOURCE_PATH}carla/opendrive/parser/*.h
|
||||
${LIBCARLA_SOURCE_PATH}carla/pointcloud/*.cpp
|
||||
${LIBCARLA_SOURCE_PATH}carla/pointcloud/*.h
|
||||
${LIBCARLA_SOURCE_PATH}carla/profiler/*.h
|
||||
${LIBCARLA_SOURCE_PATH}carla/road/*.cpp
|
||||
${LIBCARLA_SOURCE_PATH}carla/road/*.h
|
||||
${LIBCARLA_SOURCE_PATH}carla/road/element/*.cpp
|
||||
${LIBCARLA_SOURCE_PATH}carla/road/element/*.h
|
||||
${LIBCARLA_SOURCE_PATH}carla/road/general/*.cpp
|
||||
${LIBCARLA_SOURCE_PATH}carla/road/general/*.h
|
||||
${LIBCARLA_SOURCE_PATH}carla/road/object/*.cpp
|
||||
${LIBCARLA_SOURCE_PATH}carla/road/object/*.h
|
||||
${LIBCARLA_SOURCE_PATH}carla/road/signal/*.cpp
|
||||
${LIBCARLA_SOURCE_PATH}carla/road/signal/*.h
|
||||
${LIBCARLA_SOURCE_PATH}carla/rpc/*.cpp
|
||||
${LIBCARLA_SOURCE_PATH}carla/rpc/*.h
|
||||
${LIBCARLA_SOURCE_PATH}carla/rss/*.cpp
|
||||
${LIBCARLA_SOURCE_PATH}carla/rss/*.h
|
||||
${LIBCARLA_SOURCE_PATH}carla/sensor/*.cpp
|
||||
${LIBCARLA_SOURCE_PATH}carla/sensor/*.h
|
||||
${LIBCARLA_SOURCE_PATH}carla/sensor/data/*.cpp
|
||||
${LIBCARLA_SOURCE_PATH}carla/sensor/data/*.h
|
||||
${LIBCARLA_SOURCE_PATH}carla/sensor/s11n/*.cpp
|
||||
${LIBCARLA_SOURCE_PATH}carla/sensor/s11n/*.h
|
||||
${LIBCARLA_SOURCE_PATH}carla/streaming/*.cpp
|
||||
${LIBCARLA_SOURCE_PATH}carla/streaming/*.h
|
||||
${LIBCARLA_SOURCE_PATH}carla/streaming/detail/*.cpp
|
||||
${LIBCARLA_SOURCE_PATH}carla/streaming/detail/*.h
|
||||
${LIBCARLA_SOURCE_PATH}carla/streaming/detail/tcp/*.cpp
|
||||
${LIBCARLA_SOURCE_PATH}carla/streaming/detail/tcp/*.h
|
||||
${LIBCARLA_SOURCE_PATH}carla/streaming/low_level/*.cpp
|
||||
${LIBCARLA_SOURCE_PATH}carla/streaming/low_level/*.h
|
||||
${LIBCARLA_SOURCE_PATH}carla/multigpu/*.cpp
|
||||
${LIBCARLA_SOURCE_PATH}carla/multigpu/*.h
|
||||
${LIBCARLA_SOURCE_PATH}carla/trafficmanager/*.cpp
|
||||
${LIBCARLA_SOURCE_PATH}carla/trafficmanager/*.h
|
||||
|
||||
${LIBCARLA_THIRD_PARTY_SOURCE_PATH}/odrSpiral/*.cpp
|
||||
${LIBCARLA_THIRD_PARTY_SOURCE_PATH}/odrSpiral/*.h
|
||||
${LIBCARLA_THIRD_PARTY_SOURCE_PATH}/moodycamel/*.h
|
||||
${LIBCARLA_THIRD_PARTY_SOURCE_PATH}/pugixml/*.cpp
|
||||
${LIBCARLA_THIRD_PARTY_SOURCE_PATH}/pugixml/*.hpp
|
||||
${LIBCARLA_THIRD_PARTY_SOURCE_PATH}/pugixml/*.h
|
||||
)
|
||||
add_library (LibCarla-Client STATIC ${LIBCARLA_CLIENT_SOURCES})
|
||||
target_include_directories (LibCarla-Client PRIVATE ${LIBCARLA_CLIENT_INCLUDE_PATHS})
|
||||
endif ()
|
||||
|
||||
if (LIBCARLA_INSTALL)
|
||||
file (GLOB_RECURSE LIBCARLA_HEADERS ${LIBCARLA_SOURCE_PATH}/**/*.h,*.hpp)
|
||||
set (LIBCARLA_HEADERS_RELATIVE)
|
||||
foreach (HEADER LIBCARLA_HEADERS)
|
||||
cmake_path (RELATIVE_PATH HEADER BASE_DIRECTORY ${LIBCARLA_SOURCE_PATH} OUTPUT_VARIABLE HEADER_RELATIVE)
|
||||
list (APPEND LIBCARLA_HEADERS_RELATIVE HEADER_RELATIVE)
|
||||
endforeach ()
|
||||
install (FILES LIBCARLA_HEADERS DESTINATION LIBCARLA_HEADERS_RELATIVE)
|
||||
endif ()
|
131
Configure.py
131
Configure.py
|
@ -3,10 +3,55 @@ from argparse import ArgumentParser
|
|||
from pathlib import Path
|
||||
import subprocess, tarfile, zipfile, requests, psutil, shutil, glob, json, sys, os
|
||||
|
||||
c_compiler = 'clang-cl' if os.name == 'nt' else 'clang'
|
||||
cpp_compiler = 'clang-cl' if os.name == 'nt' else 'clang'
|
||||
linker = 'llvm-link' if os.name == 'nt' else 'lld'
|
||||
lib = 'llvm-lib' if os.name == 'nt' else 'llvm-ar'
|
||||
def TestForExecutablePresence(name):
|
||||
if os.name == 'nt':
|
||||
return subprocess.call([ 'where', name ], shell = True) == 0
|
||||
else:
|
||||
return subprocess.call([ 'whereis', name ], shell = True) == 0
|
||||
|
||||
def FindExistingExecutable(candidates : list):
|
||||
for e in candidates:
|
||||
if TestForExecutablePresence(e):
|
||||
return e
|
||||
return None
|
||||
|
||||
c_compiler_list = [
|
||||
'clang-cl',
|
||||
'cl'
|
||||
] if os.name == 'nt' else [
|
||||
'clang',
|
||||
'gcc'
|
||||
]
|
||||
|
||||
cpp_compiler_list = [
|
||||
'clang-cl',
|
||||
'cl'
|
||||
] if os.name == 'nt' else [
|
||||
'clang++',
|
||||
'g++'
|
||||
]
|
||||
|
||||
linker_list = [
|
||||
'llvm-link',
|
||||
'link'
|
||||
] if os.name == 'nt' else [
|
||||
'lld',
|
||||
'ld'
|
||||
]
|
||||
|
||||
library_list = [
|
||||
'llvm-lib',
|
||||
'lib',
|
||||
'llvm-ar'
|
||||
] if os.name == 'nt' else [
|
||||
'llvm-ar',
|
||||
'ar'
|
||||
]
|
||||
|
||||
c_compiler = FindExistingExecutable(c_compiler_list)
|
||||
cpp_compiler = FindExistingExecutable(cpp_compiler_list)
|
||||
linker = FindExistingExecutable(linker_list)
|
||||
lib = FindExistingExecutable(library_list)
|
||||
|
||||
# Basic paths
|
||||
workspace_path = Path(__file__).parent.resolve()
|
||||
|
@ -63,10 +108,12 @@ omniverse_plugin_path = ue_workspace_path / 'Engine' / 'Plugins' / 'Marketplace'
|
|||
omniverse_patch_path = util_path / 'Patches' / 'omniverse_4.26'
|
||||
# Script settings
|
||||
parallelism = psutil.cpu_count(logical = True)
|
||||
force_sequential = False
|
||||
force_sequential = True
|
||||
cmake_generator = 'Ninja'
|
||||
|
||||
readthedocs_build_url = 'http://carla.readthedocs.io/en/latest/' + 'how_to_build_on_windows/' if os.name == "nt" else 'build_linux/'
|
||||
readthedocs_build_url = 'http://carla.readthedocs.io/en/latest/' + (
|
||||
'how_to_build_on_windows/' if os.name == "nt" else 'build_linux/'
|
||||
)
|
||||
|
||||
error_message = (
|
||||
f'\n'
|
||||
|
@ -192,7 +239,8 @@ def DownloadDependency(name : str, path : Path, url : str):
|
|||
entries = [ file for file in extract_path.iterdir() ]
|
||||
if len(entries) == 1 and entries[0].is_dir():
|
||||
Path(entries[0]).rename(path)
|
||||
extract_path.rmdir()
|
||||
if extract_path.exists():
|
||||
extract_path.rmdir()
|
||||
else:
|
||||
extract_path.rename(path)
|
||||
except Exception as err:
|
||||
|
@ -322,9 +370,12 @@ def UpdateDependencies(c : ConfigureContext):
|
|||
|
||||
|
||||
def DefaultBuild(path : Path):
|
||||
LaunchSubprocess(
|
||||
['cmake', '--build', path ],
|
||||
display_output = True).check_returncode()
|
||||
LaunchSubprocess([ 'cmake', '--build', path ], display_output = True).check_returncode()
|
||||
|
||||
|
||||
|
||||
def DefaultInstall(path : Path, prefix : Path):
|
||||
LaunchSubprocess([ 'cmake', '--install', path, '--prefix', prefix ], display_output = True).check_returncode()
|
||||
|
||||
|
||||
|
||||
|
@ -333,6 +384,7 @@ boost_toolset_short = 'vc142'
|
|||
boost_source_path = build_path / 'boost-source'
|
||||
boost_build_path = build_path / 'boost-build'
|
||||
boost_install_path = build_path / 'boost-install'
|
||||
boost_include_path = boost_install_path / 'include'
|
||||
boost_library_path = boost_install_path / 'lib'
|
||||
boost_b2_path = boost_source_path / f'b2{executable_extension}'
|
||||
|
||||
|
@ -344,20 +396,17 @@ def ConfigureBoost():
|
|||
working_directory = boost_source_path).check_returncode()
|
||||
|
||||
def BuildBoost():
|
||||
# B2 potentially recompiles:
|
||||
if boost_build_path.exists():
|
||||
return
|
||||
LaunchSubprocess([
|
||||
boost_b2_path,
|
||||
f'-j{parallelism}',
|
||||
'--layout=versioned',
|
||||
'--layout=system',
|
||||
f'--build-dir={boost_build_path}', # ???
|
||||
'--with-system',
|
||||
'--with-filesystem',
|
||||
'--with-python',
|
||||
'--with-date_time',
|
||||
# 'architecture=x86',
|
||||
# 'address-model=64',
|
||||
'architecture=x86',
|
||||
'address-model=64',
|
||||
f'toolset={boost_toolset}',
|
||||
'variant=release',
|
||||
'link=static',
|
||||
|
@ -365,7 +414,7 @@ def BuildBoost():
|
|||
'threading=multi',
|
||||
f'--prefix={boost_build_path}',
|
||||
f'--libdir={boost_library_path}',
|
||||
f'--includedir={boost_source_path}',
|
||||
f'--includedir={boost_include_path}',
|
||||
'install'
|
||||
], display_output = True, working_directory = boost_source_path).check_returncode()
|
||||
|
||||
|
@ -491,17 +540,23 @@ def BuildSQLite():
|
|||
|
||||
if os.name == 'nt' and 'clang' in c_compiler:
|
||||
if not sqlite_executable_path.exists():
|
||||
LaunchSubprocess([
|
||||
cmd = [
|
||||
c_compiler,
|
||||
f'-fuse-ld={linker}', '-march=native', '/O2', '/MD', '/EHsc',
|
||||
f'/Fe"{sqlite_executable_path}"'
|
||||
] + sqlite_sources).check_returncode()
|
||||
]
|
||||
cmd.extend(sqlite_sources)
|
||||
cmd.append('-o')
|
||||
cmd.append(sqlite_executable_path)
|
||||
LaunchSubprocess(cmd).check_returncode()
|
||||
if not sqlite_library_path.exists():
|
||||
LaunchSubprocess([
|
||||
cmd = [
|
||||
c_compiler,
|
||||
f'-fuse-ld={lib}', '-march=native', '/c', '/O2', '/MD', '/EHsc',
|
||||
'-o', sqlite_library_path
|
||||
] + sqlite_sources).check_returncode()
|
||||
f'-fuse-ld={lib}', '-march=native', '/O2', '/MD', '/EHsc',
|
||||
]
|
||||
cmd.extend(sqlite_sources)
|
||||
cmd.append('-o')
|
||||
cmd.append(sqlite_library_path)
|
||||
LaunchSubprocess(cmd).check_returncode()
|
||||
else:
|
||||
pass
|
||||
|
||||
|
@ -613,12 +668,6 @@ def ConfigureXercesc():
|
|||
'-DCMAKE_CXX_COMPILER=' + cpp_compiler,
|
||||
'-DCMAKE_CXX_FLAGS_RELEASE="/MD"',
|
||||
'-DCMAKE_BUILD_TYPE=Release',
|
||||
'-DRPCLIB_BUILD_TESTS=OFF',
|
||||
'-DRPCLIB_GENERATE_COMPDB=OFF',
|
||||
'-DRPCLIB_BUILD_EXAMPLES=OFF',
|
||||
'-DRPCLIB_ENABLE_LOGGING=OFF',
|
||||
'-DRPCLIB_ENABLE_COVERAGE=OFF',
|
||||
'-DRPCLIB_MSVC_STATIC_RUNTIME=OFF',
|
||||
xercesc_source_path
|
||||
]).check_returncode()
|
||||
|
||||
|
@ -650,8 +699,9 @@ def BuildDependencies(c : ConfigureContext):
|
|||
c.Dispatch(ConfigureRPCLib)
|
||||
Log('--- CONFIGURING XERCES-C ---')
|
||||
c.Dispatch(ConfigureXercesc)
|
||||
Log('--- CONFIGURING CHRONO ---')
|
||||
c.Dispatch(ConfigureChrono)
|
||||
if c.arg.use_chrono:
|
||||
Log('--- CONFIGURING CHRONO ---')
|
||||
c.Dispatch(ConfigureChrono)
|
||||
c.Wait()
|
||||
Log('--- BUILDING BOOST ---')
|
||||
BuildBoost()
|
||||
|
@ -667,9 +717,18 @@ def BuildDependencies(c : ConfigureContext):
|
|||
BuildRPCLib()
|
||||
Log('--- BUILDING XERCESC ---')
|
||||
BuildXercesc()
|
||||
Log('--- BUILDING CHRONO ---')
|
||||
BuildChrono()
|
||||
pass
|
||||
if c.arg.use_chrono:
|
||||
Log('--- BUILDING CHRONO ---')
|
||||
BuildChrono()
|
||||
c.Wait()
|
||||
DefaultInstall(gtest_build_path, gtest_install_path)
|
||||
DefaultInstall(libpng_build_path, libpng_install_path)
|
||||
DefaultInstall(proj_build_path, proj_install_path)
|
||||
DefaultInstall(recast_build_path, recast_install_path)
|
||||
DefaultInstall(rpclib_build_path, rpclib_install_path)
|
||||
DefaultInstall(xercesc_build_path, xercesc_install_path)
|
||||
if c.arg.use_chrono:
|
||||
DefaultInstall(chrono_build_path, chrono_install_path)
|
||||
|
||||
|
||||
|
||||
|
@ -715,6 +774,7 @@ def ParseCommandLine():
|
|||
'-clean',
|
||||
action='store_true',
|
||||
help = 'Clean build files.')
|
||||
|
||||
# LibCarla
|
||||
|
||||
arg_parser.add_argument(
|
||||
|
@ -726,6 +786,7 @@ def ParseCommandLine():
|
|||
'-skip-libcarla-server',
|
||||
action='store_true',
|
||||
help = 'Whether to skip the libcarla server.')
|
||||
|
||||
# Carla UE:
|
||||
|
||||
arg_parser.add_argument(
|
||||
|
|
|
@ -12,7 +12,7 @@
|
|||
# pragma clang diagnostic push
|
||||
# pragma clang diagnostic ignored "-Wold-style-cast"
|
||||
#endif
|
||||
#include "moodycamel/ConcurrentQueue.h"
|
||||
#include <third-party/moodycamel/ConcurrentQueue.h>
|
||||
#if defined(__clang__)
|
||||
# pragma clang diagnostic pop
|
||||
#endif
|
||||
|
@ -20,7 +20,6 @@
|
|||
#include <memory>
|
||||
|
||||
namespace carla {
|
||||
|
||||
/// A pool of Buffer. Buffers popped from this pool automatically return to
|
||||
/// the pool on destruction so the allocated memory can be reused.
|
||||
///
|
||||
|
|
|
@ -37,7 +37,14 @@ namespace carla {
|
|||
}
|
||||
|
||||
/// Post a task to the pool.
|
||||
template <typename FunctorT, typename ResultT = typename std::result_of<FunctorT()>::type>
|
||||
template <
|
||||
typename FunctorT,
|
||||
#if __cplusplus < 201703L
|
||||
typename ResultT = typename std::result_of_t<FunctorT()>
|
||||
#else
|
||||
typename ResultT = typename std::invoke_result_t<FunctorT()>
|
||||
#endif
|
||||
>
|
||||
std::future<ResultT> Post(FunctorT &&functor) {
|
||||
auto task = std::packaged_task<ResultT()>(std::forward<FunctorT>(functor));
|
||||
auto future = task.get_future();
|
||||
|
|
|
@ -5,7 +5,7 @@
|
|||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "carla/geom/Simplification.h"
|
||||
#include "simplify/Simplify.h"
|
||||
#include <third-party/simplify/Simplify.h>
|
||||
|
||||
namespace carla {
|
||||
namespace geom {
|
||||
|
|
|
@ -53,9 +53,9 @@ namespace multigpu {
|
|||
}
|
||||
};
|
||||
|
||||
_acceptor.async_accept(session->_socket, [=](error_code ec) {
|
||||
_acceptor.async_accept(session->_socket, [=, this](error_code ec) {
|
||||
// Handle query and open a new session immediately.
|
||||
boost::asio::post(_io_context, [=]() { handle_query(ec); });
|
||||
boost::asio::post(_io_context, [ec, handle_query]() { handle_query(ec); });
|
||||
OpenSession(timeout, on_opened, on_closed, on_response);
|
||||
});
|
||||
}
|
||||
|
|
|
@ -51,7 +51,7 @@ namespace multigpu {
|
|||
void Listen(callback_function_type on_session_opened,
|
||||
callback_function_type on_session_closed,
|
||||
callback_function_type_response on_response) {
|
||||
boost::asio::post(_io_context, [=]() {
|
||||
boost::asio::post(_io_context, [=, this]() {
|
||||
OpenSession(
|
||||
_timeout,
|
||||
std::move(on_session_opened),
|
||||
|
|
|
@ -13,12 +13,12 @@
|
|||
#include "carla/geom/Transform.h"
|
||||
#include "carla/nav/WalkerManager.h"
|
||||
#include "carla/rpc/ActorId.h"
|
||||
#include <recast/Recast.h>
|
||||
#include <recast/DetourCrowd.h>
|
||||
#include <recast/DetourNavMesh.h>
|
||||
#include <recast/DetourNavMeshBuilder.h>
|
||||
#include <recast/DetourNavMeshQuery.h>
|
||||
#include <recast/DetourCommon.h>
|
||||
#include <recastnavigation/Recast.h>
|
||||
#include <recastnavigation/DetourCrowd.h>
|
||||
#include <recastnavigation/DetourNavMesh.h>
|
||||
#include <recastnavigation/DetourNavMeshBuilder.h>
|
||||
#include <recastnavigation/DetourNavMeshQuery.h>
|
||||
#include <recastnavigation/DetourCommon.h>
|
||||
|
||||
namespace carla {
|
||||
namespace nav {
|
||||
|
|
|
@ -19,7 +19,7 @@
|
|||
#include "carla/opendrive/parser/TrafficGroupParser.h"
|
||||
#include "carla/road/MapBuilder.h"
|
||||
|
||||
#include <pugixml/pugixml.hpp>
|
||||
#include <third-party/pugixml/pugixml.hpp>
|
||||
|
||||
namespace carla {
|
||||
namespace opendrive {
|
||||
|
|
|
@ -8,7 +8,7 @@
|
|||
|
||||
#include "carla/road/MapBuilder.h"
|
||||
|
||||
#include <pugixml/pugixml.hpp>
|
||||
#include <third-party/pugixml/pugixml.hpp>
|
||||
|
||||
namespace carla {
|
||||
namespace opendrive {
|
||||
|
|
|
@ -11,7 +11,7 @@
|
|||
#include "carla/geom/GeoLocation.h"
|
||||
#include "carla/road/MapBuilder.h"
|
||||
|
||||
#include <pugixml/pugixml.hpp>
|
||||
#include <third-party/pugixml/pugixml.hpp>
|
||||
|
||||
#include <limits>
|
||||
#include <string>
|
||||
|
|
|
@ -8,7 +8,7 @@
|
|||
|
||||
#include "carla/road/MapBuilder.h"
|
||||
|
||||
#include <pugixml/pugixml.hpp>
|
||||
#include <third-party/pugixml/pugixml.hpp>
|
||||
|
||||
namespace carla {
|
||||
namespace opendrive {
|
||||
|
@ -115,7 +115,7 @@ namespace parser {
|
|||
}
|
||||
|
||||
// map_builder calls
|
||||
for (auto const geo : geometry) {
|
||||
for (const auto& geo : geometry) {
|
||||
carla::road::Road *road = map_builder.GetRoad(geo.road_id);
|
||||
if (geo.type == "line") {
|
||||
map_builder.AddRoadGeometryLine(road, geo.s, geo.x, geo.y, geo.hdg, geo.length);
|
||||
|
|
|
@ -8,7 +8,7 @@
|
|||
|
||||
#include "carla/road/MapBuilder.h"
|
||||
|
||||
#include <pugixml/pugixml.hpp>
|
||||
#include <third-party/pugixml/pugixml.hpp>
|
||||
|
||||
namespace carla {
|
||||
namespace opendrive {
|
||||
|
|
|
@ -8,7 +8,7 @@
|
|||
|
||||
#include "carla/road/MapBuilder.h"
|
||||
|
||||
#include <pugixml/pugixml.hpp>
|
||||
#include <third-party/pugixml/pugixml.hpp>
|
||||
|
||||
namespace carla {
|
||||
namespace opendrive {
|
||||
|
|
|
@ -10,7 +10,7 @@
|
|||
#include "carla/road/element/RoadInfoCrosswalk.h"
|
||||
#include "carla/road/Road.h"
|
||||
|
||||
#include <pugixml/pugixml.hpp>
|
||||
#include <third-party/pugixml/pugixml.hpp>
|
||||
|
||||
namespace carla {
|
||||
namespace opendrive {
|
||||
|
|
|
@ -8,7 +8,7 @@
|
|||
|
||||
#include "carla/road/MapBuilder.h"
|
||||
|
||||
#include <pugixml/pugixml.hpp>
|
||||
#include <third-party/pugixml/pugixml.hpp>
|
||||
|
||||
namespace carla {
|
||||
namespace opendrive {
|
||||
|
|
|
@ -11,7 +11,7 @@
|
|||
#include "carla/road/MapBuilder.h"
|
||||
#include "carla/road/RoadTypes.h"
|
||||
|
||||
#include <pugixml/pugixml.hpp>
|
||||
#include <third-party/pugixml/pugixml.hpp>
|
||||
|
||||
namespace carla {
|
||||
namespace opendrive {
|
||||
|
@ -256,7 +256,7 @@ namespace parser {
|
|||
// test print
|
||||
/*
|
||||
printf("Roads: %d\n", roads.size());
|
||||
for (auto const r : roads) {
|
||||
for (const auto& r : roads) {
|
||||
printf("Road: %d\n", r.id);
|
||||
printf(" Name: %s\n", r.name.c_str());
|
||||
printf(" Length: %e\n", r.length);
|
||||
|
@ -264,18 +264,18 @@ namespace parser {
|
|||
printf(" Predecessor: %d\n", r.predecessor);
|
||||
printf(" Successor: %d\n", r.successor);
|
||||
printf(" Speed: %d\n", r.speed.size());
|
||||
for (auto const s : r.speed) {
|
||||
for (const auto& s : r.speed) {
|
||||
printf(" S offset: %e\n", s.s);
|
||||
printf(" Type: %s\n", s.type.c_str());
|
||||
printf(" Max: %e\n", s.max);
|
||||
printf(" Unit: %s\n", s.unit.c_str());
|
||||
}
|
||||
printf("LaneSections: %d\n", r.sections.size());
|
||||
for (auto const s : r.sections) {
|
||||
for (const auto& s : r.sections) {
|
||||
printf(" S offset: %e\n", s.s);
|
||||
printf(" a,b,c,d: %e,%e,%e,%e\n", s.a, s.b, s.c, s.d);
|
||||
printf(" Lanes: %d\n", s.lanes.size());
|
||||
for (auto const l : s.lanes) {
|
||||
for (const auto& l : s.lanes) {
|
||||
printf(" Id: %d\n", l.id);
|
||||
printf(" Type: %s\n", l.type.c_str());
|
||||
printf(" Level: %d\n", l.level);
|
||||
|
@ -287,7 +287,7 @@ namespace parser {
|
|||
*/
|
||||
|
||||
// map_builder calls
|
||||
for (auto const r : roads) {
|
||||
for (const auto& r : roads) {
|
||||
carla::road::Road *road = map_builder.AddRoad(r.id,
|
||||
r.name,
|
||||
r.length,
|
||||
|
@ -296,22 +296,22 @@ namespace parser {
|
|||
r.successor);
|
||||
|
||||
// type speed
|
||||
for (auto const s : r.speed) {
|
||||
for (const auto& s : r.speed) {
|
||||
map_builder.CreateRoadSpeed(road, s.s, s.type, s.max, s.unit);
|
||||
}
|
||||
|
||||
// section offsets
|
||||
for (auto const s : r.section_offsets) {
|
||||
for (const auto& s : r.section_offsets) {
|
||||
map_builder.CreateSectionOffset(road, s.s, s.a, s.b, s.c, s.d);
|
||||
}
|
||||
|
||||
// lane sections
|
||||
road::SectionId i = 0;
|
||||
for (auto const s : r.sections) {
|
||||
for (const auto& s : r.sections) {
|
||||
carla::road::LaneSection *section = map_builder.AddRoadSection(road, i++, s.s);
|
||||
|
||||
// lanes
|
||||
for (auto const l : s.lanes) {
|
||||
for (const auto& l : s.lanes) {
|
||||
/*carla::road::Lane *lane = */ map_builder.AddRoadSectionLane(section, l.id,
|
||||
static_cast<uint32_t>(l.type), l.level, l.predecessor, l.successor);
|
||||
}
|
||||
|
|
|
@ -8,7 +8,7 @@
|
|||
|
||||
#include "carla/road/MapBuilder.h"
|
||||
|
||||
#include <pugixml/pugixml.hpp>
|
||||
#include <third-party/pugixml/pugixml.hpp>
|
||||
|
||||
namespace carla {
|
||||
namespace opendrive {
|
||||
|
|
|
@ -8,7 +8,7 @@
|
|||
|
||||
#include "carla/road/MapBuilder.h"
|
||||
|
||||
#include <pugixml/pugixml.hpp>
|
||||
#include <third-party/pugixml/pugixml.hpp>
|
||||
|
||||
namespace carla {
|
||||
namespace opendrive {
|
||||
|
|
|
@ -20,7 +20,7 @@
|
|||
#include "carla/road/element/RoadInfoSpeed.h"
|
||||
#include "carla/road/element/RoadInfoSignal.h"
|
||||
|
||||
#include "marchingcube/MeshReconstruction.h"
|
||||
#include <third-party/marchingcube/MeshReconstruction.h>
|
||||
|
||||
#include <vector>
|
||||
#include <unordered_map>
|
||||
|
@ -1155,7 +1155,7 @@ namespace road {
|
|||
std::thread neworker(
|
||||
[this, &write_mutex, &mesh_factory, &road_out_mesh_list, i, num_roads_per_thread]() {
|
||||
std::map<road::Lane::LaneType, std::vector<std::unique_ptr<geom::Mesh>>> Current =
|
||||
std::move(GenerateRoadsMultithreaded(mesh_factory, i, num_roads_per_thread));
|
||||
GenerateRoadsMultithreaded(mesh_factory, i, num_roads_per_thread);
|
||||
std::lock_guard<std::mutex> guard(write_mutex);
|
||||
for ( auto&& pair : Current ) {
|
||||
if (road_out_mesh_list.find(pair.first) != road_out_mesh_list.end()) {
|
||||
|
@ -1286,7 +1286,7 @@ namespace road {
|
|||
mesh_factory.GenerateLaneMarkForRoad(pair.second, LineMarks, outinfo);
|
||||
}
|
||||
|
||||
return std::move(LineMarks);
|
||||
return LineMarks;
|
||||
}
|
||||
|
||||
std::vector<carla::geom::BoundingBox> Map::GetJunctionsBoundingBoxes() const {
|
||||
|
|
|
@ -15,7 +15,7 @@
|
|||
#include <boost/array.hpp>
|
||||
#include <boost/math/tools/rational.hpp>
|
||||
|
||||
#include <odrSpiral/odrSpiral.h>
|
||||
#include <third-party/odrSpiral/odrSpiral.h>
|
||||
|
||||
#include <algorithm>
|
||||
#include <cmath>
|
||||
|
|
|
@ -41,7 +41,7 @@ namespace tcp {
|
|||
|
||||
_acceptor.async_accept(session->_socket, [=](error_code ec) {
|
||||
// Handle query and open a new session immediately.
|
||||
boost::asio::post(_io_context, [=]() { handle_query(ec); });
|
||||
boost::asio::post(_io_context, [=, this]() { handle_query(ec); });
|
||||
OpenSession(timeout, on_opened, on_closed);
|
||||
});
|
||||
}
|
||||
|
|
|
@ -19,7 +19,7 @@
|
|||
#include <carla/road/element/RoadInfoMarkRecord.h>
|
||||
#include <carla/road/element/RoadInfoVisitor.h>
|
||||
|
||||
#include <pugixml/pugixml.hpp>
|
||||
#include <third-party/pugixml/pugixml.hpp>
|
||||
|
||||
#include <fstream>
|
||||
#include <string>
|
||||
|
|
|
@ -4,11 +4,11 @@
|
|||
"from" :
|
||||
[
|
||||
{
|
||||
"url": "https://boostorg.jfrog.io/artifactory/main/release/1.80.0/source/boost_1_80_0.zip",
|
||||
"url": "https://boostorg.jfrog.io/artifactory/main/release/1.83.0/source/boost_1_83_0.zip",
|
||||
"type": "download"
|
||||
},
|
||||
{
|
||||
"url": "https://carla-releases.s3.eu-west-3.amazonaws.com/Backup/boost_1_80_0.zip",
|
||||
"url": "https://carla-releases.s3.eu-west-3.amazonaws.com/Backup/boost_1_83_0.zip",
|
||||
"type": "download"
|
||||
}
|
||||
]
|
||||
|
|
Loading…
Reference in New Issue