Merge branch 'master' into manishthani/expose_physx_fixes

This commit is contained in:
manishthani 2019-03-14 13:56:21 +01:00 committed by GitHub
commit e3f61e285a
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
62 changed files with 880 additions and 398 deletions

1
.gitignore vendored
View File

@ -31,6 +31,7 @@ Install
.codelite .codelite
.gdb_history .gdb_history
.gtest .gtest
.idea
.tags* .tags*
.vs .vs
.vscode .vscode

View File

@ -1,5 +1,10 @@
## Latest Changes ## Latest Changes
* Allow user to disable rendering and set the server timeout from the command line
* Add timestamp to SensorData
* Allow usage of hostname for carla::Client and resolve them to IP address * Allow usage of hostname for carla::Client and resolve them to IP address
* Added `map.transform_to_geolocation` to transform Location to GNSS GeoLocation
* Added `id` property to waypoints, uniquely identifying waypoints up to half centimetre precision
* Added OpenDrive's road offset `s` as property to waypoints
* Fixed python client DLL error on Windows * Fixed python client DLL error on Windows
## CARLA 0.9.4 ## CARLA 0.9.4

View File

@ -30,10 +30,13 @@ sensor.listen(lambda data: do_something(data))
``` ```
Note that each sensor has a different set of attributes and produces different Note that each sensor has a different set of attributes and produces different
type of data. However, the data produced by a sensor comes always tagged with a type of data. However, the data produced by a sensor comes always tagged with:
**frame number** and a **transform**. The frame number is used to identify the
frame at which the measurement took place, the transform gives you the | Sensor data attribute | Type | Description |
transformation in world coordinates of the sensor at that same frame. | --------------------- | ------ | ----------- |
| `frame_number` | int | Frame number when the measurement took place |
| `timestamp` | double | Timestamp of the measurement in simulation seconds since the beginning of the epispode |
| `transform` | carla.Transform | Transform in world coordinates of the sensor at the time of the measurement |
Most sensor data objects, like images and lidar measurements, have a function Most sensor data objects, like images and lidar measurements, have a function
for saving the measurements to disk. for saving the measurements to disk.
@ -59,7 +62,7 @@ The "RGB" camera acts as a regular camera capturing images from the scene.
| ------------------- | ---- | ------- | ----------- | | ------------------- | ---- | ------- | ----------- |
| `image_size_x` | int | 800 | Image width in pixels | | `image_size_x` | int | 800 | Image width in pixels |
| `image_size_y` | int | 600 | Image height in pixels | | `image_size_y` | int | 600 | Image height in pixels |
| `fov` | float | 90.0 | Field of view in degrees | | `fov` | float | 90.0 | Horizontal field of view in degrees |
| `enable_postprocess_effects` | bool | True | Whether the post-process effect in the scene affect the image | | `enable_postprocess_effects` | bool | True | Whether the post-process effect in the scene affect the image |
| `sensor_tick` | float | 0.0 | Seconds between sensor captures (ticks) | | `sensor_tick` | float | 0.0 | Seconds between sensor captures (ticks) |
@ -81,11 +84,12 @@ objects.
| Sensor data attribute | Type | Description | | Sensor data attribute | Type | Description |
| --------------------- | ---- | ----------- | | --------------------- | ---- | ----------- |
| `frame_number` | int | Frame count when the measurement took place | | `frame_number` | int | Frame number when the measurement took place |
| `timestamp` | double | Timestamp of the measurement in simulation seconds since the beginning of the epispode |
| `transform` | carla.Transform | Transform in world coordinates of the sensor at the time of the measurement | | `transform` | carla.Transform | Transform in world coordinates of the sensor at the time of the measurement |
| `width` | int | Image width in pixels | | `width` | int | Image width in pixels |
| `height` | int | Image height in pixels | | `height` | int | Image height in pixels |
| `fov` | float | Field of view in degrees | | `fov` | float | Horizontal field of view in degrees |
| `raw_data` | bytes | Array of BGRA 32-bit pixels | | `raw_data` | bytes | Array of BGRA 32-bit pixels |
sensor.camera.depth sensor.camera.depth
@ -100,7 +104,7 @@ pixel to the camera (also known as **depth buffer** or **z-buffer**).
| ------------------- | ---- | ------- | ----------- | | ------------------- | ---- | ------- | ----------- |
| `image_size_x` | int | 800 | Image width in pixels | | `image_size_x` | int | 800 | Image width in pixels |
| `image_size_y` | int | 600 | Image height in pixels | | `image_size_y` | int | 600 | Image height in pixels |
| `fov` | float | 90.0 | Field of view in degrees | | `fov` | float | 90.0 | Horizontal field of view in degrees |
| `sensor_tick` | float | 0.0 | Seconds between sensor captures (ticks) | | `sensor_tick` | float | 0.0 | Seconds between sensor captures (ticks) |
This sensor produces [`carla.Image`](python_api.md#carlaimagecarlasensordata) This sensor produces [`carla.Image`](python_api.md#carlaimagecarlasensordata)
@ -108,11 +112,12 @@ objects.
| Sensor data attribute | Type | Description | | Sensor data attribute | Type | Description |
| --------------------- | ---- | ----------- | | --------------------- | ---- | ----------- |
| `frame_number` | int | Frame count when the measurement took place | | `frame_number` | int | Frame number when the measurement took place |
| `timestamp` | double | Timestamp of the measurement in simulation seconds since the beginning of the epispode |
| `transform` | carla.Transform | Transform in world coordinates of the sensor at the time of the measurement | | `transform` | carla.Transform | Transform in world coordinates of the sensor at the time of the measurement |
| `width` | int | Image width in pixels | | `width` | int | Image width in pixels |
| `height` | int | Image height in pixels | | `height` | int | Image height in pixels |
| `fov` | float | Field of view in degrees | | `fov` | float | Horizontal field of view in degrees |
| `raw_data` | bytes | Array of BGRA 32-bit pixels | | `raw_data` | bytes | Array of BGRA 32-bit pixels |
@ -138,7 +143,7 @@ pedestrians appear in a different color than vehicles.
| ------------------- | ---- | ------- | ----------- | | ------------------- | ---- | ------- | ----------- |
| `image_size_x` | int | 800 | Image width in pixels | | `image_size_x` | int | 800 | Image width in pixels |
| `image_size_y` | int | 600 | Image height in pixels | | `image_size_y` | int | 600 | Image height in pixels |
| `fov` | float | 90.0 | Field of view in degrees | | `fov` | float | 90.0 | Horizontal field of view in degrees |
| `sensor_tick` | float | 0.0 | Seconds between sensor captures (ticks) | | `sensor_tick` | float | 0.0 | Seconds between sensor captures (ticks) |
This sensor produces [`carla.Image`](python_api.md#carlaimagecarlasensordata) This sensor produces [`carla.Image`](python_api.md#carlaimagecarlasensordata)
@ -146,11 +151,12 @@ objects.
| Sensor data attribute | Type | Description | | Sensor data attribute | Type | Description |
| --------------------- | ---- | ----------- | | --------------------- | ---- | ----------- |
| `frame_number` | int | Frame count when the measurement took place | | `frame_number` | int | Frame number when the measurement took place |
| `timestamp` | double | Timestamp of the measurement in simulation seconds since the beginning of the epispode |
| `transform` | carla.Transform | Transform in world coordinates of the sensor at the time of the measurement | | `transform` | carla.Transform | Transform in world coordinates of the sensor at the time of the measurement |
| `width` | int | Image width in pixels | | `width` | int | Image width in pixels |
| `height` | int | Image height in pixels | | `height` | int | Image height in pixels |
| `fov` | float | Field of view in degrees | | `fov` | float | Horizontal field of view in degrees |
| `raw_data` | bytes | Array of BGRA 32-bit pixels | | `raw_data` | bytes | Array of BGRA 32-bit pixels |
The server provides an image with the tag information **encoded in the red The server provides an image with the tag information **encoded in the red
@ -213,7 +219,8 @@ objects.
| Sensor data attribute | Type | Description | | Sensor data attribute | Type | Description |
| -------------------------- | ---------- | ----------- | | -------------------------- | ---------- | ----------- |
| `frame_number` | int | Frame count when the measurement took place | | `frame_number` | int | Frame number when the measurement took place |
| `timestamp` | double | Timestamp of the measurement in simulation seconds since the beginning of the epispode |
| `transform` | carla.Transform | Transform in world coordinates of the sensor at the time of the measurement | | `transform` | carla.Transform | Transform in world coordinates of the sensor at the time of the measurement |
| `horizontal_angle` | float | Angle in XY plane of the lidar this frame (in degrees) | | `horizontal_angle` | float | Angle in XY plane of the lidar this frame (in degrees) |
| `channels` | int | Number of channels (lasers) of the lidar | | `channels` | int | Number of channels (lasers) of the lidar |
@ -251,7 +258,8 @@ object for each collision registered
| Sensor data attribute | Type | Description | | Sensor data attribute | Type | Description |
| ---------------------- | ----------- | ----------- | | ---------------------- | ----------- | ----------- |
| `frame_number` | int | Frame count when the measurement took place | | `frame_number` | int | Frame number when the measurement took place |
| `timestamp` | double | Timestamp of the measurement in simulation seconds since the beginning of the epispode |
| `transform` | carla.Transform | Transform in world coordinates of the sensor at the time of the measurement | | `transform` | carla.Transform | Transform in world coordinates of the sensor at the time of the measurement |
| `actor` | carla.Actor | Actor that measured the collision ("self" actor) | | `actor` | carla.Actor | Actor that measured the collision ("self" actor) |
| `other_actor` | carla.Actor | Actor against whom we collide | | `other_actor` | carla.Actor | Actor against whom we collide |
@ -282,7 +290,8 @@ object for each lane marking crossed by the actor
| Sensor data attribute | Type | Description | | Sensor data attribute | Type | Description |
| ----------------------- | ----------- | ----------- | | ----------------------- | ----------- | ----------- |
| `frame_number` | int | Frame count when the measurement took place | | `frame_number` | int | Frame number when the measurement took place |
| `timestamp` | double | Timestamp of the measurement in simulation seconds since the beginning of the epispode |
| `transform` | carla.Transform | Transform in world coordinates of the sensor at the time of the measurement | | `transform` | carla.Transform | Transform in world coordinates of the sensor at the time of the measurement |
| `actor` | carla.Actor | Actor that invaded another lane ("self" actor) | | `actor` | carla.Actor | Actor that invaded another lane ("self" actor) |
| `crossed_lane_markings` | carla.LaneMarking list | List of lane markings that have been crossed | | `crossed_lane_markings` | carla.LaneMarking list | List of lane markings that have been crossed |
@ -300,7 +309,8 @@ objects.
| Sensor data attribute | Type | Description | | Sensor data attribute | Type | Description |
| ---------------------- | ----------- | ----------- | | ---------------------- | ----------- | ----------- |
| `frame_number` | int | Frame count when the measurement took place | | `frame_number` | int | Frame number when the measurement took place |
| `timestamp` | double | Timestamp of the measurement in simulation seconds since the beginning of the epispode |
| `transform` | carla.Transform | Transform in world coordinates of the sensor at the time of the measurement | | `transform` | carla.Transform | Transform in world coordinates of the sensor at the time of the measurement |
| `latitude` | double | Latitude position of the actor | | `latitude` | double | Latitude position of the actor |
| `longitude` | double | Longitude position of the actor | | `longitude` | double | Longitude position of the actor |

View File

@ -88,6 +88,8 @@ Other command-line options
* `-carla-port=N` Listen for client connections at port N, streaming port is set to N+1. * `-carla-port=N` Listen for client connections at port N, streaming port is set to N+1.
* `-quality-level={Low,Epic}` Change graphics quality level, "Low" mode runs significantly faster. * `-quality-level={Low,Epic}` Change graphics quality level, "Low" mode runs significantly faster.
* `-carla-server-timeout=10000ms` Set server timeout.
* `-no-rendering` Disable rendering.
* [Full list of UE4 command-line arguments][ue4clilink]. * [Full list of UE4 command-line arguments][ue4clilink].
[ue4clilink]: https://docs.unrealengine.com/en-US/Programming/Basics/CommandLineArguments [ue4clilink]: https://docs.unrealengine.com/en-US/Programming/Basics/CommandLineArguments

View File

@ -159,6 +159,7 @@
## `carla.SensorData` ## `carla.SensorData`
- `frame_number` - `frame_number`
- `timestamp`
- `transform` - `transform`
## `carla.Image(carla.SensorData)` ## `carla.Image(carla.SensorData)`
@ -254,6 +255,7 @@
- `get_waypoint(location, project_to_road=True)` - `get_waypoint(location, project_to_road=True)`
- `get_topology()` - `get_topology()`
- `generate_waypoints(distance)` - `generate_waypoints(distance)`
- `transform_to_geolocation(location)`
- `to_opendrive()` - `to_opendrive()`
- `save_to_disk(path=self.name)` - `save_to_disk(path=self.name)`

View File

@ -1,13 +1,21 @@
cmake_minimum_required(VERSION 3.5.1) cmake_minimum_required(VERSION 3.5.1)
project(libcarla) project(libcarla)
message(STATUS "Building ${PROJECT_NAME} version ${CARLA_VERSION}") option(LIBCARLA_BUILD_DEBUG "Build debug configuration" ON)
option(LIBCARLA_BUILD_RELEASE "Build release configuration" ON)
option(LIBCARLA_BUILD_TEST "Build unit tests" ON)
message(STATUS "Build debug: ${LIBCARLA_BUILD_DEBUG}")
message(STATUS "Build release: ${LIBCARLA_BUILD_RELEASE}")
message(STATUS "Build test: ${LIBCARLA_BUILD_TEST}")
set(libcarla_source_path "${PROJECT_SOURCE_DIR}/../source") set(libcarla_source_path "${PROJECT_SOURCE_DIR}/../source")
include_directories(${libcarla_source_path}) include_directories(${libcarla_source_path})
configure_file(${libcarla_source_path}/carla/Version.h.in ${libcarla_source_path}/carla/Version.h) if (CARLA_VERSION)
configure_file(${libcarla_source_path}/carla/Version.h.in ${libcarla_source_path}/carla/Version.h)
endif()
if (CMAKE_BUILD_TYPE STREQUAL "Client") if (CMAKE_BUILD_TYPE STREQUAL "Client")
add_subdirectory("client") add_subdirectory("client")
@ -18,6 +26,10 @@ else ()
endif () endif ()
# GTest is not compiled on Windows. # GTest is not compiled on Windows.
if (NOT WIN32) if ((LIBCARLA_BUILD_TEST) AND (NOT WIN32))
add_subdirectory("test") add_subdirectory("test")
endif() endif()
unset(LIBCARLA_BUILD_TEST CACHE)
unset(LIBCARLA_BUILD_RELEASE CACHE)
unset(LIBCARLA_BUILD_DEBUG CACHE)

View File

@ -84,11 +84,9 @@ file(GLOB libcarla_carla_pointcloud_sources
set(libcarla_sources "${libcarla_sources};${libcarla_carla_pointcloud_sources}") set(libcarla_sources "${libcarla_sources};${libcarla_carla_pointcloud_sources}")
install(FILES ${libcarla_carla_pointcloud_sources} DESTINATION include/carla/pointcloud) install(FILES ${libcarla_carla_pointcloud_sources} DESTINATION include/carla/pointcloud)
file(GLOB libcarla_carla_profiler_sources file(GLOB libcarla_carla_profiler_headers
"${libcarla_source_path}/carla/profiler/*.cpp"
"${libcarla_source_path}/carla/profiler/*.h") "${libcarla_source_path}/carla/profiler/*.h")
set(libcarla_sources "${libcarla_sources};${libcarla_carla_profiler_sources}") install(FILES ${libcarla_carla_profiler_headers} DESTINATION include/carla/profiler)
install(FILES ${libcarla_carla_profiler_sources} DESTINATION include/carla/profiler)
file(GLOB libcarla_carla_road_sources file(GLOB libcarla_carla_road_sources
"${libcarla_source_path}/carla/road/*.cpp" "${libcarla_source_path}/carla/road/*.cpp"
@ -165,23 +163,35 @@ install(FILES ${libcarla_moodycamel_sources} DESTINATION include/moodycamel)
# Create targets for debug and release in the same build type. # Create targets for debug and release in the same build type.
# ============================================================================== # ==============================================================================
foreach(target carla_client_debug carla_client) if (LIBCARLA_BUILD_RELEASE)
add_library(${target} STATIC ${libcarla_sources})
target_include_directories(${target} PRIVATE add_library(carla_client STATIC ${libcarla_sources})
target_include_directories(carla_client PRIVATE
"${BOOST_INCLUDE_PATH}" "${BOOST_INCLUDE_PATH}"
"${RPCLIB_INCLUDE_PATH}") "${RPCLIB_INCLUDE_PATH}")
install(TARGETS ${target} DESTINATION lib) install(TARGETS carla_client DESTINATION lib)
endforeach(target)
# Specific options for debug. if (WIN32) # @todo Fix PythonAPI build on Windows.
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.
if (WIN32) # @todo Fix PythonAPI build on Windows.
set_target_properties(carla_client PROPERTIES COMPILE_FLAGS ${CMAKE_CXX_FLAGS_RELEASE}) set_target_properties(carla_client PROPERTIES COMPILE_FLAGS ${CMAKE_CXX_FLAGS_RELEASE})
else () else ()
set_target_properties(carla_client PROPERTIES COMPILE_FLAGS ${CMAKE_CXX_FLAGS_RELEASE_CLIENT}) set_target_properties(carla_client PROPERTIES COMPILE_FLAGS ${CMAKE_CXX_FLAGS_RELEASE_CLIENT})
endif (WIN32) endif (WIN32)
endif()
if (LIBCARLA_BUILD_DEBUG)
add_library(carla_client_debug STATIC ${libcarla_sources})
target_include_directories(carla_client_debug PRIVATE
"${BOOST_INCLUDE_PATH}"
"${RPCLIB_INCLUDE_PATH}")
install(TARGETS carla_client_debug DESTINATION lib)
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)
endif()

View File

@ -107,20 +107,35 @@ file(GLOB libcarla_server_sources
"${libcarla_source_path}/carla/streaming/detail/tcp/*.h" "${libcarla_source_path}/carla/streaming/detail/tcp/*.h"
"${libcarla_source_path}/carla/streaming/low_level/*.h") "${libcarla_source_path}/carla/streaming/low_level/*.h")
# ==============================================================================
# Create targets for debug and release in the same build type. # 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 if (LIBCARLA_BUILD_RELEASE)
add_library(carla_server STATIC ${libcarla_server_sources})
target_include_directories(carla_server PRIVATE
"${BOOST_INCLUDE_PATH}" "${BOOST_INCLUDE_PATH}"
"${RPCLIB_INCLUDE_PATH}") "${RPCLIB_INCLUDE_PATH}")
install(TARGETS ${target} DESTINATION lib) install(TARGETS carla_server DESTINATION lib OPTIONAL)
endforeach(target)
# Specific options for debug. set_target_properties(carla_server PROPERTIES COMPILE_FLAGS ${CMAKE_CXX_FLAGS_RELEASE})
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. endif()
set_target_properties(carla_server PROPERTIES COMPILE_FLAGS ${CMAKE_CXX_FLAGS_RELEASE})
if (LIBCARLA_BUILD_DEBUG)
add_library(carla_server_debug STATIC ${libcarla_server_sources})
target_include_directories(carla_server_debug PRIVATE
"${BOOST_INCLUDE_PATH}"
"${RPCLIB_INCLUDE_PATH}")
install(TARGETS carla_server_debug DESTINATION lib OPTIONAL)
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)
endif()

View File

@ -23,8 +23,17 @@ file(GLOB libcarla_test_sources
file(GLOB libcarla_test_client_sources "") file(GLOB libcarla_test_client_sources "")
if (LIBCARLA_BUILD_DEBUG)
list(APPEND build_targets libcarla_test_${carla_config}_debug)
endif()
if (LIBCARLA_BUILD_RELEASE)
list(APPEND build_targets libcarla_test_${carla_config}_release)
endif()
# Create targets for debug and release in the same build type. # Create targets for debug and release in the same build type.
foreach(target libcarla_test_${carla_config}_debug libcarla_test_${carla_config}_release) foreach(target ${build_targets})
add_executable(${target} ${libcarla_test_sources}) add_executable(${target} ${libcarla_test_sources})
target_compile_definitions(${target} PUBLIC target_compile_definitions(${target} PUBLIC
@ -47,14 +56,18 @@ foreach(target libcarla_test_${carla_config}_debug libcarla_test_${carla_config}
target_link_libraries(${target} "-lgtest") target_link_libraries(${target} "-lgtest")
endif() endif()
install(TARGETS ${target} DESTINATION test) install(TARGETS ${target} DESTINATION test OPTIONAL)
endforeach(target) endforeach(target)
# Specific options for debug. if (LIBCARLA_BUILD_DEBUG)
set_target_properties(libcarla_test_${carla_config}_debug PROPERTIES COMPILE_FLAGS ${CMAKE_CXX_FLAGS_DEBUG}) # Specific options for debug.
target_link_libraries(libcarla_test_${carla_config}_debug "carla_${carla_config}_debug") set_target_properties(libcarla_test_${carla_config}_debug PROPERTIES COMPILE_FLAGS ${CMAKE_CXX_FLAGS_DEBUG})
target_compile_definitions(libcarla_test_${carla_config}_debug PUBLIC -DBOOST_ASIO_ENABLE_BUFFER_DEBUGGING) target_link_libraries(libcarla_test_${carla_config}_debug "carla_${carla_config}_debug")
target_compile_definitions(libcarla_test_${carla_config}_debug PUBLIC -DBOOST_ASIO_ENABLE_BUFFER_DEBUGGING)
endif()
# Specific options for release. if (LIBCARLA_BUILD_RELEASE)
set_target_properties(libcarla_test_${carla_config}_release PROPERTIES COMPILE_FLAGS ${CMAKE_CXX_FLAGS_RELEASE}) # Specific options for release.
target_link_libraries(libcarla_test_${carla_config}_release "carla_${carla_config}") set_target_properties(libcarla_test_${carla_config}_release PROPERTIES COMPILE_FLAGS ${CMAKE_CXX_FLAGS_RELEASE})
target_link_libraries(libcarla_test_${carla_config}_release "carla_${carla_config}")
endif()

View File

@ -85,10 +85,19 @@ namespace carla {
copy_from(source); copy_from(source);
} }
Buffer(const value_type *data, size_type size) { explicit Buffer(const value_type *data, size_type size) {
copy_from(data, size); copy_from(data, size);
} }
/// @copydoc Buffer(size_type)
explicit Buffer(const value_type *data, uint64_t size)
: Buffer(data, [size]() {
if (size > max_size()) {
throw_exception(std::invalid_argument("message size too big"));
}
return static_cast<size_type>(size);
} ()) {}
Buffer(const Buffer &) = delete; Buffer(const Buffer &) = delete;
Buffer(Buffer &&rhs) noexcept Buffer(Buffer &&rhs) noexcept
@ -326,7 +335,7 @@ namespace carla {
/// Copy @a size bytes of the memory pointed by @a data into this buffer, /// Copy @a size bytes of the memory pointed by @a data into this buffer,
/// leaving at the front an offset of @a offset bytes uninitialized. /// leaving at the front an offset of @a offset bytes uninitialized.
/// Allocates memory if necessary. /// Allocates memory if necessary.
void copy_from(size_t offset, const value_type *data, size_type size) { void copy_from(size_type offset, const value_type *data, size_type size) {
copy_from(offset, boost::asio::buffer(data, size)); copy_from(offset, boost::asio::buffer(data, size));
} }

View File

@ -6,6 +6,7 @@
#pragma once #pragma once
#include "carla/Debug.h"
#include "carla/NonCopyable.h" #include "carla/NonCopyable.h"
#include <thread> #include <thread>

View File

@ -8,60 +8,13 @@
#include "carla/Logging.h" #include "carla/Logging.h"
#include "carla/client/Map.h" #include "carla/client/Map.h"
#include "carla/client/detail/Simulator.h" #include "carla/client/detail/Simulator.h"
#include "carla/geom/Math.h"
#include "carla/sensor/data/GnssEvent.h" #include "carla/sensor/data/GnssEvent.h"
#include "carla/StringUtil.h"
#include <exception> #include <exception>
#include <cmath>
#include <sstream>
#include <limits>
#if defined(_WIN32) && !defined(_USE_MATH_DEFINES)
#define _USE_MATH_DEFINES
#include <math.h> // cmath is not enough for MSVC
#endif
namespace carla { namespace carla {
namespace client { namespace client {
const double EARTH_RADIUS_EQUA = 6378137.0;// earth radius at equator [m]
// inlined functions to avoid multiple definitions
/// @brief convert latitude to scale, which is needed by mercator transformations
/// @param lat latitude in degrees (DEG)
/// @return scale factor
/// @note when converting from lat/lon -> mercator and back again,
/// or vice versa, use the same scale in both transformations!
inline double LatToScale (double lat) {
return cos(lat * geom::Math::pi() / 180.0);
}
/// @brief converts lat/lon/scale to mx/my (mx/my in meters if correct scale is given)
///
template<class float_type>
inline void LatLonToMercator (double lat, double lon, double scale, float_type &mx, float_type &my) {
mx = scale * lon * geom::Math::pi() * EARTH_RADIUS_EQUA / 180.0;
my = scale * EARTH_RADIUS_EQUA * log( tan((90.0+lat) * geom::Math::pi() / 360.0) );
}
/// @brief converts mx/my/scale to lat/lon (mx/my in meters if correct scale is given)
inline void MercatorToLatLon (double mx, double my, double scale, double &lat, double &lon) {
lon = mx * 180.0 / (geom::Math::pi() * EARTH_RADIUS_EQUA * scale);
lat = 360.0 * atan( exp(my/(EARTH_RADIUS_EQUA * scale)) ) / geom::Math::pi() - 90.0;
}
/// @brief adds meters dx/dy to given lat/lon and returns new lat/lon
inline void LatLonAddMeters (double lat_start, double lon_start, double dx, double dy, double &lat_end, double &lon_end) {
double scale = LatToScale (lat_start);
double mx,my;
LatLonToMercator (lat_start, lon_start, scale, mx, my);
mx += dx;
my += dy;
MercatorToLatLon (mx, my, scale, lat_end, lon_end);
}
GnssSensor::~GnssSensor() = default; GnssSensor::~GnssSensor() = default;
void GnssSensor::Listen(CallbackFunctionType callback) { void GnssSensor::Listen(CallbackFunctionType callback) {
@ -76,40 +29,11 @@ namespace client {
} }
SharedPtr<Map> map = GetWorld().GetMap(); SharedPtr<Map> map = GetWorld().GetMap();
DEBUG_ASSERT(map != nullptr); DEBUG_ASSERT(map != nullptr);
_geo_reference = map->GetGeoReference();
auto self = boost::static_pointer_cast<GnssSensor>(shared_from_this()); auto self = boost::static_pointer_cast<GnssSensor>(shared_from_this());
//parse geo reference string
_map_latitude = std::numeric_limits<double>::quiet_NaN();
_map_longitude = std::numeric_limits<double>::quiet_NaN();
std::vector<std::string> geo_ref_splitted;
StringUtil::Split(geo_ref_splitted, map->GetGeoReference(), " ");
for (auto element: geo_ref_splitted) {
std::vector<std::string> geo_ref_key_value;
StringUtil::Split(geo_ref_key_value, element, "=");
if (geo_ref_key_value.size() != 2u) {
continue;
}
if (geo_ref_key_value[0] == "+lat_0") {
_map_latitude = ParseDouble(geo_ref_key_value[1]);
} else if (geo_ref_key_value[0] == "+lon_0") {
_map_longitude = ParseDouble(geo_ref_key_value[1]);
}
}
if (std::isnan(_map_latitude) || std::isnan(_map_longitude)) {
log_warning(GetDisplayId(), ": cannot parse georeference: '" + map->GetGeoReference() + "'. Using default values.");
_map_latitude = 42.0;
_map_longitude = 2.0;
}
log_debug(GetDisplayId(), ": map geo reference: latitude ", _map_latitude, ", longitude ", _map_longitude);
log_debug(GetDisplayId(), ": subscribing to tick event"); log_debug(GetDisplayId(), ": subscribing to tick event");
GetEpisode().Lock()->RegisterOnTickEvent([ GetEpisode().Lock()->RegisterOnTickEvent([
cb=std::move(callback), cb=std::move(callback),
@ -122,43 +46,27 @@ namespace client {
} }
} }
}); });
_is_listening = true;
}
double GnssSensor::ParseDouble(std::string const &stringValue) const { _is_listening = true;
double value;
std::istringstream istr(stringValue);
istr.imbue(std::locale("C"));
istr >> value;
if (istr.fail() || !istr.eof()) {
value = std::numeric_limits<double>::quiet_NaN();
}
return value;
} }
SharedPtr<sensor::SensorData> GnssSensor::TickGnssSensor( SharedPtr<sensor::SensorData> GnssSensor::TickGnssSensor(
const Timestamp &timestamp) { const Timestamp &timestamp) {
try { try {
const auto location = GetLocation();
double current_lat, current_lon;
LatLonAddMeters(_map_latitude, _map_longitude, location.x, location.y, current_lat, current_lon);
return MakeShared<sensor::data::GnssEvent>( return MakeShared<sensor::data::GnssEvent>(
timestamp.frame_count, timestamp.frame_count,
timestamp.elapsed_seconds,
GetTransform(), GetTransform(),
current_lat, _geo_reference.Transform(GetLocation()));
current_lon,
location.z);
} catch (const std::exception &e) { } catch (const std::exception &e) {
/// @todo We need to unsubscribe the sensor. /// @todo We need to unsubscribe the sensor.
// log_error("LaneDetector:", e.what()); // log_error("LaneDetector:", e.what());
return nullptr; return nullptr;
} }
} }
void GnssSensor::Stop() { void GnssSensor::Stop() {
/// @todo We need unsubscribe from the world on tick.
_is_listening = false; _is_listening = false;
} }

View File

@ -6,14 +6,11 @@
#pragma once #pragma once
#include "carla/client/Sensor.h" #include "carla/client/Sensor.h"
#include <string> #include "carla/geom/GeoLocation.h"
namespace carla { namespace carla {
namespace client { namespace client {
class Map;
class Vehicle;
class GnssSensor final : public Sensor { class GnssSensor final : public Sensor {
public: public:
@ -43,14 +40,9 @@ namespace client {
SharedPtr<sensor::SensorData> TickGnssSensor(const Timestamp &timestamp); SharedPtr<sensor::SensorData> TickGnssSensor(const Timestamp &timestamp);
double ParseDouble(std::string const &stringValue) const; geom::GeoLocation _geo_reference;
double _map_latitude;
double _map_longitude;
bool _is_listening = false; bool _is_listening = false;
}; };
} // namespace client } // namespace client

View File

@ -92,6 +92,7 @@ namespace client {
nullptr : nullptr :
MakeShared<sensor::data::LaneInvasionEvent>( MakeShared<sensor::data::LaneInvasionEvent>(
timestamp.frame_count, timestamp.frame_count,
timestamp.elapsed_seconds,
_vehicle->GetTransform(), _vehicle->GetTransform(),
_vehicle, _vehicle,
crossed_lanes); crossed_lanes);

View File

@ -23,14 +23,17 @@ namespace client {
Map::Map(rpc::MapInfo description) Map::Map(rpc::MapInfo description)
: _description(std::move(description)), : _description(std::move(description)),
_map(MakeMap(_description.open_drive_file)) {} _map(MakeMap(_description.open_drive_file)) {
if (_map == nullptr) {
throw_exception(std::runtime_error("failed to generate map"));
}
}
Map::~Map() = default; Map::~Map() = default;
SharedPtr<Waypoint> Map::GetWaypoint( SharedPtr<Waypoint> Map::GetWaypoint(
const geom::Location &location, const geom::Location &location,
bool project_to_road) const { bool project_to_road) const {
DEBUG_ASSERT(_map != nullptr);
boost::optional<road::element::Waypoint> waypoint; boost::optional<road::element::Waypoint> waypoint;
if (project_to_road) { if (project_to_road) {
waypoint = _map->GetClosestWaypointOnRoad(location); waypoint = _map->GetClosestWaypointOnRoad(location);
@ -43,7 +46,6 @@ namespace client {
} }
Map::TopologyList Map::GetTopology() const { Map::TopologyList Map::GetTopology() const {
DEBUG_ASSERT(_map != nullptr);
namespace re = carla::road::element; namespace re = carla::road::element;
std::unordered_map<re::id_type, std::unordered_map<int, SharedPtr<Waypoint>>> waypoints; std::unordered_map<re::id_type, std::unordered_map<int, SharedPtr<Waypoint>>> waypoints;
@ -82,14 +84,12 @@ namespace client {
std::vector<road::element::LaneMarking> Map::CalculateCrossedLanes( std::vector<road::element::LaneMarking> Map::CalculateCrossedLanes(
const geom::Location &origin, const geom::Location &origin,
const geom::Location &destination) const { const geom::Location &destination) const {
DEBUG_ASSERT(_map != nullptr);
return _map->CalculateCrossedLanes(origin, destination); return _map->CalculateCrossedLanes(origin, destination);
} }
const geom::GeoLocation &Map::GetGeoReference() const {
std::string Map::GetGeoReference() const {
DEBUG_ASSERT(_map != nullptr);
return _map->GetData().GetGeoReference(); return _map->GetData().GetGeoReference();
} }
} // namespace client } // namespace client
} // namespace carla } // namespace carla

View File

@ -14,6 +14,7 @@
#include <string> #include <string>
namespace carla { namespace carla {
namespace geom { class GeoLocation; }
namespace road { class Map; } namespace road { class Map; }
namespace client { namespace client {
@ -54,13 +55,13 @@ namespace client {
const geom::Location &origin, const geom::Location &origin,
const geom::Location &destination) const; const geom::Location &destination) const;
std::string GetGeoReference() const; const geom::GeoLocation &GetGeoReference() const;
private: private:
rpc::MapInfo _description; const rpc::MapInfo _description;
SharedPtr<road::Map> _map; const SharedPtr<const road::Map> _map;
}; };
} // namespace client } // namespace client

View File

@ -8,8 +8,9 @@
#include "carla/Memory.h" #include "carla/Memory.h"
#include "carla/NonCopyable.h" #include "carla/NonCopyable.h"
#include "carla/road/element/Waypoint.h"
#include "carla/road/element/RoadInfoMarkRecord.h" #include "carla/road/element/RoadInfoMarkRecord.h"
#include "carla/road/element/Waypoint.h"
#include "carla/road/element/WaypointHash.h"
namespace carla { namespace carla {
namespace client { namespace client {
@ -31,6 +32,14 @@ namespace client {
~Waypoint(); ~Waypoint();
/// Returns an unique Id identifying this waypoint.
///
/// The Id takes into account OpenDrive's road Id, lane Id, and s distance
/// on its road segment up to half-centimetre precision.
uint64_t GetId() const {
return road::element::WaypointHash()(_waypoint);
}
const geom::Transform &GetTransform() const { const geom::Transform &GetTransform() const {
return _transform; return _transform;
} }
@ -51,6 +60,10 @@ namespace client {
return _waypoint.GetLaneId(); return _waypoint.GetLaneId();
} }
double GetDistance() const {
return _waypoint.GetDistance();
}
std::string GetType() const { std::string GetType() const {
return _waypoint.GetType(); return _waypoint.GetType();
} }

View File

@ -9,7 +9,6 @@
#include "carla/Debug.h" #include "carla/Debug.h"
#include "carla/Memory.h" #include "carla/Memory.h"
#include "carla/NonCopyable.h" #include "carla/NonCopyable.h"
#include "carla/Version.h"
#include "carla/client/Actor.h" #include "carla/client/Actor.h"
#include "carla/client/GarbageCollectionPolicy.h" #include "carla/client/GarbageCollectionPolicy.h"
#include "carla/client/TrafficLight.h" #include "carla/client/TrafficLight.h"

View File

@ -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 <https://opensource.org/licenses/MIT>.
#include "carla/geom/GeoLocation.h"
#include "carla/geom/Location.h"
#include "carla/geom/Math.h"
#include <cmath>
#if defined(_WIN32) && !defined(_USE_MATH_DEFINES)
# define _USE_MATH_DEFINES
# include <math.h> // cmath is not enough for MSVC
#endif
namespace carla {
namespace geom {
/// Earth radius at equator [m].
static constexpr double EARTH_RADIUS_EQUA = 6378137.0;
/// Convert latitude to scale, which is needed by mercator
/// transformations
/// @param lat latitude in degrees (DEG)
/// @return scale factor
/// @note when converting from lat/lon -> mercator and back again,
/// or vice versa, use the same scale in both transformations!
static double LatToScale(double lat) {
return std::cos(Math::to_radians(lat));
}
/// Converts lat/lon/scale to mx/my (mx/my in meters if correct scale
/// is given).
template <class float_type>
static void LatLonToMercator(double lat, double lon, double scale, float_type &mx, float_type &my) {
mx = scale * Math::to_radians(lon) * EARTH_RADIUS_EQUA;
my = scale * EARTH_RADIUS_EQUA * std::log(std::tan((90.0 + lat) * Math::pi() / 360.0));
}
/// Converts mx/my/scale to lat/lon (mx/my in meters if correct scale
/// is given).
static void MercatorToLatLon(double mx, double my, double scale, double &lat, double &lon) {
lon = mx * 180.0 / (Math::pi() * EARTH_RADIUS_EQUA * scale);
lat = 360.0 * std::atan(std::exp(my / (EARTH_RADIUS_EQUA * scale))) / Math::pi() - 90.0;
}
/// Adds meters dx/dy to given lat/lon and returns new lat/lon.
static void LatLonAddMeters(
double lat_start,
double lon_start,
double dx,
double dy,
double &lat_end,
double &lon_end) {
double scale = LatToScale(lat_start);
double mx, my;
LatLonToMercator(lat_start, lon_start, scale, mx, my);
mx += dx;
my += dy;
MercatorToLatLon(mx, my, scale, lat_end, lon_end);
}
GeoLocation GeoLocation::Transform(const Location &location) const {
GeoLocation result{0.0, 0.0, altitude + location.z};
LatLonAddMeters(
latitude, longitude,
location.x, location.y,
result.latitude, result.longitude);
return result;
}
} // namespace geom
} // namespace carla

View File

@ -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 <https://opensource.org/licenses/MIT>.
#pragma once
namespace carla {
namespace geom {
class Location;
class GeoLocation {
public:
// =========================================================================
// -- Public data members --------------------------------------------------
// =========================================================================
double latitude = 0.0;
double longitude = 0.0;
double altitude = 0.0;
// =========================================================================
// -- Constructors ---------------------------------------------------------
// =========================================================================
GeoLocation() = default;
GeoLocation(const GeoLocation &) = default;
GeoLocation(double latitude, double longitude, double altitude)
: latitude(latitude),
longitude(longitude),
altitude(altitude) {}
// =========================================================================
// -- Transform locations --------------------------------------------------
// =========================================================================
/// Transform the given @a location to a GeoLocation using this as
/// geo-reference.
GeoLocation Transform(const Location &location) const;
// =========================================================================
// -- Comparison operators -------------------------------------------------
// =========================================================================
bool operator==(const GeoLocation &rhs) const {
return (latitude == rhs.latitude) && (longitude == rhs.longitude) && (altitude == rhs.altitude);
}
bool operator!=(const GeoLocation &rhs) const {
return !(*this == rhs);
}
};
} // namespace geom
} // namespace carla

View File

@ -0,0 +1,67 @@
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
// de Barcelona (UAB).
//
// This work is licensed under the terms of the MIT license.
// For a copy, see <https://opensource.org/licenses/MIT>.
#include "carla/opendrive/parser/GeoReferenceParser.h"
#include "carla/Logging.h"
#include "carla/StringUtil.h"
#include <limits>
#include <sstream>
#include <vector>
namespace carla {
namespace opendrive {
namespace parser {
static double ParseDouble(const std::string &string_value) {
double value;
std::istringstream istr(string_value);
istr.imbue(std::locale("C"));
istr >> value;
if (istr.fail() || !istr.eof()) {
value = std::numeric_limits<double>::quiet_NaN();
}
return value;
}
geom::GeoLocation GeoReferenceParser::Parse(const std::string &geo_reference_string) {
geom::GeoLocation result{
std::numeric_limits<double>::quiet_NaN(),
std::numeric_limits<double>::quiet_NaN(),
0.0};
std::vector<std::string> geo_ref_splitted;
StringUtil::Split(geo_ref_splitted, geo_reference_string, " ");
for (auto element: geo_ref_splitted) {
std::vector<std::string> geo_ref_key_value;
StringUtil::Split(geo_ref_key_value, element, "=");
if (geo_ref_key_value.size() != 2u) {
continue;
}
if (geo_ref_key_value[0] == "+lat_0") {
result.latitude = ParseDouble(geo_ref_key_value[1]);
} else if (geo_ref_key_value[0] == "+lon_0") {
result.longitude = ParseDouble(geo_ref_key_value[1]);
}
}
if (std::isnan(result.latitude) || std::isnan(result.longitude)) {
log_warning("cannot parse georeference: '" + geo_reference_string + "'. Using default values.");
result.latitude = 42.0;
result.longitude = 2.0;
}
log_debug("map geo reference: latitude ", result.latitude, ", longitude ", result.longitude);
return result;
}
} // parser
} // opendrive
} // carla

View File

@ -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 <https://opensource.org/licenses/MIT>.
#pragma once
#include "carla/geom/GeoLocation.h"
#include <string>
namespace carla {
namespace opendrive {
namespace parser {
class GeoReferenceParser {
public:
static geom::GeoLocation Parse(const std::string &geo_reference_string);
};
} // parser
} // opendrive
} // carla

View File

@ -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 <https://opensource.org/licenses/MIT>.
#include "carla/opendrive/parser/OpenDriveParser.h"
#include "carla/geom/GeoLocation.h"
#include "carla/opendrive/parser/GeoReferenceParser.h"
#include "carla/opendrive/parser/GeometryParser.h"
#include "carla/opendrive/parser/JunctionParser.h"
#include "carla/opendrive/parser/LaneParser.h"
#include "carla/opendrive/parser/ProfilesParser.h"
#include "carla/opendrive/parser/RoadLinkParser.h"
#include "carla/opendrive/parser/TrafficGroupParser.h"
#include "carla/opendrive/parser/TrafficSignParser.h"
#include "carla/opendrive/parser/TrafficSignalsParser.h"
#include "./pugixml/pugixml.hpp"
bool OpenDriveParser::Parse(
const char *xml,
carla::opendrive::types::OpenDriveData &out_open_drive_data,
XmlInputType inputType,
std::string *out_error) {
namespace odp = carla::opendrive::parser;
pugi::xml_document xmlDoc;
pugi::xml_parse_result pugiParseResult;
switch (inputType) {
case XmlInputType::FILE: {
pugiParseResult = xmlDoc.load_file(xml);
} break;
case XmlInputType::CONTENT: {
pugiParseResult = xmlDoc.load_string(xml);
} break;
default: {
// TODO(Andrei): Log some kind of error
return false;
} break;
}
if (pugiParseResult == false) {
if (out_error != nullptr) {
*out_error = pugiParseResult.description();
}
return false;
}
for (pugi::xml_node road = xmlDoc.child("OpenDRIVE").child("road");
road;
road = road.next_sibling("road")) {
carla::opendrive::types::RoadInformation openDriveRoadInformation;
openDriveRoadInformation.attributes.name = road.attribute("name").value();
openDriveRoadInformation.attributes.id = std::atoi(road.attribute("id").value());
openDriveRoadInformation.attributes.length = std::stod(road.attribute("length").value());
openDriveRoadInformation.attributes.junction = std::atoi(road.attribute("junction").value());
///////////////////////////////////////////////////////////////////////////////
odp::ProfilesParser::Parse(road, openDriveRoadInformation.road_profiles);
odp::RoadLinkParser::Parse(road.child("link"), openDriveRoadInformation.road_link);
odp::TrafficSignalsParser::Parse(road.child("signals"),
openDriveRoadInformation.trafic_signals);
odp::LaneParser::Parse(road.child("lanes"), openDriveRoadInformation.lanes);
odp::GeometryParser::Parse(road.child("planView"),
openDriveRoadInformation.geometry_attributes);
out_open_drive_data.roads.emplace_back(std::move(openDriveRoadInformation));
}
for (pugi::xml_node junction = xmlDoc.child("OpenDRIVE").child("junction");
junction;
junction = junction.next_sibling("junction")) {
odp::JunctionParser::Parse(junction, out_open_drive_data.junctions);
}
for (pugi::xml_node tlgroup = xmlDoc.child("OpenDRIVE").child("tlGroup");
tlgroup;
tlgroup = tlgroup.next_sibling("tlGroup")) {
odp::TrafficGroupParser::Parse(tlgroup, out_open_drive_data.trafficlightgroups);
}
for (pugi::xml_node trafficsigns = xmlDoc.child("OpenDRIVE").child("trafficsign");
trafficsigns;
trafficsigns = trafficsigns.next_sibling("trafficsign")) {
odp::TrafficSignParser::Parse(trafficsigns, out_open_drive_data.trafficsigns);
}
out_open_drive_data.geoReference = odp::GeoReferenceParser::Parse(
xmlDoc.child("OpenDRIVE").child("header").child_value("geoReference"));
return true;
}

View File

@ -6,20 +6,7 @@
#pragma once #pragma once
#include "TrafficSignalsParser.h" #include "carla/opendrive/types.h"
#include "RoadLinkParser.h"
#include "JunctionParser.h"
#include "ProfilesParser.h"
#include "GeometryParser.h"
#include "LaneParser.h"
#include "TrafficGroupParser.h"
#include "TrafficSignParser.h"
#include "./pugixml/pugixml.hpp"
#include <iostream>
enum class XmlInputType : int { enum class XmlInputType : int {
FILE, FILE,
@ -31,78 +18,5 @@ struct OpenDriveParser {
const char *xml, const char *xml,
carla::opendrive::types::OpenDriveData &out_open_drive_data, carla::opendrive::types::OpenDriveData &out_open_drive_data,
XmlInputType inputType, XmlInputType inputType,
std::string *out_error = nullptr) { std::string *out_error = nullptr);
pugi::xml_document xmlDoc;
pugi::xml_parse_result pugiParseResult;
switch (inputType) {
case XmlInputType::FILE: {
pugiParseResult = xmlDoc.load_file(xml);
} break;
case XmlInputType::CONTENT: {
pugiParseResult = xmlDoc.load_string(xml);
} break;
default: {
// TODO(Andrei): Log some kind of error
return false;
} break;
}
if (pugiParseResult == false) {
if (out_error != nullptr) {
*out_error = pugiParseResult.description();
}
return false;
}
for (pugi::xml_node road = xmlDoc.child("OpenDRIVE").child("road");
road;
road = road.next_sibling("road")) {
carla::opendrive::types::RoadInformation openDriveRoadInformation;
openDriveRoadInformation.attributes.name = road.attribute("name").value();
openDriveRoadInformation.attributes.id = std::atoi(road.attribute("id").value());
openDriveRoadInformation.attributes.length = std::stod(road.attribute("length").value());
openDriveRoadInformation.attributes.junction = std::atoi(road.attribute("junction").value());
///////////////////////////////////////////////////////////////////////////////
carla::opendrive::parser::ProfilesParser::Parse(road, openDriveRoadInformation.road_profiles);
carla::opendrive::parser::RoadLinkParser::Parse(road.child("link"), openDriveRoadInformation.road_link);
carla::opendrive::parser::TrafficSignalsParser::Parse(road.child("signals"),
openDriveRoadInformation.trafic_signals);
carla::opendrive::parser::LaneParser::Parse(road.child("lanes"), openDriveRoadInformation.lanes);
carla::opendrive::parser::GeometryParser::Parse(road.child("planView"),
openDriveRoadInformation.geometry_attributes);
out_open_drive_data.roads.emplace_back(std::move(openDriveRoadInformation));
}
for (pugi::xml_node junction = xmlDoc.child("OpenDRIVE").child("junction");
junction;
junction = junction.next_sibling("junction")) {
carla::opendrive::parser::JunctionParser::Parse(junction, out_open_drive_data.junctions);
}
for (pugi::xml_node tlgroup = xmlDoc.child("OpenDRIVE").child("tlGroup");
tlgroup;
tlgroup = tlgroup.next_sibling("tlGroup")) {
carla::opendrive::parser::TrafficGroupParser::Parse(tlgroup, out_open_drive_data.trafficlightgroups);
}
for (pugi::xml_node trafficsigns = xmlDoc.child("OpenDRIVE").child("trafficsign");
trafficsigns;
trafficsigns = trafficsigns.next_sibling("trafficsign")) {
carla::opendrive::parser::TrafficSignParser::Parse(trafficsigns, out_open_drive_data.trafficsigns);
}
out_open_drive_data.geoReference = xmlDoc.child("OpenDRIVE").child("header").child_value("geoReference");
return true;
}
}; };

View File

@ -6,6 +6,8 @@
#pragma once #pragma once
#include "carla/geom/GeoLocation.h"
#include <memory> #include <memory>
#include <string> #include <string>
#include <vector> #include <vector>
@ -305,7 +307,7 @@ namespace types {
///////////////////////////////////////////////////////////////// /////////////////////////////////////////////////////////////////
struct OpenDriveData { struct OpenDriveData {
std::string geoReference; geom::GeoLocation geoReference;
std::vector<RoadInformation> roads; std::vector<RoadInformation> roads;
std::vector<Junction> junctions; std::vector<Junction> junctions;
std::vector<TrafficLightGroup> trafficlightgroups; std::vector<TrafficLightGroup> trafficlightgroups;

View File

@ -23,7 +23,7 @@ namespace road {
_map_data.SetJunctionInformation(junctionInfo); _map_data.SetJunctionInformation(junctionInfo);
} }
void SetGeoReference(const std::string &geoReference) { void SetGeoReference(const geom::GeoLocation &geoReference) {
_map_data.SetGeoReference(geoReference); _map_data.SetGeoReference(geoReference);
} }

View File

@ -53,7 +53,7 @@ namespace road {
return _junction_information; return _junction_information;
} }
const std::string &GetGeoReference() const { const geom::GeoLocation &GetGeoReference() const {
return _geo_reference; return _geo_reference;
} }
@ -83,7 +83,7 @@ namespace road {
_junction_information = junctionInfo; _junction_information = junctionInfo;
} }
void SetGeoReference(const std::string &geoReference) { void SetGeoReference(const geom::GeoLocation &geoReference) {
_geo_reference = geoReference; _geo_reference = geoReference;
} }
@ -95,7 +95,7 @@ namespace road {
_traffic_signs = trafficSignData; _traffic_signs = trafficSignData;
} }
std::string _geo_reference; geom::GeoLocation _geo_reference;
std::vector<lane_junction_t> _junction_information; std::vector<lane_junction_t> _junction_information;

View File

@ -8,8 +8,9 @@
#include "carla/road/element/RoadInfoVisitor.h" #include "carla/road/element/RoadInfoVisitor.h"
#include <string>
#include <map> #include <map>
#include <string>
#include <vector>
namespace carla { namespace carla {
namespace road { namespace road {

View File

@ -37,6 +37,10 @@ namespace element {
return _lane_id; return _lane_id;
} }
double GetDistance() const {
return _dist;
}
const std::string &GetType() const; const std::string &GetType() const;
const RoadSegment &GetRoadSegment() const; const RoadSegment &GetRoadSegment() const;

View File

@ -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 <https://opensource.org/licenses/MIT>.
#include "carla/road/element/WaypointHash.h"
#include "carla/road/element/Waypoint.h"
#include <boost/container_hash/hash.hpp>
namespace carla {
namespace road {
namespace element {
uint64_t WaypointHash::operator()(const Waypoint &waypoint) const {
uint64_t seed = 0u;
boost::hash_combine(seed, waypoint.GetRoadId());
boost::hash_combine(seed, waypoint.GetLaneId());
boost::hash_combine(seed, static_cast<float>(std::floor(waypoint.GetDistance() * 200.0)));
return seed;
}
} // namespace element
} // namespace road
} // namespace carla

View File

@ -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 <https://opensource.org/licenses/MIT>.
#pragma once
#include <cstdint>
namespace carla {
namespace road {
namespace element {
class Waypoint;
struct WaypointHash {
using argument_type = Waypoint;
using result_type = uint64_t;
/// Generates an unique id for @a waypoint based on its road_id, lane_id,
/// and "s" offset. The "s" offset is truncated to half centimetre
/// precision.
uint64_t operator()(const Waypoint &waypoint) const;
};
} // namespace element
} // namespace road
} // namespace carla

View File

@ -37,6 +37,11 @@ namespace sensor {
return GetHeader().frame_number; return GetHeader().frame_number;
} }
/// Timestamp when the data was generated.
double GetTimestamp() const {
return GetHeader().timestamp;
}
/// Sensor's transform when the data was generated. /// Sensor's transform when the data was generated.
const rpc::Transform &GetSensorTransform() const { const rpc::Transform &GetSensorTransform() const {
return GetHeader().sensor_transform; return GetHeader().sensor_transform;

View File

@ -23,12 +23,13 @@ namespace sensor {
private NonCopyable { private NonCopyable {
protected: protected:
SensorData(size_t frame_number, const rpc::Transform &sensor_transform) SensorData(size_t frame_number, double timestamp, const rpc::Transform &sensor_transform)
: _frame_number(frame_number), : _frame_number(frame_number),
_timestamp(timestamp),
_sensor_transform(sensor_transform) {} _sensor_transform(sensor_transform) {}
explicit SensorData(const RawData &data) explicit SensorData(const RawData &data)
: SensorData(data.GetFrameNumber(), data.GetSensorTransform()) {} : SensorData(data.GetFrameNumber(), data.GetTimestamp(), data.GetSensorTransform()) {}
public: public:
@ -39,6 +40,11 @@ namespace sensor {
return _frame_number; return _frame_number;
} }
/// Time the data was generated.
double GetTimestamp() const {
return _timestamp;
}
/// Sensor's transform when the data was generated. /// Sensor's transform when the data was generated.
const rpc::Transform &GetSensorTransform() const { const rpc::Transform &GetSensorTransform() const {
return _sensor_transform; return _sensor_transform;
@ -58,6 +64,8 @@ namespace sensor {
const size_t _frame_number; const size_t _frame_number;
const double _timestamp;
const rpc::Transform _sensor_transform; const rpc::Transform _sensor_transform;
}; };

View File

@ -5,49 +5,44 @@
#pragma once #pragma once
#include "carla/road/element/LaneMarking.h" #include "carla/geom/GeoLocation.h"
#include "carla/sensor/SensorData.h" #include "carla/sensor/SensorData.h"
#include <vector>
namespace carla { namespace carla {
namespace sensor { namespace sensor {
namespace data { namespace data {
/// A change of gnss data /// A change of GNSS data.
class GnssEvent : public SensorData { class GnssEvent : public SensorData {
public: public:
explicit GnssEvent( explicit GnssEvent(
size_t frame_number, size_t frame_number,
double timestamp,
const rpc::Transform &sensor_transform, const rpc::Transform &sensor_transform,
double lat, const geom::GeoLocation &geo_location)
double lon, : SensorData(frame_number, timestamp, sensor_transform),
double alt) _geo_location(geo_location) {}
: SensorData(frame_number, sensor_transform),
_lat(std::move(lat)),
_lon(std::move(lon)),
_alt(std::move(alt)) {}
const double &GetLatitude() const { const geom::GeoLocation &GetGeoLocation() const {
return _lat; return _geo_location;
} }
const double &GetLongitude() const { double GetLongitude() const {
return _lon; return _geo_location.longitude;
} }
const double &GetAltitude() const { double GetLatitude() const {
return _alt; return _geo_location.latitude;
}
double GetAltitude() const {
return _geo_location.altitude;
} }
private: private:
double _lat; geom::GeoLocation _geo_location;
double _lon;
double _alt;
}; };
} // namespace data } // namespace data

View File

@ -23,10 +23,11 @@ namespace data {
explicit LaneInvasionEvent( explicit LaneInvasionEvent(
size_t frame_number, size_t frame_number,
double timestamp,
const rpc::Transform &sensor_transform, const rpc::Transform &sensor_transform,
SharedPtr<client::Actor> self_actor, SharedPtr<client::Actor> self_actor,
std::vector<LaneMarking> crossed_lane_markings) std::vector<LaneMarking> crossed_lane_markings)
: SensorData(frame_number, sensor_transform), : SensorData(frame_number, timestamp, sensor_transform),
_self_actor(std::move(self_actor)), _self_actor(std::move(self_actor)),
_crossed_lane_markings(std::move(crossed_lane_markings)) {} _crossed_lane_markings(std::move(crossed_lane_markings)) {}

View File

@ -13,7 +13,7 @@ namespace sensor {
namespace s11n { namespace s11n {
static_assert( static_assert(
SensorHeaderSerializer::header_offset == 2u * 8u + 6u * 4u, SensorHeaderSerializer::header_offset == 3u * 8u + 6u * 4u,
"Header size missmatch"); "Header size missmatch");
static Buffer PopBufferFromPool() { static Buffer PopBufferFromPool() {
@ -24,10 +24,12 @@ namespace s11n {
Buffer SensorHeaderSerializer::Serialize( Buffer SensorHeaderSerializer::Serialize(
const uint64_t index, const uint64_t index,
const uint64_t frame, const uint64_t frame,
double timestamp,
const rpc::Transform transform) { const rpc::Transform transform) {
Header h; Header h;
h.sensor_type = index; h.sensor_type = index;
h.frame_number = frame; h.frame_number = frame;
h.timestamp = timestamp;
h.sensor_transform = transform; h.sensor_transform = transform;
auto buffer = PopBufferFromPool(); auto buffer = PopBufferFromPool();
buffer.copy_from(reinterpret_cast<const unsigned char *>(&h), sizeof(h)); buffer.copy_from(reinterpret_cast<const unsigned char *>(&h), sizeof(h));

View File

@ -21,13 +21,14 @@ namespace s11n {
struct Header { struct Header {
uint64_t sensor_type; uint64_t sensor_type;
uint64_t frame_number; uint64_t frame_number;
double timestamp;
rpc::Transform sensor_transform; rpc::Transform sensor_transform;
}; };
#pragma pack(pop) #pragma pack(pop)
constexpr static auto header_offset = sizeof(Header); constexpr static auto header_offset = sizeof(Header);
static Buffer Serialize(uint64_t index, uint64_t frame, rpc::Transform transform); static Buffer Serialize(uint64_t index, uint64_t frame, double timestamp, rpc::Transform transform);
static const Header &Deserialize(const Buffer &message) { static const Header &Deserialize(const Buffer &message) {
return *reinterpret_cast<const Header *>(message.data()); return *reinterpret_cast<const Header *>(message.data());

View File

@ -75,7 +75,7 @@ namespace detail {
static inline auto make_address(const std::string &address) { static inline auto make_address(const std::string &address) {
boost::asio::io_service io_service; boost::asio::io_service io_service;
boost::asio::ip::tcp::resolver resolver(io_service); boost::asio::ip::tcp::resolver resolver(io_service);
boost::asio::ip::tcp::resolver::query query(address, ""); boost::asio::ip::tcp::resolver::query query(boost::asio::ip::tcp::v4(), address, "", boost::asio::ip::tcp::resolver::query::canonical_name);
boost::asio::ip::tcp::resolver::iterator iter = resolver.resolve(query); boost::asio::ip::tcp::resolver::iterator iter = resolver.resolve(query);
boost::asio::ip::tcp::resolver::iterator end; boost::asio::ip::tcp::resolver::iterator end;
while (iter != end) while (iter != end)

View File

@ -24,7 +24,7 @@ namespace detail {
using StreamStateBase::StreamStateBase; using StreamStateBase::StreamStateBase;
template <typename... Buffers> template <typename... Buffers>
void Write(Buffers... buffers) { void Write(Buffers &&... buffers) {
auto message = Session::MakeMessage(std::move(buffers)...); auto message = Session::MakeMessage(std::move(buffers)...);
std::lock_guard<std::mutex> lock(_mutex); std::lock_guard<std::mutex> lock(_mutex);
for (auto &session : _sessions) { for (auto &session : _sessions) {

View File

@ -48,7 +48,7 @@ namespace detail {
/// Flush @a buffers down the stream. No copies are made. /// Flush @a buffers down the stream. No copies are made.
template <typename... Buffers> template <typename... Buffers>
void Write(Buffers... buffers) { void Write(Buffers &&... buffers) {
_shared_state->Write(std::move(buffers)...); _shared_state->Write(std::move(buffers)...);
} }

View File

@ -20,7 +20,7 @@ namespace detail {
using StreamStateBase::StreamStateBase; using StreamStateBase::StreamStateBase;
template <typename... Buffers> template <typename... Buffers>
void Write(Buffers... buffers) { void Write(Buffers &&... buffers) {
auto session = _session.load(); auto session = _session.load();
if (session != nullptr) { if (session != nullptr) {
session->Write(std::move(buffers)...); session->Write(std::move(buffers)...);

View File

@ -44,7 +44,7 @@ namespace tcp {
MessageTmpl(size_t) {} MessageTmpl(size_t) {}
template <typename... Buffers> template <typename... Buffers>
MessageTmpl(size_t size, Buffer buffer, Buffers... buffers) MessageTmpl(size_t size, Buffer &&buffer, Buffers &&... buffers)
: MessageTmpl(size, std::move(buffers)...) { : MessageTmpl(size, std::move(buffers)...) {
++_number_of_buffers; ++_number_of_buffers;
_total_size += buffer.size(); _total_size += buffer.size();
@ -55,7 +55,7 @@ namespace tcp {
public: public:
template <typename... Buffers> template <typename... Buffers>
MessageTmpl(Buffer buf, Buffers... buffers) MessageTmpl(Buffer &&buf, Buffers &&... buffers)
: MessageTmpl(sizeof...(Buffers) + 1u, std::move(buf), std::move(buffers)...) { : MessageTmpl(sizeof...(Buffers) + 1u, std::move(buf), std::move(buffers)...) {
static_assert(sizeof...(Buffers) < max_size(), "Too many buffers!"); static_assert(sizeof...(Buffers) < max_size(), "Too many buffers!");
_buffer_views[0u] = boost::asio::buffer(&_total_size, sizeof(_total_size)); _buffer_views[0u] = boost::asio::buffer(&_total_size, sizeof(_total_size));

View File

@ -53,7 +53,7 @@ namespace tcp {
} }
template <typename... Buffers> template <typename... Buffers>
static auto MakeMessage(Buffers... buffers) { static auto MakeMessage(Buffers &&... buffers) {
static_assert( static_assert(
are_same<Buffer, Buffers...>::value, are_same<Buffer, Buffers...>::value,
"This function only accepts arguments of type Buffer."); "This function only accepts arguments of type Buffer.");
@ -65,7 +65,7 @@ namespace tcp {
/// Writes some data to the socket. /// Writes some data to the socket.
template <typename... Buffers> template <typename... Buffers>
void Write(Buffers... buffers) { void Write(Buffers &&... buffers) {
Write(MakeMessage(std::move(buffers)...)); Write(MakeMessage(std::move(buffers)...));
} }

View File

@ -38,8 +38,7 @@ def get_libcarla_extensions():
os.path.join(pwd, 'dependencies/lib', pylib)] os.path.join(pwd, 'dependencies/lib', pylib)]
extra_compile_args = [ extra_compile_args = [
'-fPIC', '-std=c++14', '-Wno-missing-braces', '-fPIC', '-std=c++14', '-Wno-missing-braces',
'-DBOOST_ERROR_CODE_HEADER_ONLY', '-DLIBCARLA_WITH_PYTHON_SUPPORT', '-DBOOST_ERROR_CODE_HEADER_ONLY', '-DLIBCARLA_WITH_PYTHON_SUPPORT'
'-DLIBCARLA_ENABLE_LIFETIME_PROFILER',
] ]
if 'TRAVIS' in os.environ and os.environ['TRAVIS'] == 'true': if 'TRAVIS' in os.environ and os.environ['TRAVIS'] == 'true':
print('Travis CI build detected: disabling PNG support.') print('Travis CI build detected: disabling PNG support.')

View File

@ -5,6 +5,7 @@
// For a copy, see <https://opensource.org/licenses/MIT>. // For a copy, see <https://opensource.org/licenses/MIT>.
#include <carla/geom/BoundingBox.h> #include <carla/geom/BoundingBox.h>
#include <carla/geom/GeoLocation.h>
#include <carla/geom/Location.h> #include <carla/geom/Location.h>
#include <carla/geom/Rotation.h> #include <carla/geom/Rotation.h>
#include <carla/geom/Transform.h> #include <carla/geom/Transform.h>
@ -68,6 +69,13 @@ namespace geom {
return out; return out;
} }
std::ostream &operator<<(std::ostream &out, const GeoLocation &geo_location) {
out << "GeoLocation(latitude=" << geo_location.latitude
<< ", longitude=" << geo_location.longitude
<< ", altitude=" << geo_location.altitude << ')';
return out;
}
} // namespace geom } // namespace geom
} // namespace carla } // namespace carla
@ -129,7 +137,7 @@ void export_geom() {
.def(self_ns::str(self_ns::self)) .def(self_ns::str(self_ns::self))
; ;
class_<cg::Location, bases<cg::Vector3D>>("Location") class_<cg::Location, bases<cg::Vector3D>>("Location")
.def(init<float, float, float>((arg("x")=0.0f, arg("y")=0.0f, arg("z")=0.0f))) .def(init<float, float, float>((arg("x")=0.0f, arg("y")=0.0f, arg("z")=0.0f)))
.def(init<const cg::Vector3D &>((arg("rhs")))) .def(init<const cg::Vector3D &>((arg("rhs"))))
.add_property("x", +[](const cg::Location &self) { return self.x; }, +[](cg::Location &self, float x) { self.x = x; }) .add_property("x", +[](const cg::Location &self) { return self.x; }, +[](cg::Location &self, float x) { self.x = x; })
@ -177,4 +185,14 @@ class_<cg::Location, bases<cg::Vector3D>>("Location")
.def("__ne__", &cg::BoundingBox::operator!=) .def("__ne__", &cg::BoundingBox::operator!=)
.def(self_ns::str(self_ns::self)) .def(self_ns::str(self_ns::self))
; ;
class_<cg::GeoLocation>("GeoLocation")
.def(init<double, double, double>((arg("latitude")=0.0, arg("longitude")=0.0, arg("altitude")=0.0)))
.def_readwrite("latitude", &cg::GeoLocation::latitude)
.def_readwrite("longitude", &cg::GeoLocation::longitude)
.def_readwrite("altitude", &cg::GeoLocation::altitude)
.def("__eq__", &cg::GeoLocation::operator==)
.def("__ne__", &cg::GeoLocation::operator!=)
.def(self_ns::str(self_ns::self))
;
} }

View File

@ -47,6 +47,12 @@ static auto GetTopology(const carla::client::Map &self) {
return result; return result;
} }
static carla::geom::GeoLocation ToGeolocation(
const carla::client::Map &self,
const carla::geom::Location &location) {
return self.GetGeoReference().Transform(location);
}
void export_map() { void export_map() {
using namespace boost::python; using namespace boost::python;
namespace cc = carla::client; namespace cc = carla::client;
@ -58,6 +64,7 @@ void export_map() {
.def("get_waypoint", &cc::Map::GetWaypoint, (arg("location"), arg("project_to_road")=true)) .def("get_waypoint", &cc::Map::GetWaypoint, (arg("location"), arg("project_to_road")=true))
.def("get_topology", &GetTopology) .def("get_topology", &GetTopology)
.def("generate_waypoints", CALL_RETURNING_LIST_1(cc::Map, GenerateWaypoints, double), (args("distance"))) .def("generate_waypoints", CALL_RETURNING_LIST_1(cc::Map, GenerateWaypoints, double), (args("distance")))
.def("transform_to_geolocation", &ToGeolocation, (arg("location")))
.def("to_opendrive", CALL_RETURNING_COPY(cc::Map, GetOpenDrive)) .def("to_opendrive", CALL_RETURNING_COPY(cc::Map, GetOpenDrive))
.def("save_to_disk", &SaveOpenDriveToDisk, (arg("path")="")) .def("save_to_disk", &SaveOpenDriveToDisk, (arg("path")=""))
.def(self_ns::str(self_ns::self)) .def(self_ns::str(self_ns::self))
@ -71,11 +78,13 @@ void export_map() {
; ;
class_<cc::Waypoint, boost::noncopyable, boost::shared_ptr<cc::Waypoint>>("Waypoint", no_init) class_<cc::Waypoint, boost::noncopyable, boost::shared_ptr<cc::Waypoint>>("Waypoint", no_init)
.add_property("id", &cc::Waypoint::GetId)
.add_property("transform", CALL_RETURNING_COPY(cc::Waypoint, GetTransform)) .add_property("transform", CALL_RETURNING_COPY(cc::Waypoint, GetTransform))
.add_property("is_intersection", &cc::Waypoint::IsIntersection) .add_property("is_intersection", &cc::Waypoint::IsIntersection)
.add_property("lane_width", &cc::Waypoint::GetLaneWidth) .add_property("lane_width", &cc::Waypoint::GetLaneWidth)
.add_property("road_id", &cc::Waypoint::GetRoadId) .add_property("road_id", &cc::Waypoint::GetRoadId)
.add_property("lane_id", &cc::Waypoint::GetLaneId) .add_property("lane_id", &cc::Waypoint::GetLaneId)
.add_property("s", &cc::Waypoint::GetDistance)
.add_property("lane_change", &cc::Waypoint::GetLaneChange) .add_property("lane_change", &cc::Waypoint::GetLaneChange)
.add_property("lane_type", &cc::Waypoint::GetType) .add_property("lane_type", &cc::Waypoint::GetType)
.def("next", CALL_RETURNING_LIST_1(cc::Waypoint, Next, double), (args("distance"))) .def("next", CALL_RETURNING_LIST_1(cc::Waypoint, Next, double), (args("distance")))

View File

@ -28,6 +28,7 @@ namespace data {
std::ostream &operator<<(std::ostream &out, const Image &image) { std::ostream &operator<<(std::ostream &out, const Image &image) {
out << "Image(frame=" << image.GetFrameNumber() out << "Image(frame=" << image.GetFrameNumber()
<< ", timestamp=" << image.GetTimestamp()
<< ", size=" << image.GetWidth() << 'x' << image.GetHeight() << ", size=" << image.GetWidth() << 'x' << image.GetHeight()
<< ')'; << ')';
return out; return out;
@ -35,6 +36,7 @@ namespace data {
std::ostream &operator<<(std::ostream &out, const LidarMeasurement &meas) { std::ostream &operator<<(std::ostream &out, const LidarMeasurement &meas) {
out << "LidarMeasurement(frame=" << meas.GetFrameNumber() out << "LidarMeasurement(frame=" << meas.GetFrameNumber()
<< ", timestamp=" << meas.GetTimestamp()
<< ", number_of_points=" << meas.size() << ", number_of_points=" << meas.size()
<< ')'; << ')';
return out; return out;
@ -42,6 +44,7 @@ namespace data {
std::ostream &operator<<(std::ostream &out, const CollisionEvent &meas) { std::ostream &operator<<(std::ostream &out, const CollisionEvent &meas) {
out << "CollisionEvent(frame=" << meas.GetFrameNumber() out << "CollisionEvent(frame=" << meas.GetFrameNumber()
<< ", timestamp=" << meas.GetTimestamp()
<< ", other_actor=" << meas.GetOtherActor() << ", other_actor=" << meas.GetOtherActor()
<< ')'; << ')';
return out; return out;
@ -49,18 +52,22 @@ namespace data {
std::ostream &operator<<(std::ostream &out, const ObstacleDetectionEvent &meas) { std::ostream &operator<<(std::ostream &out, const ObstacleDetectionEvent &meas) {
out << "ObstacleDetectionEvent(frame=" << meas.GetFrameNumber() out << "ObstacleDetectionEvent(frame=" << meas.GetFrameNumber()
<< ", timestamp=" << meas.GetTimestamp()
<< ", other_actor=" << meas.GetOtherActor() << ", other_actor=" << meas.GetOtherActor()
<< ')'; << ')';
return out; return out;
} }
std::ostream &operator<<(std::ostream &out, const LaneInvasionEvent &meas) { std::ostream &operator<<(std::ostream &out, const LaneInvasionEvent &meas) {
out << "LaneInvasionEvent(frame=" << meas.GetFrameNumber() << ')'; out << "LaneInvasionEvent(frame=" << meas.GetFrameNumber()
<< ", timestamp=" << meas.GetTimestamp()
<< ')';
return out; return out;
} }
std::ostream &operator<<(std::ostream &out, const GnssEvent &meas) { std::ostream &operator<<(std::ostream &out, const GnssEvent &meas) {
out << "GnssEvent(frame=" << meas.GetFrameNumber() out << "GnssEvent(frame=" << meas.GetFrameNumber()
<< ", timestamp=" << meas.GetTimestamp()
<< ", lat=" << meas.GetLatitude() << ", lat=" << meas.GetLatitude()
<< ", lon=" << meas.GetLongitude() << ", lon=" << meas.GetLongitude()
<< ", alt=" << meas.GetAltitude() << ", alt=" << meas.GetAltitude()
@ -156,6 +163,7 @@ void export_sensor_data() {
class_<cs::SensorData, boost::noncopyable, boost::shared_ptr<cs::SensorData>>("SensorData", no_init) class_<cs::SensorData, boost::noncopyable, boost::shared_ptr<cs::SensorData>>("SensorData", no_init)
.add_property("frame_number", &cs::SensorData::GetFrameNumber) .add_property("frame_number", &cs::SensorData::GetFrameNumber)
.add_property("timestamp", &cs::SensorData::GetTimestamp)
.add_property("transform", CALL_RETURNING_COPY(cs::SensorData, GetSensorTransform)) .add_property("transform", CALL_RETURNING_COPY(cs::SensorData, GetSensorTransform))
; ;
@ -228,9 +236,9 @@ void export_sensor_data() {
; ;
class_<csd::GnssEvent, bases<cs::SensorData>, boost::noncopyable, boost::shared_ptr<csd::GnssEvent>>("GnssEvent", no_init) class_<csd::GnssEvent, bases<cs::SensorData>, boost::noncopyable, boost::shared_ptr<csd::GnssEvent>>("GnssEvent", no_init)
.add_property("latitude", CALL_RETURNING_COPY(csd::GnssEvent, GetLatitude)) .add_property("latitude", &csd::GnssEvent::GetLatitude)
.add_property("longitude", CALL_RETURNING_COPY(csd::GnssEvent, GetLongitude)) .add_property("longitude", &csd::GnssEvent::GetLongitude)
.add_property("altitude", CALL_RETURNING_COPY(csd::GnssEvent, GetAltitude)) .add_property("altitude", &csd::GnssEvent::GetAltitude)
.def(self_ns::str(self_ns::self)) .def(self_ns::str(self_ns::self))
; ;
} }

View File

@ -63,7 +63,7 @@ private:
/// @pre This functions needs to be called in the game-thread. /// @pre This functions needs to be called in the game-thread.
template <typename SensorT> template <typename SensorT>
explicit FAsyncDataStreamTmpl(const SensorT &InSensor, StreamType InStream); explicit FAsyncDataStreamTmpl(const SensorT &InSensor, float Timepoint, StreamType InStream);
StreamType Stream; StreamType Stream;
@ -95,13 +95,15 @@ template <typename T>
template <typename SensorT> template <typename SensorT>
inline FAsyncDataStreamTmpl<T>::FAsyncDataStreamTmpl( inline FAsyncDataStreamTmpl<T>::FAsyncDataStreamTmpl(
const SensorT &Sensor, const SensorT &Sensor,
float Timepoint,
StreamType InStream) StreamType InStream)
: Stream(std::move(InStream)), : Stream(std::move(InStream)),
Header([&Sensor]() { Header([&Sensor, Timepoint]() {
check(IsInGameThread()); check(IsInGameThread());
using Serializer = carla::sensor::s11n::SensorHeaderSerializer; using Serializer = carla::sensor::s11n::SensorHeaderSerializer;
return Serializer::Serialize( return Serializer::Serialize(
carla::sensor::SensorRegistry::template get<SensorT*>::index, carla::sensor::SensorRegistry::template get<SensorT*>::index,
GFrameCounter, GFrameCounter,
Timepoint,
Sensor.GetActorTransform()); Sensor.GetActorTransform());
}()) {} }()) {}

View File

@ -62,7 +62,7 @@ void ACollisionSensor::OnCollisionEvent(
{ {
constexpr float TO_METERS = 1e-2; constexpr float TO_METERS = 1e-2;
NormalImpulse *= TO_METERS; NormalImpulse *= TO_METERS;
GetDataStream(*this).Send( GetDataStream(*this, Actor->GetWorld()->GetTimeSeconds()).Send(
*this, *this,
Episode->SerializeActor(Episode->FindOrFakeActor(Actor)), Episode->SerializeActor(Episode->FindOrFakeActor(Actor)),
Episode->SerializeActor(Episode->FindOrFakeActor(OtherActor)), Episode->SerializeActor(Episode->FindOrFakeActor(OtherActor)),

View File

@ -37,10 +37,10 @@ public:
/// ///
/// @pre This functions needs to be called in the game-thread. /// @pre This functions needs to be called in the game-thread.
template <typename SensorT> template <typename SensorT>
auto MakeAsyncDataStream(const SensorT &Sensor) auto MakeAsyncDataStream(const SensorT &Sensor, float Timestamp)
{ {
check(Stream.has_value()); check(Stream.has_value());
return FAsyncDataStreamTmpl<T>{Sensor, *Stream}; return FAsyncDataStreamTmpl<T>{Sensor, Timestamp, *Stream};
} }
/// Return the token that allows subscribing to this stream. /// Return the token that allows subscribing to this stream.

View File

@ -134,7 +134,7 @@ void AObstacleDetectionSensor::Tick(float DeltaSeconds)
if (isHitReturned) if (isHitReturned)
{ {
OnObstacleDetectionEvent(this, HitOut.Actor.Get(), HitOut.Distance, HitOut); OnObstacleDetectionEvent(this, HitOut.Actor.Get(), HitOut.Distance, HitOut, currentWorld->GetTimeSeconds());
} }
} }
@ -142,11 +142,12 @@ void AObstacleDetectionSensor::OnObstacleDetectionEvent(
AActor *Actor, AActor *Actor,
AActor *OtherActor, AActor *OtherActor,
float HitDistance, float HitDistance,
const FHitResult &Hit) const FHitResult &Hit,
float Timestamp)
{ {
if ((Episode != nullptr) && (Actor != nullptr) && (OtherActor != nullptr)) if ((Episode != nullptr) && (Actor != nullptr) && (OtherActor != nullptr))
{ {
GetDataStream(*this).Send(*this, GetDataStream(*this, Timestamp).Send(*this,
Episode->SerializeActor(Episode->FindOrFakeActor(Actor)), Episode->SerializeActor(Episode->FindOrFakeActor(Actor)),
Episode->SerializeActor(Episode->FindOrFakeActor(OtherActor)), Episode->SerializeActor(Episode->FindOrFakeActor(OtherActor)),
HitRadius); HitRadius);

View File

@ -38,7 +38,8 @@ private:
AActor *Actor, AActor *Actor,
AActor *OtherActor, AActor *OtherActor,
float Distance, float Distance,
const FHitResult &Hit); const FHitResult &Hit,
float Timestamp);
UPROPERTY() UPROPERTY()
const UCarlaEpisode *Episode = nullptr; const UCarlaEpisode *Episode = nullptr;

View File

@ -87,7 +87,7 @@ void FPixelReader::SendPixelsInRenderThread(TSensor &Sensor)
// First we create the message header (needs to be created in the // First we create the message header (needs to be created in the
// game-thread). // game-thread).
auto AsyncStream = Sensor.GetDataStream(Sensor); auto AsyncStream = Sensor.GetDataStream(Sensor, Sensor.GetWorld()->GetTimeSeconds());
// We need a shared ptr here because UE4 macros do not move the arguments -_- // We need a shared ptr here because UE4 macros do not move the arguments -_-
auto StreamPtr = std::make_shared<decltype(AsyncStream)>(std::move(AsyncStream)); auto StreamPtr = std::make_shared<decltype(AsyncStream)>(std::move(AsyncStream));

View File

@ -69,7 +69,7 @@ void ARayCastLidar::Tick(const float DeltaTime)
ReadPoints(DeltaTime); ReadPoints(DeltaTime);
auto DataStream = GetDataStream(*this); auto DataStream = GetDataStream(*this, GetWorld()->GetTimeSeconds());
DataStream.Send(*this, LidarMeasurement, DataStream.PopBufferFromPool()); DataStream.Send(*this, LidarMeasurement, DataStream.PopBufferFromPool());
} }

View File

@ -47,9 +47,9 @@ protected:
/// You need to provide a reference to self, this is necessary for template /// You need to provide a reference to self, this is necessary for template
/// deduction. /// deduction.
template <typename SensorT> template <typename SensorT>
FAsyncDataStream GetDataStream(const SensorT &Self) FAsyncDataStream GetDataStream(const SensorT &Self, float Timestamp)
{ {
return Stream.MakeAsyncDataStream(Self); return Stream.MakeAsyncDataStream(Self, Timestamp);
} }
private: private:

View File

@ -150,7 +150,7 @@ static carla::Buffer FWorldObserver_Serialize(
void FWorldObserver::BroadcastTick(const UCarlaEpisode &Episode, float DeltaSeconds) void FWorldObserver::BroadcastTick(const UCarlaEpisode &Episode, float DeltaSeconds)
{ {
auto AsyncStream = Stream.MakeAsyncDataStream(*this); auto AsyncStream = Stream.MakeAsyncDataStream(*this, Episode.GetWorld()->GetTimeSeconds());
auto buffer = FWorldObserver_Serialize( auto buffer = FWorldObserver_Serialize(
AsyncStream.PopBufferFromPool(), AsyncStream.PopBufferFromPool(),

View File

@ -178,6 +178,14 @@ void UCarlaSettings::LoadSettings()
{ {
QualityLevel = QualityLevelFromString(StringQualityLevel, EQualityLevel::Epic); QualityLevel = QualityLevelFromString(StringQualityLevel, EQualityLevel::Epic);
} }
if (FParse::Value(FCommandLine::Get(), TEXT("-carla-server-timeout="), Value))
{
ServerTimeOut = Value;
}
if (FParse::Param(FCommandLine::Get(), TEXT("-no-rendering")))
{
bDisableRendering = true;
}
} }
} }

View File

@ -8,13 +8,34 @@ source $(dirname "$0")/Environment.sh
DOC_STRING="Build LibCarla." DOC_STRING="Build LibCarla."
USAGE_STRING="Usage: $0 [-h|--help] [--rebuild] [--server] [--client] [--clean]" USAGE_STRING=$(cat <<- END
Usage: $0 [-h|--help]
Choose one or more build configurations
[--server] Build server-side configuration.
[--client] Build client-side configuration.
and choose one or more build options
[--debug] Build debug targets.
[--release] Build release targets.
Other commands
[--clean] Clean intermediate files.
[--rebuild] Clean and rebuild both configurations.
END
)
REMOVE_INTERMEDIATE=false REMOVE_INTERMEDIATE=false
BUILD_SERVER=false BUILD_SERVER=false
BUILD_CLIENT=false BUILD_CLIENT=false
BUILD_OPTION_DEBUG=false
BUILD_OPTION_RELEASE=false
BUILD_OPTION_DUMMY=false
OPTS=`getopt -o h --long help,rebuild,server,client,clean -n 'parse-options' -- "$@"` OPTS=`getopt -o h --long help,rebuild,server,client,clean,debug,release -n 'parse-options' -- "$@"`
if [ $? != 0 ] ; then echo "$USAGE_STRING" ; exit 2 ; fi if [ $? != 0 ] ; then echo "$USAGE_STRING" ; exit 2 ; fi
@ -26,6 +47,8 @@ while true; do
REMOVE_INTERMEDIATE=true; REMOVE_INTERMEDIATE=true;
BUILD_SERVER=true; BUILD_SERVER=true;
BUILD_CLIENT=true; BUILD_CLIENT=true;
BUILD_OPTION_DEBUG=true;
BUILD_OPTION_RELEASE=true;
shift ;; shift ;;
--server ) --server )
BUILD_SERVER=true; BUILD_SERVER=true;
@ -35,6 +58,13 @@ while true; do
shift ;; shift ;;
--clean ) --clean )
REMOVE_INTERMEDIATE=true; REMOVE_INTERMEDIATE=true;
BUILD_OPTION_DUMMY=true;
shift ;;
--debug )
BUILD_OPTION_DEBUG=true;
shift ;;
--release )
BUILD_OPTION_RELEASE=true;
shift ;; shift ;;
-h | --help ) -h | --help )
echo "$DOC_STRING" echo "$DOC_STRING"
@ -50,6 +80,10 @@ if ! { ${REMOVE_INTERMEDIATE} || ${BUILD_SERVER} || ${BUILD_CLIENT}; }; then
fatal_error "Nothing selected to be done." fatal_error "Nothing selected to be done."
fi fi
if ! { ${BUILD_OPTION_DUMMY} || ${BUILD_OPTION_DEBUG} || ${BUILD_OPTION_RELEASE} ; }; then
fatal_error "Choose --debug and/or --release."
fi
# ============================================================================== # ==============================================================================
# -- Clean intermediate files -------------------------------------------------- # -- Clean intermediate files --------------------------------------------------
# ============================================================================== # ==============================================================================
@ -58,30 +92,57 @@ if ${REMOVE_INTERMEDIATE} ; then
log "Cleaning intermediate files and folders." log "Cleaning intermediate files and folders."
rm -Rf ${LIBCARLA_BUILD_SERVER_FOLDER} ${LIBCARLA_BUILD_CLIENT_FOLDER} rm -Rf ${LIBCARLA_BUILD_SERVER_FOLDER}* ${LIBCARLA_BUILD_CLIENT_FOLDER}*
rm -Rf ${LIBCARLA_INSTALL_SERVER_FOLDER} ${LIBCARLA_INSTALL_CLIENT_FOLDER} rm -Rf ${LIBCARLA_INSTALL_SERVER_FOLDER} ${LIBCARLA_INSTALL_CLIENT_FOLDER}
rm -f ${LIBCARLA_ROOT_FOLDER}/source/carla/Version.h
fi fi
# ============================================================================== # ==============================================================================
# -- Build Server configuration ------------------------------------------------ # -- Define build function -----------------------------------------------------
# ============================================================================== # ==============================================================================
if ${BUILD_SERVER} ; then # Build LibCarla for the given configuration.
#
# usage: build_libcarla {Server,Client} {Debug,Release}
#
function build_libcarla {
log "Building LibCarla \"Server\" configuration." if [ $1 == Server ] ; then
M_TOOLCHAIN=${LIBCPP_TOOLCHAIN_FILE}
M_BUILD_FOLDER=${LIBCARLA_BUILD_SERVER_FOLDER}.$(echo "$2" | tr '[:upper:]' '[:lower:]')
M_INSTALL_FOLDER=${LIBCARLA_INSTALL_SERVER_FOLDER}
elif [ $1 == Client ] ; then
M_TOOLCHAIN=${LIBSTDCPP_TOOLCHAIN_FILE}
M_BUILD_FOLDER=${LIBCARLA_BUILD_CLIENT_FOLDER}.$(echo "$2" | tr '[:upper:]' '[:lower:]')
M_INSTALL_FOLDER=${LIBCARLA_INSTALL_CLIENT_FOLDER}
else
fatal_error "Invalid build configuration \"$1\""
fi
mkdir -p ${LIBCARLA_BUILD_SERVER_FOLDER} if [ $2 == Debug ] ; then
pushd "${LIBCARLA_BUILD_SERVER_FOLDER}" >/dev/null M_DEBUG=ON
M_RELEASE=OFF
elif [ $2 == Release ] ; then
M_DEBUG=OFF
M_RELEASE=ON
else
fatal_error "Invalid build option \"$2\""
fi
log "Building LibCarla \"$1.$2\" configuration."
mkdir -p ${M_BUILD_FOLDER}
pushd "${M_BUILD_FOLDER}" >/dev/null
if [ ! -f "build.ninja" ]; then if [ ! -f "build.ninja" ]; then
cmake \ cmake \
-G "Ninja" \ -G "Ninja" \
-DCMAKE_BUILD_TYPE=Server \ -DCMAKE_BUILD_TYPE=$1 \
-DCMAKE_TOOLCHAIN_FILE=${LIBCPP_TOOLCHAIN_FILE} \ -DLIBCARLA_BUILD_DEBUG=${M_DEBUG} \
-DCMAKE_INSTALL_PREFIX=${LIBCARLA_INSTALL_SERVER_FOLDER} \ -DLIBCARLA_BUILD_RELEASE=${M_RELEASE} \
-DCMAKE_TOOLCHAIN_FILE=${M_TOOLCHAIN} \
-DCMAKE_INSTALL_PREFIX=${M_INSTALL_FOLDER} \
-DCMAKE_EXPORT_COMPILE_COMMANDS=1 \ -DCMAKE_EXPORT_COMPILE_COMMANDS=1 \
${CARLA_ROOT_FOLDER} ${CARLA_ROOT_FOLDER}
@ -92,37 +153,33 @@ if ${BUILD_SERVER} ; then
ninja install | grep -v "Up-to-date:" ninja install | grep -v "Up-to-date:"
popd >/dev/null popd >/dev/null
}
# ==============================================================================
# -- Build all possible configurations -----------------------------------------
# ==============================================================================
if { ${BUILD_SERVER} && ${BUILD_OPTION_DEBUG}; }; then
build_libcarla Server Debug
fi fi
# ============================================================================== if { ${BUILD_SERVER} && ${BUILD_OPTION_RELEASE}; }; then
# -- Build Client configuration ------------------------------------------------
# ==============================================================================
if ${BUILD_CLIENT} ; then build_libcarla Server Release
log "Building LibCarla \"Client\" configuration." fi
mkdir -p ${LIBCARLA_BUILD_CLIENT_FOLDER} if { ${BUILD_CLIENT} && ${BUILD_OPTION_DEBUG}; }; then
pushd "${LIBCARLA_BUILD_CLIENT_FOLDER}" >/dev/null
if [ ! -f "build.ninja" ]; then build_libcarla Client Debug
cmake \ fi
-G "Ninja" \
-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 if { ${BUILD_CLIENT} && ${BUILD_OPTION_RELEASE}; }; then
ninja build_libcarla Client Release
ninja install | grep -v "Up-to-date:"
popd >/dev/null
fi fi

View File

@ -3,7 +3,7 @@ default: help
help: help:
@less ${CARLA_BUILD_TOOLS_FOLDER}/Linux.mk.help @less ${CARLA_BUILD_TOOLS_FOLDER}/Linux.mk.help
launch: LibCarla.server launch: LibCarla.server.release
@${CARLA_BUILD_TOOLS_FOLDER}/BuildCarlaUE4.sh --build --launch @${CARLA_BUILD_TOOLS_FOLDER}/BuildCarlaUE4.sh --build --launch
launch-only: launch-only:
@ -41,10 +41,10 @@ check: LibCarla PythonAPI
check.LibCarla: LibCarla check.LibCarla: LibCarla
@${CARLA_BUILD_TOOLS_FOLDER}/Check.sh --libcarla-debug --libcarla-release $(ARGS) @${CARLA_BUILD_TOOLS_FOLDER}/Check.sh --libcarla-debug --libcarla-release $(ARGS)
check.LibCarla.debug: LibCarla check.LibCarla.debug: LibCarla.debug
@${CARLA_BUILD_TOOLS_FOLDER}/Check.sh --libcarla-debug $(ARGS) @${CARLA_BUILD_TOOLS_FOLDER}/Check.sh --libcarla-debug $(ARGS)
check.LibCarla.release: LibCarla check.LibCarla.release: LibCarla.release
@${CARLA_BUILD_TOOLS_FOLDER}/Check.sh --libcarla-release $(ARGS) @${CARLA_BUILD_TOOLS_FOLDER}/Check.sh --libcarla-release $(ARGS)
check.PythonAPI: PythonAPI check.PythonAPI: PythonAPI
@ -56,31 +56,40 @@ check.PythonAPI.2: PythonAPI.2
check.PythonAPI.3: PythonAPI.3 check.PythonAPI.3: PythonAPI.3
@${CARLA_BUILD_TOOLS_FOLDER}/Check.sh --python-api-3 $(ARGS) @${CARLA_BUILD_TOOLS_FOLDER}/Check.sh --python-api-3 $(ARGS)
benchmark: LibCarla.server benchmark: LibCarla.release
@${CARLA_BUILD_TOOLS_FOLDER}/Check.sh --benchmark $(ARGS) @${CARLA_BUILD_TOOLS_FOLDER}/Check.sh --benchmark $(ARGS)
@cat profiler.csv @cat profiler.csv
CarlaUE4Editor: LibCarla.server CarlaUE4Editor: LibCarla.server.release
@${CARLA_BUILD_TOOLS_FOLDER}/BuildCarlaUE4.sh --build @${CARLA_BUILD_TOOLS_FOLDER}/BuildCarlaUE4.sh --build
.PHONY: PythonAPI .PHONY: PythonAPI
PythonAPI: LibCarla.client PythonAPI: LibCarla.client.release
@${CARLA_BUILD_TOOLS_FOLDER}/BuildPythonAPI.sh --py2 --py3 @${CARLA_BUILD_TOOLS_FOLDER}/BuildPythonAPI.sh --py2 --py3
PythonAPI.2: LibCarla.client PythonAPI.2: LibCarla.client.release
@${CARLA_BUILD_TOOLS_FOLDER}/BuildPythonAPI.sh --py2 @${CARLA_BUILD_TOOLS_FOLDER}/BuildPythonAPI.sh --py2
PythonAPI.3: LibCarla.client PythonAPI.3: LibCarla.client.release
@${CARLA_BUILD_TOOLS_FOLDER}/BuildPythonAPI.sh --py3 @${CARLA_BUILD_TOOLS_FOLDER}/BuildPythonAPI.sh --py3
.PHONY: LibCarla .PHONY: LibCarla
LibCarla: LibCarla.server LibCarla.client LibCarla: LibCarla.server LibCarla.client
LibCarla.server: setup LibCarla.debug: LibCarla.server.debug LibCarla.client.debug
@${CARLA_BUILD_TOOLS_FOLDER}/BuildLibCarla.sh --server LibCarla.release: LibCarla.server.release LibCarla.client.release
LibCarla.client: setup LibCarla.server: LibCarla.server.debug LibCarla.server.release
@${CARLA_BUILD_TOOLS_FOLDER}/BuildLibCarla.sh --client LibCarla.server.debug: setup
@${CARLA_BUILD_TOOLS_FOLDER}/BuildLibCarla.sh --server --debug
LibCarla.server.release: setup
@${CARLA_BUILD_TOOLS_FOLDER}/BuildLibCarla.sh --server --release
LibCarla.client: LibCarla.client.debug LibCarla.client.release
LibCarla.client.debug: setup
@${CARLA_BUILD_TOOLS_FOLDER}/BuildLibCarla.sh --client --debug
LibCarla.client.release: setup
@${CARLA_BUILD_TOOLS_FOLDER}/BuildLibCarla.sh --client --release
setup: setup:
@${CARLA_BUILD_TOOLS_FOLDER}/Setup.sh @${CARLA_BUILD_TOOLS_FOLDER}/Setup.sh

View File

@ -73,7 +73,7 @@ for developers:
Build and package the Python API module for Python 2 and/or 3. Build and package the Python API module for Python 2 and/or 3.
LibCarla(.server|.client): LibCarla(.server|.client)(.debug|.release):
Build LibCarla, "Server" and/or "Client" configurations. Build LibCarla, "Server" and/or "Client" configurations.

View File

@ -280,6 +280,21 @@ fi
unset GTEST_BASENAME unset GTEST_BASENAME
# ==============================================================================
# -- Generate Version.h --------------------------------------------------------
# ==============================================================================
CARLA_VERSION=$(get_carla_version)
log "CARLA version ${CARLA_VERSION}."
VERSION_H_FILE=${LIBCARLA_ROOT_FOLDER}/source/carla/Version.h
VERSION_H_FILE_GEN=${CARLA_BUILD_FOLDER}/Version.h
sed -e "s|\${CARLA_VERSION}|${CARLA_VERSION}|g" ${VERSION_H_FILE}.in > ${VERSION_H_FILE_GEN}
move_if_changed "${VERSION_H_FILE_GEN}" "${VERSION_H_FILE}"
# ============================================================================== # ==============================================================================
# -- Generate CMake toolchains and config -------------------------------------- # -- Generate CMake toolchains and config --------------------------------------
# ============================================================================== # ==============================================================================
@ -298,7 +313,7 @@ set(CMAKE_CXX_FLAGS "\${CMAKE_CXX_FLAGS} -std=c++14 -pthread -fPIC" CACHE STRING
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)
# @todo These flags need to be compatible with setup.py compilation. # @todo These flags need to be compatible with setup.py compilation.
set(CMAKE_CXX_FLAGS_RELEASE_CLIENT "\${CMAKE_CXX_FLAGS_RELEASE} -DNDEBUG -g -fwrapv -O2 -Wall -Wstrict-prototypes -fno-strict-aliasing -Wdate-time -D_FORTIFY_SOURCE=2 -g -fstack-protector-strong -Wformat -Werror=format-security -fPIC -std=c++14 -Wno-missing-braces -DBOOST_ERROR_CODE_HEADER_ONLY -DLIBCARLA_ENABLE_LIFETIME_PROFILER -DLIBCARLA_WITH_PYTHON_SUPPORT" CACHE STRING "" FORCE) set(CMAKE_CXX_FLAGS_RELEASE_CLIENT "\${CMAKE_CXX_FLAGS_RELEASE} -DNDEBUG -g -fwrapv -O2 -Wall -Wstrict-prototypes -fno-strict-aliasing -Wdate-time -D_FORTIFY_SOURCE=2 -g -fstack-protector-strong -Wformat -Werror=format-security -fPIC -std=c++14 -Wno-missing-braces -DBOOST_ERROR_CODE_HEADER_ONLY -DLIBCARLA_WITH_PYTHON_SUPPORT" CACHE STRING "" FORCE)
EOL EOL
# -- LIBCPP_TOOLCHAIN_FILE ----------------------------------------------------- # -- LIBCPP_TOOLCHAIN_FILE -----------------------------------------------------
@ -320,8 +335,6 @@ EOL
cat >${CMAKE_CONFIG_FILE}.gen <<EOL cat >${CMAKE_CONFIG_FILE}.gen <<EOL
# Automatically generated by `basename "$0"` # Automatically generated by `basename "$0"`
set(CARLA_VERSION $(get_carla_version))
add_definitions(-DBOOST_ERROR_CODE_HEADER_ONLY) add_definitions(-DBOOST_ERROR_CODE_HEADER_ONLY)
if (CMAKE_BUILD_TYPE STREQUAL "Server") if (CMAKE_BUILD_TYPE STREQUAL "Server")

View File

@ -77,7 +77,7 @@
} }
}, },
{ {
"name": "CARLA - make LibCarla (Server)", "name": "CARLA - make LibCarla (Server All)",
"working_dir": "${project_path}/..", "working_dir": "${project_path}/..",
"file_regex": "^../../([^:]*):([0-9]+):?([0-9]+)?:? (.*)$", "file_regex": "^../../([^:]*):([0-9]+):?([0-9]+)?:? (.*)$",
"syntax": "Packages/Makefile/Make Output.sublime-syntax", "syntax": "Packages/Makefile/Make Output.sublime-syntax",
@ -87,7 +87,27 @@
} }
}, },
{ {
"name": "CARLA - make LibCarla (Client)", "name": "CARLA - make LibCarla (Server Debug)",
"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.server.debug"
}
},
{
"name": "CARLA - make LibCarla (Server Release)",
"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.server.release"
}
},
{
"name": "CARLA - make LibCarla (Client All)",
"working_dir": "${project_path}/..", "working_dir": "${project_path}/..",
"file_regex": "^../../([^:]*):([0-9]+):?([0-9]+)?:? (.*)$", "file_regex": "^../../([^:]*):([0-9]+):?([0-9]+)?:? (.*)$",
"syntax": "Packages/Makefile/Make Output.sublime-syntax", "syntax": "Packages/Makefile/Make Output.sublime-syntax",
@ -96,6 +116,26 @@
"shell_cmd": "CARLA_BUILD_NO_COLOR=true make LibCarla.client" "shell_cmd": "CARLA_BUILD_NO_COLOR=true make LibCarla.client"
} }
}, },
{
"name": "CARLA - make LibCarla (Client Debug)",
"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.client.debug"
}
},
{
"name": "CARLA - make LibCarla (Client Release)",
"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.client.release"
}
},
{ {
"name": "CARLA - make PythonAPI (All)", "name": "CARLA - make PythonAPI (All)",
"working_dir": "${project_path}/..", "working_dir": "${project_path}/..",